Skip to content

Commit

Permalink
Add acceleration limits to DriveOnHeading and BackUp behaviors (#4810)
Browse files Browse the repository at this point in the history
* 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]>
(cherry picked from commit 2ee3cef)
  • Loading branch information
RBT22 authored and mergify[bot] committed Jan 28, 2025
1 parent 9a5689e commit 72ed627
Show file tree
Hide file tree
Showing 2 changed files with 64 additions and 1 deletion.
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
#include <chrono>
#include <memory>
#include <utility>
#include <limits>

#include "nav2_behaviors/timed_behavior.hpp"
#include "nav2_msgs/action/drive_on_heading.hpp"
Expand Down Expand Up @@ -131,7 +132,30 @@ class DriveOnHeading : public TimedBehavior<ActionT>
cmd_vel->header.frame_id = this->robot_base_frame_;
cmd_vel->twist.linear.y = 0.0;
cmd_vel->twist.angular.z = 0.0;
cmd_vel->twist.linear.x = command_speed_;

double current_speed = last_vel_ == std::numeric_limits<double>::max() ? 0.0 : last_vel_;
bool forward = command_speed_ > 0.0;
double min_feasible_speed, max_feasible_speed;
if (forward) {
min_feasible_speed = current_speed + deceleration_limit_ / this->cycle_frequency_;
max_feasible_speed = current_speed + acceleration_limit_ / this->cycle_frequency_;
} else {
min_feasible_speed = current_speed - acceleration_limit_ / this->cycle_frequency_;
max_feasible_speed = current_speed - deceleration_limit_ / this->cycle_frequency_;
}
cmd_vel->twist.linear.x = std::clamp(command_speed_, min_feasible_speed, max_feasible_speed);

// Check if we need to slow down to avoid overshooting
auto remaining_distance = std::fabs(command_x_) - distance;
double max_vel_to_stop = std::sqrt(-2.0 * deceleration_limit_ * remaining_distance);
if (max_vel_to_stop < std::abs(cmd_vel->twist.linear.x)) {
cmd_vel->twist.linear.x = forward ? max_vel_to_stop : -max_vel_to_stop;
}

// Ensure we don't go below minimum speed
if (std::fabs(cmd_vel->twist.linear.x) < minimum_speed_) {
cmd_vel->twist.linear.x = forward ? minimum_speed_ : -minimum_speed_;
}

geometry_msgs::msg::Pose2D pose2d;
pose2d.x = current_pose.pose.position.x;
Expand All @@ -144,6 +168,7 @@ class DriveOnHeading : public TimedBehavior<ActionT>
return ResultStatus{Status::FAILED, ActionT::Result::COLLISION_AHEAD};
}

last_vel_ = cmd_vel->twist.linear.x;
this->vel_pub_->publish(std::move(cmd_vel));

return ResultStatus{Status::RUNNING, ActionT::Result::NONE};
Expand All @@ -155,6 +180,14 @@ class DriveOnHeading : public TimedBehavior<ActionT>
*/
CostmapInfoType getResourceInfo() override {return CostmapInfoType::LOCAL;}

void onCleanup() override {last_vel_ = std::numeric_limits<double>::max();}

void onActionCompletion(std::shared_ptr<typename ActionT::Result>/*result*/)
override
{
last_vel_ = std::numeric_limits<double>::max();
}

protected:
/**
* @brief Check if pose is collision free
Expand Down Expand Up @@ -208,6 +241,26 @@ class DriveOnHeading : public TimedBehavior<ActionT>
node,
"simulate_ahead_time", rclcpp::ParameterValue(2.0));
node->get_parameter("simulate_ahead_time", simulate_ahead_time_);

nav2_util::declare_parameter_if_not_declared(
node, this->behavior_name_ + ".acceleration_limit",
rclcpp::ParameterValue(2.5));
nav2_util::declare_parameter_if_not_declared(
node, this->behavior_name_ + ".deceleration_limit",
rclcpp::ParameterValue(-2.5));
nav2_util::declare_parameter_if_not_declared(
node, this->behavior_name_ + ".minimum_speed",
rclcpp::ParameterValue(0.10));
node->get_parameter(this->behavior_name_ + ".acceleration_limit", acceleration_limit_);
node->get_parameter(this->behavior_name_ + ".deceleration_limit", deceleration_limit_);
node->get_parameter(this->behavior_name_ + ".minimum_speed", minimum_speed_);
if (acceleration_limit_ <= 0.0 || deceleration_limit_ >= 0.0) {
RCLCPP_ERROR(this->logger_,
"DriveOnHeading: acceleration_limit and deceleration_limit must be "
"positive and negative respectively");
acceleration_limit_ = std::abs(acceleration_limit_);
deceleration_limit_ = -std::abs(deceleration_limit_);
}
}

typename ActionT::Feedback::SharedPtr feedback_;
Expand All @@ -218,6 +271,10 @@ class DriveOnHeading : public TimedBehavior<ActionT>
rclcpp::Duration command_time_allowance_{0, 0};
rclcpp::Time end_time_;
double simulate_ahead_time_;
double acceleration_limit_;
double deceleration_limit_;
double minimum_speed_;
double last_vel_ = std::numeric_limits<double>::max();
};

} // namespace nav2_behaviors
Expand Down
6 changes: 6 additions & 0 deletions nav2_bringup/params/nav2_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -305,8 +305,14 @@ behavior_server:
plugin: "nav2_behaviors::Spin"
backup:
plugin: "nav2_behaviors::BackUp"
acceleration_limit: 2.5
deceleration_limit: -2.5
minimum_speed: 0.10
drive_on_heading:
plugin: "nav2_behaviors::DriveOnHeading"
acceleration_limit: 2.5
deceleration_limit: -2.5
minimum_speed: 0.10
wait:
plugin: "nav2_behaviors::Wait"
assisted_teleop:
Expand Down

0 comments on commit 72ed627

Please sign in to comment.