Graceful Controller
源代码在 Github.
优雅控制器基于 Jong Jin Park 和 Benjamin Kuipers 在“2D 环境中差速轮式移动机器人优雅运动的平滑控制律”(ICRA 2011) 中的工作实现了控制器。在此实现中,motion_target 设置在距离机器人一定距离处,该距离呈指数稳定,以生成机器人要遵循的平滑轨迹。
有关更完整的信息,请参阅软件包的 README
。
优雅控制器参数
- transform_tolerance:
Type
Default
double
0.1
- Description
TF 变换容差(s)。
- motion_target_dist:
Type
Default
double
0.6
- Description
用于查找 motion_target 点的前瞻距离(m)。
- max_robot_pose_search_dist:
Type
Default
double
Local costmap max extent (max(width, height) / 2)
- Description
沿全局规划搜索最接近机器人姿势的姿势的综合距离的上限。除非存在不离开本地代价地图的循环和交叉点的路径,否则应保留此默认值,在这种情况下,有必要将此值调小以防止走捷径。如果设置为“-1”,它将使用最大可能的距离在路径上的每个点搜索最近的路径点。
- k_phi:
Type
Default
double
3.0
- Description
phi 变化率与 r 变化率之比。控制慢速子系统的收敛。如果此值等于零,控制器将表现为纯航路点跟随器。高值提供极端的姿势跟随场景,其中 theta 的减小速度比 r 快得多。
- k_delta:
Type
Default
double
2.0
- Description
应用于航向误差反馈的常数因子。控制快速子系统的收敛。值越大,机器人收敛到参考航向的速度越快。
- beta:
Type
Default
double
0.2
- Description
应用于路径曲率的恒定因子。此值必须为正数。确定曲率增加时速度下降的速度。
- lambda:
Type
Default
double
2.0
- Description
应用于路径曲率的恒定因子。此值必须大于或等于 1。确定曲线的锐度:λ 值越高,曲线越锐利。
- v_linear_min:
Type
Default
double
0.1
- Description
最小线速度(米/秒)。
- v_linear_max:
Type
Default
double
0.5
- Description
最大线速度(米/秒)。
- v_angular_max:
Type
Default
double
1.0
- Description
控制律产生的最大角速度(rad/s)。
- slowdown_radius:
Type
Default
double
1.5
- Description
机器人开始减速的目标姿势周围的半径(m)。
- initial_rotation:
Type
Default
bool
true
Description 在开始路径之前,启用到目标的原地旋转。控制律可能会生成到目标姿势的大弧线,具体取决于初始机器人方向和“k_phi”、“k_delta”。
- initial_rotation_min_angle:
Type
Default
double
0.75
- Description
如果启用了“initial_rotation”,则路径方向和起始机器人方向的差异会触发原地旋转。
- final_rotation:
Type
Default
bool
true
- Description
与“initial_rotation”类似,当目标方向与路径不一致时,控制律可以生成大弧。如果启用此功能,最终姿势将被忽略,机器人将遵循路径的方向,并在原地进行最终旋转以达到目标方向。
- rotation_scaling_factor:
Type
Default
double
0.5
- Description
应用于原地旋转速度的比例因子。
- allow_backward:
Type
Default
bool
false
- Description
是否允许机器人向后移动。
Example
controller_server:
ros__parameters:
use_sim_time: True
controller_frequency: 20.0
min_x_velocity_threshold: 0.001
min_y_velocity_threshold: 0.5
min_theta_velocity_threshold: 0.001
progress_checker_plugins: ["progress_checker"] # progress_checker_plugin: "progress_checker" For Humble and older
goal_checker_plugins: ["goal_checker"]
controller_plugins: ["FollowPath"]
progress_checker:
plugin: "nav2_controller::SimpleProgressChecker"
required_movement_radius: 0.5
movement_time_allowance: 10.0
goal_checker:
plugin: "nav2_controller::SimpleGoalChecker"
xy_goal_tolerance: 0.25
yaw_goal_tolerance: 0.25
stateful: True
FollowPath:
plugin: nav2_graceful_controller::GracefulController
transform_tolerance: 0.1
motion_target_dist: 0.6
initial_rotation: true
initial_rotation_min_angle: 0.75
final_rotation: true
allow_backward: false
k_phi: 3.0
k_delta: 2.0
beta: 0.4
lambda: 2.0
v_linear_min: 0.1
v_linear_max: 1.0
v_angular_max: 5.0
slowdown_radius: 1.5