Show EOL distros: 

navigation_experimental: assisted_teleop | eband_local_planner | goal_passer | pose_base_controller | pose_follower | sbpl_lattice_planner | sbpl_recovery | twist_recovery

Package Summary

The eband_local_planner package implements a plugin to the base_local_planner. It implements the Elastic Band method on the SE2 manifold.

navigation_experimental: assisted_teleop | eband_local_planner | goal_passer | pose_base_controller | pose_follower | sbpl_lattice_planner | sbpl_recovery | twist_recovery

Package Summary

The eband_local_planner package implements a plugin to the base_local_planner. It implements the Elastic Band method on the SE2 manifold.

Package Summary

eband_local_planner implements a plugin to the base_local_planner. It implements the Elastic Band method on the SE2 manifold.

Package Summary

eband_local_planner implements a plugin to the base_local_planner. It implements the Elastic Band method on the SE2 manifold.

Package Summary

eband_local_planner implements a plugin to the base_local_planner. It implements the Elastic Band method on the SE2 manifold.

Package Summary

eband_local_planner implements a plugin to the base_local_planner. It implements the Elastic Band method on the SE2 manifold.

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.

  2. 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.

  3. 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.:

  <node pkg="move_base" type="move_base" name="move_base">
    <param name="base_local_planner" value="eband_local_planner/EBandPlannerROS"/>
    ...
  </node>

Common Parameters

~/EBandPlannerROS/xy_goal_tolerance (double, default: 0.1)

  • Distance tolerance for reaching the goal pose
~/EBandPlannerROS/yaw_goal_tolerance (double, default: 0.05)
  • Orientation tolerance for reaching the desired goal pose
~/EBandPlannerROS/rot_stopped_vel (double, default: 0.01)
  • Angular velocity lower bound that determines if the robot should stop to avoid limit-cycles or locks
~/EBandPlannerROS/trans_stopped_vel (double, default: 0.01)
  • Linear velocity lower bound that determines if the robot should stop to avoid limit-cycles or locks

Visualization Parameters

~/EBandPlannerROS/marker_lifetime (double, default: 0.5)

  • Lifetime of eband visualization markers

Elastic Band Parameters

~/EBandPlannerROS/eband_min_relative_overlap (double, default: 0.7)

  • Min distance that denotes connectivity between consecutive bubbles
~/EBandPlannerROS/eband_tiny_bubble_distance (double, default: 0.01)
  • Bubble geometric bound regarding tiny bubble distance
~/EBandPlannerROS/eband_tiny_bubble_expansion (double, default: 0.01)
  • Bubble geometric bound regarding tiny bubble expansion
~/EBandPlannerROS/eband_internal_force_gain (double, default: 1.0)
  • Force gain of forces between consecutive bubbles that tend to stretch the elastic band
~/EBandPlannerROS/eband_external_force_gain (double, default: 2.0)
  • Force gain of forces that tend to move the bubbles away from obstacles
~/EBandPlannerROS/num_iterations_eband_optimization (int, default: 3)
  • Number of iterations for eband optimization
~/EBandPlannerROS/eband_equilibrium_approx_max_recursion_depth (int, default: 4)
  • Number of iterations for reaching the equilibrium between internal and external forces
~/EBandPlannerROS/eband_equilibrium_relative_overshoot (double, default: 0.75)
  • Maximum relative equlibrium overshoot
~/EBandPlannerROS/eband_significant_force_lower_bound (double, default: 0.15)
  • Minimum magnitude of force that is considered significant and used in the calculations
~/EBandPlannerROS/costmap_weight (double, default: 10.0)
  • Costmap weight factor used in the calculation of distance to obstacles

Trajectory Controller Parameters

~/EBandPlannerROS/max_vel_lin (double, default: 0.75)

  • Maximum linear velocity
~/EBandPlannerROS/max_vel_th (double, default: 1.0)
  • Maximum angular velocity
~/EBandPlannerROS/min_vel_lin (double, default: 0.1)
  • Minimum linear velocity
~/EBandPlannerROS/min_vel_th (double, default: 0.0)
  • Minimum angular velocity
~/EBandPlannerROS/min_in_place_vel_th (double, default: 0.0)
  • Minimum in-place angular velocity
~/EBandPlannerROS/in_place_trans_vel (double, default: 0.0)
  • Minimum in place linear velocity
~/EBandPlannerROS/k_prop (double, default: 4.0)
  • Proportional gain of the PID controller
~/EBandPlannerROS/k_damp (double, default: 3.5)
  • Damping gain of the PID controller
~/EBandPlannerROS/Ctrl_Rate (double, default: 10.0)
  • Control rate
~/EBandPlannerROS/max_acceleration (double, default: 0.5)
  • Maximum allowable acceleration
~/EBandPlannerROS/virtual_mass (double, default: 0.75)
  • Virtual mass
~/EBandPlannerROS/max_translational_acceleration (double, default: 0.5)
  • Maximum linear acceleration
~/EBandPlannerROS/max_rotational_acceleration (double, default: 1.5)
  • Maximum angular acceleration
~/EBandPlannerROS/rotation_correction_threshold (double, default: 0.5)
  • Rotation correction threshold
~/EBandPlannerROS/differential_drive (bool, default: True)
  • Denotes whether to use the differential drive mode
~/EBandPlannerROS/bubble_velocity_multiplier (double, default: 2.0)
  • Multiplier of bubble radius
~/EBandPlannerROS/rotation_threshold_multiplier (double, default: 1.0)
  • Multiplier of rotation threshold
~/EBandPlannerROS/disallow_hysteresis (bool, default: False)
  • Determines whether to try getting closer to the goal, in case of going past the tolerance

Wiki: eband_local_planner (last edited 2018-01-16 14:24:09 by FelixWidmaier)