Browse Source

ArduPilot DO_MOUNT_CONTROL values are centi-degrees

QGC4.4
Don Gagne 3 years ago committed by Patrick José Pereira
parent
commit
e9a2f9b3d0
  1. 6
      src/Vehicle/Vehicle.cc

6
src/Vehicle/Vehicle.cc

@ -3907,6 +3907,12 @@ void Vehicle::flashBootloader() @@ -3907,6 +3907,12 @@ void Vehicle::flashBootloader()
void Vehicle::gimbalControlValue(double pitch, double yaw)
{
if (apmFirmware()) {
// ArduPilot firmware treats this values as centi-degrees
pitch *= 100;
yaw *= 100;
}
//qDebug() << "Gimbal:" << pitch << yaw;
sendMavCommand(
_defaultComponentId,

Loading…
Cancel
Save