@@ -203,56 +203,70 @@ controller_server:
203
203
yaw_goal_tolerance : 0.05
204
204
stateful : True
205
205
# neo_local_planner controller parameters
206
+ controller_server :
207
+ ros__parameters :
208
+ # controller server parameters (see Controller Server for more info)
209
+ use_sim_time : False
210
+ controller_frequency : 50.0
211
+ min_x_velocity_threshold : 0.001
212
+ min_y_velocity_threshold : 0.5
213
+ min_theta_velocity_threshold : 0.001
214
+ progress_checker_plugin : " progress_checker"
215
+ goal_checker_plugins : ["general_goal_checker"]
216
+ progress_checker_plugin : " progress_checker"
217
+ progress_checker :
218
+ plugin : " nav2_controller::SimpleProgressChecker"
219
+ required_movement_radius : 0.5
220
+ movement_time_allowance : 100.0
221
+ general_goal_checker :
222
+ plugin : " nav2_controller::SimpleGoalChecker"
223
+ xy_goal_tolerance : 0.05
224
+ yaw_goal_tolerance : 0.05
225
+ stateful : True
206
226
FollowPath :
207
- plugin : " neo_local_planner ::NeoLocalPlanner"
227
+ plugin : " neo_local_planner2 ::NeoLocalPlanner"
208
228
# The x acceleration limit of the robot in meters/sec^2
209
- acc_lim_x : 0.25
210
- # The y acceleration limit of the robot in meters/sec^2
211
- acc_lim_y : 0.25
229
+ acc_lim_x : 0.2
212
230
# The rotational acceleration limit of the robot in radians/sec^2
213
- acc_lim_theta : 1.0
231
+ acc_lim_theta : 0.6
214
232
# The maximum x velocity for the robot in m/s.
215
- max_vel_x : 0.6
233
+ max_vel_x : 0.8
216
234
# The minimum x velocity for the robot in m/s, negative for backwards motion.
217
- min_vel_x : -0.2
218
- # The maximum y velocity for the robot in m/s
219
- max_vel_y : 0.5
220
- # The minimum y velocity for the robot in m/s
221
- min_vel_y : -0.5
235
+ min_vel_x : -0.1
222
236
# The absolute value of the maximum rotational velocity for the robot in rad/s
223
- max_rot_vel : 0.8
237
+ max_rot_vel : 0.6
224
238
# The absolute value of the minimum rotational velocity for the robot in rad/s
225
239
min_rot_vel : 0.1
226
240
# The absolute value of the maximum translational velocity for the robot in m/s
227
- max_trans_vel : 0.6
241
+ max_trans_vel : 0.8
228
242
# The absolute value of the minimum translational velocity for the robot in m/s
229
243
min_trans_vel : 0.1
230
244
# The tolerance in radians for the controller in yaw/rotation when achieving its goal
231
- yaw_goal_tolerance : 0.005
245
+ yaw_goal_tolerance : 0.01
232
246
# The tolerance in meters for the controller in the x & y distance when achieving a goal
233
- xy_goal_tolerance : 0.01
247
+ xy_goal_tolerance : 0.1
234
248
# How long to fine tune for goal position after reaching tolerance limits [s]
235
- goal_tune_time : 2 .0
249
+ goal_tune_time : 3 .0
236
250
# How far to predict control pose into the future based on latest odometry [s]
237
251
lookahead_time : 0.4
238
252
# How far to look ahead when computing path orientation [m]
239
253
lookahead_dist : 0.5
240
254
# Threshold yaw error below which we consider to start moving [rad]
241
- start_yaw_error : 0.5
255
+ start_yaw_error : 0.2
242
256
# Gain when adjusting final x position for goal [1/s]
243
257
pos_x_gain : 1.0
244
- # Gain when adjusting y position (holonomic only) [1/s]
245
- pos_y_gain : 1.0
258
+ # Gain for lane keeping based on y error (differential only) [rad/s^2]
259
+ pos_y_yaw_gain : 1.0
260
+ # Gain for lane keeping based on yaw error (differential only) [1/s]
261
+ yaw_gain : 2.0
246
262
# Gain for adjusting yaw when not translating, or in case of holonomic drive [1/s]
247
263
static_yaw_gain : 3.0
248
- # Gain for x cost avoidance (holonomic only)
249
- cost_x_gain : 0.2
250
- # Gain for y cost avoidance (holonomic only)
251
- cost_y_gain : 0.2
264
+ # Gain for y cost avoidance (differential only)
265
+ cost_y_yaw_gain : 0.3
252
266
# How far ahead to compute y cost gradient (constant offset) [m]
253
- cost_y_lookahead_dist : 0.0
267
+ cost_y_lookahead_dist : 0.3
254
268
# How far ahead to compute y cost gradient (dynamic offset) [s]
255
- cost_y_lookahead_time : 2.0
269
+ cost_y_lookahead_time : 1.5
256
270
# Gain for yaw cost avoidance
257
271
cost_yaw_gain : 2.0
258
272
# Gain for final control low pass filter
@@ -262,15 +276,13 @@ controller_server:
262
276
# Max velocity based on curvature [rad/s]
263
277
max_curve_vel : 0.3
264
278
# Max distance to goal when looking for it [m]
265
- max_goal_dist : 0.5
279
+ max_goal_dist : 0.3
266
280
# Max distance allowable for backing up (zero = unlimited) [m]
267
- max_backup_dist : 0.0
281
+ max_backup_dist : 0.1
268
282
# Minimal distance for stopping [m]
269
- min_stop_dist : 0.6
283
+ min_stop_dist : 0.3
270
284
# If robot has differential drive, holonomic otherwise
271
- differential_drive : false
272
- # Enable or disable reversing
273
- allow_reversing : false
285
+ differential_drive : true
274
286
275
287
local_costmap :
276
288
local_costmap :
0 commit comments