Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
46 changes: 45 additions & 1 deletion docs/en/qgc-user-guide/fly_view/fly_view_toolbar.md
Original file line number Diff line number Diff line change
Expand Up @@ -95,7 +95,51 @@ The RC RSSI indicator appears when RC signal information is available. It shows

### Gimbal <img src="../../../assets/fly/toolbar/gimbal_indicator.png" alt="Gimbal indicator" style="height: 1.15em; vertical-align: text-bottom;" />

The Gimbal indicator is shown when the vehicle supports the [MAVLink Gimbal Protocol](https://mavlink.io/en/services/gimbal_v2.html). It displays active gimbal status and provides access to gimbal controls and settings.
The Gimbal indicator appears in the toolbar when the vehicle supports the [MAVLink Gimbal Protocol v2](https://mavlink.io/en/services/gimbal_v2.html). It displays the current gimbal status and provides controls for gimbal operation.

#### Gimbal Status Display

The toolbar indicator shows:

* **Pitch angle** - Current pitch position in degrees
* **Yaw value** - Either local yaw (relative to vehicle heading) or azimuth (absolute earth frame), depending on settings
* **Yaw Lock status** - Visual indicator showing whether yaw lock is enabled or disabled
* **Yaw Lock (Locked icon)** - Gimbal yaw is locked to earth frame (maintains absolute heading)
* **Yaw Follow (Follow icon)** - Gimbal yaw follows vehicle body frame (rotates with vehicle)

#### Gimbal Controls

Clicking the gimbal indicator opens a dropdown panel with the following controls:

##### Quick controls

* **Center** - Points the gimbal forward (0° pitch, 0° yaw relative to vehicle)
* **Tilt 90** - Points the gimbal straight down (-90° pitch)
* **Point Home** - Points the gimbal towards the home position
* **Retract** - Sets gimbal to retracted position. This is not supported by all gimbals.
* **Yaw Lock/Unlock** - More info below
* **Gimbal Control Acquisition** - More info below

##### Yaw Lock Mode Toggle

Toggle between two yaw control modes:

* **Yaw Lock** - Gimbal maintains a fixed heading relative to earth/north. When the vehicle rotates, the gimbal counter-rotates to maintain its absolute heading.
* **Yaw Follow** - Gimbal yaw is relative to the vehicle body. When the vehicle rotates, the gimbal rotates with it.

##### Gimbal Control Acquisition

If the option "Show Acquire/Release control button" is set, a new **Acquire/Release Control** button will appear
* Click to request control from the current operator, or to release control if we have it.
* Control is typically needed before sending gimbal commands. If not in control, **it will be requested automatically** when sending other commands.

#### Yaw Lock Behavior with Center and Tilt 90 Commands

By default, the Center and Tilt 90 buttons will also set yaw to follow mode. This is the typical user expectation for these commands.

**Example**: If you're in Yaw Lock mode and press "Center", the gimbal will point forward relative to the vehicle (Yaw Follow mode) rather than maintaining its absolute earth heading.

To change this behaviour and preserve last yaw lock status, you can enable the setting "Preserve yaw lock status on tilt 90 and center commands, don't force yaw follow".

### VTOL Transitions <img src="../../../assets/fly/toolbar/vtol_indicator.png" alt="VTOL indicator" style="height: 1.15em; vertical-align: text-bottom;" />

Expand Down
27 changes: 26 additions & 1 deletion src/Gimbal/GimbalController.cc
Original file line number Diff line number Diff line change
Expand Up @@ -425,7 +425,32 @@ void GimbalController::centerGimbal()
qCCritical(GimbalControllerLog) << "gimbalYawStep: active gimbal is nullptr, returning";
return;
}
sendPitchBodyYaw(0.0, 0.0, true);

const bool preserveYawLock = SettingsManager::instance()->gimbalControllerSettings()->preserveYawLockOnPositionCommands()->rawValue().toBool();
if (preserveYawLock && _activeGimbal->yawLock()) {
// Preserve yaw lock: send command in earth frame with yaw lock flag
sendPitchAbsoluteYaw(0.0, _vehicle->heading()->rawValue().toFloat(), true);
} else {
// Default behavior: send command in body frame (yaw follow)
sendPitchBodyYaw(0.0, 0.0, true);
}
}

