-
Notifications
You must be signed in to change notification settings - Fork 4
/
Copy pathnav2_params.yaml
558 lines (530 loc) · 23.7 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
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
ign_sim_pointcloud_tool:
ros__parameters:
pcd_topic: livox/lidar
n_scan: 32
horizon_scan: 1875
ang_bottom: 7.0
ang_res_y: 1.84375 # (7+52) / 32
point_lio:
ros__parameters:
use_imu_as_input: False # Change to True to use IMU as input of Point-LIO
prop_at_freq_of_imu: True
check_satu: True
init_map_size: 10
point_filter_num: 8 # Options: 4, 3
space_down_sample: True
filter_size_surf: 0.5 # Options: 0.5, 0.3, 0.2, 0.15, 0.1
filter_size_map: 0.5 # Options: 0.5, 0.3, 0.15, 0.1
ivox_nearby_type: 18 # Options: 0, 6, 18, 26
runtime_pos_log_enable: False # Option: True
common:
lid_topic: "velodyne_points"
imu_topic: "livox/imu"
con_frame: False # True: if you need to combine several LiDAR frames into one
con_frame_num: 1 # the number of frames combined
cut_frame: False # True: if you need to cut one LiDAR frame into several subframes
cut_frame_time_interval: 0.05 # should be integral fraction of 1 / LiDAR frequency
time_diff_lidar_to_imu: 0.0 # Time offset between LiDAR and IMU calibrated by other algorithms, e.g., LI-Init (find in Readme)
prior_pcd:
enable: False
# NOTE: `prior_pcd_map_path` will be provided in the launch file
# prior_pcd_map_path: ""
init_pose: [ 0.0, 0.0, 0.0 ]
preprocess:
lidar_type: 2 # 1 for Livox serials LiDAR, 2 for Velodyne LiDAR, 3 for ouster LiDAR
scan_line: 32
timestamp_unit: 2 # the unit of time/t field in the PointCloud2 rostopic: 0-second, 1-milisecond, 2-microsecond, 3-nanosecond.
blind: 0.5
mapping:
imu_en: True
extrinsic_est_en: False # for aggressive motion, set this variable False
imu_time_inte: 0.005 # = 1 / frequency of IMU
lidar_time_inte: 0.1
satu_acc: 30.0 # the saturation value of IMU's acceleration. not related to the units
satu_gyro: 35.0 # the saturation value of IMU's angular velocity. not related to the units
acc_norm: 9.81 # 1.0 for g as unit, 9.81 for m/s^2 as unit of the IMU's acceleration
lidar_meas_cov: 0.001 # 0.001
acc_cov_output: 500.0
gyr_cov_output: 1000.0
b_acc_cov: 0.0001
b_gyr_cov: 0.0001
imu_meas_acc_cov: 0.1 # 0.1 # 2
imu_meas_omg_cov: 0.1 # 0.1 # 2
gyr_cov_input: 0.01 # for IMU as input model
acc_cov_input: 0.1 # for IMU as input model
plane_thr: 0.1 # 0.05, the threshold for plane criteria, the smaller, the flatter a plane
match_s: 81.0
ivox_grid_resolution: 0.5
gravity: [ 0.0, -4.9, -8.487047153776548 ] # gravity to be aligned # rpy = [0, pi/6, 0]
gravity_init: [ 0.0, -4.9, -8.487047153776548 ] # preknown gravity in the first IMU body frame, use when imu_en is False or start from a non-stationary state
extrinsic_T: [ 0.0, 0.0, 0.0 ]
extrinsic_R: [ 1.0, 0.0, 0.0,
0.0, 1.0, 0.0,
0.0, 0.0, 1.0 ]
odometry:
publish_odometry_without_downsample: True
publish:
path_en: False # False: close the path output
scan_publish_en: True # False: close all the point cloud output
scan_bodyframe_pub_en: False # True: output the point cloud scans in IMU-body-frame
tf_send_en: False # True: send transform from 'camera_init' to 'aft_mapped'
pcd_save:
pcd_save_en: False
interval: -1 # how many LiDAR frames saved in each pcd file;
# -1 : all frames will be saved in ONE pcd file, may lead to memory crash when having too much frames.
loam_interface:
ros__parameters:
use_sim_time: True
state_estimation_topic: "aft_mapped_to_init"
registered_scan_topic: "cloud_registered"
odom_frame: "odom"
base_frame: "base_footprint"
lidar_frame: "front_mid360"
sensor_scan_generation:
ros__parameters:
use_sim_time: True
lidar_frame: "front_mid360"
base_frame: "base_footprint"
robot_base_frame: "gimbal_yaw"
terrain_analysis:
ros__parameters:
sensor_frame: "front_mid360"
scan_voxel_size: 0.05
decay_time: 0.5
no_decay_dis: 0.5
clearing_dis: 8.0
use_sorting: True
quantile_z: 0.4
consider_drop: False
limit_ground_lift: False
max_ground_lift: 0.3
clear_dy_obs: True
min_dy_obs_dis: 0.3
min_dy_obs_angle: 0.0
min_dy_obs_rel_z: -0.3
abs_dy_obs_rel_z_thre: 0.2
min_dy_obs_vfov: -28.0
max_dy_obs_vfov: 33.0
min_dy_obs_point_num: 1
no_data_obstacle: False
no_data_block_skip_num: 0
min_block_point_num: 10
vehicle_height: 0.5
voxel_point_update_thre: 100
voxel_time_update_thre: 1.0
min_rel_z: -1.5
max_rel_z: 0.5
dis_ratio_z: 0.2
fake_vel_transform:
ros__parameters:
use_sim_time: True
odom_topic: "odometry"
robot_base_frame: "gimbal_yaw"
fake_robot_base_frame: "gimbal_yaw_fake"
input_cmd_vel_topic: "cmd_vel_nav2_result"
output_cmd_vel_topic: "cmd_vel"
spin_speed: 3.14
small_gicp_relocalization:
ros__parameters:
use_sim_time: True
num_threads: 4
num_neighbors: 10
global_leaf_size: 0.25
registered_leaf_size: 0.25
max_dist_sq: 1.0
map_frame: "map"
odom_frame: "odom"
base_frame: "base_footprint"
robot_base_frame: "gimbal_yaw"
lidar_frame: "front_mid360"
# The prior_pcd_file does not need to be specified since it going to be set by defaults in launch.
# prior_pcd_file: ""
bt_navigator:
ros__parameters:
use_sim_time: true
global_frame: map
robot_base_frame: gimbal_yaw_fake
odom_topic: odometry
bt_loop_duration: 10
default_server_timeout: 100
wait_for_service_timeout: 1000
default_nav_to_pose_bt_xml: $(find-pkg-share pb2025_nav_bringup)/behavior_trees/navigate_to_pose_w_replanning_and_recovery.xml # or $(find-pkg-share my_package)/behavior_tree/my_nav_to_pose_bt.xml
default_nav_through_poses_bt_xml: $(find-pkg-share pb2025_nav_bringup)/behavior_trees/navigate_through_poses_w_replanning_and_recovery.xml # or $(find-pkg-share my_package)/behavior_tree/my_nav_through_poses_bt.xml
plugin_lib_names:
- nav2_compute_path_to_pose_action_bt_node
- nav2_compute_path_through_poses_action_bt_node
- nav2_smooth_path_action_bt_node
- nav2_follow_path_action_bt_node
- nav2_spin_action_bt_node
- nav2_wait_action_bt_node
- nav2_assisted_teleop_action_bt_node
- nav2_back_up_action_bt_node
- nav2_drive_on_heading_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_globally_updated_goal_condition_bt_node
- nav2_is_path_valid_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_speed_controller_bt_node
- nav2_truncate_path_action_bt_node
- nav2_truncate_path_local_action_bt_node
- nav2_goal_updater_node_bt_node
- nav2_recovery_node_bt_node
- nav2_pipeline_sequence_bt_node
- nav2_round_robin_node_bt_node
- nav2_transform_available_condition_bt_node
- nav2_time_expired_condition_bt_node
- nav2_path_expiring_timer_condition
- nav2_distance_traveled_condition_bt_node
- nav2_single_trigger_bt_node
- nav2_goal_updated_controller_bt_node
- nav2_is_battery_low_condition_bt_node
- nav2_navigate_through_poses_action_bt_node
- nav2_navigate_to_pose_action_bt_node
- nav2_remove_passed_goals_action_bt_node
- nav2_planner_selector_bt_node
- nav2_controller_selector_bt_node
- nav2_goal_checker_selector_bt_node
- nav2_controller_cancel_bt_node
- nav2_path_longer_on_approach_bt_node
- nav2_wait_cancel_bt_node
- nav2_spin_cancel_bt_node
- nav2_back_up_cancel_bt_node
- nav2_assisted_teleop_cancel_bt_node
- nav2_drive_on_heading_cancel_bt_node
- nav2_is_battery_charging_condition_bt_node
controller_server:
ros__parameters:
use_sim_time: true
odom_topic: odometry
controller_frequency: 20.0
min_x_velocity_threshold: 0.001
min_y_velocity_threshold: 0.5
min_theta_velocity_threshold: 0.001
failure_tolerance: 0.3
progress_checker_plugins: ["progress_checker"]
goal_checker_plugins: ["general_goal_checker"]
controller_plugins: ["FollowPath"]
progress_checker:
plugin: "nav2_controller::SimpleProgressChecker"
required_movement_radius: 0.5
movement_time_allowance: 10.0
general_goal_checker:
stateful: True
plugin: "nav2_controller::SimpleGoalChecker"
xy_goal_tolerance: 0.15
yaw_goal_tolerance: 6.28
FollowPath:
plugin: "pb_omni_pid_pursuit_controller::OmniPidPursuitController"
translation_kp: 3.0
translation_ki: 0.1
translation_kd: 0.3
rotation_kp: 3.0
rotation_ki: 0.1
rotation_kd: 0.3
transform_tolerance: 0.1
min_max_sum_error: 1.0
lookahead_dist: 2.0
use_velocity_scaled_lookahead_dist: true
lookahead_time: 1.0
min_lookahead_dist: 0.5
max_lookahead_dist: 1.0
use_interpolation: false
use_rotate_to_heading: false
use_rotate_to_heading_treshold: 0.1
min_approach_linear_velocity: 0.5
approach_velocity_scaling_dist: 1.0
min_translation_speed: -2.5
max_translation_speed: 2.5
min_rotation_speed: -3.0
max_rotation_speed: 3.0
local_costmap:
local_costmap:
ros__parameters:
use_sim_time: true
update_frequency: 10.0
publish_frequency: 5.0
global_frame: odom
robot_base_frame: gimbal_yaw_fake
rolling_window: true
width: 5
height: 5
resolution: 0.05
robot_radius: 0.2
# plugins: ["static_layer", "voxel_layer", "inflation_layer"]
# voxel_layer:
# plugin: "nav2_costmap_2d::VoxelLayer"
# 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: scan
# scan:
# # '<robot_namespace>' keyword shall be replaced with 'namespace' where user defined.
# # It doesn't need to start with '/'
# topic: <robot_namespace>/rplidar_a2/scan
# max_obstacle_height: 2.0
# clearing: True
# marking: True
# data_type: "LaserScan"
# raytrace_max_range: 3.0
# raytrace_min_range: 0.0
# obstacle_max_range: 2.5
# obstacle_min_range: 0.5
plugins: ["static_layer", "stvl_layer", "inflation_layer"]
stvl_layer:
plugin: "spatio_temporal_voxel_layer/SpatioTemporalVoxelLayer"
# https://github.com/SteveMacenski/spatio_temporal_voxel_layer
enabled: true
voxel_decay: 0.2 # 如果是线性衰减,单位为秒;如果是指数衰减,则为 e 的 n 次方
decay_model: 0 # 衰减模型,0=线性,1=指数,-1=持久
voxel_size: 0.05 # 每个体素的尺寸,单位为米
track_unknown_space: true # default space is unknown
mark_threshold: 0 # voxel height
update_footprint_enabled: true
combination_method: 1 # 1=max, 0=override
origin_z: 0.0 # 单位为米
publish_voxel_map: false # default false, 是否发布体素地图
transform_tolerance: 0.2 # 单位为秒
mapping_mode: false # default off, saves map not for navigation
map_save_duration: 60.0 # default 60s, how often to autosave
observation_sources: mark clear
mark:
data_type: PointCloud2
topic: <robot_namespace>/terrain_map
marking: true
clearing: false
obstacle_range: 5.0 # meters
min_obstacle_height: 0.2 # default 0, meters
max_obstacle_height: 2.0 # default 3, meters
expected_update_rate: 0.0 # default 0, if not updating at this rate at least, remove from buffer
observation_persistence: 0.0 # default 0, use all measurements taken during now-value, 0=latest
inf_is_valid: false # default false, for laser scans
filter: "voxel" # default passthrough, apply "voxel", "passthrough", or no filter to sensor data, recommend on
voxel_min_points: 0 # default 0, minimum points per voxel for voxel filter
clear_after_reading: true # default false, clear the buffer after the layer gets readings from it
clear:
enabled: true # default true, can be toggled on/off with associated service call
data_type: PointCloud2
topic: <robot_namespace>/terrain_map
marking: false
clearing: true
max_z: 5.0 # default 10, meters
min_z: 0.1 # default 0, meters
vertical_fov_angle: 1.029 # 垂直视场角,单位为弧度,For 3D lidars it's the symmetric FOV about the planar axis.
vertical_fov_padding: 0.05 # 3D Lidar only. Default 0, in meters
horizontal_fov_angle: 6.29 # 3D 激光雷达水平视场角
decay_acceleration: 5.0 # default 0, 1/s^2.
model_type: 1 # 0=深度相机,1=3D激光雷达
static_layer:
plugin: "nav2_costmap_2d::StaticLayer"
map_subscribe_transient_local: True
inflation_layer:
plugin: "nav2_costmap_2d::InflationLayer"
cost_scaling_factor: 4.0
inflation_radius: 0.7
always_send_full_costmap: True
global_costmap:
global_costmap:
ros__parameters:
use_sim_time: true
update_frequency: 5.0
publish_frequency: 2.0
global_frame: map
robot_base_frame: gimbal_yaw_fake
robot_radius: 0.2
resolution: 0.05
track_unknown_space: true
# plugins: ["static_layer", "obstacle_layer", "inflation_layer"]
# obstacle_layer:
# plugin: "nav2_costmap_2d::ObstacleLayer"
# enabled: True
# observation_sources: scan
# scan:
# # '<robot_namespace>' keyword shall be replaced with 'namespace' where user defined.
# # It doesn't need to start with '/'
# topic: <robot_namespace>/rplidar_a2/scan
# max_obstacle_height: 2.0
# clearing: True
# marking: True
# data_type: "LaserScan"
# raytrace_max_range: 3.0
# raytrace_min_range: 0.0
# obstacle_max_range: 2.5
# obstacle_min_range: 0.5
plugins: ["static_layer", "stvl_layer", "inflation_layer"]
stvl_layer:
plugin: "spatio_temporal_voxel_layer/SpatioTemporalVoxelLayer"
# https://github.com/SteveMacenski/spatio_temporal_voxel_layer
enabled: true
voxel_decay: 0.2 # 如果是线性衰减,单位为秒;如果是指数衰减,则为 e 的 n 次方
decay_model: 0 # 衰减模型,0=线性,1=指数,-1=持久
voxel_size: 0.05 # 每个体素的尺寸,单位为米
track_unknown_space: true # default space is unknown
mark_threshold: 0 # voxel height
update_footprint_enabled: true
combination_method: 1 # 1=max, 0=override
origin_z: 0.0 # 单位为米
publish_voxel_map: false # default false, 是否发布体素地图
transform_tolerance: 0.2 # 单位为秒
mapping_mode: false # default off, saves map not for navigation
map_save_duration: 60.0 # default 60s, how often to autosave
observation_sources: mark clear
mark:
data_type: PointCloud2
topic: <robot_namespace>/terrain_map
marking: true
clearing: false
obstacle_range: 10.0 # meters
min_obstacle_height: 0.2 # default 0, meters
max_obstacle_height: 2.0 # default 3, meters
expected_update_rate: 0.0 # default 0, if not updating at this rate at least, remove from buffer
observation_persistence: 0.0 # default 0, use all measurements taken during now-value, 0=latest
inf_is_valid: false # default false, for laser scans
filter: "voxel" # default passthrough, apply "voxel", "passthrough", or no filter to sensor data, recommend on
voxel_min_points: 0 # default 0, minimum points per voxel for voxel filter
clear_after_reading: true # default false, clear the buffer after the layer gets readings from it
clear:
enabled: true # default true, can be toggled on/off with associated service call
data_type: PointCloud2
topic: <robot_namespace>/terrain_map
marking: false
clearing: true
max_z: 5.0 # default 10, meters
min_z: 0.1 # default 0, meters
vertical_fov_angle: 1.029 # 垂直视场角,单位为弧度,For 3D lidars it's the symmetric FOV about the planar axis.
vertical_fov_padding: 0.05 # 3D Lidar only. Default 0, in meters
horizontal_fov_angle: 6.29 # 3D 激光雷达水平视场角
decay_acceleration: 5.0 # default 0, 1/s^2.
model_type: 1 # 0=深度相机,1=3D激光雷达
static_layer:
plugin: "nav2_costmap_2d::StaticLayer"
map_subscribe_transient_local: True
inflation_layer:
plugin: "nav2_costmap_2d::InflationLayer"
cost_scaling_factor: 4.0
inflation_radius: 0.7
always_send_full_costmap: True
# The yaml_filename does not need to be specified since it going to be set by defaults in launch.
# If you'd rather set it in the yaml, remove the default "map" value in the tb3_simulation_launch.py
# file & provide full path to map below. If CLI map configuration or launch default is provided, that will be used.
map_server:
ros__parameters:
yaml_filename: ""
map_saver:
ros__parameters:
use_sim_time: true
save_map_timeout: 5.0
free_thresh_default: 0.25
occupied_thresh_default: 0.65
map_subscribe_transient_local: True
planner_server:
ros__parameters:
use_sim_time: true
expected_planner_frequency: 5.0
planner_plugins: ["GridBased"]
GridBased:
plugin: "nav2_navfn_planner/NavfnPlanner"
tolerance: 0.5
use_astar: false
allow_unknown: true
smoother_server:
ros__parameters:
use_sim_time: true
smoother_plugins: ["simple_smoother"]
simple_smoother:
plugin: "nav2_smoother::SimpleSmoother"
tolerance: 1.0e-10
max_its: 1000
do_refinement: True
behavior_server:
ros__parameters:
use_sim_time: true
local_costmap_topic: local_costmap/costmap_raw
global_costmap_topic: global_costmap/costmap_raw
local_footprint_topic: local_costmap/published_footprint
global_footprint_topic: global_costmap/published_footprint
cycle_frequency: 10.0
behavior_plugins: ["spin", "backup", "drive_on_heading", "assisted_teleop", "wait"]
spin:
plugin: "nav2_behaviors/Spin"
backup:
plugin: "nav2_behaviors/BackUp"
drive_on_heading:
plugin: "nav2_behaviors/DriveOnHeading"
wait:
plugin: "nav2_behaviors/Wait"
assisted_teleop:
plugin: "nav2_behaviors/AssistedTeleop"
local_frame: odom
global_frame: map
robot_base_frame: gimbal_yaw_fake
transform_tolerance: 0.1
simulate_ahead_time: 2.0
max_rotational_vel: 1.0
min_rotational_vel: 0.4
rotational_acc_lim: 3.2
waypoint_follower:
ros__parameters:
use_sim_time: true
loop_rate: 20
stop_on_failure: false
waypoint_task_executor_plugin: "wait_at_waypoint"
wait_at_waypoint:
plugin: "nav2_waypoint_follower::WaitAtWaypoint"
enabled: True
waypoint_pause_duration: 200
velocity_smoother:
ros__parameters:
use_sim_time: true
smoothing_frequency: 20.0
scale_velocities: False
feedback: "OPEN_LOOP"
max_velocity: [2.5, 2.5, 3.0]
min_velocity: [-2.5, -2.5, -3.0]
max_accel: [4.5, 4.5, 5.0]
max_decel: [-4.5, -4.5, -5.0]
odom_topic: "odometry"
odom_duration: 0.1
deadband_velocity: [0.0, 0.0, 0.0]
velocity_timeout: 1.0
pb_teleop_twist_joy_node:
ros__parameters:
use_sim_time: true
robot_base_frame: gimbal_yaw
control_mode: auto_control # Option: auto_control, manual_control
require_enable_button: true
enable_button: 4 # L1 shoulder button
enable_turbo_button: 5 # R1 shoulder button
axis_chassis:
x: 1 # Left thumb stick vertical
y: 0 # Left thumb stick horizontal
yaw: 6 # button_left and button_right
scale_chassis:
x: 2.5
y: 2.5
yaw: 3.0
scale_chassis_turbo:
x: 4.0
y: 4.0
yaw: 6.0
axis_gimbal:
roll: -1 # Disable
pitch: 4 # Right thumb stick vertical
yaw: 3 # Right thumb stick horizontal
scale_gimbal:
roll: 0.0
pitch: -1.0
yaw: 2.5
scale_gimbal_turbo:
roll: 0.0
pitch: -1.5
yaw: 3.5