12. Navigation and avoiding12.1 Operation and use 12.1.1 Start 12.1.2 Use 12.1.3 Dynamic parameter adjustment 12.1.4 Node graph 12.1.5 tf coordinate system 12.2 navigation 12.2.1 Introduction 12.2.2 set tf 12.3 move_base 12.3.1 Introduction 12.3.2 move_base communication mechanism 1) Action 2) topic 3) tableware 4) Parameter configuration 12.3.3 Recovery Behavior 1 Introduction 2) Related function packages 12.4 costmap_params 12.4.1 costmap_common 12.4.2 global_costmap 12.4.3 local_costmap 12.4.4 costmap_2D 1 Introduction 2)topic 3) Parameter configuration 4) Layer Specifications 5)obstacle layer 6) Inflation layer 12.5 planner_params 12.5.1 global_planner 12.5.2 local_planner 1)dwa_local_planner 2)teb_local_planner
navigation: http://wiki.ros.org/navigation/
navigation/Tutorials: http://wiki.ros.org/navigation/Tutorials/RobotSetup
costmap_2d: http://wiki.ros.org/costmap_2d
nav_core: http://wiki.ros.org/nav_core
global_planner: http://wiki.ros.org/global_planner
dwa_local_planner: http://wiki.ros.org/dwa_local_planner
teb_local_planner: http://wiki.ros.org/teb_local_planner
move_base: http://wiki.ros.org/move_base
Note: [R2] of the remote control handle has the function of canceling the target point.
According to different models, you only need to set the purchased model in [.bashrc], X1(ordinary four-wheel drive) X3(Mike wheel) X3plus(Mike wheel mechanical arm) R2(Ackerman differential) and so on, to X3 as an example
Open the [.bashrc] file
sudo vim .bashrc
Find the [ROBOT_TYPE] parameter and modify the corresponding model
xxxxxxxxxx
export ROBOT_TYPE=X3 # ROBOT_TYPE: X1 X3 X3plus R2 X7
Start the driver(robot side), for the convenience of operation, this section takes [mono + laser + yahboomcar] as an example.
x#You need to enter docker first, perform this step more
#If running the script to enter docker fails, please refer to 07.Docker-orin/05, Enter the robot's docker container
~/run_docker.sh
roslaunch yahboomcar_nav laser_bringup.launch # laser + yahboomcar
roslaunch yahboomcar_nav laser_usb_bringup.launch # mono + laser + yahboomcar
roslaunch yahboomcar_nav laser_astrapro_bringup.launch # Astra + laser + yahboomcar
Start the navigation obstacle avoidance function(robot side), you can set parameters and modify the launch file according to your needs.
<Open another terminal and enter the same docker container
xxxxxxxxxx
roslaunch yahboomcar_nav yahboomcar_navigation.launch use_rviz:=false map:=house
Open the visual interface(virtual machine side)
xxxxxxxxxx
roslaunch yahboomcar_nav view_navigate.launch
1) Single point navigation
2) Multi-point navigation
3) Parameter configuration
According to different models, you only need to set the purchased model in [.bashrc], X1(ordinary four-wheel drive) X3(Mike wheel) X3plus(Mike wheel mechanical arm) R2(Ackerman differential) and so on, to X3 as an example
Open the [.bashrc] file
xxxxxxxxxx
sudo vim .bashrc
Find the [ROBOT_TYPE] parameter and modify the corresponding model
xxxxxxxxxx
export ROBOT_TYPE=X3 # ROBOT_TYPE: X1 X3 X3plus R2 X7
Looking at the yahboomcar_navigation.launch file, you can see that the navigation parameters are modified in the move_base.launch file under the yahboomcar_nav function package.
xxxxxxxxxx
< launch >
<!-- Whether to open rviz || Whether to open rviz -->
< arg name = "use_rviz" default = "true" />
<!-- map name|| Map name my_map-->
< arg name = "map" default = "my_map" />
<!-- MarkerArray node> -->
< node name = 'send_mark' pkg = "yahboomcar_nav" type = "send_mark.py" />
<!-- Load map || Load map -->
< node name = "map_server" pkg = "map_server" type = "map_server" args = "$(find yahboomcar_nav)/maps/$(arg map).yaml" />
<!-- AMCL Adaptive Monte Carlo Positioning-->
< include file = "$(find yahboomcar_nav)/launch/library/amcl.launch" />
<!-- Mobile APP Node-->
< include file = "$(find yahboomcar_nav)/launch/library/app.launch" />
<!-- Navigation core component move_base -->
< include file = "$(find yahboomcar_nav)/launch/library/move_base.launch" />
<!-- RVIZ -->
< include file = "$(find yahboomcar_nav)/launch/view/view_navigate.launch" if = "$(arg use_rviz)" />
</ launch >
Find the move_base.launch file, open the sample file as follows, you can modify and replace it according to your needs; at this time, the [DWA planner] is selected, and the [DWA] file is loaded.
xxxxxxxxxx
< launch >
< arg name = "robot_type" value = "$(env ROBOT_TYPE)" doc = "robot_type [X1,X3,X3plus,R2,X7]" />
<!-- Arguments -->
< arg name = "move_forward_only" default = "false" />
<!-- move_base -->
< node pkg = "move_base" type = "move_base" respawn = "false" name = "move_base" output = "screen" >
< rosparam file = "$(find yahboomcar_nav)/param/common/global_costmap_params.yaml" command = "load" />
< rosparam file = "$(find yahboomcar_nav)/param/common/local_costmap_params.yaml" command = "load" />
< rosparam file = "$(find yahboomcar_nav)/param/common/move_base_params.yaml" command = "load" />
< rosparam file = "$(find yahboomcar_nav)/param/common/costmap_common_params_$(arg robot_type).yaml" command = "load"
ns = "global_costmap" />
< rosparam file = "$(find yahboomcar_nav)/param/common/costmap_common_params_$(arg robot_type).yaml" command = "load"
ns = "local_costmap" />
< rosparam file = "$(find yahboomcar_nav)/param/common/dwa_local_planner_params_$(arg robot_type).yaml" command = "load" />
< param name = "base_local_planner" type = "string" value = "dwa_local_planner/DWAPlannerROS" if = "$(eval arg('robot_type') == 'X3')" />
<!-- <param name="base_local_planner" type="string" value="teb_local_planner/TebLocalPlannerROS"/>-->
< param name = "DWAPlannerROS/min_vel_x" value = "0.0" if = "$(arg move_forward_only)" />
< remap from = "cmd_vel" to = "cmd_vel" />
< remap from = "odom" to = "odom" />
</ node >
</ launch >
Note: When using the DWA planner, the difference between the omnidirectional car and the differential car is whether the speed in the Y direction is 0. There are clear comments in it, which can be modified according to the actual situation.
Enter the dwa_local_planner_params.yaml file under the yahboomcar_nav function package, some parameters are as follows:
xxxxxxxxxx
DWAPlannerROS :
# Robot Configuration Parameters
# The absolute value of the maximum linear velocity in the x direction, unit: m/s
# The maximum y velocity for the robot in m/s
max_vel_x : 0.6
# The absolute value of the minimum linear velocity in the x direction, a negative number means that it can be moved back, unit: m/s
# The minimum x velocity for the robot in m/s, negative for backwards motion.
min_vel_x : - 0.6
# The absolute value of the maximum linear velocity in the y direction, unit: m/s. Differential robot is 0
# The maximum y velocity for the robot in m/s
max_vel_y : 0.3
# The absolute value of the minimum linear velocity in the y direction, unit: m/s. Differential robot is 0
# The minimum y velocity for the robot in m/s
min_vel_y : - 0.3
…
# The limit acceleration of the robot in the x direction, the unit is meters/sec^2
# The x acceleration limit of the robot in meters/sec^2
acc_lim_x : 10.0
# The limit acceleration of the robot in the y direction, it is 0 for the differential robot
# The y acceleration limit of the robot in meters/sec^2
acc_lim_y : 10.0
... ..
Other parameter files can be opened, combined with annotations and courseware, and modified according to their own needs.
After starting the navigation function, open the dynamic parameter adjustment tool, adjust it according to your own needs, and observe the motion state of the robot until the effect is optimal, record the current parameters, and modify them to the dwa_local_planner_params.yaml file under the yahboomcar_nav function package.
xxxxxxxxxx
rosrun rqt_reconfigure rqt_reconfigure
Take [mono + laser + yahboomcar] started in section [1.1] as an example to observe the communication between nodes.
xxxxxxxxxx
rosrun rqt_graph rqt_graph
The transformation relationship between coordinates.
xxxxxxxxxx
rosrun rqt_tf_tree rqt_tf_tree
Navigation is a two-dimensional navigation obstacle avoidance function package of ROS. In simple terms, it is based on the information flow of the input odometer and other sensors and the global position of the robot, through the navigation algorithm, calculates the safe and reliable robot speed control command.
navigation main nodes and configuration
The navigation function requires the robot to publish information about the relationship between the coordinate systems using tf. Example: Lidar
Suppose we know that the lidar is mounted 10 cm and 20 cm above the center point of the mobile base. This gives us the translation offset to associate the "base_link" frame with the "base_laser" frame. Specifically, we know that to get data from the "base_link" coordinate system to the "base_laser" coordinate system, we have to apply a translation of(x: 0.1m, y: 0.0m, z: 0.2m) and get the data from the "base_laser" frame To the "base_link" frame, we have to apply the opposite translation(x: -0.1m, y: 0.0m, z: -0.20m).
move_base provides the configuration, operation and interaction interface of ROS navigation.
Implementing the robot navigation function must be configured in a specific way, as shown above:
The move_base node provides an implementation of SimpleActionServer that receives targets containing geometry_msgs/PoseStamped messages. You can communicate directly with the move_base node via ROS, but if you care about tracking the state of the target, it is recommended to use SimpleActionClient to send the target to the move_base.(See actionlib documentation )
name | type | illustrate |
---|---|---|
move_base/goal | move_base_msgs/MoveBaseActionGoal | move_base subscribes to the target point to be reached. |
move_base/cancel | actionlib_msgs/GoalID | move_base subscribes to cancel requests for a specific target. |
move_base/feedback | move_base_msgs/MoveBaseActionFeedback | The post contains the current position of the chassis. |
move_base/status | actionlib_msgs/GoalStatusArray | Publishes status information for the move to the target point process. |
move_base/result | move_base_msgs/MoveBaseActionResult | Post the final result of the move. |
name | type | illustrate |
---|---|---|
move_base_simple/goal | geometry_msgs/PoseStamped | Provides a non-action interface that does not care about the execution state of the tracking target. move_base subscribes to the target point to be reached. |
cmd_vel | geometry_msgs/Twist | Publishes the speed of the car's movement. |
name | type | illustrate |
---|---|---|
make_plan | nav_msgs/GetPlan | Allows external users to request a plan for a given pose from move_base without causing move_base to execute the plan. |
clear_unknown_space | std_srvs/Empty | Allows external users to notify move_base to clear unknown spaces in the area around the robot. This is useful when move_base's costmaps are stopped for a long period of time and then restarted at a new location in the environment. |
clear_costmaps | std_srvs/Empty | Allows external users to tell move_base to clear barriers in the costmap used by move_base. This may cause the robot to bump into things and should be used with caution |
move_base_params.yaml
xxxxxxxxxx
# Set the plugin name of the global path planner for move_base
#base_global_planner: "navfn/NavfnROS"
base_global_planner "global_planner/GlobalPlanner"
#base_global_planner: "carrot_planner/CarrotPlanner"
# Set the plugin name of the local path planner for move_base
#base_local_planner: "teb_local_planner/TebLocalPlannerROS" # Implement an online optimized local trajectory planner
base_local_planner "dwa_local_planner/DWAPlannerROS" # Implement DWA(dynamic window method) local planning algorithm
# Restore behavior.
recovery_behaviors
name 'conservative_reset'
type 'clear_costmap_recovery/ClearCostmapRecovery'
#- name: 'aggressive_reset'
# type: 'clear_costmap_recovery/ClearCostmapRecovery'
#- name: 'super_reset'
# type: 'clear_costmap_recovery/ClearCostmapRecovery'
name 'clearing_rotation'
type 'rotate_recovery/RotateRecovery'
#- name: 'move_slow_and_clear'
#type: 'move_slow_and_clear/MoveSlowAndClear'
# How often to send commands to the robot chassis cmd_vel
controller_frequency 10.0
# The time the path planner waits for a valid control command before the space cleanup operation is executed
planner_patience 5.0
# The time the controller waits for a valid control command before the space cleaning operation is executed
controller_patience 15.0
# This parameter is only used when the default restore behavior is used for move_base.
conservative_reset_dist 3.0
# Whether to enable the move_base restore behavior to try to clear space.
recovery_behavior_enabled true
# Whether the robot uses in-situ rotation to clear the space, this parameter is only used when the default recovery behavior is used.
clearing_rotation_allowed true
# When move_base enters the inactive state, whether to disable the costmap of the node
shutdown_costmaps false
# The time allowed to oscillate before performing the recovery operation, 0 means never timeout
oscillation_timeout 10.0
# The robot needs to move this distance to be considered as having no vibration. Reset timer parameters after moving
oscillation_distance 0.2
# Global path planner cycle rate.
planner_frequency 5.0
# The number of times to allow scheduled retries before performing recovery behavior. A value of -1.0 corresponds to infinite retries.
max_planning_retries -1.0
When ① the global planning fails, ② the robot oscillates, and ③ the local planning fails, it will enter the recovery behavior. These recovery behaviors can be configured with the recovery_behaviour parameter and disabled with the recovery_behavior_enabled parameter.
Desired Robot Behavior
First, obstacles outside the user-specified area are cleared from the robot's map. Next, if possible, the robot will perform a spin in place to clear the space. If this also fails, the robot will more aggressively clear the map, clearing all obstacles outside the rectangular area where the robot can rotate in place. Another in-place spin will follow. If all of these fail, the bot considers its goal unfeasible and informs the user that it has aborted.
In the set of navigation function packs, there are 3 packs related to the recovery mechanism. They are: clear_costmap_recovery, move_slow_and_clear, rotate_recovery. Three classes are defined in these three packages, all of which inherit the interface specification in nav_core.
parameter | type | Defaults | Parse |
---|---|---|---|
clearing_distance | double | 0.5 | Obstacles within the robot's clearing distance will be cleared(unit: m). |
limited_trans_speed | double | 0.25 | When performing this recovery behavior, the robot's translation speed will be limited(unit: m/s). |
limited_rot_speed | double | 0.25 | When this recovery behavior is performed, the rotational speed of the robot will be limited(unit: rad/s). |
limited_distance | double | 0.3 | The distance(unit: m) that the robot must move before releasing the speed limit. |
planner_namespace | string | "DWAPlannerROS" | The name of the planner whose parameters are to be reconfigured. |
parameter | type | Defaults | Parse |
---|---|---|---|
sim_granularity | double | 0.017 | When checking whether it is safe to rotate in place, the distance between checking obstacles is 1 degree by default(unit: rad). |
frequency | double | 20.0 | The frequency(unit: Hz) of sending speed commands to the mobile robot. |
TrajectoryPlannerROS/yaw_goal_tolerance | double | 0.05 | The tolerance in radians for the controller in yaw/rotation to achieve its goal. |
TrajectoryPlannerROS/acc_lim_th | double | 3.2 | The rotational acceleration limit of the robot(unit: rad/s^2). |
TrajectoryPlannerROS/max_rotational_vel | double | 1.0 | The maximum rotation speed allowed by the base(unit: rad/s). |
TrajectoryPlannerROS/min_in_place_rotational_vel | double | 0.4 | The minimum rotation speed(unit: rad/s) allowed by the base when performing an in-position rotation. |
Note: The TrajectoryPlannerROS parameter is only set when using the base_local_planner::TrajectoryPlannerROS planner; generally it is not required.
parameter | type | Defaults | Parse |
---|---|---|---|
clearing_distance | double | 0.5 | The length centered on the robot that the obstacle will be removed from the costmap when it reverts to a static map. |
The navigation function uses two costmaps to store information about obstacles. One costmap is used for global planning, which means creating global planning routes across the entire environment, and the other is used for local planning and obstacle avoidance. The two costmaps have some common configuration and some individual configuration. Therefore, the costmap configuration has the following three parts: general configuration, global configuration and local configuration.
Costmap public parameter configuration costmap_common_params.yaml
xxxxxxxxxx
obstacle_range 2.5
raytrace_range 3.0
footprint x0 y0 x1 y1 ... xn at
# robot_radius: ir_of_robot
inflation_radius 0.55
observation_sources laser_scan_sensor
laser_scan_sensor sensor_frame frame_name data_type LaserScan topic topic_name marking true clearing true
parameter parsing
obstacle_range: The default value is 2.5 meters, which means that the robot will only update information about obstacles within a range of 2.5 meters.
raytrace_range: The default value is 3.0 meters, which means the robot will try to clear space beyond 3.0 meters in front of it.
Footprint: Set the occupied area of the robot. When filling in the footprint specified by "footprint" according to the robot coordinate setting, the center of the robot is considered to be at(0.0, 0.0), both clockwise and counterclockwise can be set.
robot_radius: The occupied area of the robot is a circle, and the radius can be set directly. Not shared with footprint.
inflation_radius: Set the costmap inflation radius. Default 0.55. It means that the robot will consider the obstacle within 0.55 meters of the obstacle.
observation_sources: defines a list of sensors that pass information to a space-separated costmap.
laser_scan_sensor: defines each sensor.
Global costmap parameter configuration global_costmap_params.yaml
xxxxxxxxxx
global_costmap
global_frame map
robot_base_frame base_link
update_frequency 5.0
static_map true
Local costmap parameter configuration local_costmap_params.yaml
xxxxxxxxxx
local_costmap
global_frame odom
robot_base_frame base_link
update_frequency 5.0
publish_frequency 2.0
static_map false
rolling_window true
width 6.0
height 6.0
resolution 0.05
parameter parsing
The costmap_2d package provides a 2D costmap implementation that takes input sensor data, builds a 2D or 3D costmap of the data(depending on whether a voxel-based implementation is used), and uses occupancy grids and user-defined inflation Radius computes the cost of the 2D costmap.
name | type | illustrate |
---|---|---|
footprint | geometry_msgs/Polygon | Robot enclosure specification. This replaces the previous parameter specification for the package outline. |
costmap | nav_msgs/OccupancyGrid | cost map |
costmap_updates | map_msgs/OccupancyGridUpdate | Update area of the costmap |
voxel_grid | costmap_2d/VoxelGrid | voxel grid |
If you don't provide the plugins parameter, the initialization code will assume your configuration is pre-Hydro, and the default namespaces are static_layer, obstacle_layer, and inflation_layer.
plugin
Coordinate system and tf parameters
Rate parameter
Map management parameters
static layer
tf transform
global_fram——>robot_base_frame
Static layer static map layer : The static layer is basically unchanged in the cost map.
Subscribe to topics
parameter
Obstacle layer : The obstacle layer tracks the obstacles read by the sensor data. The collision costmap plugin labels and raytraces obstacles in 2D, while the VoxelCostmapPlugin labels and raytraces obstacles in 3D.
Inflation layer : Add new values around lethal obstacles(i.e. inflate obstacles) so that the costmap represents the robot's configuration space.
Other layers: Other layers can be implemented and used in the costmap through pluginlib .
Obstacle layers and voxel layers contain information from sensors in the form of point clouds or laser scans. Barrier layers track in 2D, while voxel layers track in 3D.
The costmap is automatically subscribed to the sensor topic and updated accordingly. Each sensor is used for marking(inserting obstacle information into the costmap), clearing(removing obstacle information from the costmap). Each time the data is observed, the clear operation performs ray tracing through the mesh from the sensor origin outwards. In the voxel layer, the obstacle information in each column is down-projected into a 2D map.
Subscribe to topics
topic name | type | Parse |
---|---|---|
point_cloud_topic | sensor_msgs/PointCloud | Update PointCloud information to costmap. |
point_cloud2_topic | sensor_msgs/PointCloud2 | Update PointCloud2 information to costmap |
laser_scan_topic | sensor_msgs/LaserScan | Update LaserScan information to costmap |
map | nav_msgs/OccupancyGrid | The costmap has the option to initialize from a user-generated static map |
Sensor Management Parameters
observation_sources: list of observation source names
Each source name in an observation source defines a namespace where parameters can be set:
Global filter parameters: These parameters apply to all sensors.
ObstacleCostmapPlugin
VoxelCostmapPlugin
The inflation cost decreases as the robot's distance from the obstacle increases. Define 5 specific symbols related to bots for the cost value of the costmap.
parameter
nav_core::BaseGlobalPlanner provides an interface for the global planner used in navigation. All global planners written as move_base node plugins must adhere to this interface. Documentation on NavaCys::BaseGoLBalPrimeNe:C++ documentation can be found here: BaseGlobalPlanner documentation .
Global Path Planning Plugin
Global path planning global_planner_params.yaml
xxxxxxxxxx
GlobalPlanner
allow_unknown false
default_tolerance 0.2
visualize_potential false
use_dijkstra true
use_quadratic true
use_grid_path false
old_navfn_behavior false
lethal_cost 253
neutral_cost 50
cost_factor 3.0
publish_potential true
orientation_mode 0
orientation_window_size 1
parameter parsing
track_unknown_space
must also be set to true
. Global path planning algorithm renderings
If it appears in the very first stage:
xxxxxxxxxx
[ERROR] [1611670223.557818434, 295.312000000]: NO PATH!
[ERROR] [1611670223.557951973, 295.312000000]: Failed to get a plan from potential when a legal potential was found. This shouldn't happen.
This situation is related to the direction set by the robot. It is recommended to try the default [navfn] plugin for global path planning.
nav_core::BaseLocalPlanner provides an interface for local path planners used in navigation. All local path planners written as move_base node plugins must adhere to this interface. Documentation on NavaCys::BaseLoCalPrnor's C++ API can be found here: BaseLocalPlanner documentation .
Local path planning plugin
Comparison of TEB and DWA:
teb will adjust its orientation during the movement. When it reaches the target point, usually the orientation of the robot is also the orientation of the target and does not need to rotate.
dwa first reaches the target coordinate point, and then rotates to the target orientation in situ.
For a two-wheel differential chassis, adjusting the orientation of the teb during movement will make the movement path unsmooth, and unnecessary backwards will occur when starting and reaching the target point, which is not allowed in some application scenarios. Because backing up may encounter obstacles. Rotating in place to a suitable orientation and then walking away is a more appropriate exercise strategy. This is also where teb needs to be optimized according to the scene.
The dwa_local_planner package supports any robot whose chassis can be represented as a convex polygon or a circle. This package provides a controller that drives the robot to move in a plane. This controller connects the path planner to the robot. The planner uses the map to create a motion trajectory for the robot from the starting point to the target position, sending the dx, dy, dtheta velocities to the robot.
The basic idea of DWA algorithm
A number of ROS parameters can be set to customize the behavior of dwa_local_planner::DWAPlannerROS. These parameters fall into several categories: robot configuration, target tolerance, forward simulation, trajectory scoring, oscillation prevention, and global planning. These parameters can be debugged using the dynamic_reconfigure tool to tune the local path planner in a running system.
xxxxxxxxxx
DWAPlannerROS :
# Robot Configuration Parameters
acc_lim_x : 2.5
acc_lim_y : 2.5
acc_lim_th : 3.2
max_vel_trans : 0.55
min_vel_trans : 0.1
max_vel_x : 0.55
min_vel_x : 0.0
max_vel_y : 0.1
min_vel_y : -0.1
max_rot_vel : 1.0
min_rot_vel : 0.4
# Goal Tolerance Parameters
yaw_goal_tolerance : 0.05
xy_goal_tolerance : 0.10
latch_xy_goal_tolerance : false
# Forward Simulation Parameters
sim_time : 2.0
sim_granularity : 0.025
vx_samples : 6
vy_samples : 1
vth_samples : 20
controller_frequency : 5.0
# Trajectory Scoring Parameters
path_distance_bias : 90.0 # 32.0
goal_distance_bias : 24.0 # 24.0
occdist_scale : 0.3 # 0.01
forward_point_distance : 0.325 # 0.325
stop_time_buffer : 0.2 # 0.2
scaling_speed : 0.20 # 0.25
max_scaling_factor : 0.2 # 0.2
publish_cost_grid : false
# Oscillation Prevention Parameters
oscillation_reset_dist : 0.05 # default 0.05
# Global Plan Parameters
prune_plan : false
Robot configuration parameters
Target tolerance parameter
Forward Simulation Parameters
Trajectory Scoring Parameters
Anti-vibration parameters
Global Planning Parameters
teb_local_planner is an optimization-based local trajectory planner. Support difference model, car-like model. This software package implements an online optimal local trajectory planner for mobile robot navigation and control, which efficiently obtains the optimal trajectory by solving a sparse scalar multi-objective optimization problem. Users can provide weights to optimization problems to specify behavior in case of conflicting goals.
The teb_local_planner package allows users to set parameters to customize the behavior. These parameters are grouped into categories: robot configuration, target tolerance, trajectory configuration, obstacles, optimization, planning in unique topologies, and other parameters. Some of them were selected to meet basic local planners. Many(but not all) parameters can be modified at runtime using rqt_reconfig.
Local path planner teb_local_planner_params.yaml
xxxxxxxxxx
TebLocalPlannerROS
# Miscellaneous Parameters
map_frame:odom
odom_topic odom
# Robot
acc_lim_x 0.5
acc_lim_theta 0.5
max_vel_x 0.4
max_vel_x_backwards 0.2
max_vel_theta 0.3
min_turning_radius 0.0
footprint_model
type "point"
# GoalTolerance
xy_goal_tolerance 0.2
yaw_goal_tolerance 0.1
free_goal_vel False
# Trajectory
dt_ref 0.3
dt_hysteresis 0.1
min_samples 3
global_plan_overwrite_orientation True
allow_init_with_backwards_motion False
max_global_plan_lookahead_dist 3.0
global_plan_viapoint_sep -1
global_plan_prune_distance 1
exact_arc_length False
feasibility_check_no_poses 5
publish_feedback False
# Obstacles
min_obstacle_dist 0.25
inflation_dist 0.6
include_costmap_obstacles True
costmap_obstacles_behind_robot_dist 1.5
obstacle_poses_affected 15
dynamic_obstacle_inflation_dist 0.6
include_dynamic_obstacles True
costmap_converter_plugin ""
costmap_converter_spin_thread True
costmap_converter_rate 5
# Optimization
no_inner_iterations 5
no_outer_iterations 4
optimization_activate True
optimization_verbose False
penalty_epsilon 0.1
obstacle_cost_exponent 4
weight_max_vel_x 2
weight_max_vel_theta 1
weight_acc_lim_x 1
weight_acc_lim_theta 1
weight_kinematics_nh 1000
weight_kinematics_forward_drive 1
weight_kinematics_turning_radius 1
weight_optimaltime 1 # must be > 0
weight_shortest_path 0
weight_obstacle 100
weight_inflation 0.2
weight_dynamic_obstacle 10
weight_dynamic_obstacle_inflation 0.2
weight_viapoint 1
weight_adapt_factor 2
# Parallel Planning
enable_homotopy_class_planning True
enable_multithreading True
max_number_classes 4
selection_cost_hysteresis 1.0
selection_prefer_initial_plan 0.9
selection_obst_cost_scale 100.0
selection_alternative_time_cost False
roadmap_graph_no_samples 15
roadmap_graph_area_width 5
roadmap_graph_area_length_scale 1.0
h_signature_prescaler 0.5
h_signature_threshold 0.1
obstacle_heading_threshold 0.45
switching_blocking_period 0.0
viapoints_all_candidates True
delete_detours_backwards True
max_ratio_detours_duration_best_duration 3.0
visualize_hc_graph False
visualize_with_time_as_z_axis_scale False
# Recovery
shrink_horizon_backup True
shrink_horizon_min_duration 10
oscillation_recovery True
oscillation_v_eps 0.1
oscillation_omega_eps 0.1
oscillation_recovery_min_duration 10
oscillation_filter_duration 10
Robot configuration
acc_lim_x: The maximum translational acceleration of the robot(unit: m/s^2).
acc_lim_theta: The maximum angular acceleration of the robot(unit: rad/s^2).
max_vel_x: The maximum translation speed of the robot(unit: m/s).
max_vel_x_backwards: The maximum absolute translation speed of the robot when traveling backwards(unit: m/s).
max_vel_theta: The maximum angular velocity of the robot(unit: rad/s).
The following parameters are only relevant for carlike robots
min_turning_radius: Minimum turning radius for carlike robots(for differential robots, set to zero).
wheelbase: The distance between the rear axle and the front axle. For rear-wheeled robots, this value may be negative(only required if /cmd_angle_instead_rotvel is set to true).
cmd_angle_instead_rotvel: Replace the rotation speed in the command speed information with the corresponding steering angle [-pi/2, pi/2].
The following parameters are only relevant for full robots: New parameters in ROS dynamics
max_vel_y: The robot's maximum strafing velocity(should be zero for non-omnidirectional robots!).
acc_lim_y: The maximum strafing acceleration of the robot.
The following parameters are relevant to the chassis model used for optimization
footprint_model:
type: "point":
Parameter [footprint_model]
Specifies the robot schematic model type used for optimization. The different types are "point", "circular", "line", "two_circles", "polygon". The type of model significantly affects the computation time required.
footprint_model/radius: This parameter is only relevant for the "circular" type. It contains the radius of the circle. The center of the circle is on the axis of rotation of the robot.
footprint_model/line_start: This parameter is only relevant for the "line" type. It contains the starting coordinates of the line segment.
footprint_model/line_end: This parameter is only relevant for the "line" type. It contains the endpoint coordinates of the line segment.
footprint_model/front_offset: This parameter is only relevant for the ''two_circles'' type. It describes how much the center of the front circle moves along the robot's x-axis. Suppose the robot's axis of rotation is at [0,0].
footprint_model/front_radius: This parameter is only relevant for the ''two_circles'' type. .It contains the radius of the front circle.
footprint_model/rear_offset: This parameter is only relevant for the ''two_circles'' type. It describes how much the center of the back circle moves along the robot's negative x-axis. Suppose the robot's axis of rotation is at [0,0].
footprint_model/rear_radius: This parameter is only relevant for the ''two_circles'' type. It contains the radius of the back circle.
footprint_model/vertices: This parameter is only relevant for the "polygon" type. It contains a list of polygon vertices(2D coordinates of each vertex). Polygons are always closed: don't repeat the first vertex at the end.
is_footprint_dynamic: If true, the footprint is updated before the trajectory feasibility is checked.
target tolerance
Track configuration
obstacle
The following parameters are only costmap_converter plugin is required:
costmap_converter_plugin: ""
Defines the plugin name for converting costmap cells to points/lines/polygons. Set an empty string to disable conversion so that all cells are treated as point obstacles.
costmap_converter_spin_thread: If set to true, costmap_converter will call its callback queue in a different thread
costmap_converter_rate: Defines the rate at which the costmap_converter plugin processes the current costmap frequency(unit: Hz).
optimization
planning