Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(mrm_emergency_stop_operator): add support for real time param reconfigure for mrm_emergency_stop #6994

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
// ROS 2 core
#include <rclcpp/rclcpp.hpp>

#include <vector>
namespace mrm_emergency_stop_operator
{
using autoware_auto_control_msgs::msg::AckermannControlCommand;
Expand All @@ -48,6 +49,10 @@ class MrmEmergencyStopOperator : public rclcpp::Node
private:
// Parameters
Parameters params_;
OnSetParametersCallbackHandle::SharedPtr set_param_res_;

rcl_interfaces::msg::SetParametersResult onParameter(
const std::vector<rclcpp::Parameter> & parameters);

// Subscriber
rclcpp::Subscription<AckermannControlCommand>::SharedPtr sub_control_cmd_;
Expand Down
1 change: 1 addition & 0 deletions system/mrm_emergency_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>std_msgs</depend>
<depend>std_srvs</depend>
<depend>tier4_autoware_utils</depend>
<depend>tier4_system_msgs</depend>

<test_depend>ament_lint_auto</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,8 @@

#include "mrm_emergency_stop_operator/mrm_emergency_stop_operator_core.hpp"

#include <tier4_autoware_utils/ros/update_param.hpp>

namespace mrm_emergency_stop_operator
{

Expand Down Expand Up @@ -49,6 +51,23 @@ MrmEmergencyStopOperator::MrmEmergencyStopOperator(const rclcpp::NodeOptions & n
// Initialize
status_.state = MrmBehaviorStatus::AVAILABLE;
is_prev_control_cmd_subscribed_ = false;

// Parameter Callback
set_param_res_ = add_on_set_parameters_callback(
std::bind(&MrmEmergencyStopOperator::onParameter, this, std::placeholders::_1));
}

rcl_interfaces::msg::SetParametersResult MrmEmergencyStopOperator::onParameter(
const std::vector<rclcpp::Parameter> & parameters)
{
using tier4_autoware_utils::updateParam;
updateParam<double>(parameters, "target_acceleration", params_.target_acceleration);
updateParam<double>(parameters, "target_jerk", params_.target_jerk);

rcl_interfaces::msg::SetParametersResult result;
result.successful = true;
result.reason = "success";
return result;
}

void MrmEmergencyStopOperator::onControlCommand(AckermannControlCommand::ConstSharedPtr msg)
Expand Down
Loading