@@ -45,7 +45,7 @@ MrmStopOperator::MrmStopOperator(const rclcpp::NodeOptions & node_options)
45
45
create_publisher<tier4_planning_msgs::msg::VelocityLimitClearCommand>(
46
46
" ~/output/velocity_limit_clear_command" , rclcpp::QoS{10 }.transient_local ());
47
47
pub_mrm_state_ =
48
- create_publisher<tier4_system_msgs ::msg::MrmState>(" ~/output/mrm_state" , rclcpp::QoS{1 });
48
+ create_publisher<autoware_adapi_v1_msgs ::msg::MrmState>(" ~/output/mrm_state" , rclcpp::QoS{1 });
49
49
50
50
// Timer
51
51
const auto update_period_ns = rclcpp::Rate (10 ).period ();
@@ -80,24 +80,24 @@ void MrmStopOperator::onMrmRequest(const tier4_system_msgs::msg::MrmBehavior::Co
80
80
pub_velocity_limit_->publish (velocity_limit);
81
81
82
82
last_mrm_request_ = *msg;
83
- current_mrm_state_.behavior = * msg;
84
- current_mrm_state_.state = tier4_system_msgs ::msg::MrmState::MRM_OPERATING;
83
+ current_mrm_state_.behavior = msg-> type ;
84
+ current_mrm_state_.state = autoware_adapi_v1_msgs ::msg::MrmState::MRM_OPERATING;
85
85
}
86
86
}
87
87
88
88
void MrmStopOperator::initState ()
89
89
{
90
90
last_mrm_request_.type = tier4_system_msgs::msg::MrmBehavior::NONE;
91
- current_mrm_state_.state = tier4_system_msgs ::msg::MrmState::NORMAL;
92
- current_mrm_state_.behavior . type = tier4_system_msgs ::msg::MrmBehavior ::NONE;
91
+ current_mrm_state_.state = autoware_adapi_v1_msgs ::msg::MrmState::NORMAL;
92
+ current_mrm_state_.behavior = autoware_adapi_v1_msgs ::msg::MrmState ::NONE;
93
93
}
94
94
95
95
void MrmStopOperator::onTimer ()
96
96
{
97
- if (current_mrm_state_.state == tier4_system_msgs ::msg::MrmState::MRM_OPERATING) {
98
- if (current_mrm_state_.behavior . type == tier4_system_msgs ::msg::MrmBehavior ::COMFORTABLE_STOP) {
97
+ if (current_mrm_state_.state == autoware_adapi_v1_msgs ::msg::MrmState::MRM_OPERATING) {
98
+ if (current_mrm_state_.behavior == autoware_adapi_v1_msgs ::msg::MrmState ::COMFORTABLE_STOP) {
99
99
if (isStopped ()) {
100
- current_mrm_state_.state = tier4_system_msgs ::msg::MrmState::MRM_SUCCEEDED;
100
+ current_mrm_state_.state = autoware_adapi_v1_msgs ::msg::MrmState::MRM_SUCCEEDED;
101
101
} else {
102
102
// nothing to do
103
103
}
0 commit comments