sequenceDiagram
participant MR as Mission Runner
participant OM as Orca Manager
participant BT as Behavior Tree
box Nav2 Plugins
participant P as Planner
participant C3D as Controller 3D
participant GC as Goal Checker
participant PC as Progress Checker
end
participant BC as Base Controller
participant MA as MAVROS/ArduSub
MR->>MR: Define waypoints[1]
MR->>OM: Set AUV mode[2]
OM->>MA: Set ALT_HOLD mode[3]
OM->>BC: Enable control[4]
MR->>BT: Send waypoints[5]
BT->>P: Request path[6]
P->>BT: Return 3D path[7]
loop Until all waypoints reached
BT->>C3D: Follow path[8]
C3D->>BC: Publish vel cmds[9]
BC->>BC: Read SLAM pose[10]
BC->>MA: Publish RC override[11]
MA->>BC: Publish local position[12]
MA->>OM: Publish vehicle state[13]
BC->>BT: Publish motion and odometry[14]
BT->>GC: Check goal[15]
Note over BT,PC: Progress Checker used internally[16]
GC->>BT: Goal status[17]
end
BT->>MR: All waypoints reached[18]
MR->>OM: Set ROV mode[19]
OM->>MA: Set MANUAL mode[20]
OM->>BC: Disable control[21]
- Mission Runner: Define waypoints
- Mission Runner: Set AUV mode
- Orca Manager: Set ALT_HOLD mode
- Orca Manager: Enable control
- Mission Runner: Send nav goal
- Behavior Tree: Request path
- Planner: Return 3D path
- Behavior Tree: Follow path
- Controller: Publish vel cmds
- Base Controller: Read SLAM pose
- Base Controller: Publish RC override
- MAVROS/ArduSub: Publish local position
- MAVROS/ArduSub: Publish vehicle state
- Base Controller: Publish motion and odometry
- Behavior Tree: Check goal
- Progress Checker: Check progress (internal to Nav2)
- Goal Checker: Goal status
- Mission Runner: Goal reached
- Mission Runner: Set ROV mode
- Orca Manager: Set MANUAL mode
- Orca Manager: Disable control
The following Nav2 plugins provide basic 3D planning and control suitable for open water. They all
ignore the global and local costmaps. They all largely ignore yaw, though the
PurePursuitController3D
will generate a value for yaw (angular.z
) in cmd_vel
.
Note for Humble: Nav2 now includes a velocity smoother node which takes cmd_vel output from the Nav2 controller(s) and does velocity, acceleration, and deadband smoothing. This node isn't 3D-aware, so it isn't used in Orca4.
The StraightLinePlanner3D
plugin is similar to the
StraightLinePlanner
plugin.
The planner can plan in two segments (vertical motion first, then horizontal) or one segment
(vertical and horizontal motion combined).
Parameters:
Parameter | Type | Default | Notes |
---|---|---|---|
planning_dist | double | 0.1 | How far apart the plan poses are, m |
z_before_xy | bool | false | If true plan in 2 segments: z then xy |
The PurePursuitController3D
plugin is similar to the
PurePursuitController
plugin.
It limits horizontal, vertical and yaw acceleration to reduce pitching and drift.
The BlueROV2 frame is holonomic, but forward/backward drag is lower than the left/right drag, so the
controller generates diff-drive motion (linear.x
, linear.z
and angular.z
).
Parameters:
Parameter | Type | Default | Notes |
---|---|---|---|
xy_vel | double | 0.4 | Desired horizontal velocity, m/s |
xy_accel | double | 0.4 | Max horizontal acceleration, m/s^2 |
z_vel | double | 0.2 | Desired vertical velocity, m/s |
z_accel | double | 0.2 | Max vertical acceleration, m/s^2 |
yaw_vel | double | 0.4 | Desired yaw velocity, r/s |
yaw_accel | double | 0.4 | Max yaw acceleration, r/s^2 |
lookahead_dist | double | 1.0 | Lookahead distance for pure pursuit algorithm, m |
transform_tolerance | double | 1.0 | How stale a transform can be and still be used, s |
goal_tolerance | double | 0.1 | Stop moving when goal is closer than goal_tolerance. Should be less than the values in GoalChecker3D |
tick_rate | double | 20 | The BT tick rate, used to calculate dt |
The ProgressChecker3D
plugin is similar to the
SimpleProgressChecker
plugin.
Parameters:
Parameter | Type | Default | Notes |
---|---|---|---|
radius | double | 0.5 | Minimum distance to move, m |
time_allowance | double | 10.0 | Time allowed to move the minimum distance, s |
The GoalChecker3D
plugin is similar to the
SimpleGoalChecker
plugin.
Parameters:
Parameter | Type | Default | Notes |
---|---|---|---|
xy_goal_tolerance | double | 0.25 | Horizontal goal tolerance |
z_goal_tolerance | double | 0.25 | Vertical goal tolerance |