Skip to content

Commit a31ff42

Browse files
committed
Add acceleration limits to DriveOnHeading and BackUp behaviors (ros-navigation#4810)
* Add acceleration constraints Signed-off-by: RBT22 <rozgonyibalint@gmail.com> * Cleanup code Signed-off-by: RBT22 <rozgonyibalint@gmail.com> * Format code Signed-off-by: RBT22 <rozgonyibalint@gmail.com> * Add <limits> header to drive_on_heading.hpp Signed-off-by: RBT22 <rozgonyibalint@gmail.com> * Remove vel pointer Signed-off-by: RBT22 <rozgonyibalint@gmail.com> * Use the limits only if both of them is set Signed-off-by: RBT22 <rozgonyibalint@gmail.com> * Fix onActionCompletion params Signed-off-by: RBT22 <rozgonyibalint@gmail.com> * Add default acc params and change decel sign Signed-off-by: RBT22 <rozgonyibalint@gmail.com> * Add minimum speed parameter Signed-off-by: RBT22 <rozgonyibalint@gmail.com> * Update minimum speed parameter to 0.10 Signed-off-by: RBT22 <rozgonyibalint@gmail.com> * Log warning when acceleration or deceleration limits are not set Signed-off-by: RBT22 <rozgonyibalint@gmail.com> * Add param sign assert Signed-off-by: RBT22 <rozgonyibalint@gmail.com> * Remove unnecessary param checking Signed-off-by: RBT22 <rozgonyibalint@gmail.com> * Refactor acceleration limits to handle forward and backward movement separately Signed-off-by: RBT22 <rozgonyibalint@gmail.com> * Fix sign checking condition Signed-off-by: RBT22 <rozgonyibalint@gmail.com> * Replace throwing with silent sign correction Signed-off-by: RBT22 <rozgonyibalint@gmail.com> --------- Signed-off-by: RBT22 <rozgonyibalint@gmail.com>
1 parent 30f2163 commit a31ff42

File tree

2 files changed

+63
-1
lines changed

2 files changed

+63
-1
lines changed

‎nav2_behaviors/include/nav2_behaviors/plugins/drive_on_heading.hpp‎

Lines changed: 57 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919
#include <chrono>
2020
#include <memory>
2121
#include <utility>
22+
#include <limits>
2223

2324
#include "nav2_behaviors/timed_behavior.hpp"
2425
#include "nav2_msgs/action/drive_on_heading.hpp"
@@ -126,7 +127,30 @@ class DriveOnHeading : public TimedBehavior<ActionT>
126127
auto cmd_vel = std::make_unique<geometry_msgs::msg::Twist>();
127128
cmd_vel->linear.y = 0.0;
128129
cmd_vel->angular.z = 0.0;
129-
cmd_vel->linear.x = command_speed_;
130+
131+
double current_speed = last_vel_ == std::numeric_limits<double>::max() ? 0.0 : last_vel_;
132+
bool forward = command_speed_ > 0.0;
133+
double min_feasible_speed, max_feasible_speed;
134+
if (forward) {
135+
min_feasible_speed = current_speed + deceleration_limit_ / this->cycle_frequency_;
136+
max_feasible_speed = current_speed + acceleration_limit_ / this->cycle_frequency_;
137+
} else {
138+
min_feasible_speed = current_speed - acceleration_limit_ / this->cycle_frequency_;
139+
max_feasible_speed = current_speed - deceleration_limit_ / this->cycle_frequency_;
140+
}
141+
cmd_vel->linear.x = std::clamp(command_speed_, min_feasible_speed, max_feasible_speed);
142+
143+
// Check if we need to slow down to avoid overshooting
144+
auto remaining_distance = std::fabs(command_x_) - distance;
145+
double max_vel_to_stop = std::sqrt(-2.0 * deceleration_limit_ * remaining_distance);
146+
if (max_vel_to_stop < std::abs(cmd_vel->linear.x)) {
147+
cmd_vel->linear.x = forward ? max_vel_to_stop : -max_vel_to_stop;
148+
}
149+
150+
// Ensure we don't go below minimum speed
151+
if (std::fabs(cmd_vel->linear.x) < minimum_speed_) {
152+
cmd_vel->linear.x = forward ? minimum_speed_ : -minimum_speed_;
153+
}
130154

131155
geometry_msgs::msg::Pose2D pose2d;
132156
pose2d.x = current_pose.pose.position.x;
@@ -139,11 +163,19 @@ class DriveOnHeading : public TimedBehavior<ActionT>
139163
return Status::FAILED;
140164
}
141165

