Skip to content

Commit 67b5704

Browse files
author
star
committed
fix problem with nav2 params to work with lateast update amd ekf localization yaml file
1 parent b50817d commit 67b5704

File tree

2 files changed

+157
-68
lines changed

2 files changed

+157
-68
lines changed

nav2_gps_waypoint_follower_demo/config/dual_ekf_navsat_params.yaml

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -10,10 +10,10 @@ ekf_filter_node_odom:
1010

1111
map_frame: map
1212
odom_frame: odom
13-
base_link_frame: base_footprint # the frame id used by the turtlebot's diff drive plugin
13+
base_link_frame: base_link # the frame id used by the turtlebot's diff drive plugin
1414
world_frame: odom
1515

16-
odom0: odom
16+
odom0: /demo/odom
1717
odom0_config: [false, false, false,
1818
false, false, false,
1919
true, true, true,
@@ -23,7 +23,7 @@ ekf_filter_node_odom:
2323
odom0_differential: false
2424
odom0_relative: false
2525

26-
imu0: imu
26+
imu0: demo/imu
2727
imu0_config: [false, false, false,
2828
false, false, true,
2929
false, false, false,
@@ -62,10 +62,10 @@ ekf_filter_node_map:
6262

6363
map_frame: map
6464
odom_frame: odom
65-
base_link_frame: base_footprint # the frame id used by the turtlebot's diff drive plugin
65+
base_link_frame: base_link # the frame id used by the turtlebot's diff drive plugin
6666
world_frame: map
6767

68-
odom0: odom
68+
odom0: /demo/odom
6969
odom0_config: [false, false, false,
7070
false, false, false,
7171
true, true, true,
@@ -85,7 +85,7 @@ ekf_filter_node_map:
8585
odom1_differential: false
8686
odom1_relative: false
8787

88-
imu0: imu
88+
imu0: /demo/imu
8989
imu0_config: [false, false, false,
9090
false, false, true,
9191
false, false, false,

nav2_gps_waypoint_follower_demo/config/nav2_no_map_params.yaml

Lines changed: 151 additions & 62 deletions
Original file line numberDiff line numberDiff line change
@@ -10,70 +10,70 @@ bt_navigator:
1010
ros__parameters:
1111
global_frame: map
1212
robot_base_frame: base_link
13-
odom_topic: /odom
13+
odom_topic: /odometry/global
1414
bt_loop_duration: 10
1515
default_server_timeout: 20
1616
navigators: ["navigate_to_pose", "navigate_through_poses"]
1717
navigate_to_pose:
18-
plugin: "nav2_bt_navigator/NavigateToPoseNavigator"
18+
plugin: "nav2_bt_navigator::NavigateToPoseNavigator"
1919
navigate_through_poses:
20-
plugin: "nav2_bt_navigator/NavigateThroughPosesNavigator"
20+
plugin: "nav2_bt_navigator::NavigateThroughPosesNavigator"
2121
# 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are use defaults:
2222
# nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml
2323
# nav2_bt_navigator/navigate_through_poses_w_replanning_and_recovery.xml
2424
# They can be set here or via a RewrittenYaml remap from a parent launch file to Nav2.
25-
plugin_lib_names:
26-
- nav2_compute_path_to_pose_action_bt_node
27-
- nav2_compute_path_through_poses_action_bt_node
28-
- nav2_smooth_path_action_bt_node
29-
- nav2_follow_path_action_bt_node
30-
- nav2_spin_action_bt_node
31-
- nav2_wait_action_bt_node
32-
- nav2_assisted_teleop_action_bt_node
33-
- nav2_back_up_action_bt_node
34-
- nav2_drive_on_heading_bt_node
35-
- nav2_clear_costmap_service_bt_node
36-
- nav2_is_stuck_condition_bt_node
37-
- nav2_goal_reached_condition_bt_node
38-
- nav2_goal_updated_condition_bt_node
39-
- nav2_globally_updated_goal_condition_bt_node
40-
- nav2_is_path_valid_condition_bt_node
41-
- nav2_are_error_codes_active_condition_bt_node
42-
- nav2_would_a_controller_recovery_help_condition_bt_node
43-
- nav2_would_a_planner_recovery_help_condition_bt_node
44-
- nav2_would_a_smoother_recovery_help_condition_bt_node
45-
- nav2_initial_pose_received_condition_bt_node
46-
- nav2_reinitialize_global_localization_service_bt_node
47-
- nav2_rate_controller_bt_node
48-
- nav2_distance_controller_bt_node
49-
- nav2_speed_controller_bt_node
50-
- nav2_truncate_path_action_bt_node
51-
- nav2_truncate_path_local_action_bt_node
52-
- nav2_goal_updater_node_bt_node
53-
- nav2_recovery_node_bt_node
54-
- nav2_pipeline_sequence_bt_node
55-
- nav2_round_robin_node_bt_node
56-
- nav2_transform_available_condition_bt_node
57-
- nav2_time_expired_condition_bt_node
58-
- nav2_path_expiring_timer_condition
59-
- nav2_distance_traveled_condition_bt_node
60-
- nav2_single_trigger_bt_node
61-
- nav2_goal_updated_controller_bt_node
62-
- nav2_is_battery_low_condition_bt_node
63-
- nav2_navigate_through_poses_action_bt_node
64-
- nav2_navigate_to_pose_action_bt_node
65-
- nav2_remove_passed_goals_action_bt_node
66-
- nav2_planner_selector_bt_node
67-
- nav2_controller_selector_bt_node
68-
- nav2_goal_checker_selector_bt_node
69-
- nav2_controller_cancel_bt_node
70-
- nav2_path_longer_on_approach_bt_node
71-
- nav2_wait_cancel_bt_node
72-
- nav2_spin_cancel_bt_node
73-
- nav2_back_up_cancel_bt_node
74-
- nav2_assisted_teleop_cancel_bt_node
75-
- nav2_drive_on_heading_cancel_bt_node
76-
- nav2_is_battery_charging_condition_bt_node
25+
# plugin_lib_names:
26+
# - nav2_compute_path_to_pose_action_bt_node
27+
# - nav2_compute_path_through_poses_action_bt_node
28+
# - nav2_smooth_path_action_bt_node
29+
# - nav2_follow_path_action_bt_node
30+
# - nav2_spin_action_bt_node
31+
# - nav2_wait_action_bt_node
32+
# - nav2_assisted_teleop_action_bt_node
33+
# - nav2_back_up_action_bt_node
34+
# - nav2_drive_on_heading_bt_node
35+
# - nav2_clear_costmap_service_bt_node
36+
# - nav2_is_stuck_condition_bt_node
37+
# - nav2_goal_reached_condition_bt_node
38+
# - nav2_goal_updated_condition_bt_node
39+
# - nav2_globally_updated_goal_condition_bt_node
40+
# - nav2_is_path_valid_condition_bt_node
41+
# - nav2_are_error_codes_active_condition_bt_node
42+
# - nav2_would_a_controller_recovery_help_condition_bt_node
43+
# - nav2_would_a_planner_recovery_help_condition_bt_node
44+
# - nav2_would_a_smoother_recovery_help_condition_bt_node
45+
# - nav2_initial_pose_received_condition_bt_node
46+
# - nav2_reinitialize_global_localization_service_bt_node
47+
# - nav2_rate_controller_bt_node
48+
# - nav2_distance_controller_bt_node
49+
# - nav2_speed_controller_bt_node
50+
# - nav2_truncate_path_action_bt_node
51+
# - nav2_truncate_path_local_action_bt_node
52+
# - nav2_goal_updater_node_bt_node
53+
# - nav2_recovery_node_bt_node
54+
# - nav2_pipeline_sequence_bt_node
55+
# - nav2_round_robin_node_bt_node
56+
# - nav2_transform_available_condition_bt_node
57+
# - nav2_time_expired_condition_bt_node
58+
# - nav2_path_expiring_timer_condition
59+
# - nav2_distance_traveled_condition_bt_node
60+
# - nav2_single_trigger_bt_node
61+
# - nav2_goal_updated_controller_bt_node
62+
# - nav2_is_battery_low_condition_bt_node
63+
# - nav2_navigate_through_poses_action_bt_node
64+
# - nav2_navigate_to_pose_action_bt_node
65+
# - nav2_remove_passed_goals_action_bt_node
66+
# - nav2_planner_selector_bt_node
67+
# - nav2_controller_selector_bt_node
68+
# - nav2_goal_checker_selector_bt_node
69+
# - nav2_controller_cancel_bt_node
70+
# - nav2_path_longer_on_approach_bt_node
71+
# - nav2_wait_cancel_bt_node
72+
# - nav2_spin_cancel_bt_node
73+
# - nav2_back_up_cancel_bt_node
74+
# - nav2_assisted_teleop_cancel_bt_node
75+
# - nav2_drive_on_heading_cancel_bt_node
76+
# - nav2_is_battery_charging_condition_bt_node
7777
error_code_names:
7878
- compute_path_error_code
7979
- follow_path_error_code
@@ -249,7 +249,7 @@ planner_server:
249249
expected_planner_frequency: 20.0
250250
planner_plugins: ["GridBased"]
251251
GridBased:
252-
plugin: "nav2_navfn_planner/NavfnPlanner"
252+
plugin: "nav2_navfn_planner::NavfnPlanner"
253253
tolerance: 0.5
254254
use_astar: false
255255
allow_unknown: true
@@ -272,15 +272,15 @@ behavior_server:
272272
cycle_frequency: 10.0
273273
behavior_plugins: ["spin", "backup", "drive_on_heading", "assisted_teleop", "wait"]
274274
spin:
275-
plugin: "nav2_behaviors/Spin"
275+
plugin: "nav2_behaviors::Spin"
276276
backup:
277-
plugin: "nav2_behaviors/BackUp"
277+
plugin: "nav2_behaviors::BackUp"
278278
drive_on_heading:
279-
plugin: "nav2_behaviors/DriveOnHeading"
279+
plugin: "nav2_behaviors::DriveOnHeading"
280280
wait:
281-
plugin: "nav2_behaviors/Wait"
281+
plugin: "nav2_behaviors::Wait"
282282
assisted_teleop:
283-
plugin: "nav2_behaviors/AssistedTeleop"
283+
plugin: "nav2_behaviors::AssistedTeleop"
284284
local_frame: odom
285285
global_frame: map
286286
robot_base_frame: base_link
@@ -309,7 +309,96 @@ velocity_smoother:
309309
min_velocity: [-0.26, 0.0, -1.0]
310310
max_accel: [2.5, 0.0, 3.2]
311311
max_decel: [-2.5, 0.0, -3.2]
312-
odom_topic: "odom"
312+
odom_topic: "odometry/global"
313313
odom_duration: 0.1
314314
deadband_velocity: [0.0, 0.0, 0.0]
315315
velocity_timeout: 1.0
316+
317+
collision_monitor:
318+
ros__parameters:
319+
base_frame_id: "base_footprint"
320+
odom_frame_id: "odom"
321+
cmd_vel_in_topic: "cmd_vel_smoothed"
322+
cmd_vel_out_topic: "cmd_vel"
323+
state_topic: "collision_monitor_state"
324+
transform_tolerance: 0.2
325+
source_timeout: 1.0
326+
base_shift_correction: True
327+
stop_pub_timeout: 2.0
328+
# Polygons represent zone around the robot for "stop", "slowdown" and "limit" action types,
329+
# and robot footprint for "approach" action type.
330+
polygons: ["FootprintApproach"]
331+
FootprintApproach:
332+
type: "polygon"
333+
action_type: "approach"
334+
footprint_topic: "/local_costmap/published_footprint"
335+
time_before_collision: 1.2
336+
simulation_time_step: 0.1
337+
min_points: 6
338+
visualize: False
339+
enabled: True
340+
observation_sources: ["scan"]
341+
scan:
342+
type: "scan"
343+
topic: "scan"
344+
min_height: 0.15
345+
max_height: 2.0
346+
enabled: True
347+
348+
349+
350+
docking_server:
351+
ros__parameters:
352+
controller_frequency: 10.0
353+
initial_perception_timeout: 20.0 # Default 5.0
354+
wait_charge_timeout: 5.0
355+
dock_approach_timeout: 30.0
356+
undock_linear_tolerance: 0.05
357+
undock_angular_tolerance: 0.05
358+
max_retries: 3
359+
base_frame: "base_link"
360+
fixed_frame: "odom"
361+
dock_backwards: false
362+
dock_prestaging_tolerance: 0.5
363+
364+
# Types of docks
365+
dock_plugins: ['rosmaster_x3_dock']
366+
rosmaster_x3_dock:
367+
plugin: 'opennav_docking::SimpleChargingDock'
368+
docking_threshold: 0.02
369+
staging_x_offset: 0.75
370+
staging_yaw_offset: 3.14
371+
use_external_detection_pose: true
372+
use_battery_status: false
373+
use_stall_detection: false
374+
stall_velocity_threshold: 1.0
375+
stall_effort_threshold: 1.0
376+
charging_threshold: 0.5
377+
378+
external_detection_timeout: 1.0
379+
external_detection_translation_x: -0.18
380+
external_detection_translation_y: 0.0
381+
external_detection_rotation_roll: -1.57
382+
external_detection_rotation_pitch: 1.57
383+
external_detection_rotation_yaw: 0.0
384+
filter_coef: 0.1
385+
386+
# Dock instances
387+
# dock_database: $(find-pkg-share yahboom_rosmaster_docking)/config/dock_database.yaml
388+
389+
controller:
390+
k_phi: 3.0
391+
k_delta: 2.0
392+
beta: 0.4
393+
lambda: 2.0
394+
v_linear_min: 0.1
395+
v_linear_max: 0.15
396+
v_angular_max: 0.75
397+
slowdown_radius: 0.25
398+
use_collision_detection: true
399+
costmap_topic: "/local_costmap/costmap_raw"
400+
footprint_topic: "/local_costmap/published_footprint"
401+
transform_tolerance: 0.1
402+
projection_time: 5.0
403+
simulation_step: 0.1
404+
dock_collision_threshold: 0.3

0 commit comments

Comments
 (0)