35 #include "dwb_plugins/kinematic_parameters.hpp"
41 #include "nav_2d_utils/parameters.hpp"
42 #include "nav2_util/node_utils.hpp"
43 #include "nav2_costmap_2d/costmap_filters/filter_values.hpp"
45 using nav2_util::declare_parameter_if_not_declared;
46 using rcl_interfaces::msg::ParameterType;
47 using std::placeholders::_1;
52 KinematicsHandler::KinematicsHandler()
54 kinematics_.store(
new KinematicParameters);
57 KinematicsHandler::~KinematicsHandler()
59 auto node = node_.lock();
60 if (dyn_params_handler_ && node) {
61 node->remove_on_set_parameters_callback(dyn_params_handler_.get());
63 dyn_params_handler_.reset();
64 delete kinematics_.load();
67 void KinematicsHandler::initialize(
68 const nav2_util::LifecycleNode::SharedPtr & nh,
69 const std::string & plugin_name)
72 plugin_name_ = plugin_name;
74 declare_parameter_if_not_declared(nh, plugin_name +
".min_vel_x", rclcpp::ParameterValue(0.0));
75 declare_parameter_if_not_declared(nh, plugin_name +
".min_vel_y", rclcpp::ParameterValue(0.0));
76 declare_parameter_if_not_declared(nh, plugin_name +
".max_vel_x", rclcpp::ParameterValue(0.0));
77 declare_parameter_if_not_declared(nh, plugin_name +
".max_vel_y", rclcpp::ParameterValue(0.0));
78 declare_parameter_if_not_declared(
79 nh, plugin_name +
".max_vel_theta",
80 rclcpp::ParameterValue(0.0));
81 declare_parameter_if_not_declared(
82 nh, plugin_name +
".min_speed_xy",
83 rclcpp::ParameterValue(0.0));
84 declare_parameter_if_not_declared(
85 nh, plugin_name +
".max_speed_xy",
86 rclcpp::ParameterValue(0.0));
87 declare_parameter_if_not_declared(
88 nh, plugin_name +
".min_speed_theta",
89 rclcpp::ParameterValue(0.0));
90 declare_parameter_if_not_declared(nh, plugin_name +
".acc_lim_x", rclcpp::ParameterValue(0.0));
91 declare_parameter_if_not_declared(nh, plugin_name +
".acc_lim_y", rclcpp::ParameterValue(0.0));
92 declare_parameter_if_not_declared(
93 nh, plugin_name +
".acc_lim_theta",
94 rclcpp::ParameterValue(0.0));
95 declare_parameter_if_not_declared(nh, plugin_name +
".decel_lim_x", rclcpp::ParameterValue(0.0));
96 declare_parameter_if_not_declared(nh, plugin_name +
".decel_lim_y", rclcpp::ParameterValue(0.0));
97 declare_parameter_if_not_declared(
98 nh, plugin_name +
".decel_lim_theta",
99 rclcpp::ParameterValue(0.0));
101 KinematicParameters kinematics;
103 nh->get_parameter(plugin_name +
".min_vel_x", kinematics.min_vel_x_);
104 nh->get_parameter(plugin_name +
".min_vel_y", kinematics.min_vel_y_);
105 nh->get_parameter(plugin_name +
".max_vel_x", kinematics.max_vel_x_);
106 nh->get_parameter(plugin_name +
".max_vel_y", kinematics.max_vel_y_);
107 nh->get_parameter(plugin_name +
".max_vel_theta", kinematics.max_vel_theta_);
108 nh->get_parameter(plugin_name +
".min_speed_xy", kinematics.min_speed_xy_);
109 nh->get_parameter(plugin_name +
".max_speed_xy", kinematics.max_speed_xy_);
110 nh->get_parameter(plugin_name +
".min_speed_theta", kinematics.min_speed_theta_);
111 nh->get_parameter(plugin_name +
".acc_lim_x", kinematics.acc_lim_x_);
112 nh->get_parameter(plugin_name +
".acc_lim_y", kinematics.acc_lim_y_);
113 nh->get_parameter(plugin_name +
".acc_lim_theta", kinematics.acc_lim_theta_);
114 nh->get_parameter(plugin_name +
".decel_lim_x", kinematics.decel_lim_x_);
115 nh->get_parameter(plugin_name +
".decel_lim_y", kinematics.decel_lim_y_);
116 nh->get_parameter(plugin_name +
".decel_lim_theta", kinematics.decel_lim_theta_);
118 kinematics.base_max_vel_x_ = kinematics.max_vel_x_;
119 kinematics.base_max_vel_y_ = kinematics.max_vel_y_;
120 kinematics.base_max_speed_xy_ = kinematics.max_speed_xy_;
121 kinematics.base_max_vel_theta_ = kinematics.max_vel_theta_;
124 dyn_params_handler_ = nh->add_on_set_parameters_callback(
127 kinematics.min_speed_xy_sq_ = kinematics.min_speed_xy_ * kinematics.min_speed_xy_;
128 kinematics.max_speed_xy_sq_ = kinematics.max_speed_xy_ * kinematics.max_speed_xy_;
130 update_kinematics(kinematics);
133 void KinematicsHandler::setSpeedLimit(
134 const double & speed_limit,
const bool & percentage)
136 KinematicParameters kinematics(*kinematics_.load());
138 if (speed_limit == nav2_costmap_2d::NO_SPEED_LIMIT) {
140 kinematics.max_speed_xy_ = kinematics.base_max_speed_xy_;
141 kinematics.max_vel_x_ = kinematics.base_max_vel_x_;
142 kinematics.max_vel_y_ = kinematics.base_max_vel_y_;
143 kinematics.max_vel_theta_ = kinematics.base_max_vel_theta_;
147 kinematics.max_speed_xy_ = kinematics.base_max_speed_xy_ * speed_limit / 100.0;
148 kinematics.max_vel_x_ = kinematics.base_max_vel_x_ * speed_limit / 100.0;
149 kinematics.max_vel_y_ = kinematics.base_max_vel_y_ * speed_limit / 100.0;
150 kinematics.max_vel_theta_ = kinematics.base_max_vel_theta_ * speed_limit / 100.0;
153 if (speed_limit < kinematics.base_max_speed_xy_) {
154 kinematics.max_speed_xy_ = speed_limit;
159 const double ratio = speed_limit / kinematics.base_max_speed_xy_;
160 kinematics.max_vel_x_ = kinematics.base_max_vel_x_ * ratio;
161 kinematics.max_vel_y_ = kinematics.base_max_vel_y_ * ratio;
162 kinematics.max_vel_theta_ = kinematics.base_max_vel_theta_ * ratio;
168 kinematics.max_speed_xy_sq_ = kinematics.max_speed_xy_ * kinematics.max_speed_xy_;
170 update_kinematics(kinematics);
173 rcl_interfaces::msg::SetParametersResult
176 rcl_interfaces::msg::SetParametersResult result;
179 for (
auto parameter : parameters) {
180 const auto & type = parameter.get_type();
181 const auto & name = parameter.get_name();
183 if (type == ParameterType::PARAMETER_DOUBLE) {
184 if (name == plugin_name_ +
".min_vel_x") {
185 kinematics.min_vel_x_ = parameter.as_double();
186 }
else if (name == plugin_name_ +
".min_vel_y") {
187 kinematics.min_vel_y_ = parameter.as_double();
188 }
else if (name == plugin_name_ +
".max_vel_x") {
189 kinematics.max_vel_x_ = parameter.as_double();
190 kinematics.base_max_vel_x_ = kinematics.max_vel_x_;
191 }
else if (name == plugin_name_ +
".max_vel_y") {
192 kinematics.max_vel_y_ = parameter.as_double();
193 kinematics.base_max_vel_y_ = kinematics.max_vel_y_;
194 }
else if (name == plugin_name_ +
".max_vel_theta") {
195 kinematics.max_vel_theta_ = parameter.as_double();
196 kinematics.base_max_vel_theta_ = kinematics.max_vel_theta_;
197 }
else if (name == plugin_name_ +
".min_speed_xy") {
198 kinematics.min_speed_xy_ = parameter.as_double();
199 kinematics.min_speed_xy_sq_ = kinematics.min_speed_xy_ * kinematics.min_speed_xy_;
200 }
else if (name == plugin_name_ +
".max_speed_xy") {
201 kinematics.max_speed_xy_ = parameter.as_double();
202 kinematics.base_max_speed_xy_ = kinematics.max_speed_xy_;
203 }
else if (name == plugin_name_ +
".min_speed_theta") {
204 kinematics.min_speed_theta_ = parameter.as_double();
205 kinematics.max_speed_xy_sq_ = kinematics.max_speed_xy_ * kinematics.max_speed_xy_;
206 }
else if (name == plugin_name_ +
".acc_lim_x") {
207 kinematics.acc_lim_x_ = parameter.as_double();
208 }
else if (name == plugin_name_ +
".acc_lim_y") {
209 kinematics.acc_lim_y_ = parameter.as_double();
210 }
else if (name == plugin_name_ +
".acc_lim_theta") {
211 kinematics.acc_lim_theta_ = parameter.as_double();
212 }
else if (name == plugin_name_ +
".decel_lim_x") {
213 kinematics.decel_lim_x_ = parameter.as_double();
214 }
else if (name == plugin_name_ +
".decel_lim_y") {
215 kinematics.decel_lim_y_ = parameter.as_double();
216 }
else if (name == plugin_name_ +
".decel_lim_theta") {
217 kinematics.decel_lim_theta_ = parameter.as_double();
221 update_kinematics(kinematics);
222 result.successful =
true;
228 delete kinematics_.load();
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a paramter change is detected.
A struct containing one representation of the robot's kinematics.