Skip to content

Commit 8aa0062

Browse files
authored
feat: daynamic reconfigurable is_mrm_recoverable parameter (#1333)
daynamic reconfigurable mrm_holding parameter
1 parent 4388a51 commit 8aa0062

File tree

3 files changed

+25
-0
lines changed

3 files changed

+25
-0
lines changed

system/mrm_handler/include/mrm_handler/mrm_handler_core.hpp

+8
Original file line numberDiff line numberDiff line change
@@ -20,8 +20,11 @@
2020
#include <optional>
2121
#include <string>
2222
#include <variant>
23+
#include <vector>
2324

2425
// Autoware
26+
#include <tier4_autoware_utils/ros/update_param.hpp>
27+
2528
#include <autoware_adapi_v1_msgs/msg/mrm_state.hpp>
2629
#include <autoware_adapi_v1_msgs/msg/operation_mode_state.hpp>
2730
#include <autoware_auto_vehicle_msgs/msg/control_mode_report.hpp>
@@ -119,6 +122,11 @@ class MrmHandler : public rclcpp::Node
119122
autoware_adapi_v1_msgs::msg::MrmState mrm_state_;
120123
void publishMrmState();
121124

125+
// parameter callback
126+
rcl_interfaces::msg::SetParametersResult onParam(
127+
const std::vector<rclcpp::Parameter> & parameters);
128+
OnSetParametersCallbackHandle::SharedPtr set_param_res_;
129+
122130
// Clients
123131
rclcpp::CallbackGroup::SharedPtr client_mrm_pull_over_group_;
124132
rclcpp::Client<tier4_system_msgs::srv::OperateMrm>::SharedPtr client_mrm_pull_over_;

system/mrm_handler/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@
2020
<depend>rclcpp</depend>
2121
<depend>std_msgs</depend>
2222
<depend>std_srvs</depend>
23+
<depend>tier4_autoware_utils</depend>
2324
<depend>tier4_system_msgs</depend>
2425

2526
<test_depend>ament_lint_auto</test_depend>

system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp

+16
Original file line numberDiff line numberDiff line change
@@ -103,6 +103,9 @@ MrmHandler::MrmHandler() : Node("mrm_handler")
103103
const auto update_period_ns = rclcpp::Rate(param_.update_rate).period();
104104
timer_ = rclcpp::create_timer(
105105
this, get_clock(), update_period_ns, std::bind(&MrmHandler::onTimer, this));
106+
107+
// set parameter callback
108+
set_param_res_ = this->add_on_set_parameters_callback(std::bind(&MrmHandler::onParam, this, _1));
106109
}
107110

108111
void MrmHandler::onOdometry(const nav_msgs::msg::Odometry::ConstSharedPtr msg)
@@ -168,6 +171,19 @@ void MrmHandler::onOperationModeState(
168171
operation_mode_state_ = msg;
169172
}
170173

174+
rcl_interfaces::msg::SetParametersResult MrmHandler::onParam(
175+
const std::vector<rclcpp::Parameter> & parameters)
176+
{
177+
using tier4_autoware_utils::updateParam;
178+
updateParam<bool>(parameters, "is_mrm_recoverable", param_.is_mrm_recoverable);
179+
if (param_.is_mrm_recoverable) is_mrm_holding_ = false;
180+
rcl_interfaces::msg::SetParametersResult result;
181+
result.successful = true;
182+
result.reason = "success";
183+
184+
return result;
185+
}
186+
171187
void MrmHandler::publishHazardCmd()
172188
{
173189
using autoware_auto_vehicle_msgs::msg::HazardLightsCommand;

0 commit comments

Comments
 (0)