Skip to content

Commit 4c547dd

Browse files
Feat/migrate gps nav2 system test (ros-navigation#4682)
* include missing docking station parameters Signed-off-by: stevedan <[email protected]> * fix crach RL Signed-off-by: stevedan <[email protected]> * lintering Signed-off-by: stevedan <[email protected]> * Change naming Signed-off-by: stevedan <[email protected]> * update submodule Signed-off-by: stevedan <[email protected]> * minor changes Signed-off-by: stevedan <[email protected]> * fix issue with caching Signed-off-by: stevedan <[email protected]> * fix issue with caching, increase version number Signed-off-by: stevedan <[email protected]> * Pin git ref via sha to bust underlay workspace cache --------- Signed-off-by: stevedan <[email protected]> Co-authored-by: ruffsl <[email protected]> Signed-off-by: stevedanomodolor <[email protected]>
1 parent 8481cb4 commit 4c547dd

File tree

8 files changed

+193
-121
lines changed

8 files changed

+193
-121
lines changed

.circleci/config.yml

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -33,12 +33,12 @@ _commands:
3333
- restore_cache:
3434
name: Restore Cache << parameters.key >>
3535
keys:
36-
- "<< parameters.key >>-v26\
36+
- "<< parameters.key >>-v28\
3737
-{{ arch }}\
3838
-{{ .Branch }}\
3939
-{{ .Environment.CIRCLE_PR_NUMBER }}\
4040
-{{ checksum \"<< parameters.workspace >>/lockfile.txt\" }}"
41-
- "<< parameters.key >>-v26\
41+
- "<< parameters.key >>-v28\
4242
-{{ arch }}\
4343
-main\
4444
-<no value>\
@@ -58,7 +58,7 @@ _commands:
5858
steps:
5959
- save_cache:
6060
name: Save Cache << parameters.key >>
61-
key: "<< parameters.key >>-v26\
61+
key: "<< parameters.key >>-v28\
6262
-{{ arch }}\
6363
-{{ .Branch }}\
6464
-{{ .Environment.CIRCLE_PR_NUMBER }}\

nav2_system_tests/CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -113,7 +113,7 @@ if(BUILD_TESTING)
113113
add_subdirectory(src/system_failure)
114114
add_subdirectory(src/updown)
115115
add_subdirectory(src/waypoint_follower)
116-
# add_subdirectory(src/gps_navigation)
116+
add_subdirectory(src/gps_navigation)
117117
add_subdirectory(src/behaviors/wait)
118118
add_subdirectory(src/behaviors/spin)
119119
add_subdirectory(src/behaviors/backup)

nav2_system_tests/src/gps_navigation/CMakeLists.txt

Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -5,7 +5,5 @@ ament_add_test(test_gps_waypoint_follower
55
TIMEOUT 180
66
ENV
77
TEST_DIR=${CMAKE_CURRENT_SOURCE_DIR}
8-
TEST_WORLD=${PROJECT_SOURCE_DIR}/worlds/turtlebot3_ros2_demo_gps.world
9-
GAZEBO_MODEL_PATH=${PROJECT_SOURCE_DIR}/models
10-
BT_NAVIGATOR_XML=navigate_to_pose_w_replanning_and_recovery.xml
118
)
9+

nav2_system_tests/src/gps_navigation/dual_ekf_navsat_params.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -121,7 +121,7 @@ navsat_transform:
121121
magnetic_declination_radians: 0.0429351 # For lat/long 55.944831, -3.186998
122122
yaw_offset: 0.0
123123
zero_altitude: true
124-
broadcast_utm_transform: true
124+
broadcast_cartesian_transform: true
125125
publish_filtered_gps: true
126126
use_odometry_yaw: true
127127
wait_for_datum: false

nav2_system_tests/src/gps_navigation/nav2_no_map_params.yaml

Lines changed: 134 additions & 40 deletions
Original file line numberDiff line numberDiff line change
@@ -53,46 +53,93 @@ controller_server:
5353
yaw_goal_tolerance: 0.25
5454
# DWB parameters
5555
FollowPath:
56-
plugin: "dwb_core::DWBLocalPlanner"
57-
debug_trajectory_details: True
58-
min_vel_x: 0.0
59-
min_vel_y: 0.0
60-
max_vel_x: 0.26
61-
max_vel_y: 0.0
62-
max_vel_theta: 1.0
63-
min_speed_xy: 0.0
64-
max_speed_xy: 0.26
65-
min_speed_theta: 0.0
66-
# Add high threshold velocity for turtlebot 3 issue.
67-
# https://github.com/ROBOTIS-GIT/turtlebot3_simulations/issues/75
68-
acc_lim_x: 2.5
69-
acc_lim_y: 0.0
70-
acc_lim_theta: 3.2
71-
decel_lim_x: -2.5
72-
decel_lim_y: 0.0
73-
decel_lim_theta: -3.2
74-
vx_samples: 20
75-
vy_samples: 5
76-
vtheta_samples: 20
77-
sim_time: 1.7
78-
linear_granularity: 0.05
79-
angular_granularity: 0.025
80-
transform_tolerance: 0.2
81-
xy_goal_tolerance: 0.25
82-
trans_stopped_velocity: 0.25
83-
short_circuit_trajectory_evaluation: True
84-
stateful: True
85-
critics: ["RotateToGoal", "Oscillation", "BaseObstacle", "GoalAlign", "PathAlign", "PathDist", "GoalDist"]
86-
BaseObstacle.scale: 0.02
87-
PathAlign.scale: 32.0
88-
PathAlign.forward_point_distance: 0.1
89-
GoalAlign.scale: 24.0
90-
GoalAlign.forward_point_distance: 0.1
91-
PathDist.scale: 32.0
92-
GoalDist.scale: 24.0
93-
RotateToGoal.scale: 32.0
94-
RotateToGoal.slowing_factor: 5.0
95-
RotateToGoal.lookahead_time: -1.0
56+
plugin: "nav2_mppi_controller::MPPIController"
57+
time_steps: 56
58+
model_dt: 0.05
59+
batch_size: 2000
60+
ax_max: 3.0
61+
ax_min: -3.0
62+
ay_max: 3.0
63+
az_max: 3.5
64+
vx_std: 0.2
65+
vy_std: 0.2
66+
wz_std: 0.4
67+
vx_max: 0.5
68+
vx_min: -0.35
69+
vy_max: 0.5
70+
wz_max: 1.9
71+
iteration_count: 1
72+
prune_distance: 1.7
73+
transform_tolerance: 0.1
74+
temperature: 0.3
75+
gamma: 0.015
76+
motion_model: "DiffDrive"
77+
visualize: true
78+
regenerate_noises: true
79+
TrajectoryVisualizer:
80+
trajectory_step: 5
81+
time_step: 3
82+
AckermannConstraints:
83+
min_turning_r: 0.2
84+
critics: [
85+
"ConstraintCritic", "CostCritic", "GoalCritic",
86+
"GoalAngleCritic", "PathAlignCritic", "PathFollowCritic",
87+
"PathAngleCritic", "PreferForwardCritic"]
88+
ConstraintCritic:
89+
enabled: true
90+
cost_power: 1
91+
cost_weight: 4.0
92+
GoalCritic:
93+
enabled: true
94+
cost_power: 1
95+
cost_weight: 5.0
96+
threshold_to_consider: 1.4
97+
GoalAngleCritic:
98+
enabled: true
99+
cost_power: 1
100+
cost_weight: 3.0
101+
threshold_to_consider: 0.5
102+
PreferForwardCritic:
103+
enabled: true
104+
cost_power: 1
105+
cost_weight: 5.0
106+
threshold_to_consider: 0.5
107+
CostCritic:
108+
enabled: true
109+
cost_power: 1
110+
cost_weight: 3.81
111+
critical_cost: 300.0
112+
consider_footprint: true
113+
collision_cost: 1000000.0
114+
near_goal_distance: 1.0
115+
trajectory_point_step: 2
116+
PathAlignCritic:
117+
enabled: true
118+
cost_power: 1
119+
cost_weight: 14.0
120+
max_path_occupancy_ratio: 0.05
121+
trajectory_point_step: 4
122+
threshold_to_consider: 0.5
123+
offset_from_furthest: 20
124+
use_path_orientations: false
125+
PathFollowCritic:
126+
enabled: true
127+
cost_power: 1
128+
cost_weight: 5.0
129+
offset_from_furthest: 5
130+
threshold_to_consider: 1.4
131+
PathAngleCritic:
132+
enabled: true
133+
cost_power: 1
134+
cost_weight: 2.0
135+
offset_from_furthest: 4
136+
threshold_to_consider: 0.5
137+
max_angle_to_furthest: 1.0
138+
mode: 0
139+
# TwirlingCritic:
140+
# enabled: true
141+
# twirling_cost_power: 1
142+
# twirling_cost_weight: 10.0
96143

97144
local_costmap:
98145
local_costmap:
@@ -151,6 +198,8 @@ global_costmap:
151198
rolling_window: True
152199
width: 50
153200
height: 50
201+
# origin_x: 0.0
202+
# origin_y: 0.0
154203
track_unknown_space: true
155204
# no static map
156205
plugins: ["obstacle_layer", "inflation_layer"]
@@ -290,3 +339,48 @@ collision_monitor:
290339
min_height: 0.15
291340
max_height: 2.0
292341
enabled: True
342+
343+
docking_server:
344+
ros__parameters:
345+
controller_frequency: 50.0
346+
initial_perception_timeout: 5.0
347+
wait_charge_timeout: 5.0
348+
dock_approach_timeout: 30.0
349+
undock_linear_tolerance: 0.05
350+
undock_angular_tolerance: 0.1
351+
max_retries: 3
352+
base_frame: "base_link"
353+
fixed_frame: "odom"
354+
dock_backwards: false
355+
dock_prestaging_tolerance: 0.5
356+
357+
# Types of docks
358+
dock_plugins: ['simple_charging_dock']
359+
simple_charging_dock:
360+
plugin: 'opennav_docking::SimpleChargingDock'
361+
docking_threshold: 0.05
362+
staging_x_offset: -0.7
363+
use_external_detection_pose: true
364+
use_battery_status: false # true
365+
use_stall_detection: false # true
366+
367+
external_detection_timeout: 1.0
368+
external_detection_translation_x: -0.18
369+
external_detection_translation_y: 0.0
370+
external_detection_rotation_roll: -1.57
371+
external_detection_rotation_pitch: -1.57
372+
external_detection_rotation_yaw: 0.0
373+
filter_coef: 0.1
374+
375+
# Dock instances
376+
docks: ['home_dock'] # Input your docks here
377+
home_dock:
378+
type: 'simple_charging_dock'
379+
frame: map
380+
pose: [0.0, 0.0, 0.0]
381+
382+
controller:
383+
k_phi: 3.0
384+
k_delta: 2.0
385+
v_linear_min: 0.15
386+
v_linear_max: 0.15

0 commit comments

Comments
 (0)