Browse Source

Add gimbal control command to Vehicle

QGC4.4
Gus Grubba 6 years ago
parent
commit
1a87d7f5ff
  1. 15
      src/Vehicle/Vehicle.cc
  2. 2
      src/Vehicle/Vehicle.h

15
src/Vehicle/Vehicle.cc

@ -3977,6 +3977,21 @@ void Vehicle::flashBootloader(void) @@ -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
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------

2
src/Vehicle/Vehicle.h

@ -761,6 +761,8 @@ public: @@ -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

Loading…
Cancel
Save