Skip to content

Commit

Permalink
feat: delete control cmd sub and pub for refactoring
Browse files Browse the repository at this point in the history
  • Loading branch information
TetsuKawa committed Feb 1, 2024
1 parent 100aac2 commit 1155ca5
Show file tree
Hide file tree
Showing 3 changed files with 0 additions and 27 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,6 @@
// Autoware
#include <autoware_adapi_v1_msgs/msg/mrm_state.hpp>
#include <autoware_adapi_v1_msgs/msg/operation_mode_state.hpp>
#include <autoware_auto_control_msgs/msg/ackermann_control_command.hpp>
#include <autoware_auto_vehicle_msgs/msg/control_mode_report.hpp>
#include <autoware_auto_vehicle_msgs/msg/gear_command.hpp>
#include <autoware_auto_vehicle_msgs/msg/hazard_lights_command.hpp>
Expand Down Expand Up @@ -65,8 +64,6 @@ class EmergencyHandler : public rclcpp::Node

private:
// Subscribers
rclcpp::Subscription<autoware_auto_control_msgs::msg::AckermannControlCommand>::SharedPtr
sub_prev_control_command_;
rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr sub_odom_;
rclcpp::Subscription<autoware_auto_vehicle_msgs::msg::ControlModeReport>::SharedPtr
sub_control_mode_;
Expand All @@ -81,7 +78,6 @@ class EmergencyHandler : public rclcpp::Node
rclcpp::Subscription<autoware_adapi_v1_msgs::msg::OperationModeState>::SharedPtr
sub_operation_mode_state_;

autoware_auto_control_msgs::msg::AckermannControlCommand::ConstSharedPtr prev_control_command_;
nav_msgs::msg::Odometry::ConstSharedPtr odom_;
autoware_auto_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr control_mode_;
tier4_system_msgs::msg::OperationModeAvailability::ConstSharedPtr operation_mode_availability_;
Expand All @@ -90,8 +86,6 @@ class EmergencyHandler : public rclcpp::Node
tier4_system_msgs::msg::MrmBehaviorStatus::ConstSharedPtr mrm_emergency_stop_status_;
autoware_adapi_v1_msgs::msg::OperationModeState::ConstSharedPtr operation_mode_state_;

void onPrevControlCommand(
const autoware_auto_control_msgs::msg::AckermannControlCommand::ConstSharedPtr msg);
void onOdometry(const nav_msgs::msg::Odometry::ConstSharedPtr msg);
void onControlMode(const autoware_auto_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr msg);
void onOperationModeAvailability(
Expand All @@ -105,8 +99,6 @@ class EmergencyHandler : public rclcpp::Node
const autoware_adapi_v1_msgs::msg::OperationModeState::ConstSharedPtr msg);

// Publisher
rclcpp::Publisher<autoware_auto_control_msgs::msg::AckermannControlCommand>::SharedPtr
pub_control_command_;

// rclcpp::Publisher<tier4_vehicle_msgs::msg::ShiftStamped>::SharedPtr pub_shift_;
// rclcpp::Publisher<tier4_vehicle_msgs::msg::TurnSignal>::SharedPtr pub_turn_signal_;
Expand Down
2 changes: 0 additions & 2 deletions system/emergency_handler/launch/emergency_handler.launch.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
<launch>
<arg name="input_operation_mode_availability" default="/system/operation_mode/availability"/>
<!-- To be replaced by ControlCommand -->
<arg name="input_prev_control_command" default="/control/command/control_cmd"/>
<arg name="input_odometry" default="/localization/kinematic_state"/>
<arg name="input_control_mode" default="/vehicle/status/control_mode"/>
<arg name="input_mrm_pull_over_state" default="/system/mrm/pull_over_manager/status"/>
Expand All @@ -21,7 +20,6 @@
<!-- emergency_handler -->
<node pkg="emergency_handler" exec="emergency_handler" name="emergency_handler" output="screen">
<remap from="~/input/operation_mode_availability" to="$(var input_operation_mode_availability)"/>
<remap from="~/input/prev_control_command" to="$(var input_prev_control_command)"/>
<remap from="~/input/odometry" to="$(var input_odometry)"/>
<remap from="~/input/control_mode" to="$(var input_control_mode)"/>
<remap from="~/input/mrm/pull_over/status" to="$(var input_mrm_pull_over_state)"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,10 +36,6 @@ EmergencyHandler::EmergencyHandler() : Node("emergency_handler")
using std::placeholders::_1;

// Subscriber
sub_prev_control_command_ =
create_subscription<autoware_auto_control_msgs::msg::AckermannControlCommand>(
"~/input/prev_control_command", rclcpp::QoS{1},
std::bind(&EmergencyHandler::onPrevControlCommand, this, _1));
sub_odom_ = create_subscription<nav_msgs::msg::Odometry>(
"~/input/odometry", rclcpp::QoS{1}, std::bind(&EmergencyHandler::onOdometry, this, _1));
// subscribe control mode
Expand All @@ -63,8 +59,6 @@ EmergencyHandler::EmergencyHandler() : Node("emergency_handler")
std::bind(&EmergencyHandler::onOperationModeState, this, _1));

// Publisher
pub_control_command_ = create_publisher<autoware_auto_control_msgs::msg::AckermannControlCommand>(
"~/output/control_command", rclcpp::QoS{1});
pub_hazard_cmd_ = create_publisher<autoware_auto_vehicle_msgs::msg::HazardLightsCommand>(
"~/output/hazard", rclcpp::QoS{1});
pub_gear_cmd_ =
Expand All @@ -91,8 +85,6 @@ EmergencyHandler::EmergencyHandler() : Node("emergency_handler")
// Initialize
odom_ = std::make_shared<const nav_msgs::msg::Odometry>();
control_mode_ = std::make_shared<const autoware_auto_vehicle_msgs::msg::ControlModeReport>();
prev_control_command_ = autoware_auto_control_msgs::msg::AckermannControlCommand::ConstSharedPtr(
new autoware_auto_control_msgs::msg::AckermannControlCommand);
mrm_pull_over_status_ = std::make_shared<const tier4_system_msgs::msg::MrmBehaviorStatus>();
mrm_comfortable_stop_status_ =
std::make_shared<const tier4_system_msgs::msg::MrmBehaviorStatus>();
Expand All @@ -108,15 +100,6 @@ EmergencyHandler::EmergencyHandler() : Node("emergency_handler")
this, get_clock(), update_period_ns, std::bind(&EmergencyHandler::onTimer, this));
}

void EmergencyHandler::onPrevControlCommand(
const autoware_auto_control_msgs::msg::AckermannControlCommand::ConstSharedPtr msg)
{
auto control_command = new autoware_auto_control_msgs::msg::AckermannControlCommand(*msg);
control_command->stamp = msg->stamp;
prev_control_command_ =
autoware_auto_control_msgs::msg::AckermannControlCommand::ConstSharedPtr(control_command);
}

void EmergencyHandler::onOdometry(const nav_msgs::msg::Odometry::ConstSharedPtr msg)
{
odom_ = msg;
Expand Down

0 comments on commit 1155ca5

Please sign in to comment.