Pebble Tuning Guide

The Pebble Planner is a simple local planner that is designed to follow the global plan closely. Advantages of Pebble Planner include fewer configurable parameters and less oscillating motions.

How it works

Pebble Planner takes the global plan, decimates it to space out the poses as “pebbles”, then tries to reach them one by one.

It does this by rotating towards the next pebble, then accelerating until the maximum velocity is reached.

Setting up

Filepath: ~/catkin_ws/movel_ai/config/movel/config/

File to modify: base_local_planner_params.yaml

Same steps as setting up for TEB Local Planner. In the file, uncomment the section PebbleLocalPlanner to set your local planner to use Pebble.

Filepath: ~/catkin_ws/movel_ai/config/velocity_setter/config/

File to modify: velocity_setter.yaml

Change the parameterlocal_planner: "PebbleLocalPlanner".

Make sure you changed the parameters in both files or else an error may be thrown.

Overview of parameters

base_local_planner_params
PebbleLocalPlanner:
 d_min: 0.30
 robot_frame: base_link
 map_frame: map
 xy_goal_tolerance: 0.15
 yaw_goal_tolerance: 0.3925
 kp_linear: 1.0
 ki_linear: 0.0
 kd_linear: 0.0
 kp_angular: 1.0
 ki_angular: 0.0
 kd_angular: 0.1
 max_vel_x: 0.3
 max_vel_theta: 0.785
 acc_lim_x: 0.5
 acc_lim_theta: 0.785
 allow_reverse: true
 th_turn: 1.0472 #1.0472 : 60 deg, how far the robot faces from the waypoint before suppressing linear motion
 local_obstacle_avoidance: true # whether to let the local planner do obsav. If false, rely on the global planner, and planning frequency must not be zero
 N_lookahead: 3 # how many multiples of d_min to look ahead when eval'ing obstacles

Compared to TEB, the pebble planner has fewer configurable parameters.

Configurable Parameters

Find these parameters in ~/movel/config/base_local_planner_params.yaml under the section PebbleLocalPlanner.

Can be generally classified as Probably Important, Optional, and can be Ignored.

Probably Important

robot_frame

map_frame

d_min

Defines the minimal distance between waypoints (pebbles) when decimating the global plan. This ensures that the robot’s path is simplified by reducing the number of closely spaced waypoints.

  • Impact:

    • A smaller value allows for more closely spaced waypoints, making the path smoother but potentially more complex.

    • A larger value reduces the number of waypoints, simplifying the path.

  • Unit: Meters.

allow_reverse

Determines whether the robot is allowed to move in reverse.

  • Impact:

    • True: Enables backward movement, improving flexibility and maneuverability, especially in tight spaces.

    • False: Disables backward motion, limiting the robot to forward-only movement, which may restrict its ability to navigate in certain situations. Recommended if your robot doesn't have sensors at the back.

acc_lim_x

The maximum linear acceleration of the robot in the x direction (forward motion).

  • Impact:

    • A higher value allows quicker acceleration.

    • A lower value results in smoother, more gradual acceleration.

  • Unit: Meters per second²

acc_lim_theta

The maximum angular acceleration of the robot (rotation speed change). The pebble planner will rotate the robot towards the next pebble, then accelerates towards it (till max speed). The planned path may be straighter if angular acceleration is lowered.

  • Impact:

    • A higher value allows for faster changes in rotational speed.

    • A lower value makes the robot’s rotation smoother and slower.

  • Unit: Radians per second² (0.785 rad/s ≈ 45 degrees per second).


Optional

xy_goal_tolerance

Specifies how close the robot needs to be to the goal’s x and y coordinates before considering the goal reached.

  • Impact:

    • A smaller value requires more precision in reaching the goal.

    • A larger value allows the robot to stop farther away from the exact goal position.

  • Unit: Meters.

yaw_goal_tolerance

Specifies the angular tolerance (yaw, or rotation around the z-axis) at the goal.

  • Impact:

    • A smaller value requires the robot to align more precisely with the goal orientation.

    • A larger value allows more flexibility in the robot’s final orientation.

  • Unit: Radians (0.3925 radians ≈ 22.5 degrees).

local_obstacle_avoidance

