Skip to content

Commit 815f5ae

Browse files
committed
add config files for tb3 navigation, update gadget snap with config params and connections
1 parent 0fbd9a4 commit 815f5ae

File tree

6 files changed

+374
-73
lines changed

6 files changed

+374
-73
lines changed

config/localization_params.yaml

Lines changed: 78 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,78 @@
1+
amcl:
2+
ros__parameters:
3+
4+
global_frame_id: map
5+
odom_frame_id: odom
6+
base_frame_id: base_link
7+
8+
scan_topic: scan
9+
10+
# Humble
11+
robot_model_type: nav2_amcl::OmniMotionModel
12+
13+
set_initial_pose: True
14+
always_reset_initial_pose: True
15+
initial_pose:
16+
x: 0.0
17+
y: 0.0
18+
yaw: 0.0
19+
20+
tf_broadcast: True
21+
transform_tolerance: 1.0
22+
23+
alpha1: 0.2
24+
alpha2: 0.2
25+
alpha3: 0.2
26+
alpha4: 0.2
27+
alpha5: 0.2
28+
29+
# Beam skipping - ignores beams for which a majoirty of particles do not agree with the map
30+
# prevents correct particles from getting down weighted because of unexpected obstacles
31+
# such as humans
32+
do_beamskip: False
33+
beam_skip_distance: 0.5
34+
beam_skip_error_threshold: 0.9
35+
beam_skip_threshold: 0.3
36+
37+
lambda_short: 0.1
38+
39+
laser_model_type: likelihood_field
40+
laser_likelihood_max_dist: 2.0
41+
laser_max_range: 12.0
42+
laser_min_range: -1.0
43+
44+
max_beams: 60
45+
46+
max_particles: 25000
47+
min_particles: 6000
48+
49+
pf_err: 0.05
50+
pf_z: 0.99
51+
52+
recovery_alpha_fast: 0.0
53+
recovery_alpha_slow: 0.0
54+
55+
resample_interval: 1
56+
save_pose_rate: 0.5
57+
sigma_hit: 0.2
58+
59+
update_min_a: 0.1
60+
update_min_d: 0.15
61+
62+
z_hit: 0.5
63+
z_max: 0.05
64+
z_rand: 0.5
65+
z_short: 0.05
66+
67+
map_server:
68+
ros__parameters:
69+
use_sim_time: True
70+
yaml_filename: "map.yaml"
71+
72+
map_saver:
73+
ros__parameters:
74+
use_sim_time: True
75+
save_map_timeout: 5.0
76+
free_thresh_default: 0.25
77+
occupied_thresh_default: 0.65
78+
map_subscribe_transient_local: True

config/map.pgm

Lines changed: 5 additions & 0 deletions
Large diffs are not rendered by default.

config/map.yaml

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,7 @@
1+
image: map.pgm
2+
resolution: 0.020000
3+
origin: [-10.000000, -20.240000, 0.000000]
4+
negate: 0
5+
occupied_thresh: 0.65
6+
free_thresh: 0.196
7+

config/nav2_params.yaml