void GimbalController::tilt90Gimbal()
{
if (!_activeGimbal) {
qCDebug(GimbalControllerLog) << "tilt90Gimbal: active gimbal is nullptr, returning";
return;
}

const bool preserveYawLock = SettingsManager::instance()->gimbalControllerSettings()->preserveYawLockOnPositionCommands()->rawValue().toBool();
if (preserveYawLock && _activeGimbal->yawLock()) {
// Preserve yaw lock: send command in earth frame with yaw lock flag
sendPitchAbsoluteYaw(-90.0, _activeGimbal->absoluteYaw()->rawValue().toFloat(), true);
} else {
// Default behavior: send command in body frame (yaw follow)
sendPitchBodyYaw(-90.0, 0.0, true);
}
}

void GimbalController::gimbalOnScreenControl(float panPct, float tiltPct, bool clickAndPoint, bool clickAndDrag, bool /*rateControl*/, bool /*retract*/, bool /*neutral*/, bool /*yawlock*/)
Expand Down
1 change: 1 addition & 0 deletions src/Gimbal/GimbalController.h
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,7 @@ public slots:
// These slots are conected with joysticks for button control
void gimbalYawLock(bool yawLock) { setGimbalYawLock(yawLock); }
Q_INVOKABLE void centerGimbal();
Q_INVOKABLE void tilt90Gimbal();
void gimbalPitchStart(int direction);
void gimbalYawStart(int direction);
void gimbalPitchStop();
Expand Down
7 changes: 7 additions & 0 deletions src/Settings/GimbalController.SettingsGroup.json
Original file line number Diff line number Diff line change
Expand Up @@ -75,6 +75,13 @@
"type": "uint32",
"default": 60,
"units": "deg/s"
},
{
"name": "preserveYawLockOnPositionCommands",
"shortDesc": "Preserve yaw lock state when using position commands",
"longDesc": "When enabled, gimbal position commands will maintain the current yaw lock state instead of automatically switching to yaw follow mode.",
"type": "bool",
"default": false
}
]
}
1 change: 1 addition & 0 deletions src/Settings/GimbalControllerSettings.cc
Original file line number Diff line number Diff line change
Expand Up @@ -33,3 +33,4 @@ DECLARE_SETTINGSFACT(GimbalControllerSettings, toolbarIndicatorShowAcquireReleas
DECLARE_SETTINGSFACT(GimbalControllerSettings, joystickButtonsSpeed)
DECLARE_SETTINGSFACT(GimbalControllerSettings, zoomMaxSpeed)
DECLARE_SETTINGSFACT(GimbalControllerSettings, zoomMinSpeed)
DECLARE_SETTINGSFACT(GimbalControllerSettings, preserveYawLockOnPositionCommands)
1 change: 1 addition & 0 deletions src/Settings/GimbalControllerSettings.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,4 +24,5 @@ class GimbalControllerSettings : public SettingsGroup
DEFINE_SETTINGFACT(joystickButtonsSpeed)
DEFINE_SETTINGFACT(zoomMaxSpeed)
DEFINE_SETTINGFACT(zoomMinSpeed)
DEFINE_SETTINGFACT(preserveYawLockOnPositionCommands)
};
8 changes: 7 additions & 1 deletion src/UI/toolbar/GimbalIndicator.qml
Original file line number Diff line number Diff line change
Expand Up @@ -184,7 +184,7 @@ Item {
Layout.fillWidth: true
text: qsTr("Tilt 90")
onClicked: {
gimbalController.sendPitchBodyYaw(-90, 0)
gimbalController.tilt90Gimbal()
mainWindow.closeIndicatorDrawer()
}
}
Expand Down Expand Up @@ -304,6 +304,12 @@ Item {
text: qsTr("Show Acquire/Release control button")
fact: _gimbalControllerSettings.toolbarIndicatorShowAcquireReleaseControl
}

FactCheckBoxSlider {
Layout.fillWidth: true
text: qsTr("Preserve yaw lock status on tilt 90 and center commands, don't force yaw follow")
fact: _gimbalControllerSettings.preserveYawLockOnPositionCommands
}
}
}
}
Expand Down
Loading