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 auto node = node_.lock();
59 if (dyn_params_handler_ && node) {
60 node->remove_on_set_parameters_callback(dyn_params_handler_.get());
62 dyn_params_handler_.reset();
63 delete kinematics_.load();
66 void KinematicsHandler::initialize(
67 const nav2::LifecycleNode::SharedPtr & nh,
68 const std::string & plugin_name)
71 plugin_name_ = plugin_name;
73 declare_parameter_if_not_declared(nh, plugin_name +
".min_vel_x", rclcpp::ParameterValue(0.0));
74 declare_parameter_if_not_declared(nh, plugin_name +
".min_vel_y", rclcpp::ParameterValue(0.0));
75 declare_parameter_if_not_declared(nh, plugin_name +
".max_vel_x", rclcpp::ParameterValue(0.0));
76 declare_parameter_if_not_declared(nh, plugin_name +
".max_vel_y", rclcpp::ParameterValue(0.0));
77 declare_parameter_if_not_declared(
78 nh, plugin_name +
".max_vel_theta",
79 rclcpp::ParameterValue(0.0));
80 declare_parameter_if_not_declared(
81 nh, plugin_name +
".min_speed_xy",
82 rclcpp::ParameterValue(0.0));
83 declare_parameter_if_not_declared(
84 nh, plugin_name +
".max_speed_xy",
85 rclcpp::ParameterValue(0.0));
86 declare_parameter_if_not_declared(
87 nh, plugin_name +
".min_speed_theta",
88 rclcpp::ParameterValue(0.0));
89 declare_parameter_if_not_declared(nh, plugin_name +
".acc_lim_x", rclcpp::ParameterValue(0.0));
90 declare_parameter_if_not_declared(nh, plugin_name +
".acc_lim_y", rclcpp::ParameterValue(0.0));
91 declare_parameter_if_not_declared(
92 nh, plugin_name +
".acc_lim_theta",
93 rclcpp::ParameterValue(0.0));
94 declare_parameter_if_not_declared(nh, plugin_name +
".decel_lim_x", rclcpp::ParameterValue(0.0));
95 declare_parameter_if_not_declared(nh, plugin_name +
".decel_lim_y", rclcpp::ParameterValue(0.0));
96 declare_parameter_if_not_declared(
97 nh, plugin_name +
".decel_lim_theta",
98 rclcpp::ParameterValue(0.0));
100 KinematicParameters kinematics;
102 nh->get_parameter(plugin_name +
".min_vel_x", kinematics.min_vel_x_);
103 nh->get_parameter(plugin_name +
".min_vel_y", kinematics.min_vel_y_);
104 nh->get_parameter(plugin_name +
".max_vel_x", kinematics.max_vel_x_);
105 nh->get_parameter(plugin_name +
".max_vel_y", kinematics.max_vel_y_);
106 nh->get_parameter(plugin_name +
".max_vel_theta", kinematics.max_vel_theta_);
107 nh->get_parameter(plugin_name +
".min_speed_xy", kinematics.min_speed_xy_);
108 nh->get_parameter(plugin_name +
".max_speed_xy", kinematics.max_speed_xy_);
109 nh->get_parameter(plugin_name +
".min_speed_theta", kinematics.min_speed_theta_);
110 nh->get_parameter(plugin_name +
".acc_lim_x", kinematics.acc_lim_x_);
111 nh->get_parameter(plugin_name +
".acc_lim_y", kinematics.acc_lim_y_);
112 nh->get_parameter(plugin_name +
".acc_lim_theta", kinematics.acc_lim_theta_);
113 nh->get_parameter(plugin_name +
".decel_lim_x", kinematics.decel_lim_x_);
114 nh->get_parameter(plugin_name +
".decel_lim_y", kinematics.decel_lim_y_);
115 nh->get_parameter(plugin_name +
".decel_lim_theta", kinematics.decel_lim_theta_);
117 kinematics.base_max_vel_x_ = kinematics.max_vel_x_;
118 kinematics.base_max_vel_y_ = kinematics.max_vel_y_;
119 kinematics.base_max_speed_xy_ = kinematics.max_speed_xy_;
120 kinematics.base_max_vel_theta_ = kinematics.max_vel_theta_;
123 dyn_params_handler_ = nh->add_on_set_parameters_callback(
126 kinematics.min_speed_xy_sq_ = kinematics.min_speed_xy_ * kinematics.min_speed_xy_;
127 kinematics.max_speed_xy_sq_ = kinematics.max_speed_xy_ * kinematics.max_speed_xy_;
129 update_kinematics(kinematics);
132 void KinematicsHandler::setSpeedLimit(
133 const double & speed_limit,
const bool & percentage)
135 KinematicParameters kinematics(*kinematics_.load());
137 if (speed_limit == nav2_costmap_2d::NO_SPEED_LIMIT) {
139 kinematics.max_speed_xy_ = kinematics.base_max_speed_xy_;
140 kinematics.max_vel_x_ = kinematics.base_max_vel_x_;
141 kinematics.max_vel_y_ = kinematics.base_max_vel_y_;
142 kinematics.max_vel_theta_ = kinematics.base_max_vel_theta_;
146 kinematics.max_speed_xy_ = kinematics.base_max_speed_xy_ * speed_limit / 100.0;
147 kinematics.max_vel_x_ = kinematics.base_max_vel_x_ * speed_limit / 100.0;
148 kinematics.max_vel_y_ = kinematics.base_max_vel_y_ * speed_limit / 100.0;
149 kinematics.max_vel_theta_ = kinematics.base_max_vel_theta_ * speed_limit / 100.0;
152 if (speed_limit < kinematics.base_max_speed_xy_) {
153 kinematics.max_speed_xy_ = speed_limit;
158 const double ratio = speed_limit / kinematics.base_max_speed_xy_;
159 kinematics.max_vel_x_ = kinematics.base_max_vel_x_ * ratio;
160 kinematics.max_vel_y_ = kinematics.base_max_vel_y_ * ratio;
161 kinematics.max_vel_theta_ = kinematics.base_max_vel_theta_ * ratio;
167 kinematics.max_speed_xy_sq_ = kinematics.max_speed_xy_ * kinematics.max_speed_xy_;
169 update_kinematics(kinematics);
172 rcl_interfaces::msg::SetParametersResult
175 rcl_interfaces::msg::SetParametersResult result;
178 for (
auto parameter : parameters) {
179 const auto & param_type = parameter.get_type();
180 const auto & param_name = parameter.get_name();
181 if (param_name.find(plugin_name_ +
".") != 0) {
185 if (param_type == ParameterType::PARAMETER_DOUBLE) {
186 if (param_name == plugin_name_ +
".min_vel_x") {
187 kinematics.min_vel_x_ = parameter.as_double();
188 }
else if (param_name == plugin_name_ +
".min_vel_y") {
189 kinematics.min_vel_y_ = parameter.as_double();
190 }
else if (param_name == plugin_name_ +
".max_vel_x") {
191 kinematics.max_vel_x_ = parameter.as_double();
192 kinematics.base_max_vel_x_ = kinematics.max_vel_x_;
193 }
else if (param_name == plugin_name_ +
".max_vel_y") {
194 kinematics.max_vel_y_ = parameter.as_double();
195 kinematics.base_max_vel_y_ = kinematics.max_vel_y_;
196 }
else if (param_name == plugin_name_ +
".max_vel_theta") {
197 kinematics.max_vel_theta_ = parameter.as_double();
198 kinematics.base_max_vel_theta_ = kinematics.max_vel_theta_;
199 }
else if (param_name == plugin_name_ +
".min_speed_xy") {
200 kinematics.min_speed_xy_ = parameter.as_double();
201 kinematics.min_speed_xy_sq_ = kinematics.min_speed_xy_ * kinematics.min_speed_xy_;
202 }
else if (param_name == plugin_name_ +
".max_speed_xy") {
203 kinematics.max_speed_xy_ = parameter.as_double();
204 kinematics.base_max_speed_xy_ = kinematics.max_speed_xy_;
205 }
else if (param_name == plugin_name_ +
".min_speed_theta") {
206 kinematics.min_speed_theta_ = parameter.as_double();
207 kinematics.max_speed_xy_sq_ = kinematics.max_speed_xy_ * kinematics.max_speed_xy_;
208 }
else if (param_name == plugin_name_ +
".acc_lim_x") {
209 kinematics.acc_lim_x_ = parameter.as_double();
210 }
else if (param_name == plugin_name_ +
".acc_lim_y") {
211 kinematics.acc_lim_y_ = parameter.as_double();
212 }
else if (param_name == plugin_name_ +
".acc_lim_theta") {
213 kinematics.acc_lim_theta_ = parameter.as_double();
214 }
else if (param_name == plugin_name_ +
".decel_lim_x") {
215 kinematics.decel_lim_x_ = parameter.as_double();
216 }
else if (param_name == plugin_name_ +
".decel_lim_y") {
217 kinematics.decel_lim_y_ = parameter.as_double();
218 }
else if (param_name == plugin_name_ +
".decel_lim_theta") {
219 kinematics.decel_lim_theta_ = parameter.as_double();
223 update_kinematics(kinematics);
224 result.successful =
true;
230 delete kinematics_.load();
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
A struct containing one representation of the robot's kinematics.