diff --git a/vehicle/raw_vehicle_cmd_converter/CMakeLists.txt b/vehicle/raw_vehicle_cmd_converter/CMakeLists.txt index 36b96a2a300c5..d253b2315465e 100644 --- a/vehicle/raw_vehicle_cmd_converter/CMakeLists.txt +++ b/vehicle/raw_vehicle_cmd_converter/CMakeLists.txt @@ -7,9 +7,9 @@ autoware_package() ament_auto_add_library(actuation_map_converter SHARED src/accel_map.cpp src/brake_map.cpp + src/steer_map.cpp src/csv_loader.cpp src/pid.cpp - src/steer_converter.cpp ) ament_auto_add_library(raw_vehicle_cmd_converter_node_component SHARED diff --git a/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/accel_map.hpp b/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/accel_map.hpp index bb872db838f18..fba69efdbc921 100644 --- a/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/accel_map.hpp +++ b/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/accel_map.hpp @@ -29,12 +29,12 @@ namespace raw_vehicle_cmd_converter class AccelMap { public: - bool readAccelMapFromCSV(std::string csv_path); - bool getThrottle(double acc, double vel, double & throttle); - bool getAcceleration(double throttle, double vel, double & acc); - std::vector getVelIdx() { return vel_index_; } - std::vector getThrottleIdx() { return throttle_index_; } - std::vector> getAccelMap() { return accel_map_; } + bool readAccelMapFromCSV(const std::string & csv_path); + bool getThrottle(const double acc, const double vel, double & throttle) const; + bool getAcceleration(const double throttle, const double vel, double & acc) const; + std::vector getVelIdx() const { return vel_index_; } + std::vector getThrottleIdx() const { return throttle_index_; } + std::vector> getAccelMap() const { return accel_map_; } private: rclcpp::Logger logger_{rclcpp::get_logger("raw_vehicle_cmd_converter").get_child("accel_map")}; diff --git a/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/brake_map.hpp b/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/brake_map.hpp index ba1fadfcd61c9..8d4d35545254c 100644 --- a/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/brake_map.hpp +++ b/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/brake_map.hpp @@ -29,12 +29,12 @@ namespace raw_vehicle_cmd_converter class BrakeMap { public: - bool readBrakeMapFromCSV(std::string csv_path); - bool getBrake(double acc, double vel, double & brake); - bool getAcceleration(double brake, double vel, double & acc); - std::vector getVelIdx() { return vel_index_; } - std::vector getBrakeIdx() { return brake_index_; } - std::vector> getBrakeMap() { return brake_map_; } + bool readBrakeMapFromCSV(const std::string & csv_path); + bool getBrake(const double acc, const double vel, double & brake); + bool getAcceleration(const double brake, const double vel, double & acc) const; + std::vector getVelIdx() const { return vel_index_; } + std::vector getBrakeIdx() const { return brake_index_; } + std::vector> getBrakeMap() const { return brake_map_; } private: rclcpp::Logger logger_{rclcpp::get_logger("raw_vehicle_cmd_converter").get_child("accel_map")}; diff --git a/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/csv_loader.hpp b/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/csv_loader.hpp index ff605ffa00279..1786050347362 100644 --- a/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/csv_loader.hpp +++ b/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/csv_loader.hpp @@ -24,15 +24,19 @@ namespace raw_vehicle_cmd_converter { using Table = std::vector>; +using Map = std::vector>; class CSVLoader { public: - explicit CSVLoader(std::string csv_path); + explicit CSVLoader(const std::string & csv_path); bool readCSV(Table & result, const char delim = ','); static bool validateData(const Table & table, const std::string & csv_path); + static Map getMap(const Table & table); static std::vector getRowIndex(const Table & table); static std::vector getColumnIndex(const Table & table); + static double clampValue( + const double val, const std::vector & ranges, const std::string & name); private: std::string csv_path_; diff --git a/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/node.hpp b/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/node.hpp index 068c6880b23e8..27346e99b60fb 100644 --- a/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/node.hpp +++ b/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/node.hpp @@ -18,7 +18,7 @@ #include "raw_vehicle_cmd_converter/accel_map.hpp" #include "raw_vehicle_cmd_converter/brake_map.hpp" #include "raw_vehicle_cmd_converter/pid.hpp" -#include "raw_vehicle_cmd_converter/steer_converter.hpp" +#include "raw_vehicle_cmd_converter/steer_map.hpp" #include @@ -87,6 +87,9 @@ class RawVehicleCommandConverterNode : public rclcpp::Node AckermannControlCommand::ConstSharedPtr control_cmd_ptr_; AccelMap accel_map_; BrakeMap brake_map_; + SteerMap steer_map_; + // TODO(tanaka): consider accel/brake pid too + PIDController steer_pid_; bool ff_map_initialized_; double max_accel_cmd_; double max_brake_cmd_; @@ -99,7 +102,6 @@ class RawVehicleCommandConverterNode : public rclcpp::Node bool convert_accel_cmd_; //!< @brief use accel or not bool convert_brake_cmd_; //!< @brief use brake or not bool convert_steer_cmd_; //!< @brief use steer or not - SteerConverter steer_controller_; rclcpp::Time prev_time_steer_calculation_{0, 0, RCL_ROS_TIME}; double calculateAccelMap( diff --git a/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/pid.hpp b/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/pid.hpp index a2333e95453fa..c13de9b332fa3 100644 --- a/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/pid.hpp +++ b/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/pid.hpp @@ -24,6 +24,10 @@ namespace raw_vehicle_cmd_converter class PIDController { public: + double calculateFB( + const double target_value, const double dt, const double reset_trigger_value, + const double current_value, std::vector & pid_contributions, + std::vector & errors); double calculatePID( const double error, const double dt, const bool enable_integration, std::vector & pid_contributions, std::vector & errors, bool is_debugging); @@ -33,6 +37,8 @@ class PIDController const double max_ret_i, const double min_ret_i, const double max_ret_d, const double min_ret_d); void reset(); void setDecay(const double decay) { invalid_integration_decay_ = decay; } + void setInitialized() { is_initialized_ = true; } + bool getInitialized() { return is_initialized_; } private: // parameters @@ -52,6 +58,7 @@ class PIDController double prev_error_{0.0}; bool is_first_time_{true}; double invalid_integration_decay_{0.0}; + double is_initialized_{false}; }; } // namespace raw_vehicle_cmd_converter diff --git a/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/steer_converter.hpp b/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/steer_converter.hpp deleted file mode 100644 index 3574850ac712d..0000000000000 --- a/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/steer_converter.hpp +++ /dev/null @@ -1,65 +0,0 @@ -// Copyright 2021 Tier IV, Inc. All rights reserved. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef RAW_VEHICLE_CMD_CONVERTER__STEER_CONVERTER_HPP_ -#define RAW_VEHICLE_CMD_CONVERTER__STEER_CONVERTER_HPP_ - -#include "raw_vehicle_cmd_converter/csv_loader.hpp" -#include "raw_vehicle_cmd_converter/pid.hpp" - -#include - -#include -#include - -namespace raw_vehicle_cmd_converter -{ -class SteerConverter -{ -public: - bool setFFMap(const std::string & csv_path); - void setFBGains(const double kp, const double ki, const double kd); - bool setFBLimits( - const double max_ret, const double min_ret, const double max_ret_p, const double min_ret_p, - const double max_ret_i, const double min_ret_i, const double max_ret_d, const double min_ret_d); - double calcFFSteer( - const double target_steer_angle_velocity, const double current_steer_angle) const; - double calcFBSteer( - const double target_steer_angle, const double dt, const double current_velocity, - const double current_steer_angle, std::vector & pid_contributions, - std::vector & errors); - void setDecay(const double decay) { pid_.setDecay(decay); } - -private: - double kp_, ki_, kd_; - std::string vehicle_name_; - std::vector vel_index_; - std::vector output_index_; - std::vector> steer_map_; - PIDController pid_; - bool ff_map_initialized_{false}; - bool fb_gains_initialized_{false}; - bool fb_limits_initialized_{false}; - - rclcpp::Logger logger_{ - rclcpp::get_logger("raw_vehicle_cmd_converter").get_child("steer_converter")}; - - bool readSteerMapFromCSV( - const std::string & csv_path, std::string & vehicle_name, std::vector & vel_index, - std::vector & output_index, std::vector> & steer_map) const; - void calcFFMap(double steer_vel, double current_steer_val, double & output) const; -}; -} // namespace raw_vehicle_cmd_converter - -#endif // RAW_VEHICLE_CMD_CONVERTER__STEER_CONVERTER_HPP_ diff --git a/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/steer_map.hpp b/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/steer_map.hpp new file mode 100644 index 0000000000000..5bdfdef639d20 --- /dev/null +++ b/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/steer_map.hpp @@ -0,0 +1,43 @@ +// Copyright 2021 Tier IV, Inc. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef RAW_VEHICLE_CMD_CONVERTER__STEER_MAP_HPP_ +#define RAW_VEHICLE_CMD_CONVERTER__STEER_MAP_HPP_ + +#include "raw_vehicle_cmd_converter/csv_loader.hpp" +#include "raw_vehicle_cmd_converter/pid.hpp" + +#include + +#include +#include + +namespace raw_vehicle_cmd_converter +{ +class SteerMap +{ +public: + bool readSteerMapFromCSV(const std::string & csv_path); + void getSteer(const double steer_rate, const double steer, double & output) const; + +private: + std::string vehicle_name_; + std::vector steer_index_; + std::vector output_index_; + std::vector> steer_map_; + rclcpp::Logger logger_{rclcpp::get_logger("raw_vehicle_cmd_converter").get_child("steer_map")}; +}; +} // namespace raw_vehicle_cmd_converter + +#endif // RAW_VEHICLE_CMD_CONVERTER__STEER_MAP_HPP_ diff --git a/vehicle/raw_vehicle_cmd_converter/package.xml b/vehicle/raw_vehicle_cmd_converter/package.xml index cf1e55978bfb1..e2c85916d69b9 100644 --- a/vehicle/raw_vehicle_cmd_converter/package.xml +++ b/vehicle/raw_vehicle_cmd_converter/package.xml @@ -5,10 +5,13 @@ 0.1.0 The raw_vehicle_cmd_converter package Takamasa Horibe + Tanaka Taiki + Apache License 2.0 Makoto Kurihara Takamasa Horibe + Tanaka Taiki ament_cmake_auto diff --git a/vehicle/raw_vehicle_cmd_converter/src/accel_map.cpp b/vehicle/raw_vehicle_cmd_converter/src/accel_map.cpp index 74c7f52e22085..011830accc0e7 100644 --- a/vehicle/raw_vehicle_cmd_converter/src/accel_map.cpp +++ b/vehicle/raw_vehicle_cmd_converter/src/accel_map.cpp @@ -25,7 +25,7 @@ using namespace std::literals::chrono_literals; namespace raw_vehicle_cmd_converter { -bool AccelMap::readAccelMapFromCSV(std::string csv_path) +bool AccelMap::readAccelMapFromCSV(const std::string & csv_path) { CSVLoader csv(csv_path); std::vector> table; @@ -37,76 +37,49 @@ bool AccelMap::readAccelMapFromCSV(std::string csv_path) vehicle_name_ = table[0][0]; vel_index_ = CSVLoader::getRowIndex(table); throttle_index_ = CSVLoader::getColumnIndex(table); - - for (unsigned int i = 1; i < table.size(); i++) { - std::vector accs; - for (unsigned int j = 1; j < table[i].size(); j++) { - accs.push_back(std::stod(table[i][j])); - } - accel_map_.push_back(accs); - } - + accel_map_ = CSVLoader::getMap(table); return true; } -bool AccelMap::getThrottle(double acc, double vel, double & throttle) +bool AccelMap::getThrottle(const double acc, double vel, double & throttle) const { - std::vector accs_interpolated; - - if (vel < vel_index_.front() || vel_index_.back() < vel) { - RCLCPP_WARN_SKIPFIRST_THROTTLE( - logger_, clock_, 1000, "Exceeding the min:%f < current vel:%f < max:%f.", - vel_index_.front(), vel, vel_index_.back()); - vel = std::min(std::max(vel, vel_index_.front()), vel_index_.back()); - } + std::vector interpolated_acc_vec; + const double clamped_vel = CSVLoader::clampValue(vel, vel_index_, "throttle: vel"); // (throttle, vel, acc) map => (throttle, acc) map by fixing vel - for (std::vector accs : accel_map_) { - accs_interpolated.push_back(interpolation::lerp(vel_index_, accs, vel)); + for (std::vector accelerations : accel_map_) { + interpolated_acc_vec.push_back(interpolation::lerp(vel_index_, accelerations, clamped_vel)); } // calculate throttle // When the desired acceleration is smaller than the throttle area, return false => brake sequence // When the desired acceleration is greater than the throttle area, return max throttle - if (acc < accs_interpolated.front()) { + if (acc < interpolated_acc_vec.front()) { return false; - } else if (accs_interpolated.back() < acc) { + } else if (interpolated_acc_vec.back() < acc) { throttle = throttle_index_.back(); return true; } - throttle = interpolation::lerp(accs_interpolated, throttle_index_, acc); + throttle = interpolation::lerp(interpolated_acc_vec, throttle_index_, acc); return true; } -bool AccelMap::getAcceleration(double throttle, double vel, double & acc) +bool AccelMap::getAcceleration(const double throttle, const double vel, double & acc) const { - std::vector accs_interpolated; - - if (vel < vel_index_.front() || vel_index_.back() < vel) { - RCLCPP_WARN_SKIPFIRST_THROTTLE( - logger_, clock_, 1000, "Exceeding the min:%f < current vel:%f < max:%f.", - vel_index_.front(), vel, vel_index_.back()); - vel = std::min(std::max(vel, vel_index_.front()), vel_index_.back()); - } + std::vector interpolated_acc_vec; + const double clamped_vel = CSVLoader::clampValue(vel, vel_index_, "throttle: vel"); // (throttle, vel, acc) map => (throttle, acc) map by fixing vel - for (std::vector accs : accel_map_) { - accs_interpolated.push_back(interpolation::lerp(vel_index_, accs, vel)); + for (const auto & acc_vec : accel_map_) { + interpolated_acc_vec.push_back(interpolation::lerp(vel_index_, acc_vec, clamped_vel)); } // calculate throttle - // When the desired acceleration is smaller than the throttle area, return false => brake sequence - // When the desired acceleration is greater than the throttle area, return max throttle - const double max_throttle = throttle_index_.back(); - const double min_throttle = throttle_index_.front(); - if (throttle < min_throttle || max_throttle < throttle) { - RCLCPP_WARN_SKIPFIRST_THROTTLE( - logger_, clock_, 1000, "Input throttle: %f is out off range. use closest value.", throttle); - throttle = std::min(std::max(throttle, min_throttle), max_throttle); - } - - acc = interpolation::lerp(throttle_index_, accs_interpolated, throttle); + // When the desired acceleration is smaller than the throttle area, return min acc + // When the desired acceleration is greater than the throttle area, return max acc + const double clamped_throttle = CSVLoader::clampValue(throttle, throttle_index_, "throttle: acc"); + acc = interpolation::lerp(throttle_index_, interpolated_acc_vec, clamped_throttle); return true; } diff --git a/vehicle/raw_vehicle_cmd_converter/src/brake_map.cpp b/vehicle/raw_vehicle_cmd_converter/src/brake_map.cpp index 5aec005dd1a22..6f31b446614ce 100644 --- a/vehicle/raw_vehicle_cmd_converter/src/brake_map.cpp +++ b/vehicle/raw_vehicle_cmd_converter/src/brake_map.cpp @@ -22,7 +22,7 @@ namespace raw_vehicle_cmd_converter { -bool BrakeMap::readBrakeMapFromCSV(std::string csv_path) +bool BrakeMap::readBrakeMapFromCSV(const std::string & csv_path) { CSVLoader csv(csv_path); std::vector> table; @@ -34,87 +34,60 @@ bool BrakeMap::readBrakeMapFromCSV(std::string csv_path) vehicle_name_ = table[0][0]; vel_index_ = CSVLoader::getRowIndex(table); brake_index_ = CSVLoader::getColumnIndex(table); - - for (unsigned int i = 1; i < table.size(); i++) { - std::vector accs; - for (unsigned int j = 1; j < table[i].size(); j++) { - accs.push_back(std::stod(table[i][j])); - } - brake_map_.push_back(accs); - } - + brake_map_ = CSVLoader::getMap(table); brake_index_rev_ = brake_index_; std::reverse(std::begin(brake_index_rev_), std::end(brake_index_rev_)); return true; } -bool BrakeMap::getBrake(double acc, double vel, double & brake) +bool BrakeMap::getBrake(const double acc, const double vel, double & brake) { - std::vector accs_interpolated; + std::vector interpolated_acc_vec; + const double clamped_vel = CSVLoader::clampValue(vel, vel_index_, "brake: vel"); - if (vel < vel_index_.front() || vel_index_.back() < vel) { - RCLCPP_WARN_SKIPFIRST_THROTTLE( - logger_, clock_, 1000, "Exceeding the min:%f < current vel:%f < max:%f.", - vel_index_.front(), vel, vel_index_.back()); - vel = std::min(std::max(vel, vel_index_.front()), vel_index_.back()); - } // (throttle, vel, acc) map => (throttle, acc) map by fixing vel - for (std::vector accs : brake_map_) { - accs_interpolated.push_back(interpolation::lerp(vel_index_, accs, vel)); + for (std::vector accelerations : brake_map_) { + interpolated_acc_vec.push_back(interpolation::lerp(vel_index_, accelerations, clamped_vel)); } // calculate brake // When the desired acceleration is smaller than the brake area, return max brake on the map // When the desired acceleration is greater than the brake area, return min brake on the map - if (acc < accs_interpolated.back()) { + if (acc < interpolated_acc_vec.back()) { RCLCPP_WARN_SKIPFIRST_THROTTLE( logger_, clock_, 1000, "Exceeding the acc range. Desired acc: %f < min acc on map: %f. return max " "value.", - acc, accs_interpolated.back()); + acc, interpolated_acc_vec.back()); brake = brake_index_.back(); return true; - } else if (accs_interpolated.front() < acc) { + } else if (interpolated_acc_vec.front() < acc) { brake = brake_index_.front(); return true; } - std::reverse(std::begin(accs_interpolated), std::end(accs_interpolated)); - brake = interpolation::lerp(accs_interpolated, brake_index_rev_, acc); + std::reverse(std::begin(interpolated_acc_vec), std::end(interpolated_acc_vec)); + brake = interpolation::lerp(interpolated_acc_vec, brake_index_rev_, acc); return true; } -bool BrakeMap::getAcceleration(double brake, double vel, double & acc) +bool BrakeMap::getAcceleration(const double brake, const double vel, double & acc) const { - std::vector accs_interpolated; - - if (vel < vel_index_.front() || vel_index_.back() < vel) { - RCLCPP_WARN_SKIPFIRST_THROTTLE( - logger_, clock_, 1000, - "Exceeding the vel range. Current vel: %f < min or max < %f vel on map: %f.", vel, - vel_index_.front(), vel_index_.back()); - vel = std::min(std::max(vel, vel_index_.front()), vel_index_.back()); - } + std::vector interpolated_acc_vec; + const double clamped_vel = CSVLoader::clampValue(vel, vel_index_, "brake: vel"); // (throttle, vel, acc) map => (throttle, acc) map by fixing vel - for (std::vector accs : brake_map_) { - accs_interpolated.push_back(interpolation::lerp(vel_index_, accs, vel)); + for (const auto & acc_vec : brake_map_) { + interpolated_acc_vec.push_back(interpolation::lerp(vel_index_, acc_vec, clamped_vel)); } // calculate brake - // When the desired acceleration is smaller than the brake area, return max brake on the map - // When the desired acceleration is greater than the brake area, return min brake on the map - const double max_brake = brake_index_.back(); - const double min_brake = brake_index_.front(); - if (brake < min_brake || max_brake < brake) { - RCLCPP_WARN_SKIPFIRST_THROTTLE( - logger_, clock_, 1000, "Input brake: %f is out off range. use closest value.", brake); - brake = std::min(std::max(brake, min_brake), max_brake); - } - - acc = interpolation::lerp(brake_index_, accs_interpolated, brake); + // When the desired acceleration is smaller than the brake area, return min acc + // When the desired acceleration is greater than the brake area, return min acc + const double clamped_brake = CSVLoader::clampValue(brake, brake_index_, "brake: acc"); + acc = interpolation::lerp(brake_index_, interpolated_acc_vec, clamped_brake); return true; } diff --git a/vehicle/raw_vehicle_cmd_converter/src/csv_loader.cpp b/vehicle/raw_vehicle_cmd_converter/src/csv_loader.cpp index d1f5d4877dfa4..30592c23e0f25 100644 --- a/vehicle/raw_vehicle_cmd_converter/src/csv_loader.cpp +++ b/vehicle/raw_vehicle_cmd_converter/src/csv_loader.cpp @@ -19,7 +19,7 @@ namespace raw_vehicle_cmd_converter { -CSVLoader::CSVLoader(std::string csv_path) { csv_path_ = csv_path; } +CSVLoader::CSVLoader(const std::string & csv_path) { csv_path_ = csv_path; } bool CSVLoader::readCSV(Table & result, const char delim) { @@ -56,7 +56,7 @@ bool CSVLoader::validateData(const Table & table, const std::string & csv_path) << std::endl; return false; } - for (unsigned int i = 1; i < table.size(); i++) { + for (size_t i = 1; i < table.size(); i++) { if (table[0].size() != table[i].size()) { std::cerr << "Cannot read " << csv_path.c_str() << ". Each row should have a same number of columns" << std::endl; @@ -66,10 +66,23 @@ bool CSVLoader::validateData(const Table & table, const std::string & csv_path) return true; } +Map CSVLoader::getMap(const Table & table) +{ + Map map = {}; + for (size_t i = 1; i < table.size(); i++) { + std::vector accelerations; + for (size_t j = 1; j < table[i].size(); j++) { + accelerations.push_back(std::stod(table[i][j])); + } + map.push_back(accelerations); + } + return map; +} + std::vector CSVLoader::getRowIndex(const Table & table) { std::vector index = {}; - for (unsigned int i = 1; i < table[0].size(); i++) { + for (size_t i = 1; i < table[0].size(); i++) { index.push_back(std::stod(table[0][i])); } return index; @@ -78,10 +91,23 @@ std::vector CSVLoader::getRowIndex(const Table & table) std::vector CSVLoader::getColumnIndex(const Table & table) { std::vector index = {}; - for (unsigned int i = 1; i < table.size(); i++) { + for (size_t i = 1; i < table.size(); i++) { index.push_back(std::stod(table[i][0])); } return index; } +double CSVLoader::clampValue( + const double val, const std::vector & ranges, const std::string & name) +{ + const double max_value = ranges.back(); + const double min_value = ranges.front(); + if (val < min_value || max_value < val) { + std::cerr << "Input" << name << ": " << val << " is out off range. use closest value." + << std::endl; + return std::min(std::max(val, min_value), max_value); + } + return val; +} + } // namespace raw_vehicle_cmd_converter diff --git a/vehicle/raw_vehicle_cmd_converter/src/node.cpp b/vehicle/raw_vehicle_cmd_converter/src/node.cpp index 20799155b86ad..46e3c39ee662c 100644 --- a/vehicle/raw_vehicle_cmd_converter/src/node.cpp +++ b/vehicle/raw_vehicle_cmd_converter/src/node.cpp @@ -40,48 +40,40 @@ RawVehicleCommandConverterNode::RawVehicleCommandConverterNode( // for steering steer controller use_steer_ff_ = declare_parameter("use_steer_ff", true); use_steer_fb_ = declare_parameter("use_steer_fb", true); - const auto kp_steer{declare_parameter("steer_pid.kp", 150.0)}; - const auto ki_steer{declare_parameter("steer_pid.ki", 15.0)}; - const auto kd_steer{declare_parameter("steer_pid.kd", 0.0)}; - const auto max_ret_steer{declare_parameter("steer_pid.max", 8.0)}; - const auto min_ret_steer{declare_parameter("steer_pid.min", -8.0)}; - const auto max_ret_p_steer{declare_parameter("steer_pid.max_p", 8.0)}; - const auto min_ret_p_steer{declare_parameter("steer_pid.min_p", -8.0)}; - const auto max_ret_i_steer{declare_parameter("steer_pid.max_i", 8.0)}; - const auto min_ret_i_steer{declare_parameter("steer_pid.min_i", -8.0)}; - const auto max_ret_d_steer{declare_parameter("steer_pid.max_d", 0.0)}; - const auto min_ret_d_steer{declare_parameter("steer_pid.min_d", 0.0)}; - const auto invalid_integration_decay{ - declare_parameter("steer_pid.invalid_integration_decay", 0.97)}; ff_map_initialized_ = true; if (convert_accel_cmd_) { if (!accel_map_.readAccelMapFromCSV(csv_path_accel_map)) { - RCLCPP_ERROR( - get_logger(), "Cannot read accelmap. csv path = %s. stop calculation.", - csv_path_accel_map.c_str()); ff_map_initialized_ = false; } } if (convert_brake_cmd_) { if (!brake_map_.readBrakeMapFromCSV(csv_path_brake_map)) { - RCLCPP_ERROR( - get_logger(), "Cannot read brakemap. csv path = %s. stop calculation.", - csv_path_brake_map.c_str()); ff_map_initialized_ = false; } } if (convert_steer_cmd_) { - steer_controller_.setDecay(invalid_integration_decay); - if (!steer_controller_.setFFMap(csv_path_steer_map)) { - RCLCPP_ERROR( - get_logger(), "Cannot read steer map. csv path = %s. stop calculation.", - csv_path_steer_map.c_str()); + if (!steer_map_.readSteerMapFromCSV(csv_path_steer_map)) { ff_map_initialized_ = false; } - steer_controller_.setFBGains(kp_steer, ki_steer, kd_steer); - steer_controller_.setFBLimits( + const auto kp_steer{declare_parameter("steer_pid.kp", 150.0)}; + const auto ki_steer{declare_parameter("steer_pid.ki", 15.0)}; + const auto kd_steer{declare_parameter("steer_pid.kd", 0.0)}; + const auto max_ret_steer{declare_parameter("steer_pid.max", 8.0)}; + const auto min_ret_steer{declare_parameter("steer_pid.min", -8.0)}; + const auto max_ret_p_steer{declare_parameter("steer_pid.max_p", 8.0)}; + const auto min_ret_p_steer{declare_parameter("steer_pid.min_p", -8.0)}; + const auto max_ret_i_steer{declare_parameter("steer_pid.max_i", 8.0)}; + const auto min_ret_i_steer{declare_parameter("steer_pid.min_i", -8.0)}; + const auto max_ret_d_steer{declare_parameter("steer_pid.max_d", 0.0)}; + const auto min_ret_d_steer{declare_parameter("steer_pid.min_d", 0.0)}; + const auto invalid_integration_decay{ + declare_parameter("steer_pid.invalid_integration_decay", 0.97)}; + steer_pid_.setDecay(invalid_integration_decay); + steer_pid_.setGains(kp_steer, ki_steer, kd_steer); + steer_pid_.setLimits( max_ret_steer, min_ret_steer, max_ret_p_steer, min_ret_p_steer, max_ret_i_steer, min_ret_i_steer, max_ret_d_steer, min_ret_d_steer); + steer_pid_.setInitialized(); } pub_actuation_cmd_ = create_publisher("~/output/actuation_cmd", 1); sub_control_cmd_ = create_subscription( @@ -161,12 +153,20 @@ double RawVehicleCommandConverterNode::calculateSteer( prev_time_steer_calculation_ = current_time; // feed-forward if (use_steer_ff_) { - ff_value = steer_controller_.calcFFSteer(steer_rate, *current_steer_ptr_); + if (!ff_map_initialized_) { + RCLCPP_WARN_EXPRESSION(get_logger(), is_debugging_, "FF map is not initialized!"); + } else { + steer_map_.getSteer(steer_rate, *current_steer_ptr_, ff_value); + } } // feedback if (use_steer_fb_) { - fb_value = steer_controller_.calcFBSteer( - steering, dt, vel, *current_steer_ptr_, pid_contributions, pid_errors); + if (!steer_pid_.getInitialized()) { + RCLCPP_WARN_EXPRESSION(get_logger(), is_debugging_, "FF map is not initialized!"); + } else { + fb_value = steer_pid_.calculateFB( + steering, dt, vel, *current_steer_ptr_, pid_contributions, pid_errors); + } } steering_output = ff_value + fb_value; // for steer debugging diff --git a/vehicle/raw_vehicle_cmd_converter/src/pid.cpp b/vehicle/raw_vehicle_cmd_converter/src/pid.cpp index e2a2054fe6944..216382be3dc81 100644 --- a/vehicle/raw_vehicle_cmd_converter/src/pid.cpp +++ b/vehicle/raw_vehicle_cmd_converter/src/pid.cpp @@ -19,6 +19,16 @@ namespace raw_vehicle_cmd_converter { + +double PIDController::calculateFB( + const double target_value, const double dt, const double reset_trigger_value, + const double current_value, std::vector & pid_contributions, std::vector & errors) +{ + const double error = target_value - current_value; + const bool enable_integration = (std::abs(reset_trigger_value) < 0.01) ? false : true; + return calculatePID(error, dt, enable_integration, pid_contributions, errors, false); +} + double PIDController::calculatePID( const double error, const double dt, const bool enable_integration, std::vector & pid_contributions, std::vector & errors, bool is_debugging) diff --git a/vehicle/raw_vehicle_cmd_converter/src/steer_converter.cpp b/vehicle/raw_vehicle_cmd_converter/src/steer_converter.cpp deleted file mode 100644 index 453c8555185eb..0000000000000 --- a/vehicle/raw_vehicle_cmd_converter/src/steer_converter.cpp +++ /dev/null @@ -1,139 +0,0 @@ -// Copyright 2021 Tier IV, Inc. All rights reserved. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "raw_vehicle_cmd_converter/steer_converter.hpp" - -#include "interpolation/linear_interpolation.hpp" - -#include -#include - -namespace raw_vehicle_cmd_converter -{ -bool SteerConverter::setFFMap(const std::string & csv_path) -{ - if (!readSteerMapFromCSV(csv_path, vehicle_name_, vel_index_, output_index_, steer_map_)) { - return false; - } - ff_map_initialized_ = true; - return true; -} - -void SteerConverter::setFBGains(const double kp, const double ki, const double kd) -{ - pid_.setGains(kp, ki, kd); - fb_gains_initialized_ = true; -} - -bool SteerConverter::setFBLimits( - const double max_ret, const double min_ret, const double max_ret_p, const double min_ret_p, - const double max_ret_i, const double min_ret_i, const double max_ret_d, const double min_ret_d) -{ - pid_.setLimits( - max_ret, min_ret, max_ret_p, min_ret_p, max_ret_i, min_ret_i, max_ret_d, min_ret_d); - fb_limits_initialized_ = true; - return true; -} - -double SteerConverter::calcFFSteer( - const double target_steer_angle_velocity, const double current_steer_angle) const -{ - rclcpp::Clock clock{RCL_ROS_TIME}; - - if (!ff_map_initialized_) { - RCLCPP_WARN_THROTTLE(logger_, clock, 3000, "FF map is not initialized!"); - return 0; - } - - double ff_value = 0; - calcFFMap(target_steer_angle_velocity, current_steer_angle, ff_value); - return ff_value; -} - -double SteerConverter::calcFBSteer( - const double target_steer_angle, const double dt, const double current_velocity, - const double current_steer_angle, std::vector & pid_contributions, - std::vector & errors) -{ - rclcpp::Clock clock{RCL_ROS_TIME}; - - if (!fb_gains_initialized_ || !fb_limits_initialized_) { - RCLCPP_WARN_THROTTLE(logger_, clock, 3000, "FB params are not initialized!"); - return 0; - } - - double fb_value = 0; - const double error_steer_angle = target_steer_angle - current_steer_angle; - bool enable_integration = true; - if (std::abs(current_velocity) < 0.01) { - enable_integration = false; - } - fb_value = - pid_.calculatePID(error_steer_angle, dt, enable_integration, pid_contributions, errors, false); - return fb_value; -} - -bool SteerConverter::readSteerMapFromCSV( - const std::string & csv_path, std::string & vehicle_name, std::vector & vel_index, - std::vector & output_index, std::vector> & steer_map) const -{ - rclcpp::Clock clock{RCL_ROS_TIME}; - - CSVLoader csv(csv_path); - std::vector> table; - - if (!csv.readCSV(table)) { - return false; - } - - vehicle_name = table[0][0]; - vel_index = CSVLoader::getRowIndex(table); - output_index = CSVLoader::getColumnIndex(table); - - for (unsigned int i = 1; i < table.size(); ++i) { - std::vector steer_angle_velocities; - for (unsigned int j = 1; j < table[i].size(); ++j) { - steer_angle_velocities.push_back(std::stod(table[i][j])); - } - steer_map.push_back(steer_angle_velocities); - } - - return true; -} - -void SteerConverter::calcFFMap(double steer_vel, double vehicle_vel, double & output) const -{ - rclcpp::Clock clock{RCL_ROS_TIME}; - - std::vector steer_angle_velocities_interp; - - if (vehicle_vel < vel_index_.front() || vel_index_.back() < vehicle_vel) { - RCLCPP_WARN_SKIPFIRST_THROTTLE( - logger_, clock, 1000, "Exceeding the min:%f < current vel:%f < max:%f.", vel_index_.front(), - vehicle_vel, vel_index_.back()); - vehicle_vel = std::min(std::max(vehicle_vel, vel_index_.front()), vel_index_.back()); - } - - for (std::vector steer_angle_velocities : steer_map_) { - steer_angle_velocities_interp.push_back( - interpolation::lerp(vel_index_, steer_angle_velocities, vehicle_vel)); - } - if (steer_vel < steer_angle_velocities_interp.front()) { - steer_vel = steer_angle_velocities_interp.front(); - } else if (steer_angle_velocities_interp.back() < steer_vel) { - steer_vel = steer_angle_velocities_interp.back(); - } - output = interpolation::lerp(steer_angle_velocities_interp, output_index_, steer_vel); -} -} // namespace raw_vehicle_cmd_converter diff --git a/vehicle/raw_vehicle_cmd_converter/src/steer_map.cpp b/vehicle/raw_vehicle_cmd_converter/src/steer_map.cpp new file mode 100644 index 0000000000000..1c78e3c6ee17c --- /dev/null +++ b/vehicle/raw_vehicle_cmd_converter/src/steer_map.cpp @@ -0,0 +1,53 @@ +// Copyright 2021 Tier IV, Inc. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "raw_vehicle_cmd_converter/steer_map.hpp" + +#include "interpolation/linear_interpolation.hpp" + +#include +#include + +namespace raw_vehicle_cmd_converter +{ + +bool SteerMap::readSteerMapFromCSV(const std::string & csv_path) +{ + CSVLoader csv(csv_path); + std::vector> table; + + if (!csv.readCSV(table)) { + return false; + } + + vehicle_name_ = table[0][0]; + steer_index_ = CSVLoader::getRowIndex(table); + output_index_ = CSVLoader::getColumnIndex(table); + steer_map_ = CSVLoader::getMap(table); + return true; +} + +void SteerMap::getSteer(const double steer_rate, const double steer, double & output) const +{ + const double clamped_steer = CSVLoader::clampValue(steer, steer_index_, "steer: steer"); + std::vector steer_rate_interp = {}; + for (const auto & steer_rate_vec : steer_map_) { + steer_rate_interp.push_back(interpolation::lerp(steer_index_, steer_rate_vec, clamped_steer)); + } + + const double clamped_steer_rate = + CSVLoader::clampValue(steer_rate, steer_rate_interp, "steer: steer_rate"); + output = interpolation::lerp(steer_rate_interp, output_index_, clamped_steer_rate); +} +} // namespace raw_vehicle_cmd_converter diff --git a/vehicle/raw_vehicle_cmd_converter/test/test_raw_vehicle_cmd_converter.cpp b/vehicle/raw_vehicle_cmd_converter/test/test_raw_vehicle_cmd_converter.cpp index a8e5b2c0b47a7..98f8e37f98510 100644 --- a/vehicle/raw_vehicle_cmd_converter/test/test_raw_vehicle_cmd_converter.cpp +++ b/vehicle/raw_vehicle_cmd_converter/test/test_raw_vehicle_cmd_converter.cpp @@ -16,7 +16,7 @@ #include "gtest/gtest.h" #include "raw_vehicle_cmd_converter/accel_map.hpp" #include "raw_vehicle_cmd_converter/brake_map.hpp" -#include "raw_vehicle_cmd_converter/steer_converter.hpp" +#include "raw_vehicle_cmd_converter/steer_map.hpp" #include @@ -48,7 +48,7 @@ using raw_vehicle_cmd_converter::AccelMap; using raw_vehicle_cmd_converter::BrakeMap; -using raw_vehicle_cmd_converter::SteerConverter; +using raw_vehicle_cmd_converter::SteerMap; // may throw PackageNotFoundError exception for invalid package const auto map_path = @@ -64,16 +64,16 @@ bool loadBrakeMapData(BrakeMap & brake_map) return brake_map.readBrakeMapFromCSV(map_path + "test_brake_map.csv"); } -bool loadSteerMapData(SteerConverter & steer_map) +bool loadSteerMapData(SteerMap & steer_map) { - return steer_map.setFFMap(map_path + "test_steer_map.csv"); + return steer_map.readSteerMapFromCSV(map_path + "test_steer_map.csv"); } TEST(ConverterTests, LoadValidPath) { AccelMap accel_map; BrakeMap brake_map; - SteerConverter steer_map; + SteerMap steer_map; // for valid path EXPECT_TRUE(loadAccelMapData(accel_map)); @@ -83,7 +83,7 @@ TEST(ConverterTests, LoadValidPath) // for invalid path EXPECT_FALSE(accel_map.readAccelMapFromCSV("invalid.csv")); EXPECT_FALSE(brake_map.readBrakeMapFromCSV("invalid.csv")); - EXPECT_FALSE(steer_map.setFFMap("invalid.csv")); + EXPECT_FALSE(steer_map.readSteerMapFromCSV("invalid.csv")); // for invalid maps EXPECT_FALSE(accel_map.readAccelMapFromCSV(map_path + "test_1col_map.csv")); @@ -115,6 +115,24 @@ TEST(ConverterTests, AccelMapCalculation) // case for interpolation EXPECT_DOUBLE_EQ(calcThrottle(9.0, 5.0), 0.25); + + const auto calcAcceleration = [&](double throttle, double vel) { + double output; + accel_map.getAcceleration(throttle, vel, output); + return output; + }; + + // case for min vel + EXPECT_DOUBLE_EQ(calcAcceleration(1.0, 0.0), 3.0); + + // case for min throttle + EXPECT_DOUBLE_EQ(calcAcceleration(0.0, 25.0), 21.0); + + // case for direct access + EXPECT_DOUBLE_EQ(calcAcceleration(0.5, 10.0), 22.0); + + // case for interpolation + EXPECT_DOUBLE_EQ(calcAcceleration(0.75, 5.0), 15.0); } TEST(ConverterTests, BrakeMapCalculation) @@ -142,14 +160,34 @@ TEST(ConverterTests, BrakeMapCalculation) // case for interpolation EXPECT_DOUBLE_EQ(calcBrake(-9.0, 5.0), 0.25); + + const auto calcAcceleration = [&](double brake, double vel) { + double output; + brake_map.getAcceleration(brake, vel, output); + return output; + }; + + // case for min vel + EXPECT_DOUBLE_EQ(calcAcceleration(1.0, 0.0), -3.0); + + // case for min throttle + EXPECT_DOUBLE_EQ(calcAcceleration(0.0, 25.0), -21.0); + + // case for direct access + EXPECT_DOUBLE_EQ(calcAcceleration(0.5, 10.0), -22.0); + + // case for interpolation + EXPECT_DOUBLE_EQ(calcAcceleration(0.75, 5.0), -15.0); } TEST(ConverterTests, SteerMapCalculation) { - SteerConverter steer_map; + SteerMap steer_map; loadSteerMapData(steer_map); const auto calcSteer = [&](double steer_vel, double steer) { - return steer_map.calcFFSteer(steer_vel, steer); + double output; + steer_map.getSteer(steer_vel, steer, output); + return output; }; // case for min steer