166+
last_vel_ = cmd_vel->linear.x;
142167
this->vel_pub_->publish(std::move(cmd_vel));
143168

144169
return Status::RUNNING;
145170
}
146171

172+
void onCleanup() override {last_vel_ = std::numeric_limits<double>::max();}
173+
174+
void onActionCompletion() override
175+
{
176+
last_vel_ = std::numeric_limits<double>::max();
177+
}
178+
147179
protected:
148180
/**
149181
* @brief Check if pose is collision free
@@ -197,6 +229,26 @@ class DriveOnHeading : public TimedBehavior<ActionT>
197229
node,
198230
"simulate_ahead_time", rclcpp::ParameterValue(2.0));
199231
node->get_parameter("simulate_ahead_time", simulate_ahead_time_);
232+
233+
nav2_util::declare_parameter_if_not_declared(
234+
node, this->behavior_name_ + ".acceleration_limit",
235+
rclcpp::ParameterValue(2.5));
236+
nav2_util::declare_parameter_if_not_declared(
237+
node, this->behavior_name_ + ".deceleration_limit",
238+
rclcpp::ParameterValue(-2.5));
239+
nav2_util::declare_parameter_if_not_declared(
240+
node, this->behavior_name_ + ".minimum_speed",
241+
rclcpp::ParameterValue(0.10));
242+
node->get_parameter(this->behavior_name_ + ".acceleration_limit", acceleration_limit_);
243+
node->get_parameter(this->behavior_name_ + ".deceleration_limit", deceleration_limit_);
244+
node->get_parameter(this->behavior_name_ + ".minimum_speed", minimum_speed_);
245+
if (acceleration_limit_ <= 0.0 || deceleration_limit_ >= 0.0) {
246+
RCLCPP_ERROR(this->logger_,
247+
"DriveOnHeading: acceleration_limit and deceleration_limit must be "
248+
"positive and negative respectively");
249+
acceleration_limit_ = std::abs(acceleration_limit_);
250+
deceleration_limit_ = -std::abs(deceleration_limit_);
251+
}
200252
}
201253

202254
typename ActionT::Feedback::SharedPtr feedback_;
@@ -207,6 +259,10 @@ class DriveOnHeading : public TimedBehavior<ActionT>
207259
rclcpp::Duration command_time_allowance_{0, 0};
208260
rclcpp::Time end_time_;
209261
double simulate_ahead_time_;
262+
double acceleration_limit_;
263+
double deceleration_limit_;
264+
double minimum_speed_;
265+
double last_vel_ = std::numeric_limits<double>::max();
210266
};
211267

212268
} // namespace nav2_behaviors

‎nav2_bringup/params/nav2_params.yaml‎

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -304,8 +304,14 @@ behavior_server:
304304
plugin: "nav2_behaviors/Spin"
305305
backup:
306306
plugin: "nav2_behaviors/BackUp"
307+
acceleration_limit: 2.5
308+
deceleration_limit: -2.5
309+
minimum_speed: 0.10
307310
drive_on_heading:
308311
plugin: "nav2_behaviors/DriveOnHeading"
312+
acceleration_limit: 2.5
313+
deceleration_limit: -2.5
314+
minimum_speed: 0.10
309315
wait:
310316
plugin: "nav2_behaviors/Wait"
311317
assisted_teleop:

0 commit comments

Comments
 (0)