diff --git a/nav2_behaviors/include/nav2_behaviors/plugins/drive_on_heading.hpp b/nav2_behaviors/include/nav2_behaviors/plugins/drive_on_heading.hpp index 8bffca8ae5..cc0219fcfc 100644 --- a/nav2_behaviors/include/nav2_behaviors/plugins/drive_on_heading.hpp +++ b/nav2_behaviors/include/nav2_behaviors/plugins/drive_on_heading.hpp @@ -126,7 +126,35 @@ class DriveOnHeading : public TimedBehavior auto cmd_vel = std::make_unique(); cmd_vel->linear.y = 0.0; cmd_vel->angular.z = 0.0; - cmd_vel->linear.x = command_speed_; + if (acceleration_limit_ <= 0.0 && deceleration_limit_ <= 0.0) { + cmd_vel->linear.x = command_speed_; + } else { + double current_speed = last_vel_ ? *last_vel_ : 0.0; + auto remaining_distance = std::fabs(command_x_) - distance; + double min_feasible_speed = -std::numeric_limits::infinity(); + double max_feasible_speed = std::numeric_limits::infinity(); + if (deceleration_limit_ > 0.0) { + min_feasible_speed = current_speed - deceleration_limit_ / this->cycle_frequency_; + } + if (acceleration_limit_ > 0.0) { + max_feasible_speed = current_speed + acceleration_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 + bool forward = command_speed_ > 0.0 ? true : false; + if ((forward && deceleration_limit_ > 0.0)) { + double max_vel_to_stop = std::sqrt(2.0 * deceleration_limit_ * remaining_distance); + if (max_vel_to_stop < cmd_vel->linear.x) { + cmd_vel->linear.x = max_vel_to_stop; + } + } else if ((!forward && acceleration_limit_ > 0.0)) { + double max_vel_to_stop = -std::sqrt(2.0 * acceleration_limit_ * remaining_distance); + if (max_vel_to_stop > cmd_vel->linear.x) { + cmd_vel->linear.x = max_vel_to_stop; + } + } + } geometry_msgs::msg::Pose2D pose2d; pose2d.x = current_pose.pose.position.x; @@ -139,11 +167,23 @@ class DriveOnHeading : public TimedBehavior return ResultStatus{Status::FAILED, ActionT::Goal::COLLISION_AHEAD}; } + last_vel_ = std::make_shared(cmd_vel->linear.x); + this->vel_pub_->publish(std::move(cmd_vel)); return ResultStatus{Status::RUNNING, ActionT::Goal::NONE}; } + void onCleanup() override + { + last_vel_.reset(); + } + + void onActionCompletion() override + { + last_vel_.reset(); + } + protected: /** * @brief Check if pose is collision free @@ -198,6 +238,15 @@ class DriveOnHeading : public TimedBehavior node, sim_ahead_time, rclcpp::ParameterValue(2.0)); node->get_parameter(sim_ahead_time, simulate_ahead_time_); + + nav2_util::declare_parameter_if_not_declared( + node, this->behavior_name_ + ".acceleration_limit", + rclcpp::ParameterValue(0.0)); + nav2_util::declare_parameter_if_not_declared( + node, this->behavior_name_ + ".deceleration_limit", + rclcpp::ParameterValue(0.0)); + node->get_parameter(this->behavior_name_ + ".acceleration_limit", acceleration_limit_); + node->get_parameter(this->behavior_name_ + ".deceleration_limit", deceleration_limit_); } typename ActionT::Feedback::SharedPtr feedback_; @@ -208,6 +257,9 @@ class DriveOnHeading : public TimedBehavior rclcpp::Duration command_time_allowance_{0, 0}; rclcpp::Time end_time_; double simulate_ahead_time_; + double acceleration_limit_; + double deceleration_limit_; + std::shared_ptr last_vel_; }; } // namespace nav2_behaviors