Regulated Pure Pursuit

Source code on Github.

受控的 Pure Pursuit 控制器实现了 Pure Pursuit 控制器的变体,专门针对服务/工业机器人的需求。 它通过路径曲率调节线性速度,以帮助减少盲角高速时的超调,从而使操作更加安全。 它还比 Pure Pursuit 目前可用的任何其他变体更好地遵循路径。 它还具有启发式方法,可以在接近其他障碍物时减速,以便您可以在附近发生潜在碰撞时自动减慢机器人的速度。 它还实现了自适应前瞻点功能,可以通过速度进行缩放,从而在更大范围的平移速度下实现更稳定的行为。

请参阅该包的“README”来获取更完整的信息。

如果您使用此存储库中的受监管纯追踪控制器算法或软件,请在您的论文中引用此工作:

受监管的纯追踪参数

desired_linear_vel:

Type

Default

double

0.5

Description

所需使用的最大线速度(米/秒)

lookahead_dist:

Type

Default

double

0.6

Description

当“use_velocity_scaled_lookahead_dist”为“false”时,用于查找前瞻点的前瞻距离(m)。

min_lookahead_dist:

Type

Default

double

0.3

Description

当“use_velocity_scaled_lookahead_dist”为“true”时,最小前瞻距离(m)阈值。

max_lookahead_dist:

Type

Default

double

0.9

Description

当“use_velocity_scaled_lookahead_dist”为“true”时的最大前瞻距离(m)阈值。

lookahead_time:

Type

Default

double

1.5

Description

当“use_velocity_scaled_lookahead_dist”为“true”时投射速度的时间(秒)。也称为前瞻增益。

rotate_to_heading_angular_vel:

Type

Default

double

1.8

Description

如果“use_rotate_to_heading”为“true”,则这就是要使用的角速度。

transform_tolerance:

Type

Default

double

0.1

Description

TF 变换容差(s)。

use_velocity_scaled_lookahead_dist:

Type

Default

bool

false

Description

是否使用速度缩放的前瞻距离或常数“lookahead_distance”。

min_approach_linear_velocity:

Type

Default

double

0.05

Description

接近目标时应用的最小速度(m/s)阈值以确保进度。必须“> 0.01”。

approach_velocity_scaling_dist:

Type

Default

double

0.6

Description

路径上剩余的开始减速距离(米)。应小于代价地图宽度的一半。

use_collision_detection:

Type

Default

bool

true

Description

是否启用碰撞检测。

max_allowed_time_to_collision_up_to_carrot:

Type

Default

double

1.0

Description

use_collision_detectiontrue 时,向前投射速度命令以检查碰撞的时间(秒)。在 Humble 之前,这是 max_allowed_time_to_collision

use_regulated_linear_velocity_scaling:

Type

Default

bool

true

Description

是否对路径曲率使用受管制的特征(例如,曲率大的路径速度较慢)。

use_cost_regulated_linear_velocity_scaling:

Type

Default

bool

true

Description

是否使用针对接近障碍物的受管制功能(例如,在靠近障碍物时减速)。

regulated_linear_scaling_min_radius:

Type

Default

double

0.90

Description

当“use_regulated_linear_velocity_scaling”为“true”时,触发调节功能的转弯半径(m)。请记住,转弯越急,半径就越小。

regulated_linear_scaling_min_speed:

Type

Default

double

0.25

Description

任何受控启发式方法可以发送的最小速度(m/s),以确保即使在曲率较高的高成本空间中仍可实现该过程。必须“> 0.1”。

use_fixed_curvature_lookahead:

Type

Default

bool

false

Description

是否使用固定的前瞻距离来计算曲率。由于前瞻距离可能设置为随速度而变化,因此它可能会引入参考循环,这对于较大的前瞻距离来说可能是有问题的。

curvature_lookahead_dist:

Type

Default

double

0.6

Description

沿路径向前观察的距离以检测曲率。

use_rotate_to_heading:

Type

Default

bool

true

Description

使用完整规划器时是否启用旋转到粗略航向和目标方向。建议所有可以原地旋转的机器人类型启用。

注意:use_rotate_to_headingallow_reversing 不能同时设置为 true,因为这会导致歧义的情况。

allow_reversing:

Type

Default

bool

false

Description

当规划的路径涉及倒车(由方向尖点表示)时,使机器人能够反向行驶。smac_planner 的变体支持倒车。查看 Smac Planner 了解更多信息。

rotate_to_heading_min_angle:

Type

Default

double

0.785

Description

如果“use_rotate_to_heading”为“true”,则路径方向和起始机器人方向(弧度)之间的差异会触发原地旋转。

max_angular_accel:

Type

Default

double

3.2

Description

如果“use_rotate_to_heading”为“true”,则旋转至航向时允许的最大角加速度(rad/s/s)。

use_cancel_deceleration:

Type

Default

bool

false

Description

当目标取消时是否使用减速。

cancel_deceleration:

Type

Default

double

3.2

Description

取消目标时应用的线性减速度(m/s/s)。

max_robot_pose_search_dist:

Type

Default

double

Local costmap max extent (max(width, height) / 2)

Description

沿全局规划搜索最接近机器人姿势的姿势的综合距离的上限。除非存在不离开本地代价地图的循环和交叉点的路径,否则应保留此默认值,在这种情况下,有必要将此值调小以防止走捷径。如果设置为“-1”,它将使用最大可能的距离在路径上的每个点搜索最近的路径点。

interpolate_curvature_after_goal:

Type

Default

bool

false

Description

在专用于曲率计算的目标后插入一个胡萝卜(以避免路径末端的震荡)。为了便于可视化,它将在“/curvature_lookahead_point”主题上发布,类似于“/lookahead_point”

Note: Needs use_fixed_curvature_lookahead to be true

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_regulated_pure_pursuit_controller::RegulatedPurePursuitController"
      desired_linear_vel: 0.5
      lookahead_dist: 0.6
      min_lookahead_dist: 0.3
      max_lookahead_dist: 0.9
      lookahead_time: 1.5
      rotate_to_heading_angular_vel: 1.8
      transform_tolerance: 0.1
      use_velocity_scaled_lookahead_dist: false
      min_approach_linear_velocity: 0.05
      approach_velocity_scaling_dist: 0.6
      use_collision_detection: true
      max_allowed_time_to_collision_up_to_carrot: 1.0
      use_regulated_linear_velocity_scaling: true
      use_fixed_curvature_lookahead: false
      curvature_lookahead_dist: 0.25
      use_cost_regulated_linear_velocity_scaling: false
      regulated_linear_scaling_min_radius: 0.9
      regulated_linear_scaling_min_speed: 0.25
      use_rotate_to_heading: true
      allow_reversing: false
      rotate_to_heading_min_angle: 0.785
      max_angular_accel: 3.2
      max_robot_pose_search_dist: 10.0