Skip to content

Commit 0fd2603

Browse files
committed
controller params update
1 parent 3d6134a commit 0fd2603

File tree

4 files changed

+106
-56
lines changed

4 files changed

+106
-56
lines changed

configs/mp_400/navigation.yaml

+60-22
Original file line numberDiff line numberDiff line change
@@ -204,28 +204,66 @@ controller_server:
204204
stateful: True
205205
# RegulatedPurePursuitController Parameters
206206
FollowPath:
207-
plugin: "nav2_regulated_pure_pursuit_controller::RegulatedPurePursuitController"
208-
desired_linear_vel: 0.5
209-
max_linear_accel: 0.2
210-
max_linear_decel: 0.2
211-
lookahead_dist: 0.6
212-
min_lookahead_dist: 0.3 #0.3
213-
max_lookahead_dist: 0.9 #0.9
214-
lookahead_time: 1.5 #1.5
215-
rotate_to_heading_angular_vel: 0.6
216-
transform_tolerance: 0.1
217-
use_velocity_scaled_lookahead_dist: false
218-
min_approach_linear_velocity: 0.01
219-
use_approach_linear_velocity_scaling: true
220-
max_allowed_time_to_collision: 1.0
221-
use_regulated_linear_velocity_scaling: true
222-
use_cost_regulated_linear_velocity_scaling: false
223-
regulated_linear_scaling_min_radius: 0.9
224-
regulated_linear_scaling_min_speed: 0.25
225-
use_rotate_to_heading: true
226-
rotate_to_heading_min_angle: 0.785
227-
max_angular_accel: 0.6
228-
allow_reversing: false
207+
plugin: "neo_local_planner2::NeoLocalPlanner"
208+
# The x acceleration limit of the robot in meters/sec^2
209+
# The x acceleration limit of the robot in meters/sec^2
210+
acc_lim_x : 0.25
211+
# The rotational acceleration limit of the robot in radians/sec^2
212+
acc_lim_theta : 0.8
213+
# The maximum x velocity for the robot in m/s.
214+
max_vel_x : 0.8
215+
# The minimum x velocity for the robot in m/s, negative for backwards motion.
216+
min_vel_x : -0.1
217+
# The absolute value of the maximum rotational velocity for the robot in rad/s
218+
max_rot_vel : 0.8
219+
# The absolute value of the minimum rotational velocity for the robot in rad/s
220+
min_rot_vel : 0.1
221+
# The absolute value of the maximum translational velocity for the robot in m/s
222+
max_trans_vel : 0.8
223+
# The absolute value of the minimum translational velocity for the robot in m/s
224+
min_trans_vel : 0.1
225+
# The tolerance in radians for the controller in yaw/rotation when achieving its goal
226+
yaw_goal_tolerance : 0.05
227+
# The tolerance in meters for the controller in the x & y distance when achieving a goal
228+
xy_goal_tolerance : 0.1
229+
# How long to fine tune for goal position after reaching tolerance limits [s]
230+
goal_tune_time : 3.0
231+
# How far to predict control pose into the future based on latest odometry [s]
232+
lookahead_time : 0.3
233+
# How far to look ahead when computing path orientation [m]
234+
lookahead_dist : 0.5
235+
# Threshold yaw error below which we consider to start moving [rad]
236+
start_yaw_error : 0.2
237+
# Gain when adjusting final x position for goal [1/s]
238+
pos_x_gain : 1.0
239+
# Gain for lane keeping based on y error (differential only) [rad/s^2]
240+
pos_y_yaw_gain : 1.0
241+
# Gain for lane keeping based on yaw error (differential only) [1/s]
242+
yaw_gain : 2.0
243+
# Gain for adjusting yaw when not translating, or in case of holonomic drive [1/s]
244+
static_yaw_gain : 3.0
245+
# Gain for y cost avoidance (differential only)
246+
cost_y_yaw_gain : 0.3
247+
# How far ahead to compute y cost gradient (constant offset) [m]
248+
cost_y_lookahead_dist : 0.3
249+
# How far ahead to compute y cost gradient (dynamic offset) [s]
250+
cost_y_lookahead_time : 1.5
251+
# Gain for yaw cost avoidance
252+
cost_yaw_gain : 2.0
253+
# Gain for final control low pass filter
254+
low_pass_gain : 0.2
255+
# Max cost to allow, above we slow down to min_trans_vel or even stop
256+
max_cost : 0.95
257+
# Max velocity based on curvature [rad/s]
258+
max_curve_vel : 0.3
259+
# Max distance to goal when looking for it [m]
260+
max_goal_dist : 0.3
261+
# Max distance allowable for backing up (zero = unlimited) [m]
262+
max_backup_dist : 0.1
263+
# Minimal distance for stopping [m]
264+
min_stop_dist : 0.3
265+
# If robot has differential drive, holonomic otherwise
266+
differential_drive : true
229267

