Commit 2894ffb6 authored by Gus Grubba's avatar Gus Grubba

Keep state of checklist within vehicle.

parent 76b6b9de
......@@ -432,7 +432,7 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
_firmwarePlugin->initializeVehicle(this);
}
void Vehicle::_commonInit(void)
void Vehicle::_commonInit()
{
_firmwarePlugin = _firmwarePluginManager->firmwarePluginForAutopilot(_firmwareType, _vehicleType);
......@@ -599,7 +599,7 @@ void Vehicle::_offlineHoverSpeedSettingChanged(QVariant value)
emit defaultHoverSpeedChanged(_defaultHoverSpeed);
}
QString Vehicle::firmwareTypeString(void) const
QString Vehicle::firmwareTypeString() const
{
if (px4Firmware()) {
return QStringLiteral("PX4 Pro");
......@@ -610,7 +610,7 @@ QString Vehicle::firmwareTypeString(void) const
}
}
QString Vehicle::vehicleTypeString(void) const
QString Vehicle::vehicleTypeString() const
{
if (fixedWing()) {
return tr("Fixed Wing");
......@@ -892,7 +892,7 @@ void Vehicle::_handleOrbitExecutionStatus(const mavlink_message_t& message)
_orbitTelemetryTimer.start(_orbitTelemetryTimeoutMsecs);
}
void Vehicle::_orbitTelemetryTimeout(void)
void Vehicle::_orbitTelemetryTimeout()
{
_orbitActive = false;
emit orbitActiveChanged(false);
......@@ -1524,7 +1524,7 @@ void Vehicle::_handleWind(mavlink_message_t& message)
}
#endif
bool Vehicle::_apmArmingNotRequired(void)
bool Vehicle::_apmArmingNotRequired()
{
QString armingRequireParam("ARMING_REQUIRE");
return _parameterManager->parameterExists(FactSystem::defaultComponentId, armingRequireParam) &&
......@@ -1546,7 +1546,7 @@ void Vehicle::_handleSysStatus(mavlink_message_t& message)
_battery1FactGroup.voltage()->setRawValue(VehicleBatteryFactGroup::_voltageUnavailable);
} else {
_battery1FactGroup.voltage()->setRawValue((double)sysStatus.voltage_battery / 1000.0);
// current_battery is 10 mA and voltage_battery is 1mV. (10/1e3 times 1/1e3 = 1/1e5)
// current_battery is 10 mA and voltage_battery is 1mV. (10/1e3 times 1/1e3 = 1/1e5)
_battery1FactGroup.instantPower()->setRawValue((float)(sysStatus.current_battery*sysStatus.voltage_battery)/(100000.0));
}
_battery1FactGroup.percentRemaining()->setRawValue(sysStatus.battery_remaining);
......@@ -1601,7 +1601,7 @@ void Vehicle::_handleBatteryStatus(mavlink_message_t& message)
if (bat_status.temperature == INT16_MAX) {
batteryFactGroup.temperature()->setRawValue(VehicleBatteryFactGroup::_temperatureUnavailable);
} else {
batteryFactGroup.temperature()->setRawValue((double)bat_status.temperature / 100.0);
batteryFactGroup.temperature()->setRawValue(static_cast<double>(bat_status.temperature)/100.0);
}
if (bat_status.current_consumed == -1) {
batteryFactGroup.mahConsumed()->setRawValue(VehicleBatteryFactGroup::_mahConsumedUnavailable);
......@@ -1731,7 +1731,7 @@ void Vehicle::_handleHeartbeat(mavlink_message_t& message)
// bad modes while unit testing.
previousFlightMode = flightMode();
}
_base_mode = heartbeat.base_mode;
_base_mode = heartbeat.base_mode;
_custom_mode = heartbeat.custom_mode;
if (previousFlightMode != flightMode()) {
emit flightModeChanged(flightMode());
......@@ -2080,7 +2080,7 @@ void Vehicle::_updatePriorityLink(bool updateActive, bool sendCommand)
}
}
int Vehicle::motorCount(void)
int Vehicle::motorCount()
{
switch (_vehicleType) {
case MAV_TYPE_HELICOPTER:
......@@ -2142,12 +2142,12 @@ int Vehicle::motorCount(void)
}
}
bool Vehicle::coaxialMotors(void)
bool Vehicle::coaxialMotors()
{
return _firmwarePlugin->multiRotorCoaxialMotors(this);
}
bool Vehicle::xConfigMotors(void)
bool Vehicle::xConfigMotors()
{
return _firmwarePlugin->multiRotorXConfig(this);
}
......@@ -2258,7 +2258,7 @@ void Vehicle::resetMessages()
}
}
void Vehicle::_loadSettings(void)
void Vehicle::_loadSettings()
{
if (!_active) {
return;
......@@ -2277,7 +2277,7 @@ void Vehicle::_loadSettings(void)
}
}
void Vehicle::_saveSettings(void)
void Vehicle::_saveSettings()
{
QSettings settings;
......@@ -2292,7 +2292,7 @@ void Vehicle::_saveSettings(void)
}
}
int Vehicle::joystickMode(void)
int Vehicle::joystickMode()
{
return _joystickMode;
}
......@@ -2309,7 +2309,7 @@ void Vehicle::setJoystickMode(int mode)
emit joystickModeChanged(mode);
}
QStringList Vehicle::joystickModes(void)
QStringList Vehicle::joystickModes()
{
QStringList list;
......@@ -2318,7 +2318,7 @@ QStringList Vehicle::joystickModes(void)
return list;
}
bool Vehicle::joystickEnabled(void)
bool Vehicle::joystickEnabled()
{
return _joystickEnabled;
}
......@@ -2343,7 +2343,7 @@ void Vehicle::_startJoystick(bool start)
}
}
bool Vehicle::active(void)
bool Vehicle::active()
{
return _active;
}
......@@ -2357,7 +2357,7 @@ void Vehicle::setActive(bool active)
}
}
QGeoCoordinate Vehicle::homePosition(void)
QGeoCoordinate Vehicle::homePosition()
{
return _homePosition;
}
......@@ -2371,22 +2371,22 @@ void Vehicle::setArmed(bool armed)
armed ? 1.0f : 0.0f);
}
bool Vehicle::flightModeSetAvailable(void)
bool Vehicle::flightModeSetAvailable()
{
return _firmwarePlugin->isCapable(this, FirmwarePlugin::SetFlightModeCapability);
}
QStringList Vehicle::flightModes(void)
QStringList Vehicle::flightModes()
{
return _firmwarePlugin->flightModes(this);
}
QStringList Vehicle::extraJoystickFlightModes(void)
QStringList Vehicle::extraJoystickFlightModes()
{
return _firmwarePlugin->extraJoystickFlightModes(this);
}
QString Vehicle::flightMode(void) const
QString Vehicle::flightMode() const
{
return _firmwarePlugin->flightMode(_base_mode, _custom_mode);
}
......@@ -2416,7 +2416,7 @@ void Vehicle::setFlightMode(const QString& flightMode)
}
}
QString Vehicle::priorityLinkName(void) const
QString Vehicle::priorityLinkName() const
{
if (_priorityLink) {
return _priorityLink->getName();
......@@ -2425,7 +2425,7 @@ QString Vehicle::priorityLinkName(void) const
return "none";
}
QVariantList Vehicle::links(void) const {
QVariantList Vehicle::links() const {
QVariantList ret;
for( const auto &item: _links )
......@@ -2463,7 +2463,7 @@ void Vehicle::setPriorityLinkByName(const QString& priorityLinkName)
}
}
bool Vehicle::hilMode(void)
bool Vehicle::hilMode()
{
return _base_mode & MAV_MODE_FLAG_HIL_ENABLED;
}
......@@ -2514,7 +2514,7 @@ void Vehicle::requestDataStream(MAV_DATA_STREAM stream, uint16_t rate, bool send
}
}
void Vehicle::_sendMessageMultipleNext(void)
void Vehicle::_sendMessageMultipleNext()
{
if (_nextSendMessageMultipleIndex < _sendMessageMultipleList.count()) {
qCDebug(VehicleLog) << "_sendMessageMultipleNext:" << _sendMessageMultipleList[_nextSendMessageMultipleIndex].message.msgid;
......@@ -2561,12 +2561,12 @@ void Vehicle::_rallyPointManagerError(int errorCode, const QString& errorMsg)
qgcApp()->showMessage(tr("Rally Point transfer failed. Retry transfer. Error: %1").arg(errorMsg));
}
void Vehicle::_clearCameraTriggerPoints(void)
void Vehicle::_clearCameraTriggerPoints()
{
_cameraTriggerPoints.clearAndDeleteContents();
}
void Vehicle::_flightTimerStart(void)
void Vehicle::_flightTimerStart()
{
_flightTimer.start();
_flightTimeUpdater.start();
......@@ -2574,17 +2574,17 @@ void Vehicle::_flightTimerStart(void)
_flightTimeFact.setRawValue(0);
}
void Vehicle::_flightTimerStop(void)
void Vehicle::_flightTimerStop()
{
_flightTimeUpdater.stop();
}
void Vehicle::_updateFlightTime(void)
void Vehicle::_updateFlightTime()
{
_flightTimeFact.setRawValue((double)_flightTimer.elapsed() / 1000.0);
}
void Vehicle::_startPlanRequest(void)
void Vehicle::_startPlanRequest()
{
if (_missionManagerInitialRequestSent) {
// We have already started (or possibly completed) the sequence of requesting the plan for the first time
......@@ -2622,7 +2622,7 @@ void Vehicle::_startPlanRequest(void)
}
}
void Vehicle::_missionLoadComplete(void)
void Vehicle::_missionLoadComplete()
{
// After the initial mission request completes we ask for the geofence
if (!_geoFenceManagerInitialRequestSent) {
......@@ -2637,7 +2637,7 @@ void Vehicle::_missionLoadComplete(void)
}
}
void Vehicle::_geoFenceLoadComplete(void)
void Vehicle::_geoFenceLoadComplete()
{
// After geofence request completes we ask for the rally points
if (!_rallyPointManagerInitialRequestSent) {
......@@ -2652,7 +2652,7 @@ void Vehicle::_geoFenceLoadComplete(void)
}
}
void Vehicle::_rallyPointLoadComplete(void)
void Vehicle::_rallyPointLoadComplete()
{
qCDebug(VehicleLog) << "_missionLoadComplete _initialPlanRequestComplete = true";
if (!_initialPlanRequestComplete) {
......@@ -2674,7 +2674,7 @@ void Vehicle::_parametersReady(bool parametersReady)
}
}
void Vehicle::_sendQGCTimeToVehicle(void)
void Vehicle::_sendQGCTimeToVehicle()
{
mavlink_message_t msg;
mavlink_system_time_t cmd;
......@@ -2692,7 +2692,7 @@ void Vehicle::_sendQGCTimeToVehicle(void)
sendMessageOnLink(priorityLink(), msg);
}
void Vehicle::disconnectInactiveVehicle(void)
void Vehicle::disconnectInactiveVehicle()
{
// Vehicle is no longer communicating with us, disconnect all links
......@@ -2849,57 +2849,57 @@ void Vehicle::_say(const QString& text)
_toolbox->audioOutput()->say(text.toLower());
}
bool Vehicle::fixedWing(void) const
bool Vehicle::fixedWing() const
{
return QGCMAVLink::isFixedWing(vehicleType());
}
bool Vehicle::rover(void) const
bool Vehicle::rover() const
{
return QGCMAVLink::isRover(vehicleType());
}
bool Vehicle::sub(void) const
bool Vehicle::sub() const
{
return QGCMAVLink::isSub(vehicleType());
}
bool Vehicle::multiRotor(void) const
bool Vehicle::multiRotor() const
{
return QGCMAVLink::isMultiRotor(vehicleType());
}
bool Vehicle::vtol(void) const
bool Vehicle::vtol() const
{
return _firmwarePlugin->isVtol(this);
}
bool Vehicle::supportsThrottleModeCenterZero(void) const
bool Vehicle::supportsThrottleModeCenterZero() const
{
return _firmwarePlugin->supportsThrottleModeCenterZero();
}
bool Vehicle::supportsNegativeThrust(void)
bool Vehicle::supportsNegativeThrust()
{
return _firmwarePlugin->supportsNegativeThrust(this);
}
bool Vehicle::supportsRadio(void) const
bool Vehicle::supportsRadio() const
{
return _firmwarePlugin->supportsRadio();
}
bool Vehicle::supportsJSButton(void) const
bool Vehicle::supportsJSButton() const
{
return _firmwarePlugin->supportsJSButton();
}
bool Vehicle::supportsMotorInterference(void) const
bool Vehicle::supportsMotorInterference() const
{
return _firmwarePlugin->supportsMotorInterference();
}
bool Vehicle::supportsTerrainFrame(void) const
bool Vehicle::supportsTerrainFrame() const
{
return _firmwarePlugin->supportsTerrainFrame();
}
......@@ -2939,7 +2939,7 @@ QString Vehicle::vehicleTypeName() const {
}
/// Returns the string to speak to identify the vehicle
QString Vehicle::_vehicleIdSpeech(void)
QString Vehicle::_vehicleIdSpeech()
{
if (_toolbox->multiVehicleManager()->vehicles()->count() > 1) {
return tr("vehicle %1").arg(id());
......@@ -2980,12 +2980,12 @@ void Vehicle::_setLanding(bool landing)
}
}
bool Vehicle::guidedModeSupported(void) const
bool Vehicle::guidedModeSupported() const
{
return _firmwarePlugin->isCapable(this, FirmwarePlugin::GuidedModeCapability);
}
bool Vehicle::pauseVehicleSupported(void) const
bool Vehicle::pauseVehicleSupported() const
{
return _firmwarePlugin->isCapable(this, FirmwarePlugin::PauseVehicleCapability);
}
......@@ -3019,7 +3019,7 @@ void Vehicle::guidedModeRTL(bool smartRTL)
_firmwarePlugin->guidedModeRTL(this, smartRTL);
}
void Vehicle::guidedModeLand(void)
void Vehicle::guidedModeLand()
{
if (!guidedModeSupported()) {
qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
......@@ -3037,12 +3037,12 @@ void Vehicle::guidedModeTakeoff(double altitudeRelative)
_firmwarePlugin->guidedModeTakeoff(this, altitudeRelative);
}
double Vehicle::minimumTakeoffAltitude(void)
double Vehicle::minimumTakeoffAltitude()
{
return _firmwarePlugin->minimumTakeoffAltitude(this);
}
void Vehicle::startMission(void)
void Vehicle::startMission()
{
_firmwarePlugin->startMission(this);
}
......@@ -3173,7 +3173,7 @@ void Vehicle::stopGuidedModeROI()
}
}
void Vehicle::pauseVehicle(void)
void Vehicle::pauseVehicle()
{
if (!pauseVehicleSupported()) {
qgcApp()->showMessage(QStringLiteral("Pause not supported by vehicle."));
......@@ -3191,7 +3191,7 @@ void Vehicle::abortLanding(double climbOutAltitude)
static_cast<float>(climbOutAltitude));
}
bool Vehicle::guidedMode(void) const
bool Vehicle::guidedMode() const
{
return _firmwarePlugin->isGuidedMode(this);
}
......@@ -3201,7 +3201,7 @@ void Vehicle::setGuidedMode(bool guidedMode)
return _firmwarePlugin->setGuidedMode(this, guidedMode);
}
void Vehicle::emergencyStop(void)
void Vehicle::emergencyStop()
{
sendMavCommand(
_defaultComponentId,
......@@ -3277,7 +3277,7 @@ void Vehicle::sendMavCommandInt(int component, MAV_CMD command, MAV_FRAME frame,
}
}
void Vehicle::_sendMavCommandAgain(void)
void Vehicle::_sendMavCommandAgain()
{
if(!_mavCommandQueue.size()) {
qWarning() << "Command resend with no commands in queue";
......@@ -3364,7 +3364,7 @@ void Vehicle::_sendMavCommandAgain(void)
sendMessageOnLink(priorityLink(), msg);
}
void Vehicle::_sendNextQueuedMavCommand(void)
void Vehicle::_sendNextQueuedMavCommand()
{
if (_mavCommandQueue.count()) {
_mavCommandRetryCount = 0;
......@@ -3372,7 +3372,7 @@ void Vehicle::_sendNextQueuedMavCommand(void)
}
}
void Vehicle::_handleUnsupportedRequestProtocolVersion(void)
void Vehicle::_handleUnsupportedRequestProtocolVersion()
{
// We end up here if either the vehicle does not support the MAV_CMD_REQUEST_PROTOCOL_VERSION command or if
// we never received an Ack back for the command.
......@@ -3395,7 +3395,7 @@ void Vehicle::_handleUnsupportedRequestProtocolVersion(void)
_startPlanRequest();
}
void Vehicle::_protocolVersionTimeOut(void)
void Vehicle::_protocolVersionTimeOut()
{
// The PROTOCOL_VERSION message didn't make it through the pipe from Vehicle->QGC.
// This means although the vehicle may support mavlink 2, the pipe does not.
......@@ -3405,7 +3405,7 @@ void Vehicle::_protocolVersionTimeOut(void)
_startPlanRequest();
}
void Vehicle::_handleUnsupportedRequestAutopilotCapabilities(void)
void Vehicle::_handleUnsupportedRequestAutopilotCapabilities()
{
// We end up here if either the vehicle does not support the MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES command or if
// we never received an Ack back for the command.
......@@ -3502,7 +3502,7 @@ void Vehicle::setPrearmError(const QString& prearmError)
}
}
void Vehicle::_prearmErrorTimeout(void)
void Vehicle::_prearmErrorTimeout()
{
setPrearmError(QString());
}
......@@ -3524,7 +3524,7 @@ void Vehicle::setFirmwareCustomVersion(int majorVersion, int minorVersion, int p
emit firmwareCustomVersionChanged();
}
QString Vehicle::firmwareVersionTypeString(void) const
QString Vehicle::firmwareVersionTypeString() const
{
switch (_firmwareVersionType) {
case FIRMWARE_VERSION_TYPE_DEV:
......@@ -3576,17 +3576,17 @@ void Vehicle::motorTest(int motor, int percent, int timeoutSecs)
sendMavCommand(_defaultComponentId, MAV_CMD_DO_MOTOR_TEST, true, motor, MOTOR_TEST_THROTTLE_PERCENT, percent, timeoutSecs, 0, MOTOR_TEST_ORDER_BOARD);
}
QString Vehicle::brandImageIndoor(void) const
QString Vehicle::brandImageIndoor() const
{
return _firmwarePlugin->brandImageIndoor(this);
}
QString Vehicle::brandImageOutdoor(void) const
QString Vehicle::brandImageOutdoor() const
{
return _firmwarePlugin->brandImageOutdoor(this);
}
QStringList Vehicle::unhealthySensors(void) const
QStringList Vehicle::unhealthySensors() const
{
QStringList sensorList;
......@@ -3643,7 +3643,7 @@ void Vehicle::setOfflineEditingDefaultComponentId(int defaultComponentId)
}
}
void Vehicle::triggerCamera(void)
void Vehicle::triggerCamera()
{
sendMavCommand(_defaultComponentId,
MAV_CMD_DO_DIGICAM_CONTROL,
......@@ -3752,42 +3752,42 @@ void Vehicle::setFirmwarePluginInstanceData(QObject* firmwarePluginInstanceData)
_firmwarePluginInstanceData = firmwarePluginInstanceData;
}
QString Vehicle::missionFlightMode(void) const
QString Vehicle::missionFlightMode() const
{
return _firmwarePlugin->missionFlightMode();
}
QString Vehicle::pauseFlightMode(void) const
QString Vehicle::pauseFlightMode() const
{
return _firmwarePlugin->pauseFlightMode();
}
QString Vehicle::rtlFlightMode(void) const
QString Vehicle::rtlFlightMode() const
{
return _firmwarePlugin->rtlFlightMode();
}
QString Vehicle::smartRTLFlightMode(void) const
QString Vehicle::smartRTLFlightMode() const
{
return _firmwarePlugin->smartRTLFlightMode();
}
bool Vehicle::supportsSmartRTL(void) const
bool Vehicle::supportsSmartRTL() const
{
return _firmwarePlugin->supportsSmartRTL();
}
QString Vehicle::landFlightMode(void) const
QString Vehicle::landFlightMode() const
{
return _firmwarePlugin->landFlightMode();
}
QString Vehicle::takeControlFlightMode(void) const
QString Vehicle::takeControlFlightMode() const
{
return _firmwarePlugin->takeControlFlightMode();
}
QString Vehicle::followFlightMode(void) const
QString Vehicle::followFlightMode() const
{
return _firmwarePlugin->followFlightMode();
}
......@@ -3825,7 +3825,7 @@ const QVariantList& Vehicle::toolBarIndicators()
return emptyList;
}
const QVariantList& Vehicle::staticCameraList(void) const
const QVariantList& Vehicle::staticCameraList() const
{
if (_firmwarePlugin) {
return _firmwarePlugin->cameraList(this);
......@@ -3834,12 +3834,12 @@ const QVariantList& Vehicle::staticCameraList(void) const
return emptyList;
}
bool Vehicle::vehicleYawsToNextWaypointInMission(void) const
bool Vehicle::vehicleYawsToNextWaypointInMission() const
{
return _firmwarePlugin->vehicleYawsToNextWaypointInMission(this);
}
void Vehicle::_setupAutoDisarmSignalling(void)
void Vehicle::_setupAutoDisarmSignalling()
{
QString param = _firmwarePlugin->autoDisarmParameter(this);
......@@ -3850,7 +3850,7 @@ void Vehicle::_setupAutoDisarmSignalling(void)
}
}
bool Vehicle::autoDisarm(void)
bool Vehicle::autoDisarm()
{
QString param = _firmwarePlugin->autoDisarmParameter(this);
......@@ -3893,7 +3893,7 @@ void Vehicle::_handleADSBVehicle(const mavlink_message_t& message)
}
}
void Vehicle::_updateDistanceHeadingToHome(void)
void Vehicle::_updateDistanceHeadingToHome()
{
if (coordinate().isValid() && homePosition().isValid()) {
_distanceToHomeFact.setRawValue(coordinate().distanceTo(homePosition()));
......@@ -3908,7 +3908,7 @@ void Vehicle::_updateDistanceHeadingToHome(void)
}
}
void Vehicle::_updateHeadingToNextWP(void)
void Vehicle::_updateHeadingToNextWP()
{
const int _currentIndex = _missionManager->currentIndex();
MissionItem _currentItem;
......@@ -3925,7 +3925,7 @@ void Vehicle::_updateHeadingToNextWP(void)
}
}
void Vehicle::_updateDistanceToGCS(void)
void Vehicle::_updateDistanceToGCS()
{
QGeoCoordinate gcsPosition = _toolbox->qgcPositionManager()->gcsPosition();
if (coordinate().isValid() && gcsPosition.isValid()) {
......@@ -3935,12 +3935,12 @@ void Vehicle::_updateDistanceToGCS(void)
}
}
void Vehicle::_updateHobbsMeter(void)
void Vehicle::_updateHobbsMeter()
{
_hobbsFact.setRawValue(hobbsMeter());
}
void Vehicle::forceInitialPlanRequestComplete(void)
void Vehicle::forceInitialPlanRequestComplete()
{
_initialPlanRequestComplete = true;
emit initialPlanRequestCompleteChanged(true);
......@@ -4163,7 +4163,7 @@ void Vehicle::_writeCsvLine()
}
#if !defined(NO_ARDUPILOT_DIALECT)
void Vehicle::flashBootloader(void)
void Vehicle::flashBootloader()
{
sendMavCommand(defaultComponentId(),
MAV_CMD_FLASH_BOOTLOADER,
......@@ -4239,9 +4239,9 @@ void Vehicle::_handleGimbalOrientation(const mavlink_message_t& message)
void Vehicle::_handleObstacleDistance(const mavlink_message_t& message)
{
mavlink_obstacle_distance_t o;
mavlink_msg_obstacle_distance_decode(&message, &o);
_objectAvoidance->update(&o);
mavlink_obstacle_distance_t o;
mavlink_msg_obstacle_distance_decode(&message, &o);
_objectAvoidance->update(&o);
}
void Vehicle::updateFlightDistance(double distance)
......@@ -4389,7 +4389,7 @@ VehicleClockFactGroup::VehicleClockFactGroup(QObject* parent)
_currentDateFact.setRawValue (std::numeric_limits<float>::quiet_NaN());
}
void VehicleClockFactGroup::_updateAllValues(void)
void VehicleClockFactGroup::_updateAllValues()
{
_currentTimeFact.setRawValue(QTime::currentTime().toString());
_currentDateFact.setRawValue(QDateTime::currentDateTime().toString(QLocale::system().dateFormat(QLocale::ShortFormat)));
......
......@@ -65,16 +65,16 @@ public:
Q_PROPERTY(Fact* rotationPitch90 READ rotationPitch90 CONSTANT)
Q_PROPERTY(Fact* rotationPitch270 READ rotationPitch270 CONSTANT)
Fact* rotationNone (void) { return &_rotationNoneFact; }
Fact* rotationYaw45 (void) { return &_rotationYaw45Fact; }
Fact* rotationYaw90 (void) { return &_rotationYaw90Fact; }
Fact* rotationYaw135 (void) { return &_rotationYaw90Fact; }
Fact* rotationYaw180 (void) { return &_rotationYaw180Fact; }
Fact* rotationYaw225 (void) { return &_rotationYaw180Fact; }
Fact* rotationYaw270 (void) { return &_rotationYaw270Fact; }
Fact* rotationYaw315 (void) { return &_rotationYaw315Fact; }
Fact* rotationPitch90 (void) { return &_rotationPitch90Fact; }
Fact* rotationPitch270 (void) { return &_rotationPitch270Fact; }
Fact* rotationNone () { return &_rotationNoneFact; }
Fact* rotationYaw45 () { return &_rotationYaw45Fact; }
Fact* rotationYaw90 () { return &_rotationYaw90Fact; }
Fact* rotationYaw135 () { return &_rotationYaw90Fact; }
Fact* rotationYaw180 () { return &_rotationYaw180Fact; }
Fact* rotationYaw225 () { return &_rotationYaw180Fact; }
Fact* rotationYaw270 () { return &_rotationYaw270Fact; }
Fact* rotationYaw315 () { return &_rotationYaw315Fact; }
Fact* rotationPitch90 () { return &_rotationPitch90Fact; }
Fact* rotationPitch270 () { return &_rotationPitch270Fact; }
static const char* _rotationNoneFactName;
static const char* _rotationYaw45FactName;
......@@ -114,12 +114,12 @@ public:
Q_PROPERTY(Fact* pitchRate READ pitchRate CONSTANT)
Q_PROPERTY(Fact* yawRate READ yawRate CONSTANT)
Fact* roll (void) { return &_rollFact; }
Fact* pitch (void) { return &_pitchFact; }
Fact* yaw (void) { return &_yawFact; }
Fact* rollRate (void) { return &_rollRateFact; }
Fact* pitchRate (void) { return &_pitchRateFact; }
Fact* yawRate (void) { return &_yawRateFact; }
Fact* roll () { return &_rollFact; }
Fact* pitch () { return &_pitchFact; }
Fact* yaw () { return &_yawFact; }
Fact* rollRate () { return &_rollRateFact; }
Fact* pitchRate () { return &_pitchRateFact; }
Fact* yawRate () { return &_yawRateFact; }
static const char* _rollFactName;
static const char* _pitchFactName;
......@@ -151,12 +151,12 @@ public:
Q_PROPERTY(Fact* clipCount2 READ clipCount2 CONSTANT)
Q_PROPERTY(Fact* clipCount3 READ clipCount3 CONSTANT)
Fact* xAxis (void) { return &_xAxisFact; }
Fact* yAxis (void) { return &_yAxisFact; }
Fact* zAxis (void) { return &_zAxisFact; }
Fact* clipCount1 (void) { return &_clipCount1Fact; }
Fact* clipCount2 (void) { return &_clipCount2Fact; }
Fact* clipCount3 (void) { return &_clipCount3Fact; }
Fact* xAxis () { return &_xAxisFact; }
Fact* yAxis () { return &_yAxisFact; }
Fact* zAxis () { return &_zAxisFact; }
Fact* clipCount1 () { return &_clipCount1Fact; }
Fact* clipCount2 () { return &_clipCount2Fact; }
Fact* clipCount3 () { return &_clipCount3Fact; }
static const char* _xAxisFactName;
static const char* _yAxisFactName;
......@@ -185,9 +185,9 @@ public:
Q_PROPERTY(Fact* speed READ speed CONSTANT)
Q_PROPERTY(Fact* verticalSpeed READ verticalSpeed CONSTANT)
Fact* direction (void) { return &_directionFact; }
Fact* speed (void) { return &_speedFact; }
Fact* verticalSpeed (void) { return &_verticalSpeedFact; }
Fact* direction () { return &_directionFact; }
Fact* speed () { return &_speedFact; }
Fact* verticalSpeed () { return &_verticalSpeedFact; }
static const char* _directionFactName;
static const char* _speedFactName;
......@@ -215,14 +215,14 @@ public:
Q_PROPERTY(Fact* count READ count CONSTANT)
Q_PROPERTY(Fact* lock READ lock CONSTANT)
Fact* lat (void) { return &_latFact; }
Fact* lon (void) { return &_lonFact; }
Fact* mgrs (void) { return &_mgrsFact; }
Fact* hdop (void) { return &_hdopFact; }
Fact* vdop (void) { return &_vdopFact; }
Fact* courseOverGround (void) { return &_courseOverGroundFact; }
Fact* count (void) { return &_countFact; }
Fact* lock (void) { return &_lockFact; }
Fact* lat () { return &_latFact; }
Fact* lon () { return &_lonFact; }
Fact* mgrs () { return &_mgrsFact; }
Fact* hdop () { return &_hdopFact; }
Fact* vdop () { return &_vdopFact; }
Fact* courseOverGround () { return &_courseOverGroundFact; }
Fact* count () { return &_countFact; }
Fact* lock () { return &_lockFact; }
static const char* _latFactName;
static const char* _lonFactName;
......@@ -261,15 +261,15 @@ public:
Q_PROPERTY(Fact* timeRemaining READ timeRemaining CONSTANT)
Q_PROPERTY(Fact* chargeState READ chargeState CONSTANT)
Fact* voltage (void) { return &_voltageFact; }
Fact* percentRemaining (void) { return &_percentRemainingFact; }
Fact* mahConsumed (void) { return &_mahConsumedFact; }
Fact* current (void) { return &_currentFact; }
Fact* temperature (void) { return &_temperatureFact; }
Fact* cellCount (void) { return &_cellCountFact; }
Fact* instantPower (void) { return &_instantPowerFact; }
Fact* timeRemaining (void) { return &_timeRemainingFact; }
Fact* chargeState (void) { return &_chargeStateFact; }
Fact* voltage () { return &_voltageFact; }
Fact* percentRemaining () { return &_percentRemainingFact; }
Fact* mahConsumed () { return &_mahConsumedFact; }
Fact* current () { return &_currentFact; }
Fact* temperature () { return &_temperatureFact; }
Fact* cellCount () { return &_cellCountFact; }
Fact* instantPower () { return &_instantPowerFact; }
Fact* timeRemaining () { return &_timeRemainingFact; }
Fact* chargeState () { return &_chargeStateFact; }
static const char* _voltageFactName;
static const char* _percentRemainingFactName;
......@@ -314,9 +314,9 @@ public:
Q_PROPERTY(Fact* temperature2 READ temperature2 CONSTANT)
Q_PROPERTY(Fact* temperature3 READ temperature3 CONSTANT)
Fact* temperature1 (void) { return &_temperature1Fact; }
Fact* temperature2 (void) { return &_temperature2Fact; }
Fact* temperature3 (void) { return &_temperature3Fact; }
Fact* temperature1 () { return &_temperature1Fact; }
Fact* temperature2 () { return &_temperature2Fact; }
Fact* temperature3 () { return &_temperature3Fact; }
static const char* _temperature1FactName;
static const char* _temperature2FactName;
......@@ -342,8 +342,8 @@ public:
Q_PROPERTY(Fact* currentTime READ currentTime CONSTANT)
Q_PROPERTY(Fact* currentDate READ currentDate CONSTANT)
Fact* currentTime (void) { return &_currentTimeFact; }
Fact* currentDate (void) { return &_currentDateFact; }
Fact* currentTime () { return &_currentTimeFact; }
Fact* currentDate () { return &_currentDateFact; }
static const char* _currentTimeFactName;
static const char* _currentDateFactName;
......@@ -351,7 +351,7 @@ public:
static const char* _settingsGroup;
private slots:
void _updateAllValues(void) override;
void _updateAllValues() override;
private:
Fact _currentTimeFact;
......@@ -386,26 +386,26 @@ public:
Q_PROPERTY(Fact* horizPosAccuracy READ horizPosAccuracy CONSTANT)
Q_PROPERTY(Fact* vertPosAccuracy READ vertPosAccuracy CONSTANT)
Fact* goodAttitudeEstimate (void) { return &_goodAttitudeEstimateFact; }
Fact* goodHorizVelEstimate (void) { return &_goodHorizVelEstimateFact; }
Fact* goodVertVelEstimate (void) { return &_goodVertVelEstimateFact; }
Fact* goodHorizPosRelEstimate (void) { return &_goodHorizPosRelEstimateFact; }
Fact* goodHorizPosAbsEstimate (void) { return &_goodHorizPosAbsEstimateFact; }
Fact* goodVertPosAbsEstimate (void) { return &_goodVertPosAbsEstimateFact; }
Fact* goodVertPosAGLEstimate (void) { return &_goodVertPosAGLEstimateFact; }
Fact* goodConstPosModeEstimate (void) { return &_goodConstPosModeEstimateFact; }
Fact* goodPredHorizPosRelEstimate (void) { return &_goodPredHorizPosRelEstimateFact; }
Fact* goodPredHorizPosAbsEstimate (void) { return &_goodPredHorizPosAbsEstimateFact; }
Fact* gpsGlitch (void) { return &_gpsGlitchFact; }
Fact* accelError (void) { return &_accelErrorFact; }
Fact* velRatio (void) { return &_velRatioFact; }
Fact* horizPosRatio (void) { return &_horizPosRatioFact; }
Fact* vertPosRatio (void) { return &_vertPosRatioFact; }
Fact* magRatio (void) { return &_magRatioFact; }
Fact* haglRatio (void) { return &_haglRatioFact; }
Fact* tasRatio (void) { return &_tasRatioFact; }
Fact* horizPosAccuracy (void) { return &_horizPosAccuracyFact; }
Fact* vertPosAccuracy (void) { return &_vertPosAccuracyFact; }
Fact* goodAttitudeEstimate () { return &_goodAttitudeEstimateFact; }
Fact* goodHorizVelEstimate () { return &_goodHorizVelEstimateFact; }
Fact* goodVertVelEstimate () { return &_goodVertVelEstimateFact; }
Fact* goodHorizPosRelEstimate () { return &_goodHorizPosRelEstimateFact; }
Fact* goodHorizPosAbsEstimate () { return &_goodHorizPosAbsEstimateFact; }
Fact* goodVertPosAbsEstimate () { return &_goodVertPosAbsEstimateFact; }
Fact* goodVertPosAGLEstimate () { return &_goodVertPosAGLEstimateFact; }
Fact* goodConstPosModeEstimate () { return &_goodConstPosModeEstimateFact; }
Fact* goodPredHorizPosRelEstimate () { return &_goodPredHorizPosRelEstimateFact; }
Fact* goodPredHorizPosAbsEstimate () { return &_goodPredHorizPosAbsEstimateFact; }
Fact* gpsGlitch () { return &_gpsGlitchFact; }
Fact* accelError () { return &_accelErrorFact; }
Fact* velRatio () { return &_velRatioFact; }
Fact* horizPosRatio () { return &_horizPosRatioFact; }
Fact* vertPosRatio () { return &_vertPosRatioFact; }
Fact* magRatio () { return &_magRatioFact; }
Fact* haglRatio () { return &_haglRatioFact; }
Fact* tasRatio () { return &_tasRatioFact; }
Fact* horizPosAccuracy () { return &_horizPosAccuracyFact; }
Fact* vertPosAccuracy () { return &_vertPosAccuracyFact; }
static const char* _goodAttitudeEstimateFactName;
static const char* _goodHorizVelEstimateFactName;
......@@ -534,6 +534,13 @@ public:
};
Q_ENUM(MavlinkSysStatus)
enum CheckList {
CheckListNotSetup = 0,
CheckListPassed,
CheckListFailed,
};
Q_ENUM(CheckList)
Q_PROPERTY(int id READ id CONSTANT)
Q_PROPERTY(AutoPilotPlugin* autopilot MEMBER _autopilotPlugin CONSTANT)
Q_PROPERTY(QGeoCoordinate coordinate READ coordinate NOTIFY coordinateChanged)
......@@ -637,6 +644,7 @@ public:
Q_PROPERTY(qreal gimbalYaw READ gimbalYaw NOTIFY gimbalYawChanged)
Q_PROPERTY(bool gimbalData READ gimbalData NOTIFY gimbalDataChanged)
Q_PROPERTY(bool isROIEnabled READ isROIEnabled NOTIFY isROIEnabledChanged)
Q_PROPERTY(CheckList checkListState READ checkListState WRITE setCheckListState NOTIFY checkListStateChanged)
// The following properties relate to Orbit status
Q_PROPERTY(bool orbitActive READ orbitActive NOTIFY orbitActiveChanged)
......@@ -706,19 +714,19 @@ public:
Q_INVOKABLE void resetMessages();
Q_INVOKABLE void virtualTabletJoystickValue(double roll, double pitch, double yaw, double thrust);
Q_INVOKABLE void disconnectInactiveVehicle(void);
Q_INVOKABLE void disconnectInactiveVehicle();
/// Command vehicle to return to launch
Q_INVOKABLE void guidedModeRTL(bool smartRTL);
/// Command vehicle to land at current location
Q_INVOKABLE void guidedModeLand(void);
Q_INVOKABLE void guidedModeLand();
/// Command vehicle to takeoff from current location
Q_INVOKABLE void guidedModeTakeoff(double altitudeRelative);
/// @return The minimum takeoff altitude (relative) for guided takeoff.
Q_INVOKABLE double minimumTakeoffAltitude(void);
Q_INVOKABLE double minimumTakeoffAltitude();
/// Command vehicle to move to specified location (altitude is included and relative)
Q_INVOKABLE void guidedModeGotoLocation(const QGeoCoordinate& gotoCoord);
......@@ -740,15 +748,15 @@ public:
/// Command vehicle to pause at current location. If vehicle supports guide mode, vehicle will be left
/// in guided mode after pause.
Q_INVOKABLE void pauseVehicle(void);
Q_INVOKABLE void pauseVehicle();
/// Command vehicle to kill all motors no matter what state
Q_INVOKABLE void emergencyStop(void);
Q_INVOKABLE void emergencyStop();
/// Command vehicle to abort landing
Q_INVOKABLE void abortLanding(double climbOutAltitude);
Q_INVOKABLE void startMission(void);
Q_INVOKABLE void startMission();
/// Alter the current mission item on the vehicle
Q_INVOKABLE void setCurrentMissionSequence(int seq);
......@@ -759,7 +767,7 @@ public:
/// Clear Messages
Q_INVOKABLE void clearMessages();
Q_INVOKABLE void triggerCamera(void);
Q_INVOKABLE void triggerCamera();
Q_INVOKABLE void sendPlan(QString planFile);
/// Used to check if running current version is equal or higher than the one being compared.
......@@ -781,20 +789,20 @@ public:
Q_INVOKABLE void centerGimbal ();
#if !defined(NO_ARDUPILOT_DIALECT)
Q_INVOKABLE void flashBootloader(void);
Q_INVOKABLE void flashBootloader();
#endif
bool guidedModeSupported (void) const;
bool pauseVehicleSupported (void) const;
bool orbitModeSupported (void) const;
bool roiModeSupported (void) const;
bool takeoffVehicleSupported (void) const;
QString gotoFlightMode (void) const;
bool guidedModeSupported () const;
bool pauseVehicleSupported () const;
bool orbitModeSupported () const;
bool roiModeSupported () const;
bool takeoffVehicleSupported () const;
QString gotoFlightMode () const;
// Property accessors
QGeoCoordinate coordinate (void) { return _coordinate; }
QGeoCoordinate armedPosition (void) { return _armedPosition; }
QGeoCoordinate coordinate() { return _coordinate; }
QGeoCoordinate armedPosition () { return _armedPosition; }
typedef enum {
JoystickModeRC, ///< Joystick emulates an RC Transmitter
......@@ -807,28 +815,28 @@ public:
void updateFlightDistance(double distance);
int joystickMode(void);
int joystickMode();
void setJoystickMode(int mode);
/// List of joystick mode names
QStringList joystickModes(void);
QStringList joystickModes();
bool joystickEnabled(void);
bool joystickEnabled();
void setJoystickEnabled(bool enabled);
// Is vehicle active with respect to current active vehicle in QGC
bool active(void);
bool active();
void setActive(bool active);
// Property accesors
int id(void) { return _id; }
MAV_AUTOPILOT firmwareType(void) const { return _firmwareType; }
MAV_TYPE vehicleType(void) const { return _vehicleType; }
Q_INVOKABLE QString vehicleTypeName(void) const;
int id() { return _id; }
MAV_AUTOPILOT firmwareType() const { return _firmwareType; }
MAV_TYPE vehicleType() const { return _vehicleType; }
Q_INVOKABLE QString vehicleTypeName() const;
/// Returns the highest quality link available to the Vehicle. If you need to hold a reference to this link use
/// LinkManager::sharedLinkInterfaceForGet to get QSharedPointer for link.
LinkInterface* priorityLink(void) { return _priorityLink.data(); }
LinkInterface* priorityLink() { return _priorityLink.data(); }
/// Sends a message to the specified link
/// @return true: message sent, false: Link no longer connected
......@@ -839,55 +847,55 @@ public:
void sendMessageMultiple(mavlink_message_t message);
/// Provides access to uas from vehicle. Temporary workaround until UAS is fully phased out.
UAS* uas(void) { return _uas; }
UAS* uas() { return _uas; }
/// Provides access to uas from vehicle. Temporary workaround until AutoPilotPlugin is fully phased out.
AutoPilotPlugin* autopilotPlugin(void) { return _autopilotPlugin; }
AutoPilotPlugin* autopilotPlugin() { return _autopilotPlugin; }
/// Provides access to the Firmware Plugin for this Vehicle
FirmwarePlugin* firmwarePlugin(void) { return _firmwarePlugin; }
FirmwarePlugin* firmwarePlugin() { return _firmwarePlugin; }
MissionManager* missionManager(void) { return _missionManager; }
GeoFenceManager* geoFenceManager(void) { return _geoFenceManager; }
RallyPointManager* rallyPointManager(void) { return _rallyPointManager; }
MissionManager* missionManager() { return _missionManager; }
GeoFenceManager* geoFenceManager() { return _geoFenceManager; }
RallyPointManager* rallyPointManager() { return _rallyPointManager; }
QGeoCoordinate homePosition(void);
QGeoCoordinate homePosition();
bool armed () { return _armed; }
void setArmed (bool armed);
bool flightModeSetAvailable (void);
QStringList flightModes (void);
QStringList extraJoystickFlightModes (void);
QString flightMode (void) const;
bool flightModeSetAvailable ();
QStringList flightModes ();
QStringList extraJoystickFlightModes ();
QString flightMode () const;
void setFlightMode (const QString& flightMode);
QString priorityLinkName(void) const;
QVariantList links(void) const;
QString priorityLinkName() const;
QVariantList links() const;
void setPriorityLinkByName(const QString& priorityLinkName);
bool hilMode(void);
bool hilMode();
void setHilMode(bool hilMode);
bool fixedWing(void) const;
bool multiRotor(void) const;
bool vtol(void) const;
bool rover(void) const;
bool sub(void) const;
bool fixedWing() const;
bool multiRotor() const;
bool vtol() const;
bool rover() const;
bool sub() const;
bool supportsThrottleModeCenterZero (void) const;
bool supportsNegativeThrust (void);
bool supportsRadio (void) const;
bool supportsJSButton (void) const;
bool supportsMotorInterference (void) const;
bool supportsTerrainFrame (void) const;
bool supportsThrottleModeCenterZero () const;
bool supportsNegativeThrust ();
bool supportsRadio () const;
bool supportsJSButton () const;
bool supportsMotorInterference () const;
bool supportsTerrainFrame () const;
void setGuidedMode(bool guidedMode);
QString prearmError(void) const { return _prearmError; }
QString prearmError() const { return _prearmError; }
void setPrearmError(const QString& prearmError);
QmlObjectListModel* cameraTriggerPoints (void) { return &_cameraTriggerPoints; }
QmlObjectListModel* cameraTriggerPoints () { return &_cameraTriggerPoints; }
int flowImageIndex() { return _flowImageIndex; }
......@@ -971,35 +979,35 @@ public:
/// @return the maximum version
unsigned maxProtoVersion () const { return _maxProtoVersion; }
Fact* roll (void) { return &_rollFact; }
Fact* pitch (void) { return &_pitchFact; }
Fact* heading (void) { return &_headingFact; }
Fact* rollRate (void) { return &_rollRateFact; }
Fact* pitchRate (void) { return &_pitchRateFact; }
Fact* yawRate (void) { return &_yawRateFact; }
Fact* airSpeed (void) { return &_airSpeedFact; }
Fact* groundSpeed (void) { return &_groundSpeedFact; }
Fact* climbRate (void) { return &_climbRateFact; }
Fact* altitudeRelative (void) { return &_altitudeRelativeFact; }
Fact* altitudeAMSL (void) { return &_altitudeAMSLFact; }
Fact* flightDistance (void) { return &_flightDistanceFact; }
Fact* distanceToHome (void) { return &_distanceToHomeFact; }
Fact* headingToNextWP (void) { return &_headingToNextWPFact; }
Fact* headingToHome (void) { return &_headingToHomeFact; }
Fact* distanceToGCS (void) { return &_distanceToGCSFact; }
Fact* hobbs (void) { return &_hobbsFact; }
Fact* throttlePct (void) { return &_throttlePctFact; }
FactGroup* gpsFactGroup (void) { return &_gpsFactGroup; }
FactGroup* battery1FactGroup (void) { return &_battery1FactGroup; }
FactGroup* battery2FactGroup (void) { return &_battery2FactGroup; }
FactGroup* windFactGroup (void) { return &_windFactGroup; }
FactGroup* vibrationFactGroup (void) { return &_vibrationFactGroup; }
FactGroup* temperatureFactGroup (void) { return &_temperatureFactGroup; }
FactGroup* clockFactGroup (void) { return &_clockFactGroup; }
FactGroup* setpointFactGroup (void) { return &_setpointFactGroup; }
FactGroup* distanceSensorFactGroup (void) { return &_distanceSensorFactGroup; }
FactGroup* estimatorStatusFactGroup (void) { return &_estimatorStatusFactGroup; }
Fact* roll () { return &_rollFact; }
Fact* pitch () { return &_pitchFact; }
Fact* heading () { return &_headingFact; }
Fact* rollRate () { return &_rollRateFact; }
Fact* pitchRate () { return &_pitchRateFact; }
Fact* yawRate () { return &_yawRateFact; }
Fact* airSpeed () { return &_airSpeedFact; }
Fact* groundSpeed () { return &_groundSpeedFact; }
Fact* climbRate () { return &_climbRateFact; }
Fact* altitudeRelative () { return &_altitudeRelativeFact; }
Fact* altitudeAMSL () { return &_altitudeAMSLFact; }
Fact* flightDistance () { return &_flightDistanceFact; }
Fact* distanceToHome () { return &_distanceToHomeFact; }
Fact* headingToNextWP () { return &_headingToNextWPFact; }
Fact* headingToHome () { return &_headingToHomeFact; }
Fact* distanceToGCS () { return &_distanceToGCSFact; }
Fact* hobbs () { return &_hobbsFact; }
Fact* throttlePct () { return &_throttlePctFact; }
FactGroup* gpsFactGroup () { return &_gpsFactGroup; }
FactGroup* battery1FactGroup () { return &_battery1FactGroup; }
FactGroup* battery2FactGroup () { return &_battery2FactGroup; }
FactGroup* windFactGroup () { return &_windFactGroup; }
FactGroup* vibrationFactGroup () { return &_vibrationFactGroup; }
FactGroup* temperatureFactGroup () { return &_temperatureFactGroup; }
FactGroup* clockFactGroup () { return &_clockFactGroup; }
FactGroup* setpointFactGroup () { return &_setpointFactGroup; }
FactGroup* distanceSensorFactGroup () { return &_distanceSensorFactGroup; }
FactGroup* estimatorStatusFactGroup () { return &_estimatorStatusFactGroup; }
void setConnectionLostEnabled(bool connectionLostEnabled);
......@@ -1035,41 +1043,41 @@ public:
static_cast<float>(param7));
}
int firmwareMajorVersion(void) const { return _firmwareMajorVersion; }
int firmwareMinorVersion(void) const { return _firmwareMinorVersion; }
int firmwarePatchVersion(void) const { return _firmwarePatchVersion; }
int firmwareVersionType(void) const { return _firmwareVersionType; }
int firmwareCustomMajorVersion(void) const { return _firmwareCustomMajorVersion; }
int firmwareCustomMinorVersion(void) const { return _firmwareCustomMinorVersion; }
int firmwareCustomPatchVersion(void) const { return _firmwareCustomPatchVersion; }
QString firmwareVersionTypeString(void) const;
int firmwareMajorVersion() const { return _firmwareMajorVersion; }
int firmwareMinorVersion() const { return _firmwareMinorVersion; }
int firmwarePatchVersion() const { return _firmwarePatchVersion; }
int firmwareVersionType() const { return _firmwareVersionType; }
int firmwareCustomMajorVersion() const { return _firmwareCustomMajorVersion; }
int firmwareCustomMinorVersion() const { return _firmwareCustomMinorVersion; }
int firmwareCustomPatchVersion() const { return _firmwareCustomPatchVersion; }
QString firmwareVersionTypeString() const;
void setFirmwareVersion(int majorVersion, int minorVersion, int patchVersion, FIRMWARE_VERSION_TYPE versionType = FIRMWARE_VERSION_TYPE_OFFICIAL);
void setFirmwareCustomVersion(int majorVersion, int minorVersion, int patchVersion);
static const int versionNotSetValue = -1;
QString gitHash(void) const { return _gitHash; }
quint64 vehicleUID(void) const { return _uid; }
QString gitHash() const { return _gitHash; }
quint64 vehicleUID() const { return _uid; }
QString vehicleUIDStr();
bool soloFirmware(void) const { return _soloFirmware; }
bool soloFirmware() const { return _soloFirmware; }
void setSoloFirmware(bool soloFirmware);
int defaultComponentId(void) { return _defaultComponentId; }
int defaultComponentId() { return _defaultComponentId; }
/// Sets the default component id for an offline editing vehicle
void setOfflineEditingDefaultComponentId(int defaultComponentId);
/// @return -1 = Unknown, Number of motors on vehicle
int motorCount(void);
int motorCount();
/// @return true: Motors are coaxial like an X8 config, false: Quadcopter for example
bool coaxialMotors(void);
bool coaxialMotors();
/// @return true: X confiuration, false: Plus configuration
bool xConfigMotors(void);
bool xConfigMotors();
/// @return Firmware plugin instance data associated with this Vehicle
QObject* firmwarePluginInstanceData(void) { return _firmwarePluginInstanceData; }
QObject* firmwarePluginInstanceData() { return _firmwarePluginInstanceData; }
/// Sets the firmware plugin instance data associated with this Vehicle. This object will be parented to the Vehicle
/// and destroyed when the vehicle goes away.
......@@ -1080,22 +1088,22 @@ public:
QString vehicleImageCompass () const;
const QVariantList& toolBarIndicators ();
const QVariantList& staticCameraList (void) const;
const QVariantList& staticCameraList () const;
bool capabilitiesKnown (void) const { return _vehicleCapabilitiesKnown; }
uint64_t capabilityBits (void) const { return _capabilityBits; } // Change signalled by capabilityBitsChanged
bool capabilitiesKnown () const { return _vehicleCapabilitiesKnown; }
uint64_t capabilityBits () const { return _capabilityBits; } // Change signalled by capabilityBitsChanged
QGCCameraManager* dynamicCameras () { return _cameras; }
QString hobbsMeter ();
/// @true: When flying a mission the vehicle is always facing towards the next waypoint
bool vehicleYawsToNextWaypointInMission(void) const;
bool vehicleYawsToNextWaypointInMission() const;
/// The vehicle is responsible for making the initial request for the Plan.
/// @return: true: initial request is complete, false: initial request is still in progress;
bool initialPlanRequestComplete(void) const { return _initialPlanRequestComplete; }
bool initialPlanRequestComplete() const { return _initialPlanRequestComplete; }
void forceInitialPlanRequestComplete(void);
void forceInitialPlanRequestComplete();
void _setFlying(bool flying);
void _setLanding(bool landing);
......@@ -1116,101 +1124,105 @@ public:
bool gimbalData () { return _haveGimbalData; }
bool isROIEnabled () { return _isROIEnabled; }
CheckList checkListState () { return _checkListState; }
void setCheckListState (CheckList cl) { _checkListState = cl; emit checkListStateChanged(); }
public slots:
void setVtolInFwdFlight (bool vtolInFwdFlight);
signals:
void allLinksInactive(Vehicle* vehicle);
void coordinateChanged(QGeoCoordinate coordinate);
void joystickModeChanged(int mode);
void joystickEnabledChanged(bool enabled);
void activeChanged(bool active);
void mavlinkMessageReceived(const mavlink_message_t& message);
void homePositionChanged(const QGeoCoordinate& homePosition);
void allLinksInactive (Vehicle* vehicle);
void coordinateChanged (QGeoCoordinate coordinate);
void joystickModeChanged (int mode);
void joystickEnabledChanged (bool enabled);
void activeChanged (bool active);
void mavlinkMessageReceived (const mavlink_message_t& message);
void homePositionChanged (const QGeoCoordinate& homePosition);
void armedPositionChanged();
void armedChanged(bool armed);
void flightModeChanged(const QString& flightMode);
void hilModeChanged(bool hilMode);
void armedChanged (bool armed);
void flightModeChanged (const QString& flightMode);
void hilModeChanged (bool hilMode);
/** @brief HIL actuator controls (replaces HIL controls) */
void hilActuatorControlsChanged(quint64 time, quint64 flags, float ctl_0, float ctl_1, float ctl_2, float ctl_3, float ctl_4, float ctl_5, float ctl_6, float ctl_7, float ctl_8, float ctl_9, float ctl_10, float ctl_11, float ctl_12, float ctl_13, float ctl_14, float ctl_15, quint8 mode);
void connectionLostChanged(bool connectionLost);
void connectionLostEnabledChanged(bool connectionLostEnabled);
void autoDisconnectChanged(bool autoDisconnectChanged);
void flyingChanged(bool flying);
void landingChanged(bool landing);
void guidedModeChanged(bool guidedMode);
void vtolInFwdFlightChanged(bool vtolInFwdFlight);
void prearmErrorChanged(const QString& prearmError);
void soloFirmwareChanged(bool soloFirmware);
void unhealthySensorsChanged(void);
void defaultCruiseSpeedChanged(double cruiseSpeed);
void defaultHoverSpeedChanged(double hoverSpeed);
void firmwareTypeChanged(void);
void vehicleTypeChanged(void);
void dynamicCamerasChanged();
void hobbsMeterChanged();
void capabilitiesKnownChanged(bool capabilitiesKnown);
void hilActuatorControlsChanged (quint64 time, quint64 flags, float ctl_0, float ctl_1, float ctl_2, float ctl_3, float ctl_4, float ctl_5, float ctl_6, float ctl_7, float ctl_8, float ctl_9, float ctl_10, float ctl_11, float ctl_12, float ctl_13, float ctl_14, float ctl_15, quint8 mode);
void connectionLostChanged (bool connectionLost);
void connectionLostEnabledChanged (bool connectionLostEnabled);
void autoDisconnectChanged (bool autoDisconnectChanged);
void flyingChanged (bool flying);
void landingChanged (bool landing);
void guidedModeChanged (bool guidedMode);
void vtolInFwdFlightChanged (bool vtolInFwdFlight);
void prearmErrorChanged (const QString& prearmError);
void soloFirmwareChanged (bool soloFirmware);
void unhealthySensorsChanged ();
void defaultCruiseSpeedChanged (double cruiseSpeed);
void defaultHoverSpeedChanged (double hoverSpeed);
void firmwareTypeChanged ();
void vehicleTypeChanged ();
void dynamicCamerasChanged ();
void hobbsMeterChanged ();
void capabilitiesKnownChanged (bool capabilitiesKnown);
void initialPlanRequestCompleteChanged(bool initialPlanRequestComplete);
void capabilityBitsChanged(uint64_t capabilityBits);
void toolBarIndicatorsChanged(void);
void highLatencyLinkChanged(bool highLatencyLink);
void priorityLinkNameChanged(const QString& priorityLinkName);
void linksChanged(void);
void linksPropertiesChanged(void);
void textMessageReceived(int uasid, int componentid, int severity, QString text);
void messagesReceivedChanged ();
void messagesSentChanged ();
void messagesLostChanged ();
void capabilityBitsChanged (uint64_t capabilityBits);
void toolBarIndicatorsChanged ();
void highLatencyLinkChanged (bool highLatencyLink);
void priorityLinkNameChanged (const QString& priorityLinkName);
void linksChanged ();
void linksPropertiesChanged ();
void textMessageReceived (int uasid, int componentid, int severity, QString text);
void checkListStateChanged ();
void messagesReceivedChanged ();
void messagesSentChanged ();
void messagesLostChanged ();
/// Used internally to move sendMessage call to main thread
void _sendMessageOnLinkOnThread(LinkInterface* link, mavlink_message_t message);
void messageTypeChanged ();
void newMessageCountChanged ();
void messageCountChanged ();
void formatedMessagesChanged ();
void formatedMessageChanged ();
void latestErrorChanged ();
void longitudeChanged ();
void currentConfigChanged ();
void flowImageIndexChanged ();
void rcRSSIChanged (int rcRSSI);
void telemetryRRSSIChanged (int value);
void telemetryLRSSIChanged (int value);
void telemetryRXErrorsChanged (unsigned int value);
void telemetryFixedChanged (unsigned int value);
void telemetryTXBufferChanged (unsigned int value);
void telemetryLNoiseChanged (int value);
void telemetryRNoiseChanged (int value);
void autoDisarmChanged (void);
void flightModesChanged (void);
void sensorsPresentBitsChanged (int sensorsPresentBits);
void sensorsEnabledBitsChanged (int sensorsEnabledBits);
void sensorsHealthBitsChanged (int sensorsHealthBits);
void sensorsUnhealthyBitsChanged(int sensorsUnhealthyBits);
void orbitActiveChanged (bool orbitActive);
void firmwareVersionChanged(void);
void firmwareCustomVersionChanged(void);
void gitHashChanged(QString hash);
void vehicleUIDChanged();
void messageTypeChanged ();
void newMessageCountChanged ();
void messageCountChanged ();
void formatedMessagesChanged ();
void formatedMessageChanged ();
void latestErrorChanged ();
void longitudeChanged ();
void currentConfigChanged ();
void flowImageIndexChanged ();
void rcRSSIChanged (int rcRSSI);
void telemetryRRSSIChanged (int value);
void telemetryLRSSIChanged (int value);
void telemetryRXErrorsChanged (unsigned int value);
void telemetryFixedChanged (unsigned int value);
void telemetryTXBufferChanged (unsigned int value);
void telemetryLNoiseChanged (int value);
void telemetryRNoiseChanged (int value);
void autoDisarmChanged ();
void flightModesChanged ();
void sensorsPresentBitsChanged (int sensorsPresentBits);
void sensorsEnabledBitsChanged (int sensorsEnabledBits);
void sensorsHealthBitsChanged (int sensorsHealthBits);
void sensorsUnhealthyBitsChanged (int sensorsUnhealthyBits);
void orbitActiveChanged (bool orbitActive);
void firmwareVersionChanged ();
void firmwareCustomVersionChanged ();
void gitHashChanged (QString hash);
void vehicleUIDChanged ();
/// New RC channel values
/// @param channelCount Number of available channels, cMaxRcChannels max
/// @param pwmValues -1 signals channel not available
void rcChannelsChanged(int channelCount, int pwmValues[cMaxRcChannels]);
void rcChannelsChanged (int channelCount, int pwmValues[cMaxRcChannels]);
/// Remote control RSSI changed (0% - 100%)
void remoteControlRSSIChanged(uint8_t rssi);
void remoteControlRSSIChanged (uint8_t rssi);
void mavlinkRawImu(mavlink_message_t message);
void mavlinkScaledImu1(mavlink_message_t message);
void mavlinkScaledImu2(mavlink_message_t message);
void mavlinkScaledImu3(mavlink_message_t message);
void mavlinkRawImu (mavlink_message_t message);
void mavlinkScaledImu1 (mavlink_message_t message);
void mavlinkScaledImu2 (mavlink_message_t message);
void mavlinkScaledImu3 (mavlink_message_t message);
// Mavlink Log Download
void mavlinkLogData (Vehicle* vehicle, uint8_t target_system, uint8_t target_component, uint16_t sequence, uint8_t first_message, QByteArray data, bool acked);
void mavlinkLogData (Vehicle* vehicle, uint8_t target_system, uint8_t target_component, uint16_t sequence, uint8_t first_message, QByteArray data, bool acked);
/// Signalled in response to usage of sendMavCommand
/// @param vehicleId Vehicle which command was sent to
......@@ -1218,132 +1230,132 @@ signals:
/// @param command MAV_CMD Command which was sent
/// @param result MAV_RESULT returned in ack
/// @param noResponseFromVehicle true: vehicle did not respond to command, false: vehicle responsed, MAV_RESULT in result
void mavCommandResult(int vehicleId, int component, int command, int result, bool noReponseFromVehicle);
void mavCommandResult (int vehicleId, int component, int command, int result, bool noReponseFromVehicle);
// MAVlink Serial Data
void mavlinkSerialControl(uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, QByteArray data);
void mavlinkSerialControl (uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, QByteArray data);
// MAVLink protocol version
void requestProtocolVersion (unsigned version);
void mavlinkStatusChanged ();
void requestProtocolVersion (unsigned version);
void mavlinkStatusChanged ();
void gimbalRollChanged ();
void gimbalPitchChanged ();
void gimbalYawChanged ();
void gimbalDataChanged ();
void isROIEnabledChanged ();
void gimbalRollChanged ();
void gimbalPitchChanged ();
void gimbalYawChanged ();
void gimbalDataChanged ();
void isROIEnabledChanged ();
private slots:
void _mavlinkMessageReceived(LinkInterface* link, mavlink_message_t message);
void _linkInactiveOrDeleted(LinkInterface* link);
void _sendMessageOnLink(LinkInterface* link, mavlink_message_t message);
void _sendMessageMultipleNext(void);
void _parametersReady(bool parametersReady);
void _remoteControlRSSIChanged(uint8_t rssi);
void _handleFlightModeChanged(const QString& flightMode);
void _announceArmedChanged(bool armed);
void _mavlinkMessageReceived (LinkInterface* link, mavlink_message_t message);
void _linkInactiveOrDeleted (LinkInterface* link);
void _sendMessageOnLink (LinkInterface* link, mavlink_message_t message);
void _sendMessageMultipleNext ();
void _parametersReady (bool parametersReady);
void _remoteControlRSSIChanged (uint8_t rssi);
void _handleFlightModeChanged (const QString& flightMode);
void _announceArmedChanged (bool armed);
void _offlineFirmwareTypeSettingChanged(QVariant value);
void _offlineVehicleTypeSettingChanged(QVariant value);
void _offlineCruiseSpeedSettingChanged(QVariant value);
void _offlineHoverSpeedSettingChanged(QVariant value);
void _updateHighLatencyLink(bool sendCommand = true);
void _updateHighLatencyLink (bool sendCommand = true);
void _handleTextMessage (int newCount);
void _handletextMessageReceived (UASMessage* message);
void _handleTextMessage (int newCount);
void _handletextMessageReceived (UASMessage* message);
/** @brief A new camera image has arrived */
void _imageReady (UASInterface* uas);
void _prearmErrorTimeout(void);
void _missionLoadComplete(void);
void _geoFenceLoadComplete(void);
void _rallyPointLoadComplete(void);
void _sendMavCommandAgain(void);
void _clearCameraTriggerPoints(void);
void _updateDistanceHeadingToHome(void);
void _updateHeadingToNextWP(void);
void _updateDistanceToGCS(void);
void _updateHobbsMeter(void);
void _vehicleParamLoaded(bool ready);
void _sendQGCTimeToVehicle(void);
void _mavlinkMessageStatus(int uasId, uint64_t totalSent, uint64_t totalReceived, uint64_t totalLoss, float lossPercent);
void _trafficUpdate (bool alert, QString traffic_id, QString vehicle_id, QGeoCoordinate location, float heading);
void _orbitTelemetryTimeout (void);
void _protocolVersionTimeOut(void);
void _updateFlightTime (void);
void _imageReady (UASInterface* uas);
void _prearmErrorTimeout ();
void _missionLoadComplete ();
void _geoFenceLoadComplete ();
void _rallyPointLoadComplete ();
void _sendMavCommandAgain ();
void _clearCameraTriggerPoints ();
void _updateDistanceHeadingToHome ();
void _updateHeadingToNextWP ();
void _updateDistanceToGCS ();
void _updateHobbsMeter ();
void _vehicleParamLoaded (bool ready);
void _sendQGCTimeToVehicle ();
void _mavlinkMessageStatus (int uasId, uint64_t totalSent, uint64_t totalReceived, uint64_t totalLoss, float lossPercent);
void _trafficUpdate (bool alert, QString traffic_id, QString vehicle_id, QGeoCoordinate location, float heading);
void _orbitTelemetryTimeout ();
void _protocolVersionTimeOut ();
void _updateFlightTime ();
private:
bool _containsLink (LinkInterface* link);
void _addLink (LinkInterface* link);
void _joystickChanged (Joystick* joystick);
void _loadSettings(void);
void _saveSettings(void);
void _startJoystick(bool start);
void _handlePing(LinkInterface* link, mavlink_message_t& message);
void _handleHomePosition(mavlink_message_t& message);
void _handleHeartbeat(mavlink_message_t& message);
void _handleRadioStatus(mavlink_message_t& message);
void _handleRCChannels(mavlink_message_t& message);
void _handleRCChannelsRaw(mavlink_message_t& message);
void _handleBatteryStatus(mavlink_message_t& message);
void _handleSysStatus(mavlink_message_t& message);
void _handleWindCov(mavlink_message_t& message);
void _handleVibration(mavlink_message_t& message);
void _handleExtendedSysState(mavlink_message_t& message);
void _handleCommandAck(mavlink_message_t& message);
void _handleCommandLong(mavlink_message_t& message);
void _handleAutopilotVersion(LinkInterface* link, mavlink_message_t& message);
void _handleProtocolVersion(LinkInterface* link, mavlink_message_t& message);
void _handleHilActuatorControls(mavlink_message_t& message);
void _handleGpsRawInt(mavlink_message_t& message);
void _handleGlobalPositionInt(mavlink_message_t& message);
void _handleAltitude(mavlink_message_t& message);
void _handleVfrHud(mavlink_message_t& message);
void _handleScaledPressure(mavlink_message_t& message);
void _handleScaledPressure2(mavlink_message_t& message);
void _handleScaledPressure3(mavlink_message_t& message);
void _handleHighLatency2(mavlink_message_t& message);
void _handleAttitudeWorker(double rollRadians, double pitchRadians, double yawRadians);
void _handleAttitude(mavlink_message_t& message);
void _handleAttitudeQuaternion(mavlink_message_t& message);
void _handleAttitudeTarget(mavlink_message_t& message);
void _handleDistanceSensor(mavlink_message_t& message);
void _handleEstimatorStatus(mavlink_message_t& message);
void _handleStatusText(mavlink_message_t& message, bool longVersion);
void _handleOrbitExecutionStatus(const mavlink_message_t& message);
void _handleMessageInterval(const mavlink_message_t& message);
void _handleGimbalOrientation(const mavlink_message_t& message);
void _handleObstacleDistance(const mavlink_message_t& message);
bool _containsLink (LinkInterface* link);
void _addLink (LinkInterface* link);
void _joystickChanged (Joystick* joystick);
void _loadSettings ();
void _saveSettings ();
void _startJoystick (bool start);
void _handlePing (LinkInterface* link, mavlink_message_t& message);
void _handleHomePosition (mavlink_message_t& message);
void _handleHeartbeat (mavlink_message_t& message);
void _handleRadioStatus (mavlink_message_t& message);
void _handleRCChannels (mavlink_message_t& message);
void _handleRCChannelsRaw (mavlink_message_t& message);
void _handleBatteryStatus (mavlink_message_t& message);
void _handleSysStatus (mavlink_message_t& message);
void _handleWindCov (mavlink_message_t& message);
void _handleVibration (mavlink_message_t& message);
void _handleExtendedSysState (mavlink_message_t& message);
void _handleCommandAck (mavlink_message_t& message);
void _handleCommandLong (mavlink_message_t& message);
void _handleAutopilotVersion (LinkInterface* link, mavlink_message_t& message);
void _handleProtocolVersion (LinkInterface* link, mavlink_message_t& message);
void _handleHilActuatorControls (mavlink_message_t& message);
void _handleGpsRawInt (mavlink_message_t& message);
void _handleGlobalPositionInt (mavlink_message_t& message);
void _handleAltitude (mavlink_message_t& message);
void _handleVfrHud (mavlink_message_t& message);
void _handleScaledPressure (mavlink_message_t& message);
void _handleScaledPressure2 (mavlink_message_t& message);
void _handleScaledPressure3 (mavlink_message_t& message);
void _handleHighLatency2 (mavlink_message_t& message);
void _handleAttitudeWorker (double rollRadians, double pitchRadians, double yawRadians);
void _handleAttitude (mavlink_message_t& message);
void _handleAttitudeQuaternion (mavlink_message_t& message);
void _handleAttitudeTarget (mavlink_message_t& message);
void _handleDistanceSensor (mavlink_message_t& message);
void _handleEstimatorStatus (mavlink_message_t& message);
void _handleStatusText (mavlink_message_t& message, bool longVersion);
void _handleOrbitExecutionStatus (const mavlink_message_t& message);
void _handleMessageInterval (const mavlink_message_t& message);
void _handleGimbalOrientation (const mavlink_message_t& message);
void _handleObstacleDistance (const mavlink_message_t& message);
// ArduPilot dialect messages
#if !defined(NO_ARDUPILOT_DIALECT)
void _handleCameraFeedback(const mavlink_message_t& message);
void _handleWind(mavlink_message_t& message);
void _handleCameraFeedback (const mavlink_message_t& message);
void _handleWind (mavlink_message_t& message);
#endif
void _handleCameraImageCaptured(const mavlink_message_t& message);
void _handleADSBVehicle(const mavlink_message_t& message);
void _missionManagerError(int errorCode, const QString& errorMsg);
void _geoFenceManagerError(int errorCode, const QString& errorMsg);
void _rallyPointManagerError(int errorCode, const QString& errorMsg);
void _linkActiveChanged(LinkInterface* link, bool active, int vehicleID);
void _say(const QString& text);
QString _vehicleIdSpeech(void);
void _handleMavlinkLoggingData(mavlink_message_t& message);
void _handleMavlinkLoggingDataAcked(mavlink_message_t& message);
void _ackMavlinkLogData(uint16_t sequence);
void _sendNextQueuedMavCommand(void);
void _updatePriorityLink(bool updateActive, bool sendCommand);
void _commonInit(void);
void _startPlanRequest(void);
void _setupAutoDisarmSignalling(void);
void _setCapabilities(uint64_t capabilityBits);
void _updateArmed(bool armed);
bool _apmArmingNotRequired(void);
void _pidTuningAdjustRates(bool setRatesForTuning);
void _handleUnsupportedRequestAutopilotCapabilities(void);
void _handleUnsupportedRequestProtocolVersion(void);
void _initializeCsv();
void _writeCsvLine();
void _flightTimerStart(void);
void _flightTimerStop(void);
void _handleCameraImageCaptured (const mavlink_message_t& message);
void _handleADSBVehicle (const mavlink_message_t& message);
void _missionManagerError (int errorCode, const QString& errorMsg);
void _geoFenceManagerError (int errorCode, const QString& errorMsg);
void _rallyPointManagerError (int errorCode, const QString& errorMsg);
void _linkActiveChanged (LinkInterface* link, bool active, int vehicleID);
void _say (const QString& text);
QString _vehicleIdSpeech ();
void _handleMavlinkLoggingData (mavlink_message_t& message);
void _handleMavlinkLoggingDataAcked (mavlink_message_t& message);
void _ackMavlinkLogData (uint16_t sequence);
void _sendNextQueuedMavCommand ();
void _updatePriorityLink (bool updateActive, bool sendCommand);
void _commonInit ();
void _startPlanRequest ();
void _setupAutoDisarmSignalling ();
void _setCapabilities (uint64_t capabilityBits);
void _updateArmed (bool armed);
bool _apmArmingNotRequired ();
void _pidTuningAdjustRates (bool setRatesForTuning);
void _handleUnsupportedRequestAutopilotCapabilities();
void _handleUnsupportedRequestProtocolVersion();
void _initializeCsv ();
void _writeCsvLine ();
void _flightTimerStart ();
void _flightTimerStop ();
int _id; ///< Mavlink system id
int _defaultComponentId;
......@@ -1360,8 +1372,8 @@ private:
QGCToolbox* _toolbox;
SettingsManager* _settingsManager;
QTimer _csvLogTimer;
QFile _csvLogFile;
QTimer _csvLogTimer;
QFile _csvLogFile;
QList<LinkInterface*> _links;
......@@ -1411,6 +1423,7 @@ private:
uint64_t _capabilityBits;
bool _highLatencyLink;
bool _receivingAttitudeQuaternion;
CheckList _checkListState = CheckListNotSetup;
QGCCameraManager* _cameras;
......
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