Whether to use Pebble Planner’s local obstacle avoidance. If set to false, and move_base’s planner_frequency is set to > 0 Hz, the global planner takes care of obstacle avoidance.

  • Impact:

    • True: The Pebble Planner will handle local obstacle avoidance, making the robot actively avoid obstacles along its path.

    • False: Disables local obstacle avoidance, relying on the global planner to manage obstacle avoidance based on the frequency set in move_base.

n_lookahead

How many pebbles are ahead of the active one to look ahead for obstacles. This parameter is only relevant if local_obstacle_avoidance is set to true.

  • Impact:

    • A higher value means the robot will anticipate obstacles further ahead.

    • A lower value limits how far the robot looks ahead for obstacles, focusing on the immediate area around the active pebble.

th_turn

The threshold angle beyond which the robot will stop and turn in place to face the next waypoint (pebble), instead of trying to turn and move at the same time.

  • Impact:

    • A lower value makes the robot attempt to turn while moving more often.

    • A higher value means the robot will stop and rotate in place for larger angle changes.

  • Unit: Radians (1.0472 rad ≈ 60 degrees).

th_reverse

The threshold angle for reversing. If the angle between the robot and the target exceeds this value, the robot will reverse instead of turning around.

  • Impact:

    • A smaller value makes the robot reverse less often.

    • A larger value encourages more frequent reverse movements.

  • Unit: Radians (2.3562 rad ≈ 135 degrees).

decelerate_goal

Controls whether the robot should decelerate as it approaches the goal.

  • Impact:

    • True: The robot slows down as it nears the goal for improved precision.

    • False: The robot maintains speed until it reaches the goal.

decelerate_each_waypoint

Determines whether the robot should decelerate when reaching each waypoint (pebble) along its path.

  • Impact:

    • True: The robot decelerates at each waypoint, making navigation smoother but slower.

    • False: The robot maintains speed between waypoints for quicker movement.

decelerate_distance

The distance from the waypoint at which the robot starts to decelerate.

  • Impact: Affects how early the robot starts slowing down before reaching waypoints or the goal.

  • Unit: Meters.

decelerate_factor

The rate at which the robot decelerates as it approaches a waypoint or goal.

  • Impact: A higher factor increases the rate of deceleration, while a lower factor results in more gradual deceleration.

curve_angle_tolerance

The angular tolerance allowed when following a curved path.

  • Impact:

    • A higher value allows for looser curve-following, reducing the need for sharp corrections.

    • A smaller value requires more precise curve-following.

  • Unit: Degrees.

curve_d_min

The minimum distance between waypoints (pebbles) on a curved path.

  • Impact:

    • A smaller value results in more frequent waypoints along the curve, offering finer control.

    • A larger value simplifies the path by reducing the number of waypoints.

  • Unit: Meters.

curve_vel

The speed at which the robot should travel while navigating curved paths.

  • Impact:

    • A higher value allows faster movement along curves.

    • A lower value ensures more controlled and precise movements.

  • Unit: Meters per second.

consider_circumscribed_lethal

Determines whether the circumscribed area around the robot (the area just beyond the robot’s footprint) is considered lethal (i.e., an obstacle).

  • Impact:

    • True: The circumscribed area is considered an obstacle, making the robot more conservative in its movements.

    • False: The circumscribed area is ignored, allowing the robot to navigate closer to obstacles.

inflation_cost_scaling_factor

The scaling factor for the cost of inflated obstacles in the costmap.

  • Impact:

    • A higher value increases the cost of cells near obstacles, forcing the robot to take wider detours.

    • A lower value makes the robot more willing to move closer to obstacles.

  • Unit: Unitless (scaling factor).


Can Be Ignored

max_vel_x, max_vel_theta - These values will be set by the UI depending on what values you give there. Can ignore it if you are using the UI.

(kp, ki, kd values) - Configurations for a differential drive.

max_vel_x

The maximum forward velocity of the robot.

  • Impact:

    • A higher value allows the robot to move faster.

    • A lower value limits the robot’s speed, improving safety and control.

  • Unit: Meters per second.

max_vel_theta

The maximum rotational velocity of the robot.

  • Impact:

    • A higher value enables faster turns.

    • A lower value makes the robot turn more slowly, offering smoother rotations and planned path straighter

  • Unit: Radians per second (0.785 rad/s ≈ 45 degrees per second).

Last updated