Skip to content

Commit 23b5356

Browse files
authored
feat: implement service for clear MRM behavior (#1511)
* implement service for clear MRM behavior * clang format
1 parent 9d91137 commit 23b5356

File tree

2 files changed

+25
-0
lines changed

2 files changed

+25
-0
lines changed

system/mrm_handler/include/mrm_handler/mrm_handler_core.hpp

+7
Original file line numberDiff line numberDiff line change
@@ -40,6 +40,7 @@
4040

4141
#include <diagnostic_msgs/msg/diagnostic_array.hpp>
4242
#include <nav_msgs/msg/odometry.hpp>
43+
#include <std_srvs/srv/trigger.hpp>
4344

4445
struct HazardLampPolicy
4546
{
@@ -105,6 +106,9 @@ class MrmHandler : public rclcpp::Node
105106
const tier4_system_msgs::msg::MrmBehaviorStatus::ConstSharedPtr msg);
106107
void onOperationModeState(
107108
const autoware_adapi_v1_msgs::msg::OperationModeState::ConstSharedPtr msg);
109+
void onRecoverMrm(
110+
const std_srvs::srv::Trigger::Request::SharedPtr,
111+
const std_srvs::srv::Trigger::Response::SharedPtr response);
108112

109113
// Publisher
110114

@@ -135,6 +139,9 @@ class MrmHandler : public rclcpp::Node
135139
rclcpp::CallbackGroup::SharedPtr client_mrm_emergency_stop_group_;
136140
rclcpp::Client<tier4_system_msgs::srv::OperateMrm>::SharedPtr client_mrm_emergency_stop_;
137141

142+
// Services
143+
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr service_recover_mrm_;
144+
138145
bool requestMrmBehavior(
139146
const autoware_adapi_v1_msgs::msg::MrmState::_behavior_type & mrm_behavior,
140147
RequestType request_type) const;

system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp

+18
Original file line numberDiff line numberDiff line change
@@ -86,6 +86,12 @@ MrmHandler::MrmHandler() : Node("mrm_handler")
8686
"~/output/mrm/emergency_stop/operate", rmw_qos_profile_services_default,
8787
client_mrm_emergency_stop_group_);
8888

89+
// Services
90+
service_recover_mrm_ = create_service<std_srvs::srv::Trigger>(
91+
"/system/clear_mrm",
92+
std::bind(&MrmHandler::onRecoverMrm, this, std::placeholders::_1, std::placeholders::_2),
93+
rmw_qos_profile_services_default);
94+
8995
// Initialize
9096
odom_ = std::make_shared<const nav_msgs::msg::Odometry>();
9197
control_mode_ = std::make_shared<const autoware_auto_vehicle_msgs::msg::ControlModeReport>();
@@ -619,3 +625,15 @@ bool MrmHandler::isArrivedAtGoal()
619625

620626
return operation_mode_state_->mode == OperationModeState::STOP;
621627
}
628+
629+
void MrmHandler::onRecoverMrm(
630+
const std_srvs::srv::Trigger::Request::SharedPtr,
631+
const std_srvs::srv::Trigger::Response::SharedPtr response)
632+
{
633+
if (!param_.is_mrm_recoverable) {
634+
is_mrm_holding_ = false;
635+
response->success = true;
636+
} else {
637+
response->success = false;
638+
}
639+
}

0 commit comments

Comments
 (0)