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_comfortable_stop_operator): add updateParam for mrm comfortable stop #9353

Merged
Show file tree
Hide file tree
Changes from 1 commit
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 @@ -17,6 +17,7 @@

// Core
#include <memory>
#include <vector>

// Autoware
#include <tier4_planning_msgs/msg/velocity_limit.hpp>
Expand Down Expand Up @@ -55,6 +56,9 @@ class MrmComfortableStopOperator : public rclcpp::Node
const tier4_system_msgs::srv::OperateMrm::Request::SharedPtr request,
const tier4_system_msgs::srv::OperateMrm::Response::SharedPtr response);

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

// Publisher
rclcpp::Publisher<tier4_system_msgs::msg::MrmBehaviorStatus>::SharedPtr pub_status_;
rclcpp::Publisher<tier4_planning_msgs::msg::VelocityLimit>::SharedPtr pub_velocity_limit_;
Expand All @@ -72,6 +76,9 @@ class MrmComfortableStopOperator : public rclcpp::Node

// States
tier4_system_msgs::msg::MrmBehaviorStatus status_;

// Parameter callback
OnSetParametersCallbackHandle::SharedPtr set_param_res_;
};

} // namespace mrm_comfortable_stop_operator
Expand Down
1 change: 1 addition & 0 deletions system/mrm_comfortable_stop_operator/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_adapi_v1_msgs</depend>
<depend>autoware_universe_utils</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>std_msgs</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,8 @@

#include "mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.hpp"

#include <autoware/universe_utils/ros/update_param.hpp>

namespace mrm_comfortable_stop_operator
{

Expand Down Expand Up @@ -48,6 +50,10 @@

// Initialize
status_.state = tier4_system_msgs::msg::MrmBehaviorStatus::AVAILABLE;

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

Check warning on line 56 in system/mrm_comfortable_stop_operator/src/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.cpp

View check run for this annotation

Codecov / codecov/patch

system/mrm_comfortable_stop_operator/src/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.cpp#L55-L56

Added lines #L55 - L56 were not covered by tests
}

void MrmComfortableStopOperator::operateComfortableStop(
Expand All @@ -65,6 +71,21 @@
}
}

rcl_interfaces::msg::SetParametersResult MrmComfortableStopOperator::onParameter(

Check warning on line 74 in system/mrm_comfortable_stop_operator/src/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.cpp

View check run for this annotation

Codecov / codecov/patch

system/mrm_comfortable_stop_operator/src/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.cpp#L74

Added line #L74 was not covered by tests
const std::vector<rclcpp::Parameter> & parameters)
{
using autoware::universe_utils::updateParam;
updateParam<double>(parameters, "min_acceleration", params_.min_acceleration);
params_.min_acceleration = std::abs(params_.min_acceleration);
TomohitoAndo marked this conversation as resolved.
Show resolved Hide resolved
updateParam<double>(parameters, "max_jerk", params_.max_jerk);
updateParam<double>(parameters, "min_jerk", params_.min_jerk);

Check warning on line 81 in system/mrm_comfortable_stop_operator/src/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.cpp

View check run for this annotation

Codecov / codecov/patch

system/mrm_comfortable_stop_operator/src/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.cpp#L78-L81

Added lines #L78 - L81 were not covered by tests

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

Check warning on line 86 in system/mrm_comfortable_stop_operator/src/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.cpp

View check run for this annotation

Codecov / codecov/patch

system/mrm_comfortable_stop_operator/src/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.cpp#L83-L86

Added lines #L83 - L86 were not covered by tests
}

void MrmComfortableStopOperator::publishStatus() const
{
auto status = status_;
Expand Down
Loading