Skip to content

Commit 0be2f25

Browse files
Adding config file for DWB to exercise in system tests from MPPI default migration (#4236)
* Adding config file for DWB to exercise in system tests from MPPI default migration * adding collision monitor * EOF line * correct plugin names * removing excess plugin defs
1 parent d030ea4 commit 0be2f25

File tree

2 files changed

+323
-1
lines changed

2 files changed

+323
-1
lines changed
Lines changed: 319 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,319 @@
1+
amcl:
2+
ros__parameters:
3+
alpha1: 0.2
4+
alpha2: 0.2
5+
alpha3: 0.2
6+
alpha4: 0.2
7+
alpha5: 0.2
8+
base_frame_id: "base_footprint"
9+
beam_skip_distance: 0.5
10+
beam_skip_error_threshold: 0.9
11+
beam_skip_threshold: 0.3
12+
do_beamskip: false
13+
global_frame_id: "map"
14+
lambda_short: 0.1
15+
laser_likelihood_max_dist: 2.0
16+
laser_max_range: 100.0
17+
laser_min_range: -1.0
18+
laser_model_type: "likelihood_field"
19+
max_beams: 60
20+
max_particles: 2000
21+
min_particles: 500
22+
odom_frame_id: "odom"
23+
pf_err: 0.05
24+
pf_z: 0.99
25+
recovery_alpha_fast: 0.0
26+
recovery_alpha_slow: 0.0
27+
resample_interval: 1
28+
robot_model_type: "nav2_amcl::DifferentialMotionModel"
29+
save_pose_rate: 0.5
30+
sigma_hit: 0.2
31+
tf_broadcast: true
32+
transform_tolerance: 1.0
33+
update_min_a: 0.2
34+
update_min_d: 0.25
35+
z_hit: 0.5
36+
z_max: 0.05
37+
z_rand: 0.5
38+
z_short: 0.05
39+
scan_topic: scan
40+
41+
bt_navigator:
42+
ros__parameters:
43+
global_frame: map
44+
robot_base_frame: base_link
45+
odom_topic: /odom
46+
bt_loop_duration: 10
47+
default_server_timeout: 20
48+
action_server_result_timeout: 900.0
49+
navigators: ["navigate_to_pose", "navigate_through_poses"]
50+
navigate_to_pose:
51+
plugin: "nav2_bt_navigator::NavigateToPoseNavigator"
52+
navigate_through_poses:
53+
plugin: "nav2_bt_navigator::NavigateThroughPosesNavigator"
54+
error_code_names:
55+
- compute_path_error_code
56+
- follow_path_error_code
57+
58+
controller_server:
59+
ros__parameters:
60+
controller_frequency: 20.0
61+
min_x_velocity_threshold: 0.001
62+
min_y_velocity_threshold: 0.5
63+
min_theta_velocity_threshold: 0.001
64+
failure_tolerance: 0.3
65+
progress_checker_plugins: ["progress_checker"]
66+
goal_checker_plugins: ["general_goal_checker"] # "precise_goal_checker"
67+
controller_plugins: ["FollowPath"]
68+
use_realtime_priority: false
69+
70+
# Progress checker parameters
71+
progress_checker:
72+
plugin: "nav2_controller::SimpleProgressChecker"
73+
required_movement_radius: 0.5
74+
movement_time_allowance: 10.0
75+
# Goal checker parameters
76+
#precise_goal_checker:
77+
# plugin: "nav2_controller::SimpleGoalChecker"
78+
# xy_goal_tolerance: 0.25
79+
# yaw_goal_tolerance: 0.25
80+
# stateful: True
81+
general_goal_checker:
82+
stateful: True
83+
plugin: "nav2_controller::SimpleGoalChecker"
84+
xy_goal_tolerance: 0.25
85+
yaw_goal_tolerance: 0.25
86+
# DWB parameters
87+
FollowPath:
88+
plugin: "dwb_core::DWBLocalPlanner"
89+
debug_trajectory_details: True
90+
min_vel_x: 0.0
91+
min_vel_y: 0.0
92+
max_vel_x: 0.26
93+
max_vel_y: 0.0
94+
max_vel_theta: 1.0
95+
min_speed_xy: 0.0
96+
max_speed_xy: 0.26
97+
min_speed_theta: 0.0
98+
# Add high threshold velocity for turtlebot 3 issue.
99+
# https://github.com/ROBOTIS-GIT/turtlebot3_simulations/issues/75
100+
acc_lim_x: 2.5
101+
acc_lim_y: 0.0
102+
acc_lim_theta: 3.2
103+
decel_lim_x: -2.5
104+
decel_lim_y: 0.0
105+
decel_lim_theta: -3.2
106+
vx_samples: 20
107+
vy_samples: 5
108+
vtheta_samples: 20
109+
sim_time: 1.7
110+
linear_granularity: 0.05
111+
angular_granularity: 0.025
112+
transform_tolerance: 0.2
113+
xy_goal_tolerance: 0.25
114+
trans_stopped_velocity: 0.25
115+
short_circuit_trajectory_evaluation: True
116+
stateful: True
117+
critics: ["RotateToGoal", "Oscillation", "BaseObstacle", "GoalAlign", "PathAlign", "PathDist", "GoalDist"]
118+
BaseObstacle.scale: 0.02
119+
PathAlign.scale: 32.0
120+
PathAlign.forward_point_distance: 0.1
121+
GoalAlign.scale: 24.0
122+
GoalAlign.forward_point_distance: 0.1
123+
PathDist.scale: 32.0
124+
GoalDist.scale: 24.0
125+
RotateToGoal.scale: 32.0
126+
RotateToGoal.slowing_factor: 5.0
127+
RotateToGoal.lookahead_time: -1.0
128+
129+
local_costmap:
130+
local_costmap:
131+
ros__parameters:
132+
update_frequency: 5.0
133+
publish_frequency: 2.0
134+
global_frame: odom
135+
robot_base_frame: base_link
136+
rolling_window: true
137+
width: 3
138+
height: 3
139+
resolution: 0.05
140+
robot_radius: 0.22
141+
plugins: ["voxel_layer", "inflation_layer"]
142+
inflation_layer:
143+
plugin: "nav2_costmap_2d::InflationLayer"
144+
cost_scaling_factor: 3.0
145+
inflation_radius: 0.55
146+
voxel_layer:
147+
plugin: "nav2_costmap_2d::VoxelLayer"
148+
enabled: True
149+
publish_voxel_map: True
150+
origin_z: 0.0
151+
z_resolution: 0.05
152+
z_voxels: 16
153+
max_obstacle_height: 2.0
154+
mark_threshold: 0
155+
observation_sources: scan
156+
scan:
157+
topic: /scan
158+
max_obstacle_height: 2.0
159+
clearing: True
160+
marking: True
161+
data_type: "LaserScan"
162+
raytrace_max_range: 3.0
163+
raytrace_min_range: 0.0
164+
obstacle_max_range: 2.5
165+
obstacle_min_range: 0.0
166+
static_layer:
167+
plugin: "nav2_costmap_2d::StaticLayer"
168+
map_subscribe_transient_local: True
169+
always_send_full_costmap: True
170+
171+
global_costmap:
172+
global_costmap:
173+
ros__parameters:
174+
update_frequency: 1.0
175+
publish_frequency: 1.0
176+
global_frame: map
177+
robot_base_frame: base_link
178+
robot_radius: 0.22
179+
resolution: 0.05
180+
track_unknown_space: true
181+
plugins: ["static_layer", "obstacle_layer", "inflation_layer"]
182+
obstacle_layer:
183+
plugin: "nav2_costmap_2d::ObstacleLayer"
184+
enabled: True
185+
observation_sources: scan
186+
scan:
187+
topic: /scan
188+
max_obstacle_height: 2.0
189+
clearing: True
190+
marking: True
191+
data_type: "LaserScan"
192+
raytrace_max_range: 3.0
193+
raytrace_min_range: 0.0
194+
obstacle_max_range: 2.5
195+
obstacle_min_range: 0.0
196+
static_layer:
197+
plugin: "nav2_costmap_2d::StaticLayer"
198+
map_subscribe_transient_local: True
199+
inflation_layer:
200+
plugin: "nav2_costmap_2d::InflationLayer"
201+
cost_scaling_factor: 3.0
202+
inflation_radius: 0.55
203+
always_send_full_costmap: True
204+
205+
# The yaml_filename does not need to be specified since it going to be set by defaults in launch.
206+
# If you'd rather set it in the yaml, remove the default "map" value in the tb3_simulation_launch.py
207+
# file & provide full path to map below. If CLI map configuration or launch default is provided, that will be used.
208+
# map_server:
209+
# ros__parameters:
210+
# yaml_filename: ""
211+
212+
map_saver:
213+
ros__parameters:
214+
save_map_timeout: 5.0
215+
free_thresh_default: 0.25
216+
occupied_thresh_default: 0.65
217+
map_subscribe_transient_local: True
218+
219+
planner_server:
220+
ros__parameters:
221+
expected_planner_frequency: 20.0
222+
planner_plugins: ["GridBased"]
223+
GridBased:
224+
plugin: "nav2_navfn_planner::NavfnPlanner"
225+
tolerance: 0.5
226+
use_astar: false
227+
allow_unknown: true
228+
229+
smoother_server:
230+
ros__parameters:
231+
smoother_plugins: ["simple_smoother"]
232+
simple_smoother:
233+
plugin: "nav2_smoother::SimpleSmoother"
234+
tolerance: 1.0e-10
235+
max_its: 1000
236+
do_refinement: True
237+
238+
behavior_server:
239+
ros__parameters:
240+
local_costmap_topic: local_costmap/costmap_raw
241+
global_costmap_topic: global_costmap/costmap_raw
242+
local_footprint_topic: local_costmap/published_footprint
243+
global_footprint_topic: global_costmap/published_footprint
244+
cycle_frequency: 10.0
245+
behavior_plugins: ["spin", "backup", "drive_on_heading", "assisted_teleop", "wait"]
246+
spin:
247+
plugin: "nav2_behaviors::Spin"
248+
backup:
249+
plugin: "nav2_behaviors::BackUp"
250+
drive_on_heading:
251+
plugin: "nav2_behaviors::DriveOnHeading"
252+
wait:
253+
plugin: "nav2_behaviors::Wait"
254+
assisted_teleop:
255+
plugin: "nav2_behaviors::AssistedTeleop"
256+
local_frame: odom
257+
global_frame: map
258+
robot_base_frame: base_link
259+
transform_tolerance: 0.1
260+
simulate_ahead_time: 2.0
261+
max_rotational_vel: 1.0
262+
min_rotational_vel: 0.4
263+
rotational_acc_lim: 3.2
264+
265+
waypoint_follower:
266+
ros__parameters:
267+
loop_rate: 20
268+
stop_on_failure: false
269+
action_server_result_timeout: 900.0
270+
waypoint_task_executor_plugin: "wait_at_waypoint"
271+
wait_at_waypoint:
272+
plugin: "nav2_waypoint_follower::WaitAtWaypoint"
273+
enabled: True
274+
waypoint_pause_duration: 200
275+
276+
velocity_smoother:
277+
ros__parameters:
278+
smoothing_frequency: 20.0
279+
scale_velocities: False
280+
feedback: "OPEN_LOOP"
281+
max_velocity: [0.26, 0.0, 1.0]
282+
min_velocity: [-0.26, 0.0, -1.0]
283+
max_accel: [2.5, 0.0, 3.2]
284+
max_decel: [-2.5, 0.0, -3.2]
285+
odom_topic: "odom"
286+
odom_duration: 0.1
287+
deadband_velocity: [0.0, 0.0, 0.0]
288+
velocity_timeout: 1.0
289+
290+
collision_monitor:
291+
ros__parameters:
292+
base_frame_id: "base_footprint"
293+
odom_frame_id: "odom"
294+
cmd_vel_in_topic: "cmd_vel_smoothed"
295+
cmd_vel_out_topic: "cmd_vel"
296+
state_topic: "collision_monitor_state"
297+
transform_tolerance: 0.2
298+
source_timeout: 1.0
299+
base_shift_correction: True
300+
stop_pub_timeout: 2.0
301+
# Polygons represent zone around the robot for "stop", "slowdown" and "limit" action types,
302+
# and robot footprint for "approach" action type.
303+
polygons: ["FootprintApproach"]
304+
FootprintApproach:
305+
type: "polygon"
306+
action_type: "approach"
307+
footprint_topic: "/local_costmap/published_footprint"
308+
time_before_collision: 1.2
309+
simulation_time_step: 0.1
310+
min_points: 6
311+
visualize: False
312+
enabled: True
313+
observation_sources: ["scan"]
314+
scan:
315+
type: "scan"
316+
topic: "scan"
317+
min_height: 0.15
318+
max_height: 2.0
319+
enabled: True

nav2_system_tests/src/system/test_system_launch.py

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -46,7 +46,10 @@ def generate_launch_description():
4646
)
4747

4848
bringup_dir = get_package_share_directory('nav2_bringup')
49-
params_file = os.path.join(bringup_dir, 'params', 'nav2_params.yaml')
49+
50+
# Use local param file
51+
launch_dir = os.path.dirname(os.path.realpath(__file__))
52+
params_file = os.path.join(launch_dir, 'nav2_system_params.yaml')
5053

5154
# Replace the default parameter values for testing special features
5255
# without having multiple params_files inside the nav2 stack

0 commit comments

Comments
 (0)