diff --git a/common/msgs/autoware_control_msgs/CMakeLists.txt b/common/msgs/autoware_control_msgs/CMakeLists.txt index 8d00cf1500..0474b72006 100644 --- a/common/msgs/autoware_control_msgs/CMakeLists.txt +++ b/common/msgs/autoware_control_msgs/CMakeLists.txt @@ -13,6 +13,8 @@ find_package(ament_cmake REQUIRED) find_package(rosidl_default_generators REQUIRED) rosidl_generate_interfaces(${PROJECT_NAME} + "msg/EmergencyMode.msg" + "msg/EngageMode.msg" "msg/GateMode.msg" "msg/ControlCommand.msg" "msg/ControlCommandStamped.msg" diff --git a/common/msgs/autoware_control_msgs/msg/EmergencyMode.msg b/common/msgs/autoware_control_msgs/msg/EmergencyMode.msg new file mode 100644 index 0000000000..c4be53ade4 --- /dev/null +++ b/common/msgs/autoware_control_msgs/msg/EmergencyMode.msg @@ -0,0 +1 @@ +bool is_emergency diff --git a/common/msgs/autoware_control_msgs/msg/EngageMode.msg b/common/msgs/autoware_control_msgs/msg/EngageMode.msg new file mode 100644 index 0000000000..0f7039ac4f --- /dev/null +++ b/common/msgs/autoware_control_msgs/msg/EngageMode.msg @@ -0,0 +1 @@ +bool is_engaged diff --git a/control/vehicle_cmd_gate/CMakeLists.txt b/control/vehicle_cmd_gate/CMakeLists.txt index 74daed79be..10b38367d6 100644 --- a/control/vehicle_cmd_gate/CMakeLists.txt +++ b/control/vehicle_cmd_gate/CMakeLists.txt @@ -1,48 +1,45 @@ -cmake_minimum_required(VERSION 3.0.2) +cmake_minimum_required(VERSION 3.5) project(vehicle_cmd_gate) -add_compile_options(-std=c++14) - -find_package( - catkin REQUIRED COMPONENTS - autoware_control_msgs - autoware_vehicle_msgs - geometry_msgs - roscpp - rostest - rosunit - roslint - std_msgs -) +### Compile options +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) + add_compile_options(-Wno-unused-parameter) +endif() -catkin_package( - INCLUDE_DIRS include - CATKIN_DEPENDS - autoware_control_msgs - autoware_vehicle_msgs - geometry_msgs - std_msgs -) +### Dependencies +find_package(ament_cmake REQUIRED) +find_package(autoware_control_msgs REQUIRED) +find_package(autoware_vehicle_msgs REQUIRED) +find_package(rclcpp REQUIRED) -include_directories( - include - ${catkin_INCLUDE_DIRS} -) +# Add path of include dir +include_directories(include) +# Generate exe file add_executable(vehicle_cmd_gate src/vehicle_cmd_gate_node.cpp src/vehicle_cmd_gate.cpp src/vehicle_cmd_filter.cpp) -target_link_libraries(vehicle_cmd_gate ${catkin_LIBRARIES}) -add_dependencies(vehicle_cmd_gate ${catkin_EXPORTED_TARGETS}) + +set(VEHICLE_CMD_GATE_DEPENDENCIES + autoware_control_msgs + autoware_vehicle_msgs + rclcpp +) +ament_target_dependencies(vehicle_cmd_gate ${VEHICLE_CMD_GATE_DEPENDENCIES}) +ament_export_dependencies(${VEHICLE_CMD_GATE_DEPENDENCIES}) install( TARGETS vehicle_cmd_gate - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} + DESTINATION lib/${PROJECT_NAME} ) install( DIRECTORY launch config - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} + DESTINATION share/${PROJECT_NAME} ) + +ament_package() diff --git a/control/vehicle_cmd_gate/COLCON_IGNORE b/control/vehicle_cmd_gate/COLCON_IGNORE deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/control/vehicle_cmd_gate/config/vehicle_cmd_gate.param.yaml b/control/vehicle_cmd_gate/config/vehicle_cmd_gate.param.yaml new file mode 100644 index 0000000000..6f5c6dcf9d --- /dev/null +++ b/control/vehicle_cmd_gate/config/vehicle_cmd_gate.param.yaml @@ -0,0 +1,9 @@ +/**: + ros__parameters: + update_rate: 10.0 + use_emergency_handling: false + vel_lim: 25.0 + lon_acc_lim: 5.0 + lon_jerk_lim: 5.0 + lat_acc_lim: 5.0 + lat_jerk_lim: 5.0 diff --git a/control/vehicle_cmd_gate/config/vehicle_cmd_gate.yaml b/control/vehicle_cmd_gate/config/vehicle_cmd_gate.yaml deleted file mode 100644 index 397e10d425..0000000000 --- a/control/vehicle_cmd_gate/config/vehicle_cmd_gate.yaml +++ /dev/null @@ -1,8 +0,0 @@ -update_rate: 10 -use_emergency_handling: false - -vel_lim: 25.0 -lon_acc_lim: 5.0 -lon_jerk_lim: 5.0 -lat_acc_lim: 5.0 -lat_jerk_lim: 5.0 diff --git a/control/vehicle_cmd_gate/include/vehicle_cmd_gate/vehicle_cmd_filter.h b/control/vehicle_cmd_gate/include/vehicle_cmd_gate/vehicle_cmd_filter.h index 3b5c02eb00..d2b131888e 100644 --- a/control/vehicle_cmd_gate/include/vehicle_cmd_gate/vehicle_cmd_filter.h +++ b/control/vehicle_cmd_gate/include/vehicle_cmd_gate/vehicle_cmd_filter.h @@ -17,10 +17,7 @@ #ifndef VEHICLE_CMD_GATE_VEHICLE_CMD_FILTER_H #define VEHICLE_CMD_GATE_VEHICLE_CMD_FILTER_H -#include -#include - -#include "autoware_control_msgs/ControlCommandStamped.h" +#include class VehicleCmdFilter { @@ -34,13 +31,15 @@ class VehicleCmdFilter void setLonJerkLim(double v) { lon_jerk_lim_ = v; }; void setLatAccLim(double v) { lat_acc_lim_ = v; }; void setLatJerkLim(double v) { lat_jerk_lim_ = v; }; - void setPrevCmd(const autoware_control_msgs::ControlCommand & v) { prev_cmd_ = v; }; + void setPrevCmd(const autoware_control_msgs::msg::ControlCommand & v) { prev_cmd_ = v; }; - void limitLongitudinalWithVel(autoware_control_msgs::ControlCommand & input); - void limitLongitudinalWithAcc(const double dt, autoware_control_msgs::ControlCommand & input); - void limitLongitudinalWithJerk(const double dt, autoware_control_msgs::ControlCommand & input); - void limitLateralWithLatAcc(const double dt, autoware_control_msgs::ControlCommand & input); - void limitLateralWithLatJerk(const double dt, autoware_control_msgs::ControlCommand & input); + void limitLongitudinalWithVel(autoware_control_msgs::msg::ControlCommand & input); + void limitLongitudinalWithAcc( + const double dt, autoware_control_msgs::msg::ControlCommand & input); + void limitLongitudinalWithJerk( + const double dt, autoware_control_msgs::msg::ControlCommand & input); + void limitLateralWithLatAcc(const double dt, autoware_control_msgs::msg::ControlCommand & input); + void limitLateralWithLatJerk(const double dt, autoware_control_msgs::msg::ControlCommand & input); private: double wheel_base_; @@ -49,9 +48,9 @@ class VehicleCmdFilter double lon_jerk_lim_; double lat_acc_lim_; double lat_jerk_lim_; - autoware_control_msgs::ControlCommand prev_cmd_; + autoware_control_msgs::msg::ControlCommand prev_cmd_; - double calcLatAcc(const autoware_control_msgs::ControlCommand & cmd); + double calcLatAcc(const autoware_control_msgs::msg::ControlCommand & cmd); double limitDiff(const double curr, const double prev, const double diff_lim); }; diff --git a/control/vehicle_cmd_gate/include/vehicle_cmd_gate/vehicle_cmd_gate.h b/control/vehicle_cmd_gate/include/vehicle_cmd_gate/vehicle_cmd_gate.h index 0dd86e94ef..9e885d028b 100644 --- a/control/vehicle_cmd_gate/include/vehicle_cmd_gate/vehicle_cmd_gate.h +++ b/control/vehicle_cmd_gate/include/vehicle_cmd_gate/vehicle_cmd_gate.h @@ -19,100 +19,104 @@ #include -#include -#include +#include -#include "autoware_control_msgs/ControlCommandStamped.h" -#include "autoware_control_msgs/GateMode.h" -#include "autoware_vehicle_msgs/ShiftStamped.h" -#include "autoware_vehicle_msgs/TurnSignal.h" -#include "autoware_vehicle_msgs/VehicleCommand.h" -#include "vehicle_cmd_gate/vehicle_cmd_filter.h" +#include +#include +#include +#include +#include +#include +#include + +#include struct Commands { - autoware_control_msgs::ControlCommandStamped control; - autoware_vehicle_msgs::TurnSignal turn_signal; - autoware_vehicle_msgs::ShiftStamped shift; + autoware_control_msgs::msg::ControlCommandStamped control; + autoware_vehicle_msgs::msg::TurnSignal turn_signal; + autoware_vehicle_msgs::msg::ShiftStamped shift; }; -class VehicleCmdGate +class VehicleCmdGate : public rclcpp::Node { public: VehicleCmdGate(); private: - // NodeHandle - ros::NodeHandle nh_; - ros::NodeHandle pnh_; - // Publisher - ros::Publisher vehicle_cmd_pub_; - ros::Publisher control_cmd_pub_; - ros::Publisher shift_cmd_pub_; - ros::Publisher turn_signal_cmd_pub_; - ros::Publisher gate_mode_pub_; + rclcpp::Publisher::SharedPtr vehicle_cmd_pub_; + rclcpp::Publisher::SharedPtr control_cmd_pub_; + rclcpp::Publisher::SharedPtr shift_cmd_pub_; + rclcpp::Publisher::SharedPtr turn_signal_cmd_pub_; + rclcpp::Publisher::SharedPtr gate_mode_pub_; - // Subscriber - ros::Subscriber engage_sub_; - ros::Subscriber emergency_sub_; - ros::Subscriber gate_mode_sub_; + // Subscription + rclcpp::Subscription::SharedPtr engage_sub_; + rclcpp::Subscription::SharedPtr emergency_sub_; + rclcpp::Subscription::SharedPtr gate_mode_sub_; - void onGateMode(const autoware_control_msgs::GateMode::ConstPtr & msg); - void onEngage(const std_msgs::Bool::ConstPtr msg); - void onEmergency(const std_msgs::Bool::ConstPtr msg); + void onGateMode(autoware_control_msgs::msg::GateMode::ConstSharedPtr msg); + void onEngage(autoware_control_msgs::msg::EngageMode::ConstSharedPtr msg); + void onEmergency(autoware_control_msgs::msg::EmergencyMode::ConstSharedPtr msg); bool is_engaged_; bool is_emergency_; - autoware_control_msgs::GateMode current_gate_mode_; + autoware_control_msgs::msg::GateMode current_gate_mode_; - // Subscriber for auto + // Subscription for auto Commands auto_commands_; - ros::Subscriber auto_control_cmd_sub_; - ros::Subscriber auto_turn_signal_cmd_sub_; - ros::Subscriber auto_shift_cmd_sub_; - void onAutoCtrlCmd(const autoware_control_msgs::ControlCommandStamped::ConstPtr & msg); - void onAutoTurnSignalCmd(const autoware_vehicle_msgs::TurnSignal::ConstPtr & msg); - void onAutoShiftCmd(const autoware_vehicle_msgs::ShiftStamped::ConstPtr & msg); - - // Subscriber for remote + rclcpp::Subscription::SharedPtr + auto_control_cmd_sub_; + rclcpp::Subscription::SharedPtr auto_turn_signal_cmd_sub_; + rclcpp::Subscription::SharedPtr auto_shift_cmd_sub_; + void onAutoCtrlCmd(autoware_control_msgs::msg::ControlCommandStamped::ConstSharedPtr msg); + void onAutoTurnSignalCmd(autoware_vehicle_msgs::msg::TurnSignal::ConstSharedPtr msg); + void onAutoShiftCmd(autoware_vehicle_msgs::msg::ShiftStamped::ConstSharedPtr msg); + + // Subscription for remote Commands remote_commands_; - ros::Subscriber remote_control_cmd_sub_; - ros::Subscriber remote_turn_signal_cmd_sub_; - ros::Subscriber remote_shift_cmd_sub_; - void onRemoteCtrlCmd(const autoware_control_msgs::ControlCommandStamped::ConstPtr & msg); - void onRemoteTurnSignalCmd(const autoware_vehicle_msgs::TurnSignal::ConstPtr & msg); - void onRemoteShiftCmd(const autoware_vehicle_msgs::ShiftStamped::ConstPtr & msg); - - // Subscriber for emergency + rclcpp::Subscription::SharedPtr + remote_control_cmd_sub_; + rclcpp::Subscription::SharedPtr + remote_turn_signal_cmd_sub_; + rclcpp::Subscription::SharedPtr remote_shift_cmd_sub_; + void onRemoteCtrlCmd(autoware_control_msgs::msg::ControlCommandStamped::ConstSharedPtr msg); + void onRemoteTurnSignalCmd(autoware_vehicle_msgs::msg::TurnSignal::ConstSharedPtr msg); + void onRemoteShiftCmd(autoware_vehicle_msgs::msg::ShiftStamped::ConstSharedPtr msg); + + // Subscription for emergency Commands emergency_commands_; - ros::Subscriber emergency_control_cmd_sub_; - ros::Subscriber emergency_turn_signal_cmd_sub_; - ros::Subscriber emergency_shift_cmd_sub_; - void onEmergencyCtrlCmd(const autoware_control_msgs::ControlCommandStamped::ConstPtr & msg); - void onEmergencyTurnSignalCmd(const autoware_vehicle_msgs::TurnSignal::ConstPtr & msg); - void onEmergencyShiftCmd(const autoware_vehicle_msgs::ShiftStamped::ConstPtr & msg); + rclcpp::Subscription::SharedPtr + emergency_control_cmd_sub_; + rclcpp::Subscription::SharedPtr + emergency_turn_signal_cmd_sub_; + rclcpp::Subscription::SharedPtr + emergency_shift_cmd_sub_; + void onEmergencyCtrlCmd(autoware_control_msgs::msg::ControlCommandStamped::ConstSharedPtr msg); + void onEmergencyTurnSignalCmd(autoware_vehicle_msgs::msg::TurnSignal::ConstSharedPtr msg); + void onEmergencyShiftCmd(autoware_vehicle_msgs::msg::ShiftStamped::ConstSharedPtr msg); // Parameter - double update_rate_; + double update_period_; bool use_emergency_handling_; // Timer / Event - ros::Timer timer_; + rclcpp::TimerBase::SharedPtr timer_; - void onTimer(const ros::TimerEvent & event); + void onTimer(); void publishControlCommands(const Commands & input_msg); // Algorithm - autoware_control_msgs::ControlCommand prev_control_cmd_; - autoware_control_msgs::ControlCommand createStopControlCmd() const; + autoware_control_msgs::msg::ControlCommand prev_control_cmd_; + autoware_control_msgs::msg::ControlCommand createStopControlCmd() const; - std::shared_ptr prev_time_; + std::shared_ptr prev_time_; double getDt(); VehicleCmdFilter filter_; - autoware_control_msgs::ControlCommand filterControlCommand( - const autoware_control_msgs::ControlCommand & msg); + autoware_control_msgs::msg::ControlCommand filterControlCommand( + const autoware_control_msgs::msg::ControlCommand & msg); }; #endif // VEHICLE_CMD_GATE_VEHICLE_CMD_GATE_H diff --git a/control/vehicle_cmd_gate/launch/vehicle_cmd_gate.launch b/control/vehicle_cmd_gate/launch/vehicle_cmd_gate.launch deleted file mode 100644 index 5ad8a17345..0000000000 --- a/control/vehicle_cmd_gate/launch/vehicle_cmd_gate.launch +++ /dev/null @@ -1,29 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/control/vehicle_cmd_gate/launch/vehicle_cmd_gate.launch.xml b/control/vehicle_cmd_gate/launch/vehicle_cmd_gate.launch.xml new file mode 100644 index 0000000000..a8e9c584da --- /dev/null +++ b/control/vehicle_cmd_gate/launch/vehicle_cmd_gate.launch.xml @@ -0,0 +1,29 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/control/vehicle_cmd_gate/package.xml b/control/vehicle_cmd_gate/package.xml index 4d2171cb98..84798f7a6e 100644 --- a/control/vehicle_cmd_gate/package.xml +++ b/control/vehicle_cmd_gate/package.xml @@ -6,14 +6,13 @@ h_ohta Apache 2 - catkin + ament_cmake autoware_control_msgs autoware_vehicle_msgs - geometry_msgs - roscpp - rostest - rosunit - std_msgs + rclcpp + + ament_cmake + diff --git a/control/vehicle_cmd_gate/src/vehicle_cmd_filter.cpp b/control/vehicle_cmd_gate/src/vehicle_cmd_filter.cpp index 668e4d6377..e09b60da50 100644 --- a/control/vehicle_cmd_gate/src/vehicle_cmd_filter.cpp +++ b/control/vehicle_cmd_gate/src/vehicle_cmd_filter.cpp @@ -13,31 +13,32 @@ * See the License for the specific language governing permissions and * limitations under the License. */ +#include -#include "vehicle_cmd_gate/vehicle_cmd_filter.h" +#include VehicleCmdFilter::VehicleCmdFilter() {} -void VehicleCmdFilter::limitLongitudinalWithVel(autoware_control_msgs::ControlCommand & input) +void VehicleCmdFilter::limitLongitudinalWithVel(autoware_control_msgs::msg::ControlCommand & input) { input.velocity = std::max(std::min(input.velocity, vel_lim_), -vel_lim_); } void VehicleCmdFilter::limitLongitudinalWithAcc( - const double dt, autoware_control_msgs::ControlCommand & input) + const double dt, autoware_control_msgs::msg::ControlCommand & input) { input.acceleration = std::max(std::min(input.acceleration, lon_acc_lim_), -lon_acc_lim_); input.velocity = limitDiff(input.velocity, prev_cmd_.velocity, lon_acc_lim_ * dt); } void VehicleCmdFilter::VehicleCmdFilter::limitLongitudinalWithJerk( - const double dt, autoware_control_msgs::ControlCommand & input) + const double dt, autoware_control_msgs::msg::ControlCommand & input) { input.acceleration = limitDiff(input.acceleration, prev_cmd_.acceleration, lon_jerk_lim_ * dt); } void VehicleCmdFilter::limitLateralWithLatAcc( - const double dt, autoware_control_msgs::ControlCommand & input) + const double dt, autoware_control_msgs::msg::ControlCommand & input) { double latacc = calcLatAcc(input); if (std::fabs(latacc) > lat_acc_lim_) { @@ -48,7 +49,7 @@ void VehicleCmdFilter::limitLateralWithLatAcc( } void VehicleCmdFilter::limitLateralWithLatJerk( - const double dt, autoware_control_msgs::ControlCommand & input) + const double dt, autoware_control_msgs::msg::ControlCommand & input) { double curr_latacc = calcLatAcc(input); double prev_latacc = calcLatAcc(prev_cmd_); @@ -60,7 +61,7 @@ void VehicleCmdFilter::limitLateralWithLatJerk( } } -double VehicleCmdFilter::calcLatAcc(const autoware_control_msgs::ControlCommand & cmd) +double VehicleCmdFilter::calcLatAcc(const autoware_control_msgs::msg::ControlCommand & cmd) { double v = cmd.velocity; return v * v * std::tan(cmd.steering_angle) / wheel_base_; diff --git a/control/vehicle_cmd_gate/src/vehicle_cmd_gate.cpp b/control/vehicle_cmd_gate/src/vehicle_cmd_gate.cpp index 156a4e4196..9e9c7e56a9 100644 --- a/control/vehicle_cmd_gate/src/vehicle_cmd_gate.cpp +++ b/control/vehicle_cmd_gate/src/vehicle_cmd_gate.cpp @@ -28,7 +28,14 @@ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. */ -#include "vehicle_cmd_gate/vehicle_cmd_gate.h" +#include +#include + +#include + +#include + +using std::placeholders::_1; namespace { @@ -39,9 +46,9 @@ void fillFrameId(std::string * frame_id, const std::string & name) } } -const char * getGateModeName(const autoware_control_msgs::GateMode::_data_type & gate_mode) +const char * getGateModeName(const autoware_control_msgs::msg::GateMode::_data_type & gate_mode) { - using autoware_control_msgs::GateMode; + using autoware_control_msgs::msg::GateMode; if (gate_mode == GateMode::AUTO) return "AUTO"; if (gate_mode == GateMode::REMOTE) return "REMOTE"; @@ -50,59 +57,71 @@ const char * getGateModeName(const autoware_control_msgs::GateMode::_data_type & } } // namespace -VehicleCmdGate::VehicleCmdGate() : nh_(""), pnh_("~"), is_engaged_(false), is_emergency_(false) +VehicleCmdGate::VehicleCmdGate() +: Node("vehicle_cmd_gate"), is_engaged_(false), is_emergency_(false) { + rclcpp::QoS durable_qos{1}; + durable_qos.transient_local(); // Publisher - vehicle_cmd_pub_ = - pnh_.advertise("output/vehicle_cmd", 1, true); - control_cmd_pub_ = - pnh_.advertise("output/control_cmd", 1, true); - shift_cmd_pub_ = pnh_.advertise("output/shift_cmd", 1, true); - turn_signal_cmd_pub_ = - pnh_.advertise("output/turn_signal_cmd", 1, true); - gate_mode_pub_ = pnh_.advertise("output/gate_mode", 1, true); + vehicle_cmd_pub_ = this->create_publisher( + "output/vehicle_cmd", durable_qos); + control_cmd_pub_ = this->create_publisher( + "output/control_cmd", durable_qos); + shift_cmd_pub_ = this->create_publisher( + "output/shift_cmd", durable_qos); + turn_signal_cmd_pub_ = this->create_publisher( + "output/turn_signal_cmd", durable_qos); + gate_mode_pub_ = + this->create_publisher("output/gate_mode", durable_qos); // Subscriber - engage_sub_ = pnh_.subscribe("input/engage", 1, &VehicleCmdGate::onEngage, this); - emergency_sub_ = pnh_.subscribe("input/emergency", 1, &VehicleCmdGate::onEmergency, this); - gate_mode_sub_ = pnh_.subscribe("input/gate_mode", 1, &VehicleCmdGate::onGateMode, this); + engage_sub_ = this->create_subscription( + "input/engage", 1, std::bind(&VehicleCmdGate::onEngage, this, _1)); + emergency_sub_ = this->create_subscription( + "input/emergency", 1, std::bind(&VehicleCmdGate::onEmergency, this, _1)); + gate_mode_sub_ = this->create_subscription( + "input/gate_mode", 1, std::bind(&VehicleCmdGate::onGateMode, this, _1)); // Subscriber for auto auto_control_cmd_sub_ = - pnh_.subscribe("input/auto/control_cmd", 1, &VehicleCmdGate::onAutoCtrlCmd, this); - auto_turn_signal_cmd_sub_ = - pnh_.subscribe("input/auto/turn_signal_cmd", 1, &VehicleCmdGate::onAutoTurnSignalCmd, this); - auto_shift_cmd_sub_ = - pnh_.subscribe("input/auto/shift_cmd", 1, &VehicleCmdGate::onAutoShiftCmd, this); + this->create_subscription( + "input/auto/control_cmd", 1, std::bind(&VehicleCmdGate::onAutoCtrlCmd, this, _1)); + auto_turn_signal_cmd_sub_ = this->create_subscription( + "input/auto/turn_signal_cmd", 1, std::bind(&VehicleCmdGate::onAutoTurnSignalCmd, this, _1)); + auto_shift_cmd_sub_ = this->create_subscription( + "input/auto/shift_cmd", 1, std::bind(&VehicleCmdGate::onAutoShiftCmd, this, _1)); // Subscriber for remote remote_control_cmd_sub_ = - pnh_.subscribe("input/remote/control_cmd", 1, &VehicleCmdGate::onRemoteCtrlCmd, this); - remote_turn_signal_cmd_sub_ = - pnh_.subscribe("input/remote/turn_signal_cmd", 1, &VehicleCmdGate::onRemoteTurnSignalCmd, this); - remote_shift_cmd_sub_ = - pnh_.subscribe("input/remote/shift_cmd", 1, &VehicleCmdGate::onRemoteShiftCmd, this); + this->create_subscription( + "input/remote/control_cmd", 1, std::bind(&VehicleCmdGate::onRemoteCtrlCmd, this, _1)); + remote_turn_signal_cmd_sub_ = this->create_subscription( + "input/remote/turn_signal_cmd", 1, std::bind(&VehicleCmdGate::onRemoteTurnSignalCmd, this, _1)); + remote_shift_cmd_sub_ = this->create_subscription( + "input/remote/shift_cmd", 1, std::bind(&VehicleCmdGate::onRemoteShiftCmd, this, _1)); // Subscriber for emergency emergency_control_cmd_sub_ = - pnh_.subscribe("input/emergency/control_cmd", 1, &VehicleCmdGate::onEmergencyCtrlCmd, this); - emergency_turn_signal_cmd_sub_ = pnh_.subscribe( - "input/emergency/turn_signal_cmd", 1, &VehicleCmdGate::onEmergencyTurnSignalCmd, this); - emergency_shift_cmd_sub_ = - pnh_.subscribe("input/emergency/shift_cmd", 1, &VehicleCmdGate::onEmergencyShiftCmd, this); + this->create_subscription( + "input/emergency/control_cmd", 1, std::bind(&VehicleCmdGate::onEmergencyCtrlCmd, this, _1)); + emergency_turn_signal_cmd_sub_ = + this->create_subscription( + "input/emergency/turn_signal_cmd", 1, + std::bind(&VehicleCmdGate::onEmergencyTurnSignalCmd, this, _1)); + emergency_shift_cmd_sub_ = this->create_subscription( + "input/emergency/shift_cmd", 1, std::bind(&VehicleCmdGate::onEmergencyShiftCmd, this, _1)); // Parameter - pnh_.param("update_rate", update_rate_, 10.0); - pnh_.param("use_emergency_handling", use_emergency_handling_, false); + update_period_ = 1.0 / declare_parameter("update_rate", 10.0); + use_emergency_handling_ = declare_parameter("use_emergency_handling", false); // Vehicle Parameter - double wheel_base, vel_lim, lon_acc_lim, lon_jerk_lim, lat_acc_lim, lat_jerk_lim; - pnh_.param("/vehicle_info/wheel_base", wheel_base, 2.79); - pnh_.param("vel_lim", vel_lim, 25.0); - pnh_.param("lon_acc_lim", lon_acc_lim, 5.0); - pnh_.param("lon_jerk_lim", lon_jerk_lim, 5.0); - pnh_.param("lat_acc_lim", lat_acc_lim, 5.0); - pnh_.param("lat_jerk_lim", lat_jerk_lim, 5.0); + double wheel_base = declare_parameter("/vehicle_info/wheel_base", 2.79); + double vel_lim = declare_parameter("vel_lim", 25.0); + double lon_acc_lim = declare_parameter("lon_acc_lim", 5.0); + double lon_jerk_lim = declare_parameter("lon_jerk_lim", 5.0); + double lat_acc_lim = declare_parameter("lat_acc_lim", 5.0); + double lat_jerk_lim = declare_parameter("lat_jerk_lim", 5.0); filter_.setWheelBase(wheel_base); filter_.setVelLim(vel_lim); filter_.setLonAccLim(lon_acc_lim); @@ -111,53 +130,60 @@ VehicleCmdGate::VehicleCmdGate() : nh_(""), pnh_("~"), is_engaged_(false), is_em filter_.setLatJerkLim(lat_jerk_lim); // Set default value - current_gate_mode_.data = autoware_control_msgs::GateMode::AUTO; + current_gate_mode_.data = autoware_control_msgs::msg::GateMode::AUTO; // Timer - timer_ = pnh_.createTimer(ros::Rate(update_rate_), &VehicleCmdGate::onTimer, this); + auto timer_callback = std::bind(&VehicleCmdGate::onTimer, this); + auto period = std::chrono::duration_cast( + std::chrono::duration(update_period_)); + timer_ = std::make_shared>( + this->get_clock(), period, std::move(timer_callback), + this->get_node_base_interface()->get_context()); + this->get_node_timers_interface()->add_timer(timer_, nullptr); } // for auto void VehicleCmdGate::onAutoCtrlCmd( - const autoware_control_msgs::ControlCommandStamped::ConstPtr & msg) + autoware_control_msgs::msg::ControlCommandStamped::ConstSharedPtr msg) { auto_commands_.control = *msg; - if (current_gate_mode_.data == autoware_control_msgs::GateMode::AUTO) { + if (current_gate_mode_.data == autoware_control_msgs::msg::GateMode::AUTO) { publishControlCommands(auto_commands_); } } -void VehicleCmdGate::onAutoTurnSignalCmd(const autoware_vehicle_msgs::TurnSignal::ConstPtr & msg) +void VehicleCmdGate::onAutoTurnSignalCmd(autoware_vehicle_msgs::msg::TurnSignal::ConstSharedPtr msg) { auto_commands_.turn_signal = *msg; } -void VehicleCmdGate::onAutoShiftCmd(const autoware_vehicle_msgs::ShiftStamped::ConstPtr & msg) +void VehicleCmdGate::onAutoShiftCmd(autoware_vehicle_msgs::msg::ShiftStamped::ConstSharedPtr msg) { auto_commands_.shift = *msg; } // for remote void VehicleCmdGate::onRemoteCtrlCmd( - const autoware_control_msgs::ControlCommandStamped::ConstPtr & msg) + autoware_control_msgs::msg::ControlCommandStamped::ConstSharedPtr msg) { remote_commands_.control = *msg; - if (current_gate_mode_.data == autoware_control_msgs::GateMode::REMOTE) { + if (current_gate_mode_.data == autoware_control_msgs::msg::GateMode::REMOTE) { publishControlCommands(remote_commands_); } } -void VehicleCmdGate::onRemoteTurnSignalCmd(const autoware_vehicle_msgs::TurnSignal::ConstPtr & msg) +void VehicleCmdGate::onRemoteTurnSignalCmd( + autoware_vehicle_msgs::msg::TurnSignal::ConstSharedPtr msg) { remote_commands_.turn_signal = *msg; } -void VehicleCmdGate::onRemoteShiftCmd(const autoware_vehicle_msgs::ShiftStamped::ConstPtr & msg) +void VehicleCmdGate::onRemoteShiftCmd(autoware_vehicle_msgs::msg::ShiftStamped::ConstSharedPtr msg) { remote_commands_.shift = *msg; } // for emergency void VehicleCmdGate::onEmergencyCtrlCmd( - const autoware_control_msgs::ControlCommandStamped::ConstPtr & msg) + autoware_control_msgs::msg::ControlCommandStamped::ConstSharedPtr msg) { emergency_commands_.control = *msg; @@ -166,27 +192,28 @@ void VehicleCmdGate::onEmergencyCtrlCmd( } } void VehicleCmdGate::onEmergencyTurnSignalCmd( - const autoware_vehicle_msgs::TurnSignal::ConstPtr & msg) + autoware_vehicle_msgs::msg::TurnSignal::ConstSharedPtr msg) { emergency_commands_.turn_signal = *msg; } -void VehicleCmdGate::onEmergencyShiftCmd(const autoware_vehicle_msgs::ShiftStamped::ConstPtr & msg) +void VehicleCmdGate::onEmergencyShiftCmd( + autoware_vehicle_msgs::msg::ShiftStamped::ConstSharedPtr msg) { emergency_commands_.shift = *msg; } -void VehicleCmdGate::onTimer(const ros::TimerEvent & event) +void VehicleCmdGate::onTimer() { // Select commands - autoware_vehicle_msgs::TurnSignal turn_signal; - autoware_vehicle_msgs::ShiftStamped shift; + autoware_vehicle_msgs::msg::TurnSignal turn_signal; + autoware_vehicle_msgs::msg::ShiftStamped shift; if (use_emergency_handling_ && is_emergency_) { turn_signal = emergency_commands_.turn_signal; shift = emergency_commands_.shift; - } else if (current_gate_mode_.data == autoware_control_msgs::GateMode::AUTO) { + } else if (current_gate_mode_.data == autoware_control_msgs::msg::GateMode::AUTO) { turn_signal = auto_commands_.turn_signal; shift = auto_commands_.shift; - } else if (current_gate_mode_.data == autoware_control_msgs::GateMode::REMOTE) { + } else if (current_gate_mode_.data == autoware_control_msgs::msg::GateMode::REMOTE) { turn_signal = remote_commands_.turn_signal; shift = remote_commands_.shift; } else { @@ -198,9 +225,9 @@ void VehicleCmdGate::onTimer(const ros::TimerEvent & event) fillFrameId(&turn_signal.header.frame_id, "base_link"); // Publish topics - gate_mode_pub_.publish(current_gate_mode_); - turn_signal_cmd_pub_.publish(turn_signal); - shift_cmd_pub_.publish(shift); + gate_mode_pub_->publish(current_gate_mode_); + turn_signal_cmd_pub_->publish(turn_signal); + shift_cmd_pub_->publish(shift); } void VehicleCmdGate::publishControlCommands(const Commands & commands) @@ -215,7 +242,8 @@ void VehicleCmdGate::publishControlCommands(const Commands & commands) // Check emergency if (use_emergency_handling_ && is_emergency_) { - ROS_INFO_THROTTLE(1.0, "Emergency!"); + // TODO(nikolai.morin): Use RCLCPP_INFO_THROTTLE with period 1.0 after Foxy + RCLCPP_INFO(get_logger(), "Emergency!"); filtered_commands.control = emergency_commands_.control; filtered_commands.shift = emergency_commands_.shift; // tmp } @@ -229,7 +257,7 @@ void VehicleCmdGate::publishControlCommands(const Commands & commands) filtered_commands.control.control = filterControlCommand(filtered_commands.control.control); // tmp: Create VehicleCmd - autoware_vehicle_msgs::VehicleCommand vehicle_cmd; + autoware_vehicle_msgs::msg::VehicleCommand vehicle_cmd; vehicle_cmd.header = filtered_commands.control.header; vehicle_cmd.control = filtered_commands.control.control; vehicle_cmd.shift = filtered_commands.shift.shift; @@ -240,17 +268,17 @@ void VehicleCmdGate::publishControlCommands(const Commands & commands) fillFrameId(&filtered_commands.control.header.frame_id, "base_link"); // Publish commands - vehicle_cmd_pub_.publish(vehicle_cmd); - control_cmd_pub_.publish(filtered_commands.control); + vehicle_cmd_pub_->publish(vehicle_cmd); + control_cmd_pub_->publish(filtered_commands.control); // Save ControlCmd to steering angle when disengaged prev_control_cmd_ = filtered_commands.control.control; } -autoware_control_msgs::ControlCommand VehicleCmdGate::filterControlCommand( - const autoware_control_msgs::ControlCommand & in) +autoware_control_msgs::msg::ControlCommand VehicleCmdGate::filterControlCommand( + const autoware_control_msgs::msg::ControlCommand & in) { - autoware_control_msgs::ControlCommand out = in; + autoware_control_msgs::msg::ControlCommand out = in; const double dt = getDt(); filter_.limitLongitudinalWithVel(out); @@ -263,9 +291,9 @@ autoware_control_msgs::ControlCommand VehicleCmdGate::filterControlCommand( return out; } -autoware_control_msgs::ControlCommand VehicleCmdGate::createStopControlCmd() const +autoware_control_msgs::msg::ControlCommand VehicleCmdGate::createStopControlCmd() const { - autoware_control_msgs::ControlCommand cmd; + autoware_control_msgs::msg::ControlCommand cmd; cmd.steering_angle = prev_control_cmd_.steering_angle; cmd.steering_angle_velocity = prev_control_cmd_.steering_angle_velocity; @@ -275,18 +303,24 @@ autoware_control_msgs::ControlCommand VehicleCmdGate::createStopControlCmd() con return cmd; } -void VehicleCmdGate::onEngage(const std_msgs::Bool::ConstPtr msg) { is_engaged_ = msg->data; } +void VehicleCmdGate::onEngage(autoware_control_msgs::msg::EngageMode::ConstSharedPtr msg) +{ + is_engaged_ = msg->is_engaged; +} -void VehicleCmdGate::onEmergency(const std_msgs::Bool::ConstPtr msg) { is_emergency_ = msg->data; } +void VehicleCmdGate::onEmergency(autoware_control_msgs::msg::EmergencyMode::ConstSharedPtr msg) +{ + is_emergency_ = msg->is_emergency; +} -void VehicleCmdGate::onGateMode(const autoware_control_msgs::GateMode::ConstPtr & msg) +void VehicleCmdGate::onGateMode(autoware_control_msgs::msg::GateMode::ConstSharedPtr msg) { const auto prev_gate_mode = current_gate_mode_; current_gate_mode_ = *msg; if (current_gate_mode_.data != prev_gate_mode.data) { - ROS_INFO( - "GateMode changed: %s -> %s", getGateModeName(prev_gate_mode.data), + RCLCPP_INFO( + get_logger(), "GateMode changed: %s -> %s", getGateModeName(prev_gate_mode.data), getGateModeName(current_gate_mode_.data)); } } @@ -294,12 +328,12 @@ void VehicleCmdGate::onGateMode(const autoware_control_msgs::GateMode::ConstPtr double VehicleCmdGate::getDt() { if (!prev_time_) { - prev_time_ = std::make_shared(ros::Time::now()); + prev_time_ = std::make_shared(this->now()); return 0.0; } - const auto current_time = ros::Time::now(); - const auto dt = (current_time - *prev_time_).toSec(); + const auto current_time = this->now(); + const auto dt = (current_time - *prev_time_).seconds(); *prev_time_ = current_time; return dt; diff --git a/control/vehicle_cmd_gate/src/vehicle_cmd_gate_node.cpp b/control/vehicle_cmd_gate/src/vehicle_cmd_gate_node.cpp index 1fa75f834f..333629ac09 100644 --- a/control/vehicle_cmd_gate/src/vehicle_cmd_gate_node.cpp +++ b/control/vehicle_cmd_gate/src/vehicle_cmd_gate_node.cpp @@ -14,18 +14,19 @@ * limitations under the License. */ -// ROS Includes -#include +// System includes +#include + +// ROS includes +#include "rclcpp/rclcpp.hpp" // User defined includes #include "vehicle_cmd_gate/vehicle_cmd_gate.h" int main(int argc, char ** argv) { - ros::init(argc, argv, "vehicle_cmd_gate"); - - VehicleCmdGate vehicle_cmd_gate; - - ros::spin(); + rclcpp::init(argc, argv); + rclcpp::spin(std::make_shared()); + rclcpp::shutdown(); return 0; }