Lines changed: 265 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,265 @@
1+
bt_navigator:
2+
ros__parameters:
3+
use_sim_time: True
4+
global_frame: map
5+
robot_base_frame: base_link
6+
odom_topic: /odom
7+
bt_loop_duration: 10
8+
default_server_timeout: 20
9+
enable_groot_monitoring: True
10+
groot_zmq_publisher_port: 1666
11+
groot_zmq_server_port: 1667
12+
# 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are use defaults:
13+
# nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml
14+
# nav2_bt_navigator/navigate_through_poses_w_replanning_and_recovery.xml
15+
# They can be set here or via a RewrittenYaml remap from a parent launch file to Nav2.
16+
plugin_lib_names:
17+
- nav2_compute_path_to_pose_action_bt_node
18+
- nav2_compute_path_through_poses_action_bt_node
19+
- nav2_follow_path_action_bt_node
20+
- nav2_back_up_action_bt_node
21+
- nav2_spin_action_bt_node
22+
- nav2_wait_action_bt_node
23+
- nav2_clear_costmap_service_bt_node
24+
- nav2_is_stuck_condition_bt_node
25+
- nav2_goal_reached_condition_bt_node
26+
- nav2_goal_updated_condition_bt_node
27+
- nav2_initial_pose_received_condition_bt_node
28+
- nav2_reinitialize_global_localization_service_bt_node
29+
- nav2_rate_controller_bt_node
30+
- nav2_distance_controller_bt_node
31+
- nav2_speed_controller_bt_node
32+
- nav2_truncate_path_action_bt_node
33+
- nav2_goal_updater_node_bt_node
34+
- nav2_recovery_node_bt_node
35+
- nav2_pipeline_sequence_bt_node
36+
- nav2_round_robin_node_bt_node
37+
- nav2_transform_available_condition_bt_node
38+
- nav2_time_expired_condition_bt_node
39+
- nav2_distance_traveled_condition_bt_node
40+
- nav2_single_trigger_bt_node
41+
- nav2_is_battery_low_condition_bt_node
42+
- nav2_navigate_through_poses_action_bt_node
43+
- nav2_navigate_to_pose_action_bt_node
44+
- nav2_remove_passed_goals_action_bt_node
45+
- nav2_planner_selector_bt_node
46+
- nav2_controller_selector_bt_node
47+
- nav2_goal_checker_selector_bt_node
48+
49+
bt_navigator_rclcpp_node:
50+
ros__parameters:
51+
use_sim_time: True
52+
53+
controller_server:
54+
ros__parameters:
55+
use_sim_time: True
56+
controller_frequency: 20.0
57+
min_x_velocity_threshold: 0.001
58+
min_y_velocity_threshold: 0.5
59+
min_theta_velocity_threshold: 0.001
60+
failure_tolerance: 0.3
61+
progress_checker_plugin: "progress_checker"
62+
goal_checker_plugins: ["general_goal_checker"] # "precise_goal_checker"
63+
controller_plugins: ["FollowPath"]
64+
65+
# Progress checker parameters
66+
progress_checker:
67+
plugin: "nav2_controller::SimpleProgressChecker"
68+
required_movement_radius: 0.5
69+
movement_time_allowance: 10.0
70+
# Goal checker parameters
71+
#precise_goal_checker:
72+
# plugin: "nav2_controller::SimpleGoalChecker"
73+
# xy_goal_tolerance: 0.25
74+
# yaw_goal_tolerance: 0.25
75+
# stateful: True
76+
general_goal_checker:
77+
stateful: True
78+
plugin: "nav2_controller::SimpleGoalChecker"
79+
xy_goal_tolerance: 0.25
80+
yaw_goal_tolerance: 0.25
81+
# DWB parameters
82+
FollowPath:
83+
plugin: "dwb_core::DWBLocalPlanner"
84+
debug_trajectory_details: True
85+
min_vel_x: 0.0
86+
min_vel_y: 0.0
87+
max_vel_x: 0.26
88+
max_vel_y: 0.0
89+
max_vel_theta: 1.0
90+
min_speed_xy: 0.0
91+
max_speed_xy: 0.26
92+
min_speed_theta: 0.0
93+
# Add high threshold velocity for turtlebot 3 issue.
94+
# https://github.com/ROBOTIS-GIT/turtlebot3_simulations/issues/75
95+
acc_lim_x: 2.5
96+
acc_lim_y: 0.0
97+
acc_lim_theta: 3.2
98+
decel_lim_x: -2.5
99+
decel_lim_y: 0.0
100+
decel_lim_theta: -3.2
101+
vx_samples: 20
102+
vy_samples: 5
103+
vtheta_samples: 20
104+
sim_time: 1.7
105+
linear_granularity: 0.05
106+
angular_granularity: 0.025
107+
transform_tolerance: 0.2
108+
xy_goal_tolerance: 0.25
109+
trans_stopped_velocity: 0.25
110+
short_circuit_trajectory_evaluation: True
111+
stateful: True
112+
critics: ["RotateToGoal", "Oscillation", "BaseObstacle", "GoalAlign", "PathAlign", "PathDist", "GoalDist"]
113+
BaseObstacle.scale: 0.02
114+
PathAlign.scale: 32.0
115+
PathAlign.forward_point_distance: 0.1
116+
GoalAlign.scale: 24.0
117+
GoalAlign.forward_point_distance: 0.1
118+
PathDist.scale: 32.0
119+
GoalDist.scale: 24.0
120+
RotateToGoal.scale: 32.0
121+
RotateToGoal.slowing_factor: 5.0
122+
RotateToGoal.lookahead_time: -1.0
123+
124+
controller_server_rclcpp_node:
125+
ros__parameters:
126+
use_sim_time: True
127+
128+
local_costmap:
129+
local_costmap:
130+
ros__parameters:
131+
update_frequency: 5.0
132+
publish_frequency: 2.0
133+
global_frame: odom
134+
robot_base_frame: base_link
135+
use_sim_time: True
136+
rolling_window: true
137+
width: 3
138+
height: 3
139+
resolution: 0.05
140+
footprint: "[ [0.21, 0.195], [0.21, -0.195], [-0.21, -0.195], [-0.21, 0.195] ]"
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+
map_subscribe_transient_local: True
168+
always_send_full_costmap: True
169+
local_costmap_client:
170+
ros__parameters:
171+
use_sim_time: True
172+
local_costmap_rclcpp_node:
173+
ros__parameters:
174+
use_sim_time: True
175+
176+
global_costmap:
177+
global_costmap:
178+
ros__parameters:
179+
update_frequency: 1.0
180+
publish_frequency: 1.0
181+
global_frame: map
182+
robot_base_frame: base_link
183+
use_sim_time: True
184+
robot_radius: 0.3
185+
resolution: 0.05
186+
track_unknown_space: true
187+
plugins: ["static_layer", "obstacle_layer", "inflation_layer"]
188+
obstacle_layer:
189+
plugin: "nav2_costmap_2d::ObstacleLayer"
190+
enabled: True
191+
observation_sources: scan
192+
scan:
193+
topic: /scan
194+
max_obstacle_height: 2.0
195+
clearing: True
196+
marking: True
197+
data_type: "LaserScan"
198+
raytrace_max_range: 3.0
199+
raytrace_min_range: 0.0
200+
obstacle_max_range: 2.5
201+
obstacle_min_range: 0.0
202+
static_layer:
203+
plugin: "nav2_costmap_2d::StaticLayer"
204+
map_subscribe_transient_local: True
205+
inflation_layer:
206+
plugin: "nav2_costmap_2d::InflationLayer"
207+
cost_scaling_factor: 3.0
208+
inflation_radius: 0.55
209+
always_send_full_costmap: True
210+
global_costmap_client:
211+
ros__parameters:
212+
use_sim_time: True
213+
global_costmap_rclcpp_node:
214+
ros__parameters:
215+
use_sim_time: True
216+
217+
planner_server:
218+
ros__parameters:
219+
expected_planner_frequency: 20.0
220+
use_sim_time: True
221+
planner_plugins: ["GridBased"]
222+
GridBased:
223+
plugin: "nav2_navfn_planner/NavfnPlanner"
224+
tolerance: 0.5
225+
use_astar: false
226+
allow_unknown: true
227+
228+
planner_server_rclcpp_node:
229+
ros__parameters:
230+
use_sim_time: True
231+
232+
recoveries_server:
233+
ros__parameters:
234+
costmap_topic: local_costmap/costmap_raw
235+
footprint_topic: local_costmap/published_footprint
236+
cycle_frequency: 10.0
237+
recovery_plugins: ["spin", "backup", "wait"]
238+
spin:
239+
plugin: "nav2_recoveries/Spin"
240+
backup:
241+
plugin: "nav2_recoveries/BackUp"
242+
wait:
243+
plugin: "nav2_recoveries/Wait"
244+
global_frame: odom
245+
robot_base_frame: base_link
246+
transform_timeout: 0.1
247+
use_sim_time: true
248+
simulate_ahead_time: 2.0
249+
max_rotational_vel: 1.0
250+
min_rotational_vel: 0.4
251+
rotational_acc_lim: 3.2
252+
253+
robot_state_publisher:
254+
ros__parameters:
255+
use_sim_time: True
256+
257+
waypoint_follower:
258+
ros__parameters:
259+
loop_rate: 20
260+
stop_on_failure: false
261+
waypoint_task_executor_plugin: "wait_at_waypoint"
262+
wait_at_waypoint:
263+
plugin: "nav2_waypoint_follower::WaitAtWaypoint"
264+
enabled: True
265+
waypoint_pause_duration: 200

0 commit comments

Comments
 (0)