35 #include "dwb_plugins/kinematic_parameters.hpp"
41 #include "nav2_ros_common/node_utils.hpp"
42 #include "nav2_costmap_2d/costmap_filters/filter_values.hpp"
44 using nav2::declare_parameter_if_not_declared;
45 using rcl_interfaces::msg::ParameterType;
46 using std::placeholders::_1;
51 KinematicsHandler::KinematicsHandler()
53 kinematics_.store(
new KinematicParameters);
56 KinematicsHandler::~KinematicsHandler()
58 delete kinematics_.load();
61 void KinematicsHandler::initialize(
62 const nav2::LifecycleNode::SharedPtr & nh,
63 const std::string & plugin_name)
66 plugin_name_ = plugin_name;
67 logger_ = nh->get_logger();
69 declare_parameter_if_not_declared(nh, plugin_name +
".min_vel_x", rclcpp::ParameterValue(0.0));
70 declare_parameter_if_not_declared(nh, plugin_name +
".min_vel_y", rclcpp::ParameterValue(0.0));
71 declare_parameter_if_not_declared(nh, plugin_name +
".max_vel_x", rclcpp::ParameterValue(0.0));
72 declare_parameter_if_not_declared(nh, plugin_name +
".max_vel_y", rclcpp::ParameterValue(0.0));
73 declare_parameter_if_not_declared(
74 nh, plugin_name +
".max_vel_theta",
75 rclcpp::ParameterValue(0.0));
76 declare_parameter_if_not_declared(
77 nh, plugin_name +
".min_speed_xy",
78 rclcpp::ParameterValue(0.0));
79 declare_parameter_if_not_declared(
80 nh, plugin_name +
".max_speed_xy",
81 rclcpp::ParameterValue(0.0));
82 declare_parameter_if_not_declared(
83 nh, plugin_name +
".min_speed_theta",
84 rclcpp::ParameterValue(0.0));
85 declare_parameter_if_not_declared(nh, plugin_name +
".acc_lim_x", rclcpp::ParameterValue(0.0));
86 declare_parameter_if_not_declared(nh, plugin_name +
".acc_lim_y", rclcpp::ParameterValue(0.0));
87 declare_parameter_if_not_declared(
88 nh, plugin_name +
".acc_lim_theta",
89 rclcpp::ParameterValue(0.0));
90 declare_parameter_if_not_declared(nh, plugin_name +
".decel_lim_x", rclcpp::ParameterValue(0.0));
91 declare_parameter_if_not_declared(nh, plugin_name +
".decel_lim_y", rclcpp::ParameterValue(0.0));
92 declare_parameter_if_not_declared(
93 nh, plugin_name +
".decel_lim_theta",
94 rclcpp::ParameterValue(0.0));
96 KinematicParameters kinematics;
98 nh->get_parameter(plugin_name +
".min_vel_x", kinematics.min_vel_x_);
99 nh->get_parameter(plugin_name +
".min_vel_y", kinematics.min_vel_y_);
100 nh->get_parameter(plugin_name +
".max_vel_x", kinematics.max_vel_x_);
101 nh->get_parameter(plugin_name +
".max_vel_y", kinematics.max_vel_y_);
102 nh->get_parameter(plugin_name +
".max_vel_theta", kinematics.max_vel_theta_);
103 nh->get_parameter(plugin_name +
".min_speed_xy", kinematics.min_speed_xy_);
104 nh->get_parameter(plugin_name +
".max_speed_xy", kinematics.max_speed_xy_);
105 nh->get_parameter(plugin_name +
".min_speed_theta", kinematics.min_speed_theta_);
106 nh->get_parameter(plugin_name +
".acc_lim_x", kinematics.acc_lim_x_);
107 nh->get_parameter(plugin_name +
".acc_lim_y", kinematics.acc_lim_y_);
108 nh->get_parameter(plugin_name +
".acc_lim_theta", kinematics.acc_lim_theta_);
109 nh->get_parameter(plugin_name +
".decel_lim_x", kinematics.decel_lim_x_);
110 nh->get_parameter(plugin_name +
".decel_lim_y", kinematics.decel_lim_y_);
111 nh->get_parameter(plugin_name +
".decel_lim_theta", kinematics.decel_lim_theta_);
113 kinematics.base_max_vel_x_ = kinematics.max_vel_x_;
114 kinematics.base_max_vel_y_ = kinematics.max_vel_y_;
115 kinematics.base_max_speed_xy_ = kinematics.max_speed_xy_;
116 kinematics.base_max_vel_theta_ = kinematics.max_vel_theta_;
118 kinematics.min_speed_xy_sq_ = kinematics.min_speed_xy_ * kinematics.min_speed_xy_;
119 kinematics.max_speed_xy_sq_ = kinematics.max_speed_xy_ * kinematics.max_speed_xy_;
121 update_kinematics(kinematics);
124 void KinematicsHandler::activate()
126 auto node = node_.lock();
128 post_set_params_handler_ = node->add_post_set_parameters_callback(
131 this, std::placeholders::_1));
132 on_set_params_handler_ = node->add_on_set_parameters_callback(
135 this, std::placeholders::_1));
138 void KinematicsHandler::deactivate()
140 auto node = node_.lock();
141 if (post_set_params_handler_ && node) {
142 node->remove_post_set_parameters_callback(post_set_params_handler_.get());
144 post_set_params_handler_.reset();
145 if (on_set_params_handler_ && node) {
146 node->remove_on_set_parameters_callback(on_set_params_handler_.get());
148 on_set_params_handler_.reset();
151 void KinematicsHandler::setSpeedLimit(
152 const double & speed_limit,
const bool & percentage)
154 KinematicParameters kinematics(*kinematics_.load());
156 if (speed_limit == nav2_costmap_2d::NO_SPEED_LIMIT) {
158 kinematics.max_speed_xy_ = kinematics.base_max_speed_xy_;
159 kinematics.max_vel_x_ = kinematics.base_max_vel_x_;
160 kinematics.max_vel_y_ = kinematics.base_max_vel_y_;
161 kinematics.max_vel_theta_ = kinematics.base_max_vel_theta_;
165 kinematics.max_speed_xy_ = kinematics.base_max_speed_xy_ * speed_limit / 100.0;
166 kinematics.max_vel_x_ = kinematics.base_max_vel_x_ * speed_limit / 100.0;
167 kinematics.max_vel_y_ = kinematics.base_max_vel_y_ * speed_limit / 100.0;
168 kinematics.max_vel_theta_ = kinematics.base_max_vel_theta_ * speed_limit / 100.0;
171 if (speed_limit < kinematics.base_max_speed_xy_) {
172 kinematics.max_speed_xy_ = speed_limit;
177 const double ratio = speed_limit / kinematics.base_max_speed_xy_;
178 kinematics.max_vel_x_ = kinematics.base_max_vel_x_ * ratio;
179 kinematics.max_vel_y_ = kinematics.base_max_vel_y_ * ratio;
180 kinematics.max_vel_theta_ = kinematics.base_max_vel_theta_ * ratio;
186 kinematics.max_speed_xy_sq_ = kinematics.max_speed_xy_ * kinematics.max_speed_xy_;
188 update_kinematics(kinematics);
192 std::vector<rclcpp::Parameter> parameters)
194 rcl_interfaces::msg::SetParametersResult result;
195 result.successful =
true;
196 for (
auto parameter : parameters) {
197 const auto & param_type = parameter.get_type();
198 const auto & param_name = parameter.get_name();
199 if (param_name.find(plugin_name_ +
".") != 0) {
202 if (param_type == ParameterType::PARAMETER_DOUBLE) {
203 if (parameter.as_double() < 0.0 &&
204 (param_name == plugin_name_ +
".max_vel_x" || param_name == plugin_name_ +
".max_vel_y" ||
205 param_name == plugin_name_ +
".max_vel_theta" ||
206 param_name == plugin_name_ +
".max_speed_xy" ||
207 param_name == plugin_name_ +
".acc_lim_x" || param_name == plugin_name_ +
".acc_lim_y" ||
208 param_name == plugin_name_ +
".acc_lim_theta"))
211 logger_,
"The value of parameter '%s' is incorrectly set to %f, "
212 "it should be >= 0. Ignoring parameter update.",
213 param_name.c_str(), parameter.as_double());
214 result.successful =
false;
215 }
else if (parameter.as_double() > 0.0 &&
216 (param_name == plugin_name_ +
".decel_lim_x" ||
217 param_name == plugin_name_ +
".decel_lim_y" ||
218 param_name == plugin_name_ +
".decel_lim_theta"))
221 logger_,
"The value of parameter '%s' is incorrectly set to %f, "
222 "it should be <= 0. Ignoring parameter update.",
223 param_name.c_str(), parameter.as_double());
224 result.successful =
false;
234 rcl_interfaces::msg::SetParametersResult result;
237 for (
auto parameter : parameters) {
238 const auto & param_type = parameter.get_type();
239 const auto & param_name = parameter.get_name();
240 if (param_name.find(plugin_name_ +
".") != 0) {
244 if (param_type == ParameterType::PARAMETER_DOUBLE) {
245 if (param_name == plugin_name_ +
".min_vel_x") {
246 kinematics.min_vel_x_ = parameter.as_double();
247 }
else if (param_name == plugin_name_ +
".min_vel_y") {
248 kinematics.min_vel_y_ = parameter.as_double();
249 }
else if (param_name == plugin_name_ +
".max_vel_x") {
250 kinematics.max_vel_x_ = parameter.as_double();
251 kinematics.base_max_vel_x_ = kinematics.max_vel_x_;
252 }
else if (param_name == plugin_name_ +
".max_vel_y") {
253 kinematics.max_vel_y_ = parameter.as_double();
254 kinematics.base_max_vel_y_ = kinematics.max_vel_y_;
255 }
else if (param_name == plugin_name_ +
".max_vel_theta") {
256 kinematics.max_vel_theta_ = parameter.as_double();
257 kinematics.base_max_vel_theta_ = kinematics.max_vel_theta_;
258 }
else if (param_name == plugin_name_ +
".min_speed_xy") {
259 kinematics.min_speed_xy_ = parameter.as_double();
260 kinematics.min_speed_xy_sq_ = kinematics.min_speed_xy_ * kinematics.min_speed_xy_;
261 }
else if (param_name == plugin_name_ +
".max_speed_xy") {
262 kinematics.max_speed_xy_ = parameter.as_double();
263 kinematics.base_max_speed_xy_ = kinematics.max_speed_xy_;
264 }
else if (param_name == plugin_name_ +
".min_speed_theta") {
265 kinematics.min_speed_theta_ = parameter.as_double();
266 kinematics.max_speed_xy_sq_ = kinematics.max_speed_xy_ * kinematics.max_speed_xy_;
267 }
else if (param_name == plugin_name_ +
".acc_lim_x") {
268 kinematics.acc_lim_x_ = parameter.as_double();
269 }
else if (param_name == plugin_name_ +
".acc_lim_y") {
270 kinematics.acc_lim_y_ = parameter.as_double();
271 }
else if (param_name == plugin_name_ +
".acc_lim_theta") {
272 kinematics.acc_lim_theta_ = parameter.as_double();
273 }
else if (param_name == plugin_name_ +
".decel_lim_x") {
274 kinematics.decel_lim_x_ = parameter.as_double();
275 }
else if (param_name == plugin_name_ +
".decel_lim_y") {
276 kinematics.decel_lim_y_ = parameter.as_double();
277 }
else if (param_name == plugin_name_ +
".decel_lim_theta") {
278 kinematics.decel_lim_theta_ = parameter.as_double();
282 update_kinematics(kinematics);
287 delete kinematics_.load();
rcl_interfaces::msg::SetParametersResult validateParameterUpdatesCallback(std::vector< rclcpp::Parameter > parameters)
Validate incoming parameter updates before applying them. This callback is triggered when one or more...
void updateParametersCallback(std::vector< rclcpp::Parameter > parameters)
Apply parameter updates after validation This callback is executed when parameters have been successf...
A struct containing one representation of the robot's kinematics.