diff --git a/cfg/TebLocalPlannerReconfigure.cfg b/cfg/TebLocalPlannerReconfigure.cfg index fe310357..7d38c79b 100755 --- a/cfg/TebLocalPlannerReconfigure.cfg +++ b/cfg/TebLocalPlannerReconfigure.cfg @@ -92,6 +92,10 @@ grp_robot.add("max_vel_x", double_t, 0, "Maximum translational velocity of the robot", 0.4, 0.01, 100) +grp_robot.add("min_vel_x", double_t, 0, + "Minimum translational velocity of the robot", + 0.00, 0.00, 100) + grp_robot.add("max_vel_x_backwards", double_t, 0, "Maximum translational velocity of the robot for driving backwards", 0.2, 0.01, 100) diff --git a/include/teb_local_planner/teb_config.h b/include/teb_local_planner/teb_config.h index cc7c531b..1231eb3a 100644 --- a/include/teb_local_planner/teb_config.h +++ b/include/teb_local_planner/teb_config.h @@ -93,6 +93,7 @@ class TebConfig struct Robot { double max_vel_x; //!< Maximum translational velocity of the robot + double min_vel_x; //!< Minimum translational velocity of the robot double max_vel_x_backwards; //!< Maximum translational velocity of the robot for driving backwards double max_vel_y; //!< Maximum strafing velocity of the robot (should be zero for non-holonomic robots!) double max_vel_theta; //!< Maximum angular velocity of the robot diff --git a/include/teb_local_planner/teb_local_planner_ros.h b/include/teb_local_planner/teb_local_planner_ros.h index 0fcc8494..ca12fe98 100644 --- a/include/teb_local_planner/teb_local_planner_ros.h +++ b/include/teb_local_planner/teb_local_planner_ros.h @@ -351,11 +351,12 @@ class TebLocalPlannerROS : public nav_core::BaseLocalPlanner, public mbf_costmap * @param[in,out] vy Strafing velocity which can be nonzero for holonomic robots * @param[in,out] omega The angular velocity that should be saturated. * @param max_vel_x Maximum translational velocity for forward driving + * @param min_vel_x Minimum translational velocity for forward driving * @param max_vel_y Maximum strafing velocity (for holonomic robots) * @param max_vel_theta Maximum (absolute) angular velocity * @param max_vel_x_backwards Maximum translational velocity for backwards driving */ - void saturateVelocity(double& vx, double& vy, double& omega, double max_vel_x, double max_vel_y, + void saturateVelocity(double& vx, double& vy, double& omega, double max_vel_x, double min_vel_x, double max_vel_y, double max_vel_theta, double max_vel_x_backwards) const; diff --git a/src/teb_config.cpp b/src/teb_config.cpp index a5e4d843..e3669a1b 100644 --- a/src/teb_config.cpp +++ b/src/teb_config.cpp @@ -72,6 +72,7 @@ void TebConfig::loadRosParamFromNodeHandle(const ros::NodeHandle& nh) // Robot nh.param("max_vel_x", robot.max_vel_x, robot.max_vel_x); + nh.param("min_vel_x", robot.min_vel_x, robot.min_vel_x); nh.param("max_vel_x_backwards", robot.max_vel_x_backwards, robot.max_vel_x_backwards); nh.param("max_vel_y", robot.max_vel_y, robot.max_vel_y); nh.param("max_vel_theta", robot.max_vel_theta, robot.max_vel_theta); @@ -199,10 +200,10 @@ void TebConfig::reconfigure(TebLocalPlannerReconfigureConfig& cfg) trajectory.feasibility_check_no_poses = cfg.feasibility_check_no_poses; trajectory.publish_feedback = cfg.publish_feedback; trajectory.control_look_ahead_poses = cfg.control_look_ahead_poses; - trajectory.prevent_look_ahead_poses_near_goal = cfg.prevent_look_ahead_poses_near_goal; // Robot robot.max_vel_x = cfg.max_vel_x; + robot.min_vel_x = cfg.min_vel_x; robot.max_vel_x_backwards = cfg.max_vel_x_backwards; robot.max_vel_y = cfg.max_vel_y; robot.max_vel_theta = cfg.max_vel_theta; diff --git a/src/teb_local_planner_ros.cpp b/src/teb_local_planner_ros.cpp index e83747ef..a65c166e 100644 --- a/src/teb_local_planner_ros.cpp +++ b/src/teb_local_planner_ros.cpp @@ -421,7 +421,7 @@ uint32_t TebLocalPlannerROS::computeVelocityCommands(const geometry_msgs::PoseSt // Saturate velocity, if the optimization results violates the constraints (could be possible due to soft constraints). saturateVelocity(cmd_vel.twist.linear.x, cmd_vel.twist.linear.y, cmd_vel.twist.angular.z, - cfg_.robot.max_vel_x, cfg_.robot.max_vel_y, cfg_.robot.max_vel_theta, cfg_.robot.max_vel_x_backwards); + cfg_.robot.max_vel_x, cfg_.robot.min_vel_x, cfg_.robot.max_vel_y, cfg_.robot.max_vel_theta, cfg_.robot.max_vel_x_backwards); // convert rot-vel to steering angle if desired (carlike robot). // The min_turning_radius is allowed to be slighly smaller since it is a soft-constraint @@ -869,12 +869,25 @@ double TebLocalPlannerROS::estimateLocalGoalOrientation(const std::vector max_vel_x) - ratio_x = max_vel_x / vx; + double ratio_x = 1, ratio_omega = 1, ratio_y = 1, ratio_x_min = 1; + + // backward driving + if (vx < 0) + { + if (vx < -max_vel_x_backwards) + ratio_x = -max_vel_x_backwards / vx; + else if (vx > -min_vel_x) + ratio_x = -min_vel_x / vx; + } + else // forward driving + { + if (vx > max_vel_x) + ratio_x = max_vel_x / vx; + else if (vx < min_vel_x) + ratio_x = min_vel_x / vx; + } // limit strafing velocity if (vy > max_vel_y || vy < -max_vel_y)