|
1 | 1 | /controller_server: |
2 | 2 | ros__parameters: |
3 | 3 | use_sim_time: false |
4 | | - controller_plugins: ["FollowWaypoints"] |
| 4 | + controller_plugins: ["RegulatedPurePursuitController"] |
| 5 | + controller_frequency: 10.0 |
| 6 | + transform_tolerance: 0.1 |
5 | 7 |
|
6 | | - local_costmap: |
| 8 | + progress_checker_plugins: ["progress_checker"] |
| 9 | + goal_checker_plugins: ["goal_checker"] |
| 10 | + |
| 11 | + progress_checker: |
| 12 | + plugin: "nav2_controller::SimpleProgressChecker" |
| 13 | + required_movement_radius: 0.5 |
| 14 | + movement_time_allowance: 10.0 |
| 15 | + |
| 16 | + goal_checker: |
| 17 | + plugin: "nav2_controller::SimpleGoalChecker" |
| 18 | + xy_goal_tolerance: 0.5 |
| 19 | + yaw_goal_tolerance: 0.2 |
| 20 | + stateful: true |
| 21 | + |
| 22 | + RegulatedPurePursuitController: |
| 23 | + plugin: "nav2_regulated_pure_pursuit_controller::RegulatedPurePursuitController" |
| 24 | + lookahead_dist: 0.5 |
| 25 | + desired_linear_vel: 0.25 |
| 26 | + |
| 27 | +/local_costmap: |
| 28 | + local_costmap: |
| 29 | + ros__parameters: |
7 | 30 | global_frame: local_enu |
8 | 31 | robot_base_frame: base_link |
9 | 32 | update_frequency: 5.0 |
10 | 33 | publish_frequency: 2.0 |
11 | 34 | rolling_window: true |
12 | | - width: 1000.0 |
13 | | - height: 1000.0 |
| 35 | + width: 1000 |
| 36 | + height: 1000 |
14 | 37 | resolution: 5.0 |
15 | | - transform_tolerance: 1.0 |
16 | | - inflation_radius: 0.5 |
| 38 | + transform_tolerance: 0.5 |
| 39 | + robot_radius: 0.6 |
17 | 40 | cost_scaling_factor: 10.0 |
18 | 41 |
|
19 | | - plugins: |
20 | | - - name: obstacle_layer |
21 | | - type: "nav2_costmap_2d::ObstacleLayer" |
22 | | - - name: inflation_layer |
23 | | - type: "nav2_costmap_2d::InflationLayer" |
| 42 | + static_layer: |
| 43 | + enabled: false |
| 44 | + |
| 45 | + plugins: ["obstacle_layer", "inflation_layer"] |
| 46 | + |
| 47 | + obstacle_layer: |
| 48 | + plugin: "nav2_costmap_2d::ObstacleLayer" |
24 | 49 |
|
25 | | - FollowWaypoints: |
26 | | - plugin: "nav2_controller::FollowWaypoints" |
27 | | - allow_in_place_goal: true |
28 | | - controller_frequency: 10.0 |
| 50 | + inflation_layer: |
| 51 | + plugin: "nav2_costmap_2d::InflationLayer" |
| 52 | + inflation_radius: 2.0 |
| 53 | + cost_scaling_factor: 10.0 |
29 | 54 |
|
0 commit comments