Skip to content

Commit 62b94fa

Browse files
authored
docs(frames_sub): update BlueROV2 docs and align UUV surge/heave stick mapping (#26822)
* Swap joystick surge/heave mapping in manual, stabilized and acro modes to make it similar to position modes * docs: update UUV/BlueROV2 modes and joystick mapping * Document basic control axes and joystick mapping Added basic control axes and stick mapping for BlueROV2. * Fixed formatting issue * Enhance clarity of control axes and stick mapping Clarified descriptions of motion axes and joystick controls for BlueROV2.
1 parent 1e769a7 commit 62b94fa

File tree

3 files changed

+68
-15
lines changed

3 files changed

+68
-15
lines changed

docs/en/frames_sub/bluerov2.md

Lines changed: 59 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -33,14 +33,67 @@ the [Airframe Reference](../airframes/airframe_reference.md#vectored-6-dof-uuv):
3333
- **MAIN7:** motor 7 CCW, stern starboard vertical, propeller CW
3434
- **MAIN8:** motor 8 CCW, stern port vertical, propeller CCW
3535

36+
## Basic Control Axes
37+
38+
For underwater vehicles, motion is defined in terms of body axes:
39+
40+
- **Surge:** forward/back motion - translation along the body X axis.
41+
- **Sway:** left/right motion - translation along the body Y axis.
42+
- **Heave:** up/down motion - translation along the body Z axis.
43+
- **Yaw:** rotation about the (vertical) body Z axis.
44+
45+
### Stick Mapping (Mode 2)
46+
47+
The mapping below illustrates the default joystick behavior:
48+
49+
- **Pitch stick (forward/back):** surge
50+
- **Roll stick (left/right):** sway
51+
- **Throttle stick (up/down):** heave
52+
- **Yaw stick (left/right):** yaw
53+
54+
![RC Basic Commands](../../assets/flying/rc_mode2_mc_position_mode.png)
55+
3656
## Manual Modes
3757

38-
| Mode | Description |
39-
| -------- | -------------------------------------------------------------------------------------------------------------------- |
40-
| Manual | Direct manual control of yaw and thrust. |
41-
| Acro | Manual control of yaw/thrust, but keeps roll/pitch zero |
42-
| Altitude | Manual control of x/y thrust and yaw. Control of height with PID, manually controlled by user. Keeps roll/pitch zero |
43-
| Position | Controls x/y/z and yaw. Manually controlled by user. Keeps roll/pitch zero |
58+
The following manual and assisted modes are currently supported on BlueROV2 Heavy:
59+
60+
| Mode | Description |
61+
| ---------- | --------------------------------------------------------------------------------------------------------------------------- |
62+
| Manual | Direct manual control of thrust and yaw. |
63+
| Stabilized | Manual control of thurst and yaw with roll/pitch stabilization. |
64+
| Acro | Manual control of yaw-rate and direct thrust commands with roll/pitch stabilization. |
65+
| Altitude | Manual control of x/y thrust and yaw. Control of height with PID, manually controlled by user. Keeps roll/pitch stabilized. |
66+
| Position | Controls x, y, z and yaw with position hold when sticks are released. Keeps roll/pitch stabilized. |
67+
68+
## Joystick Stick Mode
69+
70+
BlueROV2 supports two joystick mappings for manual control, selected using the
71+
[UUV_STICK_MODE](../advanced_config/parameter_reference.md#uuv_stick_mode) parameter.
72+
73+
By default, `UUV_STICK_MODE` is set to `0`, which enables the UUV stick mapping intended for vectored underwater vehicles.
74+
75+
### UUV_STICK_MODE = 0 (default)
76+
77+
This mode is intended for normal BlueROV2 operation.
78+
In `Manual`, `Stabilized`, and `Acro` modes, the sticks command:
79+
80+
- **Pitch stick:** surge - moving stick up -> moving forward, +X translation in body frame.
81+
- **Roll stick:** sway - moving stick right -> moving sideways right, +Y translation in body frame.
82+
- **Throttle stick:** heave - moving stick up -> moving upwards, -Z translation in body frame (note the Z axis points Down of the vehicle in PX4).
83+
- **Yaw stick:** yaw - moving stick right -> yawing to the right, +Z rotation in body frame.
84+
85+
In this mode, roll and pitch are kept level rather than commanded directly.
86+
87+
### UUV_STICK_MODE = 1
88+
89+
This mode enables the legacy multicopter-style stick mapping for `Manual`, `Stabilized`, and `Acro` modes:
90+
91+
- **Throttle stick:** surge - moving stick up -> moving forward, +X translation in body frame.
92+
- **Roll stick:** roll - moving stick right -> rolling to the right side, +X rotation in body frame.
93+
- **Pitch stick:** pitch - moving stick up -> pitching down, -X translation in body frame (note signs are switched to follow PX4 standard).
94+
- **Yaw stick:** yaw - moving stick right -> yawing to the right, +Z rotation in body frame.
95+
96+
This mode is mainly provided for compatibility with older setups and user preference.
4497

4598
## Airframe Configuration
4699

docs/en/frames_sub/index.md

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -6,15 +6,15 @@
66
Support for UUVs is [experimental](../airframes/index.md#experimental-vehicles).
77
Maintainer volunteers, [contribution](../contribute/index.md) of new features, new frame configurations, or other improvements would all be very welcome!
88

9-
At time of writing it has only been tested using ROS in offboard mode.
9+
At time of writing manual and assisted manual modes are available for supported UUV frames, as well as ROS in offboard mode.
1010
The following features have not been implemented:
1111

12-
- Modes like missions, depth hold, stabilised manual control, etc.
12+
- Autonomous mission-style underwater workflows are still limited compared to aerial vehicles.
1313
- BlueRobotics gripper support.
1414

1515
:::
1616

17-
PX4 has basic support for UUVs.
17+
PX4 has basic support for UUVs. For BlueROV2 Heavy, PX4 currently supports Manual, Stabilized, Acro, Altitude and Position modes.
1818

1919
## Supported Frames
2020

src/modules/uuv_att_control/uuv_att_control.cpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -270,9 +270,9 @@ void UUVAttitudeControl::generate_attitude_setpoint(float dt)
270270

271271
if (js_heave_sway_mode) {
272272
// XYZ thrust
273-
_attitude_setpoint.thrust_body[0] = _manual_control_setpoint.throttle * throttle_manual_attitude_gain; // surge +x
273+
_attitude_setpoint.thrust_body[0] = _manual_control_setpoint.pitch * throttle_manual_attitude_gain; // heave +z down
274274
_attitude_setpoint.thrust_body[1] = _manual_control_setpoint.roll * throttle_manual_attitude_gain; // sway +y
275-
_attitude_setpoint.thrust_body[2] = -_manual_control_setpoint.pitch * throttle_manual_attitude_gain; // heave +z down
275+
_attitude_setpoint.thrust_body[2] = -_manual_control_setpoint.throttle * throttle_manual_attitude_gain; // surge +x
276276

277277
} else {
278278
// Throttle only on +x (surge)
@@ -295,9 +295,9 @@ void UUVAttitudeControl::generate_rates_setpoint(float dt)
295295
_rates_setpoint.pitch = 0.0f;
296296
_rates_setpoint.yaw = _manual_control_setpoint.yaw * dt * _param_rgm_yaw.get();
297297

298-
_rates_setpoint.thrust_body[0] = _manual_control_setpoint.throttle * throttle_manual_rate_gain; // surge +x
298+
_rates_setpoint.thrust_body[0] = _manual_control_setpoint.pitch * throttle_manual_rate_gain; // heave +z down
299299
_rates_setpoint.thrust_body[1] = _manual_control_setpoint.roll * throttle_manual_rate_gain; // sway +y
300-
_rates_setpoint.thrust_body[2] = -_manual_control_setpoint.pitch * throttle_manual_rate_gain; // heave +z down
300+
_rates_setpoint.thrust_body[2] = -_manual_control_setpoint.throttle * throttle_manual_rate_gain; // surge +x
301301

302302
} else {
303303
// Roll/pitch/yaw are rate commands; thrust only surge
@@ -404,9 +404,9 @@ void UUVAttitudeControl::Run()
404404
const float pitch_u = 0.0f;
405405
const float yaw_u = _manual_control_setpoint.yaw * _param_mgm_yaw.get();
406406

407-
const float thrust_x = _manual_control_setpoint.throttle * throttle_manual_gain; // surge
407+
const float thrust_x = _manual_control_setpoint.pitch * throttle_manual_gain; // heave
408408
const float thrust_y = _manual_control_setpoint.roll * throttle_manual_gain; // sway
409-
const float thrust_z = -_manual_control_setpoint.pitch * throttle_manual_gain; // heave
409+
const float thrust_z = -_manual_control_setpoint.throttle * throttle_manual_gain; // surge
410410

411411
constrain_actuator_commands(roll_u, pitch_u, yaw_u, thrust_x, thrust_y, thrust_z);
412412

0 commit comments

Comments
 (0)