@@ -53,46 +53,93 @@ controller_server:
53
53
yaw_goal_tolerance : 0.25
54
54
# DWB parameters
55
55
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
96
143
97
144
local_costmap :
98
145
local_costmap :
@@ -151,6 +198,8 @@ global_costmap:
151
198
rolling_window : True
152
199
width : 50
153
200
height : 50
201
+ # origin_x: 0.0
202
+ # origin_y: 0.0
154
203
track_unknown_space : true
155
204
# no static map
156
205
plugins : ["obstacle_layer", "inflation_layer"]
@@ -290,3 +339,48 @@ collision_monitor:
290
339
min_height : 0.15
291
340
max_height : 2.0
292
341
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