@@ -205,56 +205,70 @@ controller_server:
205205 yaw_goal_tolerance : 0.05
206206 stateful : True
207207 # neo_local_planner controller parameters
208+ controller_server :
209+ ros__parameters :
210+ # controller server parameters (see Controller Server for more info)
211+ use_sim_time : False
212+ controller_frequency : 50.0
213+ min_x_velocity_threshold : 0.001
214+ min_y_velocity_threshold : 0.5
215+ min_theta_velocity_threshold : 0.001
216+ progress_checker_plugin : " progress_checker"
217+ goal_checker_plugins : ["general_goal_checker"]
218+ progress_checker_plugin : " progress_checker"
219+ progress_checker :
220+ plugin : " nav2_controller::SimpleProgressChecker"
221+ required_movement_radius : 0.5
222+ movement_time_allowance : 100.0
223+ general_goal_checker :
224+ plugin : " nav2_controller::SimpleGoalChecker"
225+ xy_goal_tolerance : 0.05
226+ yaw_goal_tolerance : 0.05
227+ stateful : True
208228 FollowPath :
209- plugin : " neo_local_planner ::NeoLocalPlanner"
229+ plugin : " neo_local_planner2 ::NeoLocalPlanner"
210230 # The x acceleration limit of the robot in meters/sec^2
211- acc_lim_x : 0.25
212- # The y acceleration limit of the robot in meters/sec^2
213- acc_lim_y : 0.25
231+ acc_lim_x : 0.2
214232 # The rotational acceleration limit of the robot in radians/sec^2
215- acc_lim_theta : 1.0
233+ acc_lim_theta : 0.6
216234 # The maximum x velocity for the robot in m/s.
217- max_vel_x : 0.6
235+ max_vel_x : 0.8
218236 # The minimum x velocity for the robot in m/s, negative for backwards motion.
219- min_vel_x : -0.2
220- # The maximum y velocity for the robot in m/s
221- max_vel_y : 0.5
222- # The minimum y velocity for the robot in m/s
223- min_vel_y : -0.5
237+ min_vel_x : -0.1
224238 # The absolute value of the maximum rotational velocity for the robot in rad/s
225- max_rot_vel : 0.8
239+ max_rot_vel : 0.6
226240 # The absolute value of the minimum rotational velocity for the robot in rad/s
227241 min_rot_vel : 0.1
228242 # The absolute value of the maximum translational velocity for the robot in m/s
229- max_trans_vel : 0.6
243+ max_trans_vel : 0.8
230244 # The absolute value of the minimum translational velocity for the robot in m/s
231245 min_trans_vel : 0.1
232246 # The tolerance in radians for the controller in yaw/rotation when achieving its goal
233- yaw_goal_tolerance : 0.005
247+ yaw_goal_tolerance : 0.01
234248 # The tolerance in meters for the controller in the x & y distance when achieving a goal
235- xy_goal_tolerance : 0.01
249+ xy_goal_tolerance : 0.1
236250 # How long to fine tune for goal position after reaching tolerance limits [s]
237- goal_tune_time : 2 .0
251+ goal_tune_time : 3 .0
238252 # How far to predict control pose into the future based on latest odometry [s]
239253 lookahead_time : 0.4
240254 # How far to look ahead when computing path orientation [m]
241255 lookahead_dist : 0.5
242256 # Threshold yaw error below which we consider to start moving [rad]
243- start_yaw_error : 0.5
257+ start_yaw_error : 0.2
244258 # Gain when adjusting final x position for goal [1/s]
245259 pos_x_gain : 1.0
246- # Gain when adjusting y position (holonomic only) [1/s]
247- pos_y_gain : 1.0
260+ # Gain for lane keeping based on y error (differential only) [rad/s^2]
261+ pos_y_yaw_gain : 1.0
262+ # Gain for lane keeping based on yaw error (differential only) [1/s]
263+ yaw_gain : 2.0
248264 # Gain for adjusting yaw when not translating, or in case of holonomic drive [1/s]
249265 static_yaw_gain : 3.0
250- # Gain for x cost avoidance (holonomic only)
251- cost_x_gain : 0.2
252- # Gain for y cost avoidance (holonomic only)
253- cost_y_gain : 0.2
266+ # Gain for y cost avoidance (differential only)
267+ cost_y_yaw_gain : 0.3
254268 # How far ahead to compute y cost gradient (constant offset) [m]
255- cost_y_lookahead_dist : 0.0
269+ cost_y_lookahead_dist : 0.3
256270 # How far ahead to compute y cost gradient (dynamic offset) [s]
257- cost_y_lookahead_time : 2.0
271+ cost_y_lookahead_time : 1.5
258272 # Gain for yaw cost avoidance
259273 cost_yaw_gain : 2.0
260274 # Gain for final control low pass filter
@@ -264,15 +278,13 @@ controller_server:
264278 # Max velocity based on curvature [rad/s]
265279 max_curve_vel : 0.3
266280 # Max distance to goal when looking for it [m]
267- max_goal_dist : 0.5
281+ max_goal_dist : 0.3
268282 # Max distance allowable for backing up (zero = unlimited) [m]
269- max_backup_dist : 0.0
283+ max_backup_dist : 0.1
270284 # Minimal distance for stopping [m]
271- min_stop_dist : 0.6
285+ min_stop_dist : 0.3
272286 # If robot has differential drive, holonomic otherwise
273- differential_drive : false
274- # Enable or disable reversing
275- allow_reversing : false
287+ differential_drive : true
276288
277289local_costmap :
278290 local_costmap :
0 commit comments