-
Notifications
You must be signed in to change notification settings - Fork 1.2k
/
nav2_params.yaml
248 lines (235 loc) · 7.04 KB
/
nav2_params.yaml
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
amcl:
ros__parameters:
use_sim_time: True
alpha1: 0.2
alpha2: 0.2
alpha3: 0.2
alpha4: 0.2
alpha5: 0.2
base_frame_id: "base_footprint"
beam_skip_distance: 0.5
beam_skip_error_threshold: 0.9
beam_skip_threshold: 0.3
do_beamskip: false
global_frame_id: "map"
lambda_short: 0.1
laser_likelihood_max_dist: 2.0
laser_max_range: 100.0
laser_min_range: -1.0
laser_model_type: "likelihood_field"
max_beams: 60
max_particles: 2000
min_particles: 500
odom_frame_id: "odom"
pf_err: 0.05
pf_z: 0.99
recovery_alpha_fast: 0.0
recovery_alpha_slow: 0.0
resample_interval: 1
robot_model_type: "differential"
save_pose_rate: 0.5
sigma_hit: 0.2
tf_broadcast: true
transform_tolerance: 1.0
update_min_a: 0.2
update_min_d: 0.25
z_hit: 0.5
z_max: 0.05
z_rand: 0.5
z_short: 0.05
amcl_map_client:
ros__parameters:
use_sim_time: True
amcl_rclcpp_node:
ros__parameters:
use_sim_time: True
bt_navigator:
ros__parameters:
use_sim_time: True
global_frame: map
robot_base_frame: base_link
bt_xml_filename: "navigate_w_replanning_and_recovery.xml"
plugin_lib_names:
- nav2_compute_path_to_pose_action_bt_node
- nav2_follow_path_action_bt_node
- nav2_back_up_action_bt_node
- nav2_spin_action_bt_node
- nav2_wait_action_bt_node
- nav2_clear_costmap_service_bt_node
- nav2_is_stuck_condition_bt_node
- nav2_goal_reached_condition_bt_node
- nav2_goal_updated_condition_bt_node
- nav2_initial_pose_received_condition_bt_node
- nav2_reinitialize_global_localization_service_bt_node
- nav2_rate_controller_bt_node
- nav2_distance_controller_bt_node
- nav2_recovery_node_bt_node
- nav2_pipeline_sequence_bt_node
- nav2_round_robin_node_bt_node
- nav2_transform_available_condition_bt_node
bt_navigator_rclcpp_node:
ros__parameters:
use_sim_time: True
controller_server:
ros__parameters:
use_sim_time: True
controller_frequency: 20.0
controller_plugin_types: ["dwb_core::DWBLocalPlanner"]
controller_plugin_ids: ["FollowPath"]
min_x_velocity_threshold: 0.001
min_y_velocity_threshold: 0.5
min_theta_velocity_threshold: 0.001
# DWB parameters
FollowPath.debug_trajectory_details: True
FollowPath.min_vel_x: 0.0
FollowPath.min_vel_y: 0.0
FollowPath.max_vel_x: 0.26
FollowPath.max_vel_y: 0.0
FollowPath.max_vel_theta: 1.0
FollowPath.min_speed_xy: 0.0
FollowPath.max_speed_xy: 0.26
FollowPath.min_speed_theta: 0.0
# Add high threshold velocity for turtlebot 3 issue.
# https://github.com/ROBOTIS-GIT/turtlebot3_simulations/issues/75
FollowPath.acc_lim_x: 2.5
FollowPath.acc_lim_y: 0.0
FollowPath.acc_lim_theta: 3.2
FollowPath.decel_lim_x: -2.5
FollowPath.decel_lim_y: 0.0
FollowPath.decel_lim_theta: -3.2
FollowPath.vx_samples: 20
FollowPath.vy_samples: 5
FollowPath.vtheta_samples: 20
FollowPath.sim_time: 1.7
FollowPath.linear_granularity: 0.05
FollowPath.angular_granularity: 0.025
FollowPath.transform_tolerance: 0.2
FollowPath.xy_goal_tolerance: 0.25
FollowPath.trans_stopped_velocity: 0.25
FollowPath.short_circuit_trajectory_evaluation: True
FollowPath.stateful: True
FollowPath.critics: ["RotateToGoal", "Oscillation", "BaseObstacle", "GoalAlign", "PathAlign", "PathDist", "GoalDist"]
FollowPath.BaseObstacle.scale: 0.02
FollowPath.PathAlign.scale: 0.0
FollowPath.GoalAlign.scale: 0.0
FollowPath.PathDist.scale: 32.0
FollowPath.GoalDist.scale: 24.0
FollowPath.RotateToGoal.scale: 32.0
FollowPath.RotateToGoal.slowing_factor: 5.0
FollowPath.RotateToGoal.lookahead_time: -1.0
controller_server_rclcpp_node:
ros__parameters:
use_sim_time: True
local_costmap:
local_costmap:
ros__parameters:
update_frequency: 5.0
publish_frequency: 2.0
robot_base_frame: base_link
use_sim_time: True
global_frame: odom
rolling_window: true
width: 3
height: 3
resolution: 0.05
plugin_names: ["obstacle_layer", "voxel_layer", "inflation_layer"]
plugin_types: ["nav2_costmap_2d::ObstacleLayer", "nav2_costmap_2d::VoxelLayer", "nav2_costmap_2d::InflationLayer"]
robot_radius: 0.22
inflation_layer:
cost_scaling_factor: 3.0
obstacle_layer:
enabled: True
observation_sources: scan
scan:
topic: /scan
max_obstacle_height: 2.0
clearing: True
marking: True
data_type: "LaserScan"
voxel_layer:
enabled: True
publish_voxel_map: True
origin_z: 0.0
z_resolution: 0.05
z_voxels: 16
max_obstacle_height: 2.0
mark_threshold: 0
observation_sources: pointcloud
pointcloud:
topic: /intel_realsense_r200_depth/points
max_obstacle_height: 2.0
clearing: True
marking: True
data_type: "PointCloud2"
static_layer:
map_subscribe_transient_local: True
always_send_full_costmap: True
local_costmap_client:
ros__parameters:
use_sim_time: True
local_costmap_rclcpp_node:
ros__parameters:
use_sim_time: True
global_costmap:
global_costmap:
ros__parameters:
update_frequency: 1.0
publish_frequency: 1.0
robot_base_frame: base_link
global_frame: map
use_sim_time: True
plugin_names: ["static_layer", "obstacle_layer", "voxel_layer", "inflation_layer"]
plugin_types: ["nav2_costmap_2d::StaticLayer", "nav2_costmap_2d::ObstacleLayer", "nav2_costmap_2d::VoxelLayer", "nav2_costmap_2d::InflationLayer"]
robot_radius: 0.22
resolution: 0.05
obstacle_layer:
enabled: True
observation_sources: scan
scan:
topic: /scan
max_obstacle_height: 2.0
clearing: True
marking: True
data_type: "LaserScan"
voxel_layer:
enabled: True
publish_voxel_map: True
origin_z: 0.0
z_resolution: 0.05
z_voxels: 16
max_obstacle_height: 2.0
mark_threshold: 0
observation_sources: pointcloud
pointcloud:
topic: /intel_realsense_r200_depth/points
max_obstacle_height: 2.0
clearing: True
marking: True
data_type: "PointCloud2"
static_layer:
map_subscribe_transient_local: True
always_send_full_costmap: True
global_costmap_client:
ros__parameters:
use_sim_time: True
global_costmap_rclcpp_node:
ros__parameters:
use_sim_time: True
map_server:
ros__parameters:
use_sim_time: True
yaml_filename: "turtlebot3_world.yaml"
planner_server:
ros__parameters:
planner_plugin_types: ["nav2_navfn_planner/NavfnPlanner"]
planner_plugin_ids: ["GridBased"]
use_sim_time: True
GridBased.tolerance: 0.5
GridBased.use_astar: false
GridBased.allow_unknown: true
planner_server_rclcpp_node:
ros__parameters:
use_sim_time: True
robot_state_publisher:
ros__parameters:
use_sim_time: True