Skip to content

Commit b27ecc3

Browse files
committed
controller params update
1 parent ebec963 commit b27ecc3

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

224262
local_costmap:
225263
local_costmap:

configs/mp_500/navigation.yaml

+43-31
Original file line numberDiff line numberDiff line change
@@ -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

277289
local_costmap:
278290
local_costmap:

configs/mpo_500/navigation.yaml

+1-1
Original file line numberDiff line numberDiff line change
@@ -198,7 +198,7 @@ controller_server:
198198
stateful: True
199199
# neo_local_planner parameters
200200
FollowPath:
201-
plugin: "neo_local_planner::NeoLocalPlanner"
201+
plugin: "neo_local_planner2::NeoLocalPlanner"
202202
# The x acceleration limit of the robot in meters/sec^2
203203
acc_lim_x : 0.25
204204
# 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
@@ -181,7 +181,7 @@ controller_server:
181181
# controller server parameters (see Controller Server for more info)
182182
controller_plugins: ["FollowPath"]
183183
controller_frequency: 100.0
184-
controller_plugin_types: ["neo_local_planner::NeoLocalPlanner"]
184+
controller_plugin_types: ["neo_local_planner2::NeoLocalPlanner"]
185185
goal_checker_plugins: ["general_goal_checker"]
186186
progress_checker_plugin: "progress_checker"
187187
use_sim_time: True
@@ -195,7 +195,7 @@ controller_server:
195195
yaw_goal_tolerance: 0.05
196196
stateful: True
197197
FollowPath:
198-
plugin: "neo_local_planner::NeoLocalPlanner"
198+
plugin: "neo_local_planner2::NeoLocalPlanner"
199199
acc_lim_x : 0.25
200200
acc_lim_y : 0.25
201201
acc_lim_theta : 0.8

0 commit comments

Comments
 (0)