<> <> == Road Map == The original implementation for this ROS [[move_base]] local planner only supported omni-directional (holonomic) robots. The current version was modified to work with differential drive machines. Set `differential_drive` to `false` to enable lateral/holonomic motion, but that mode has not been tested for a long time and should be considered experimental. == Video == <> == Credits == Quinlan, S. and Khatib, O. "Elastic Bands: Connecting Path Planning and Robot Control." Proc. IEEE International Conference on Robotics and Automation, Atlanta, Georgia 1993, vol 2. pp. 802-807 == EBand Local Planner Operation == The local planner computes an elastic band within the local costmap, and attempts to follow the path generated by connecting the center points of the band using various heuristics. On this page, we describe both the parameters used to generate the band, as well as the parameters that govern following the band using a differential drive controller. Prior to that, we provide a brief explanation of the heuristics used by the trajectory controller in this planner to follow the band when using differential drive control. A differential drive robot can be in one of three actions when computing velocity prior to reaching the goal location and orienation: 1. The robot is within lateral tolerance (`xy_goal_tolerance`) of the goal location, and is rotating in place to reach the goal orientation. 1. The robot is outside the lateral tolerance of the goal location, and must move towards the goal. Given the orientation of the robot, and the orientation of the next point in the elastic band, the robot first calculates the difference between these two locations. If this difference is less than the parameter `rotation_threshold_multiplier`, then the robot executes both linear and angular velocity components to arc towards the next point in the band. Once the robot is close to the goal location such that the x and y distances to the goal are less than 0.6 * `xy_goal_tolerance` then proceed to step 1. Here, 0.6 was chosen as the robot gets closer to the goal than the tolerance requires before starting the final turn, as the final turn may cause the robot to move slightly out of position. 1. If the difference computed in the previous step is greater than the parameter `rotation_threshold_multiplier`, then the robot turns in place until the difference becomes smaller, and the robot can execute action 2. == ROS Interface == This plugin runs inside the move_base process. Its parameter namespace is prefixed by that of `move_base` and the `base_local_planner` name under which it was launched, typically `EBandPlannerROS`, e.g.: {{{ ... }}} '''Common Parameters ''' {{{ #!clearsilver CS/NodeAPI param { no_header = True 1.name = ~/EBandPlannerROS/xy_goal_tolerance 1.type = double 1.desc = Distance tolerance for reaching the goal pose 1.default = 0.1 2.name = ~/EBandPlannerROS/yaw_goal_tolerance 2.type = double 2.desc = Orientation tolerance for reaching the desired goal pose 2.default = 0.05 3.name = ~/EBandPlannerROS/rot_stopped_vel 3.type = double 3.desc = Angular velocity lower bound that determines if the robot should stop to avoid limit-cycles or locks 3.default = 0.01 4.name = ~/EBandPlannerROS/trans_stopped_vel 4.type = double 4.desc = Linear velocity lower bound that determines if the robot should stop to avoid limit-cycles or locks 4.default = 0.01 } }}} '''Visualization Parameters ''' {{{ #!clearsilver CS/NodeAPI param { no_header = True 1.name = ~/EBandPlannerROS/marker_lifetime 1.type = double 1.desc = Lifetime of eband visualization markers 1.default = 0.5 } }}} '''Elastic Band Parameters ''' {{{ #!clearsilver CS/NodeAPI param { no_header = True 1.name = ~/EBandPlannerROS/eband_min_relative_overlap 1.type = double 1.desc = Min distance that denotes connectivity between consecutive bubbles 1.default = 0.7 2.name = ~/EBandPlannerROS/eband_tiny_bubble_distance 2.type = double 2.desc = Bubble geometric bound regarding tiny bubble distance 2.default = 0.01 3.name = ~/EBandPlannerROS/eband_tiny_bubble_expansion 3.type = double 3.desc = Bubble geometric bound regarding tiny bubble expansion 3.default = 0.01 4.name = ~/EBandPlannerROS/eband_internal_force_gain 4.type = double 4.desc = Force gain of forces between consecutive bubbles that tend to stretch the elastic band 4.default = 1.0 5.name = ~/EBandPlannerROS/eband_external_force_gain 5.type = double 5.desc = Force gain of forces that tend to move the bubbles away from obstacles 5.default = 2.0 6.name = ~/EBandPlannerROS/num_iterations_eband_optimization 6.type = int 6.desc = Number of iterations for eband optimization 6.default = 3 7.name = ~/EBandPlannerROS/eband_equilibrium_approx_max_recursion_depth 7.type = int 7.desc = Number of iterations for reaching the equilibrium between internal and external forces 7.default = 4 8.name = ~/EBandPlannerROS/eband_equilibrium_relative_overshoot 8.type = double 8.desc = Maximum relative equlibrium overshoot 8.default = 0.75 9.name = ~/EBandPlannerROS/eband_significant_force_lower_bound 9.type = double 9.desc = Minimum magnitude of force that is considered significant and used in the calculations 9.default = 0.15 10.name = ~/EBandPlannerROS/costmap_weight 10.type = double 10.desc = Costmap weight factor used in the calculation of distance to obstacles 10.default = 10.0 } }}} '''Trajectory Controller Parameters ''' {{{ #!clearsilver CS/NodeAPI param { no_header = True 1.name = ~/EBandPlannerROS/max_vel_lin 1.type = double 1.desc = Maximum linear velocity 1.default = 0.75 2.name = ~/EBandPlannerROS/max_vel_th 2.type = double 2.desc = Maximum angular velocity 2.default = 1.0 3.name = ~/EBandPlannerROS/min_vel_lin 3.type = double 3.desc = Minimum linear velocity 3.default = 0.1 4.name = ~/EBandPlannerROS/min_vel_th 4.type = double 4.desc = Minimum angular velocity 4.default = 0.0 5.name = ~/EBandPlannerROS/min_in_place_vel_th 5.type = double 5.desc = Minimum in-place angular velocity 5.default = 0.0 6.name = ~/EBandPlannerROS/in_place_trans_vel 6.type = double 6.desc = Minimum in place linear velocity 6.default = 0.0 7.name = ~/EBandPlannerROS/k_prop 7.type = double 7.desc = Proportional gain of the PID controller 7.default = 4.0 8.name = ~/EBandPlannerROS/k_damp 8.type = double 8.desc = Damping gain of the PID controller 8.default = 3.5 9.name = ~/EBandPlannerROS/Ctrl_Rate 9.type = double 9.desc = Control rate 9.default = 10.0 10.name = ~/EBandPlannerROS/max_acceleration 10.type = double 10.desc = Maximum allowable acceleration 10.default = 0.5 11.name = ~/EBandPlannerROS/virtual_mass 11.type = double 11.desc = Virtual mass 11.default = 0.75 12.name = ~/EBandPlannerROS/max_translational_acceleration 12.type = double 12.desc = Maximum linear acceleration 12.default = 0.5 13.name = ~/EBandPlannerROS/max_rotational_acceleration 13.type = double 13.desc = Maximum angular acceleration 13.default = 1.5 14.name = ~/EBandPlannerROS/rotation_correction_threshold 14.type = double 14.desc = Rotation correction threshold 14.default = 0.5 15.name = ~/EBandPlannerROS/differential_drive 15.type = bool 15.desc = Denotes whether to use the differential drive mode 15.default = True 16.name = ~/EBandPlannerROS/bubble_velocity_multiplier 16.type = double 16.desc = Multiplier of bubble radius 16.default = 2.0 17.name = ~/EBandPlannerROS/rotation_threshold_multiplier 17.type = double 17.desc = Multiplier of rotation threshold 17.default = 1.0 18.name = ~/EBandPlannerROS/disallow_hysteresis 18.type = bool 18.desc = Determines whether to try getting closer to the goal, in case of going past the tolerance 18.default = False } }}} ## AUTOGENERATED DON'T DELETE ## CategoryPackage