Commit 1a87d7f5 authored by Gus Grubba's avatar Gus Grubba

Add gimbal control command to Vehicle

parent cc99ed6b
......@@ -3977,6 +3977,21 @@ void Vehicle::flashBootloader(void)
}
#endif
void Vehicle::gimbalControlValue(double pitch, double yaw)
{
qDebug() << "Gimbal: " << pitch << yaw;
sendMavCommand(
_defaultComponentId,
MAV_CMD_DO_MOUNT_CONTROL,
false, // show errors
static_cast<float>(pitch), // Pitch 0 - 90
0, // Roll (not used)
static_cast<float>(yaw), // Yaw -180 - 180
0, // Altitude (not used)
0, // Latitude (not used)
0, // Longitude (not used)
MAV_MOUNT_MODE_MAVLINK_TARGETING); // MAVLink Roll,Pitch,Yaw
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
......
......@@ -761,6 +761,8 @@ public:
Q_INVOKABLE void setPIDTuningTelemetryMode(bool pidTuning);
Q_INVOKABLE void gimbalControlValue(double pitch, double yaw);
#if !defined(NO_ARDUPILOT_DIALECT)
Q_INVOKABLE void flashBootloader(void);
#endif
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment