|
| 1 | +# GLOBAL PLANNER: |
| 2 | +NavfnROS: |
| 3 | + allow_unknown: false # whether or not to allow global planner to create paths that traverse unknown spaces |
| 4 | + default_tolerance: 0.1 # global planner will attempt to plan path that is no further away than this value from the specified goal point |
| 5 | + use_dijkstra: false # if true, use Dijkstra's algorithm, otherwise use A* algorithm |
| 6 | + |
| 7 | +# LOCAL PLANNER: |
1 | 8 | TebLocalPlannerROS: |
2 | 9 | odom_topic: /odom |
3 | | - map_frame: /map |
| 10 | + map_frame: /map |
4 | 11 | # Trajectory |
5 | 12 | teb_autosize: True |
6 | 13 | dt_ref: 0.4 |
7 | 14 | dt_hysteresis: 0.1 |
8 | 15 | global_plan_overwrite_orientation: True |
9 | 16 | max_global_plan_lookahead_dist: 3.0 |
10 | 17 | feasibility_check_no_poses: 2 |
11 | | - allow_init_backward_motion: false |
12 | | - # Robot |
| 18 | + allow_init_backward_motion: false |
| 19 | + # Robot |
13 | 20 | max_vel_x: 0.2 # [sim max: 0.26 m/s] |
14 | 21 | max_vel_x_backwards: 0.2 # [sim max: 0.23 m/s] |
15 | 22 | max_vel_theta: 0.5236 # [sim max: 0.67 rad/s] angular velocity is also bounded by min_turning_radius in case of a carlike robot (omega = v/r) |
16 | 23 | acc_lim_x: 0.15 |
17 | 24 | acc_lim_theta: 0.3927 |
18 | | - # ***************** Carlike robot parameters ******************** |
| 25 | + # Carlike robot parameters |
19 | 26 | min_turning_radius: 0.24515 # min turning radius of the carlike robot (compute value using a model or adjust with rqt_reconfigure manually) |
20 | 27 | wheelbase: 0.14154 # wheelbase of the carlike robot |
21 | 28 | cmd_angle_instead_rotvel: True # return steering angle instead of the rotvel (angular.z of twist message) |
22 | 29 | footprint_model: |
23 | 30 | type: "line" |
24 | 31 | line_start: [-0.07077, 0.0] # for type "line" |
25 | 32 | line_end: [0.07077, 0.0] # for type "line" |
26 | | - # GoalTolerance |
| 33 | + # GoalTolerance |
27 | 34 | xy_goal_tolerance: 0.1 |
28 | 35 | yaw_goal_tolerance: 0.1 |
29 | | - free_goal_vel: False |
30 | | - # Obstacles |
| 36 | + free_goal_vel: False |
| 37 | + # Obstacles |
31 | 38 | min_obstacle_dist: 0.2 # this value must also include our robot's expansion, since footprint_model is set to "line". |
32 | 39 | include_costmap_obstacles: True |
33 | 40 | costmap_obstacles_behind_robot_dist: 1.5 |
34 | 41 | obstacle_poses_affected: 30 |
35 | 42 | costmap_converter_plugin: "" |
36 | 43 | costmap_converter_spin_thread: True |
37 | 44 | costmap_converter_rate: 5 |
38 | | - # Optimization |
| 45 | + # Optimization |
39 | 46 | no_inner_iterations: 3 |
40 | 47 | no_outer_iterations: 3 |
41 | 48 | optimization_activate: True |
|
0 commit comments