]> defiant.homedns.org Git - ros_wild_thumper.git/blob - config/base_local_planner_params.yaml
urdf: added antenna
[ros_wild_thumper.git] / config / base_local_planner_params.yaml
1 TrajectoryPlannerROS:
2   min_vel_x: 0.05
3   max_vel_x: 0.5
4   min_vel_theta: -1.0
5   max_vel_theta: 1.0
6   min_in_place_vel_theta: 0.4
7   max_rotational_vel: 1.0 # used by rotate recovery
8   escape_vel: 0.0 # Speed used for driving during escapes in meters/sec. Will move slowly even when the static map shows it as blocked
9
10   acc_lim_x: 0.14
11   acc_lim_y: 0.0
12   acc_lim_theta: 6.00
13
14   holonomic_robot: false
15   # gdist_scale and pdist_scale parameters should assume meters
16   meter_scoring: true
17
18   xy_goal_tolerance: 0.15
19   yaw_goal_tolerance: 0.1
20   # If goal tolerance is latched, if the robot ever reaches the goal xy location it will simply rotate in place, even if it ends up outside the goal tolerance while it is doing so.
21   latch_xy_goal_tolerance: true
22
23   # The weighting for how much the controller should attempt to avoid obstacles, default: 0.01
24   occdist_scale: 0.02
25
26   # Whether to score based on the robot's heading to the path or its distance from the path, default: false
27   heading_scoring: false
28
29   # How far to look ahead in time in seconds along the simulated trajectory when using heading scoring, default: 0.1
30   heading_scoring_timestep: 0.3
31
32   # How far the robot must travel in meters before oscillation flags are reset, default: 0.05
33   oscillation_reset_dist: 0.1
34
35   # The step size, in meters, to take between points on a given trajectory, default: 0.025
36   sim_granularity: 0.05
37
38   # The step size, in radians, to take between angular samples on a given trajectory, default: sim_granularity
39   angular_sim_granularity: 0.05
40
41 DWAPlannerROS:
42   acc_lim_x: 10.07
43   acc_lim_y: 0.0
44   acc_lim_th: 6.00
45
46   max_vel_x: 0.5
47   min_vel_x: 0.1
48   max_vel_y: 0.0
49   min_vel_y: 0.0
50
51   max_trans_vel: 0.5
52   min_trans_vel: 0.1
53   max_rot_vel: 1.0
54   min_rot_vel: 0.4
55
56   xy_goal_tolerance: 0.15
57   yaw_goal_tolerance: 0.1
58
59   # The weighting for how much the controller should attempt to avoid obstacles, default: 0.01
60   occdist_scale: 0.02
61   # The weighting for how much the controller should stay close to the path it was given, default: 32.0
62   path_distance_bias: 64.0
63
64 PoseFollower:
65   holonomic: false
66   max_vel_lin: 0.5
67   max_vel_th: 1.0
68   min_vel_lin: 0.0
69   min_vel_th: 0.0
70   tolerance_trans: 0.15
71   tolerance_rot: 0.1
72   tolerance_timeout: 0.1
73   trans_stopped_velocity: 0.001
74   rot_stopped_velocity: 0.001
75   allow_backwards: false
76   # If true, turn in place to face the new goal instead of arching towards it
77   turn_in_place_first: false
78   # If turn_in_place_first is true, turn in place if our heading is more than this far from facing the goal location
79   max_heading_diff_before_moving: 0.175
80   # Gain factor for translation component of output velocities 0..20
81   k_trans: 1.0
82   # Gain factor for rotation component of output velocities: 0..20
83   k_rot: 2.0
84   collision_planner: # =TrajectoryPlannerROS
85     holonomic_robot: false
86     meter_scoring: true
87     xy_goal_tolerance: 0.15
88     yaw_goal_tolerance: 0.1
89     heading_scoring: false
90     heading_scoring_timestep: 0.3
91     oscillation_reset_dist: 0.1
92     sim_granularity: 0.05
93     angular_sim_granularity: 0.05