Skip to content
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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 @@ -126,7 +127,30 @@ class DriveOnHeading : public TimedBehavior<ActionT>
auto cmd_vel = std::make_unique<geometry_msgs::msg::Twist>();
cmd_vel->linear.y = 0.0;
cmd_vel->angular.z = 0.0;
cmd_vel->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->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->linear.x)) {
cmd_vel->linear.x = forward ? max_vel_to_stop : -max_vel_to_stop;
}

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

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

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

return Status::RUNNING;
}

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

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

protected:
/**
* @brief Check if pose is collision free
Expand Down Expand Up @@ -197,6 +229,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 @@ -207,6 +259,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 @@ -304,8 +304,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