diff --git a/system/mrm_stop_operator/package.xml b/system/mrm_stop_operator/package.xml
index 42f5268757afc..6039028449dcc 100644
--- a/system/mrm_stop_operator/package.xml
+++ b/system/mrm_stop_operator/package.xml
@@ -12,6 +12,7 @@
autoware_cmake
+ autoware_adapi_v1_msgs
autoware_auto_vehicle_msgs
rclcpp
rclcpp_components
diff --git a/system/mrm_stop_operator/src/mrm_stop_operator.cpp b/system/mrm_stop_operator/src/mrm_stop_operator.cpp
index f7f39accaf262..1b8f5cf993284 100644
--- a/system/mrm_stop_operator/src/mrm_stop_operator.cpp
+++ b/system/mrm_stop_operator/src/mrm_stop_operator.cpp
@@ -45,7 +45,7 @@ MrmStopOperator::MrmStopOperator(const rclcpp::NodeOptions & node_options)
create_publisher(
"~/output/velocity_limit_clear_command", rclcpp::QoS{10}.transient_local());
pub_mrm_state_ =
- create_publisher("~/output/mrm_state", rclcpp::QoS{1});
+ create_publisher("~/output/mrm_state", rclcpp::QoS{1});
// Timer
const auto update_period_ns = rclcpp::Rate(10).period();
@@ -80,24 +80,24 @@ void MrmStopOperator::onMrmRequest(const tier4_system_msgs::msg::MrmBehavior::Co
pub_velocity_limit_->publish(velocity_limit);
last_mrm_request_ = *msg;
- current_mrm_state_.behavior = *msg;
- current_mrm_state_.state = tier4_system_msgs::msg::MrmState::MRM_OPERATING;
+ current_mrm_state_.behavior = msg->type;
+ current_mrm_state_.state = autoware_adapi_v1_msgs::msg::MrmState::MRM_OPERATING;
}
}
void MrmStopOperator::initState()
{
last_mrm_request_.type = tier4_system_msgs::msg::MrmBehavior::NONE;
- current_mrm_state_.state = tier4_system_msgs::msg::MrmState::NORMAL;
- current_mrm_state_.behavior.type = tier4_system_msgs::msg::MrmBehavior::NONE;
+ current_mrm_state_.state = autoware_adapi_v1_msgs::msg::MrmState::NORMAL;
+ current_mrm_state_.behavior = autoware_adapi_v1_msgs::msg::MrmState::NONE;
}
void MrmStopOperator::onTimer()
{
- if (current_mrm_state_.state == tier4_system_msgs::msg::MrmState::MRM_OPERATING) {
- if (current_mrm_state_.behavior.type == tier4_system_msgs::msg::MrmBehavior::COMFORTABLE_STOP) {
+ if (current_mrm_state_.state == autoware_adapi_v1_msgs::msg::MrmState::MRM_OPERATING) {
+ if (current_mrm_state_.behavior == autoware_adapi_v1_msgs::msg::MrmState::COMFORTABLE_STOP) {
if (isStopped()) {
- current_mrm_state_.state = tier4_system_msgs::msg::MrmState::MRM_SUCCEEDED;
+ current_mrm_state_.state = autoware_adapi_v1_msgs::msg::MrmState::MRM_SUCCEEDED;
} else {
// nothing to do
}
diff --git a/system/mrm_stop_operator/src/mrm_stop_operator.hpp b/system/mrm_stop_operator/src/mrm_stop_operator.hpp
index 2a28b66472a54..bf9022f9873cf 100644
--- a/system/mrm_stop_operator/src/mrm_stop_operator.hpp
+++ b/system/mrm_stop_operator/src/mrm_stop_operator.hpp
@@ -18,11 +18,11 @@
// include
#include
+#include
#include
#include
#include
#include
-#include
namespace mrm_stop_operator
{
@@ -56,7 +56,7 @@ class MrmStopOperator : public rclcpp::Node
rclcpp::Publisher::SharedPtr pub_velocity_limit_;
rclcpp::Publisher::SharedPtr
pub_velocity_limit_clear_command_;
- rclcpp::Publisher::SharedPtr pub_mrm_state_;
+ rclcpp::Publisher::SharedPtr pub_mrm_state_;
// Service
// Client
@@ -68,7 +68,7 @@ class MrmStopOperator : public rclcpp::Node
// State
tier4_system_msgs::msg::MrmBehavior last_mrm_request_;
- tier4_system_msgs::msg::MrmState current_mrm_state_;
+ autoware_adapi_v1_msgs::msg::MrmState current_mrm_state_;
void initState();
void onTimer();