230268
local_costmap:
231269
local_costmap:

configs/mp_500/navigation.yaml

+43-31
Original file line numberDiff line numberDiff line change
@@ -203,56 +203,70 @@ controller_server:
203203
yaw_goal_tolerance: 0.05
204204
stateful: True
205205
# 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
206226
FollowPath:
207-
plugin: "neo_local_planner::NeoLocalPlanner"
227+
plugin: "neo_local_planner2::NeoLocalPlanner"
208228
# 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
212230
# The rotational acceleration limit of the robot in radians/sec^2
213-
acc_lim_theta : 1.0
231+
acc_lim_theta : 0.6
214232
# The maximum x velocity for the robot in m/s.
215-
max_vel_x : 0.6
233+
max_vel_x : 0.8
216234
# 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
222236
# 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
224238
# The absolute value of the minimum rotational velocity for the robot in rad/s
225239
min_rot_vel : 0.1
226240
# 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
228242
# The absolute value of the minimum translational velocity for the robot in m/s
229243
min_trans_vel : 0.1
230244
# 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
232246
# 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
234248
# 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
236250
# How far to predict control pose into the future based on latest odometry [s]
237251
lookahead_time : 0.4
238252
# How far to look ahead when computing path orientation [m]
239253
lookahead_dist : 0.5
240254
# Threshold yaw error below which we consider to start moving [rad]
241-
start_yaw_error : 0.5
255+
start_yaw_error : 0.2
242256
# Gain when adjusting final x position for goal [1/s]
243257
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
246262
# Gain for adjusting yaw when not translating, or in case of holonomic drive [1/s]
247263
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
252266
# 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
254268
# 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
256270
# Gain for yaw cost avoidance
257271
cost_yaw_gain : 2.0
258272
# Gain for final control low pass filter
@@ -262,15 +276,13 @@ controller_server:
262276
# Max velocity based on curvature [rad/s]
263277
max_curve_vel : 0.3
264278
# Max distance to goal when looking for it [m]
265-
max_goal_dist : 0.5
279+
max_goal_dist : 0.3
266280
# Max distance allowable for backing up (zero = unlimited) [m]
267-
max_backup_dist : 0.0
281+
max_backup_dist : 0.1
268282
# Minimal distance for stopping [m]
269-
min_stop_dist : 0.6
283+
min_stop_dist : 0.3
270284
# If robot has differential drive, holonomic otherwise
271-
differential_drive : false
272-
# Enable or disable reversing
273-
allow_reversing: false
285+
differential_drive : true
274286

275287
local_costmap:
276288
local_costmap:

configs/mpo_500/navigation.yaml

+1-1
Original file line numberDiff line numberDiff line change
@@ -200,7 +200,7 @@ controller_server:
200200
stateful: True
201201
# neo_local_planner parameters
202202
FollowPath:
203-
plugin: "neo_local_planner::NeoLocalPlanner"
203+
plugin: "neo_local_planner2::NeoLocalPlanner"
204204
# The x acceleration limit of the robot in meters/sec^2
205205
acc_lim_x : 0.25
206206
# The y acceleration limit of the robot in meters/sec^2

configs/mpo_700/navigation.yaml

+2-2
Original file line numberDiff line numberDiff line change
@@ -187,7 +187,7 @@ controller_server:
187187
# controller server parameters (see Controller Server for more info)
188188
controller_plugins: ["FollowPath"]
189189
controller_frequency: 100.0
190-
controller_plugin_types: ["neo_local_planner::NeoLocalPlanner"]
190+
controller_plugin_types: ["neo_local_planner2::NeoLocalPlanner"]
191191
goal_checker_plugins: ["general_goal_checker"]
192192
progress_checker_plugin: "progress_checker"
193193
progress_checker:
@@ -200,7 +200,7 @@ controller_server:
200200
yaw_goal_tolerance: 0.05
201201
stateful: True
202202
FollowPath:
203-
plugin: "neo_local_planner::NeoLocalPlanner"
203+
plugin: "neo_local_planner2::NeoLocalPlanner"
204204
acc_lim_x : 0.25
205205
acc_lim_y : 0.25
206206
acc_lim_theta : 0.8

0 commit comments

Comments
 (0)