Skip to content

Commit aabad9a

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

File tree

1 file changed

+62
-1
lines changed

1 file changed

+62
-1
lines changed

nav2_behaviors/include/nav2_behaviors/plugins/drive_on_heading.hpp

Lines changed: 62 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,35 @@ 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+
bool forward = command_speed_ > 0.0;
132+
if (acceleration_limit_ == 0.0 || deceleration_limit_ == 0.0) {
133+
RCLCPP_INFO_ONCE(this->logger_, "DriveOnHeading: no acceleration or deceleration limits set");
134+
cmd_vel->linear.x = command_speed_;
135+
} else {
136+
double current_speed = last_vel_ == std::numeric_limits<double>::max() ? 0.0 : last_vel_;
137+
double min_feasible_speed, max_feasible_speed;
138+
if (forward) {
139+
min_feasible_speed = current_speed + deceleration_limit_ / this->cycle_frequency_;
140+
max_feasible_speed = current_speed + acceleration_limit_ / this->cycle_frequency_;
141+
} else {
142+
min_feasible_speed = current_speed - acceleration_limit_ / this->cycle_frequency_;
143+
max_feasible_speed = current_speed - deceleration_limit_ / this->cycle_frequency_;
144+
}
145+
cmd_vel->linear.x = std::clamp(command_speed_, min_feasible_speed, max_feasible_speed);
146+
147+
// Check if we need to slow down to avoid overshooting
148+
auto remaining_distance = std::fabs(command_x_) - distance;
149+
double max_vel_to_stop = std::sqrt(-2.0 * deceleration_limit_ * remaining_distance);
150+
if (max_vel_to_stop < std::abs(cmd_vel->linear.x)) {
151+
cmd_vel->linear.x = forward ? max_vel_to_stop : -max_vel_to_stop;
152+
}
153+
}
154+
155+
// Ensure we don't go below minimum speed
156+
if (std::fabs(cmd_vel->linear.x) < minimum_speed_) {
157+
cmd_vel->linear.x = forward ? minimum_speed_ : -minimum_speed_;
158+
}
130159

131160
geometry_msgs::msg::Pose2D pose2d;
132161
pose2d.x = current_pose.pose.position.x;
@@ -139,11 +168,19 @@ class DriveOnHeading : public TimedBehavior<ActionT>
139168
return Status::FAILED;
140169
}
141170

171+
last_vel_ = cmd_vel->linear.x;
142172
this->vel_pub_->publish(std::move(cmd_vel));
143173

144174
return Status::RUNNING;
145175
}
146176

177+
void onCleanup() override {last_vel_ = std::numeric_limits<double>::max();}
178+
179+
void onActionCompletion() override
180+
{
181+
last_vel_ = std::numeric_limits<double>::max();
182+
}
183+
147184
protected:
148185
/**
149186
* @brief Check if pose is collision free
@@ -197,6 +234,26 @@ class DriveOnHeading : public TimedBehavior<ActionT>
197234
node,
198235
"simulate_ahead_time", rclcpp::ParameterValue(2.0));
199236
node->get_parameter("simulate_ahead_time", simulate_ahead_time_);
237+
238+
nav2_util::declare_parameter_if_not_declared(
239+
node, this->behavior_name_ + ".acceleration_limit",
240+
rclcpp::ParameterValue(0.0));
241+
nav2_util::declare_parameter_if_not_declared(
242+
node, this->behavior_name_ + ".deceleration_limit",
243+
rclcpp::ParameterValue(0.0));
244+
nav2_util::declare_parameter_if_not_declared(
245+
node, this->behavior_name_ + ".minimum_speed",
246+
rclcpp::ParameterValue(0.0));
247+
node->get_parameter(this->behavior_name_ + ".acceleration_limit", acceleration_limit_);
248+
node->get_parameter(this->behavior_name_ + ".deceleration_limit", deceleration_limit_);
249+
node->get_parameter(this->behavior_name_ + ".minimum_speed", minimum_speed_);
250+
if (acceleration_limit_ < 0.0 || deceleration_limit_ > 0.0) {
251+
RCLCPP_ERROR(this->logger_,
252+
"DriveOnHeading: acceleration_limit and deceleration_limit must be "
253+
"positive and negative respectively");
254+
acceleration_limit_ = std::abs(acceleration_limit_);
255+
deceleration_limit_ = -std::abs(deceleration_limit_);
256+
}
200257
}
201258

202259
typename ActionT::Feedback::SharedPtr feedback_;
@@ -207,6 +264,10 @@ class DriveOnHeading : public TimedBehavior<ActionT>
207264
rclcpp::Duration command_time_allowance_{0, 0};
208265
rclcpp::Time end_time_;
209266
double simulate_ahead_time_;
267+
double acceleration_limit_;
268+
double deceleration_limit_;
269+
double minimum_speed_;
270+
double last_vel_ = std::numeric_limits<double>::max();
210271
};
211272

212273
} // namespace nav2_behaviors

0 commit comments

Comments
 (0)