Skip to content

Commit

Permalink
fix: use adapi mrm state
Browse files Browse the repository at this point in the history
Signed-off-by: TetsuKawa <[email protected]>
  • Loading branch information
TetsuKawa committed Aug 16, 2024
1 parent 07144ae commit f9f32e3
Show file tree
Hide file tree
Showing 3 changed files with 12 additions and 11 deletions.
1 change: 1 addition & 0 deletions system/mrm_stop_operator/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
<depend>rclcpp_components</depend>
<depend>tier4_planning_msgs</depend>
<depend>tier4_system_msgs</depend>
<depend>autoware_adapi_v1_msgs</depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>
Expand Down
16 changes: 8 additions & 8 deletions system/mrm_stop_operator/src/mrm_stop_operator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ MrmStopOperator::MrmStopOperator(const rclcpp::NodeOptions & node_options)
create_publisher<tier4_planning_msgs::msg::VelocityLimitClearCommand>(
"~/output/velocity_limit_clear_command", rclcpp::QoS{10}.transient_local());
pub_mrm_state_ =
create_publisher<tier4_system_msgs::msg::MrmState>("~/output/mrm_state", rclcpp::QoS{1});
create_publisher<autoware_adapi_v1_msgs::msg::MrmState>("~/output/mrm_state", rclcpp::QoS{1});

// Timer
const auto update_period_ns = rclcpp::Rate(10).period();
Expand Down Expand Up @@ -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
}
Expand Down
6 changes: 3 additions & 3 deletions system/mrm_stop_operator/src/mrm_stop_operator.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
#include <tier4_planning_msgs/msg/velocity_limit.hpp>
#include <tier4_planning_msgs/msg/velocity_limit_clear_command.hpp>
#include <tier4_system_msgs/msg/mrm_behavior.hpp>
#include <tier4_system_msgs/msg/mrm_state.hpp>
#include <autoware_adapi_v1_msgs/msg/mrm_state.hpp>

namespace mrm_stop_operator
{
Expand Down Expand Up @@ -56,7 +56,7 @@ class MrmStopOperator : public rclcpp::Node
rclcpp::Publisher<tier4_planning_msgs::msg::VelocityLimit>::SharedPtr pub_velocity_limit_;
rclcpp::Publisher<tier4_planning_msgs::msg::VelocityLimitClearCommand>::SharedPtr
pub_velocity_limit_clear_command_;
rclcpp::Publisher<tier4_system_msgs::msg::MrmState>::SharedPtr pub_mrm_state_;
rclcpp::Publisher<autoware_adapi_v1_msgs::msg::MrmState>::SharedPtr pub_mrm_state_;
// Service

// Client
Expand All @@ -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();
Expand Down

0 comments on commit f9f32e3

Please sign in to comment.