86#include <QtCore/QDateTime>
90#define UPDATE_TIMER 50
91#define DEFAULT_LAT 38.965767f
92#define DEFAULT_LON -120.083923f
96#define REQUEST_OPERATOR_CONTROL_ALLOW_TAKEOVER_TIMEOUT_MSECS 10000
103 int defaultComponentId,
104 MAV_AUTOPILOT firmwareType,
105 MAV_TYPE vehicleType,
108 , _systemID (vehicleId)
109 , _defaultComponentId (defaultComponentId)
110 , _firmwareType (firmwareType)
111 , _vehicleType (vehicleType)
112 , _defaultCruiseSpeed (
SettingsManager::instance()->appSettings()->offlineEditingCruiseSpeed()->rawValue().toDouble())
113 , _defaultHoverSpeed (
SettingsManager::instance()->appSettings()->offlineEditingHoverSpeed()->rawValue().toDouble())
117 , _orbitMapCircle (std::make_unique<
QGCMapCircle>(this))
118 , _mavlinkStreamConfig (std::make_unique<
MAVLinkStreamConfig>(std::bind(&
Vehicle::_setMessageInterval, this, std::placeholders::_1, std::placeholders::_2)))
119 , _vehicleFactGroup (this)
146 _autopilotPlugin->setParent(
this);
149 connect(&_prearmErrorTimer, &QTimer::timeout,
this, &Vehicle::_prearmErrorTimeout);
150 _prearmErrorTimer.setInterval(_prearmErrorTimeoutMSecs);
151 _prearmErrorTimer.setSingleShot(
true);
166 _sendMultipleTimer.start(_sendMessageMultipleIntraMessageDelay);
167 connect(&_sendMultipleTimer, &QTimer::timeout,
this, &Vehicle::_sendMessageMultipleNext);
169 connect(&_orbitTelemetryTimer, &QTimer::timeout,
this, &Vehicle::_orbitTelemetryTimeout);
172 connect(&_csvLogTimer, &QTimer::timeout,
this, &Vehicle::_writeCsvLine);
173 _csvLogTimer.start(1000);
179 MAV_TYPE vehicleType,
183 , _defaultComponentId (MAV_COMP_ID_ALL)
184 , _offlineEditingVehicle (true)
185 , _firmwareType (firmwareType)
186 , _vehicleType (vehicleType)
187 , _defaultCruiseSpeed (
SettingsManager::instance()->appSettings()->offlineEditingCruiseSpeed()->rawValue().toDouble())
188 , _defaultHoverSpeed (
SettingsManager::instance()->appSettings()->offlineEditingHoverSpeed()->rawValue().toDouble())
189 , _capabilityBitsKnown (true)
190 , _capabilityBits (MAV_PROTOCOL_CAPABILITY_MISSION_FENCE | MAV_PROTOCOL_CAPABILITY_MISSION_RALLY)
194 , _orbitMapCircle (std::make_unique<
QGCMapCircle>(this))
195 , _mavlinkStreamConfig (std::make_unique<
MAVLinkStreamConfig>(std::bind(&
Vehicle::_setMessageInterval, this, std::placeholders::_1, std::placeholders::_2)))
196 , _vehicleFactGroup (this)
203 _commonInit(
nullptr );
289 this, &Vehicle::_gotProgressUpdate);
332 if (!_offlineEditingVehicle) {
338 _createImageProtocolManager();
339 _createStatusTextHandler();
340 _createMAVLinkLogManager();
341 _createSigningController();
342 _createMAVLinkEventManager();
365 QMap<QString, FactGroup*>* fwFactGroups = _firmwarePlugin->
factGroups();
367 for (
auto it = fwFactGroups->keyValueBegin(); it != fwFactGroups->keyValueEnd(); ++it) {
372 _flightTimeUpdater.setInterval(1000);
373 _flightTimeUpdater.setSingleShot(
false);
374 connect(&_flightTimeUpdater, &QTimer::timeout,
this, &Vehicle::_updateFlightTime);
385 _createCameraManager();
390 qCDebug(VehicleLog) <<
"~Vehicle" <<
this;
397 _mavCmdQueue->
stop();
399 _sendMultipleTimer.stop();
400 _sendMultipleTimer.disconnect();
401 _prearmErrorTimer.stop();
402 _prearmErrorTimer.disconnect();
407 delete _autopilotPlugin;
408 _autopilotPlugin =
nullptr;
437void Vehicle::_deleteCameraManager()
441 _cameraManager->disconnect();
442 delete _cameraManager;
443 _cameraManager =
nullptr;
447void Vehicle::_deleteGimbalController()
449 if (_gimbalController) {
451 _gimbalController->disconnect();
452 delete _gimbalController;
453 _gimbalController =
nullptr;
457void Vehicle::_stopCommandProcessing()
459 qCDebug(VehicleLog) <<
"_stopCommandProcessing - stopping timers and clearing pending commands";
465 _mavCmdQueue->
stop();
468 _reqMsgCoord->
stop();
470 _sendMultipleTimer.stop();
471 _sendMultipleTimer.disconnect();
476 _firmwareType =
static_cast<MAV_AUTOPILOT
>(varFirmwareType.toInt());
478 if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
479 _capabilityBits |= MAV_PROTOCOL_CAPABILITY_TERRAIN;
481 _capabilityBits &= ~MAV_PROTOCOL_CAPABILITY_TERRAIN;
489 _vehicleType =
static_cast<MAV_TYPE
>(varVehicleType.toInt());
493void Vehicle::_offlineCruiseSpeedSettingChanged(QVariant value)
495 _defaultCruiseSpeed = value.toDouble();
499void Vehicle::_offlineHoverSpeedSettingChanged(QVariant value)
501 _defaultHoverSpeed = value.toDouble();
512 _messagesReceived = 0;
521 if (message.sysid != _systemID && message.sysid != 0) {
535 if(message.msgid == MAVLINK_MSG_ID_HEARTBEAT) {
537 _compID = message.compid;
538 _messageSeq = message.seq + 1;
541 if(_compID == message.compid) {
542 uint16_t seq_received =
static_cast<uint16_t
>(message.seq);
543 uint16_t packet_lost_count = 0;
545 if(seq_received < _messageSeq) {
546 packet_lost_count = (seq_received + 255) - _messageSeq;
548 packet_lost_count = seq_received - _messageSeq;
550 _messageSeq = message.seq + 1;
551 _messagesLost += packet_lost_count;
552 if(packet_lost_count)
571 _parameterManager->mavlinkMessageReceived(message);
572 (void) QMetaObject::invokeMethod(_imageProtocolManager,
"mavlinkMessageReceived", Qt::AutoConnection, message);
583 factGroup->handleMessage(
this, message);
588 switch (message.msgid) {
589 case MAVLINK_MSG_ID_HOME_POSITION:
590 _handleHomePosition(message);
592 case MAVLINK_MSG_ID_HEARTBEAT:
593 _handleHeartbeat(message);
595 case MAVLINK_MSG_ID_RC_CHANNELS:
596 _handleRCChannels(message);
598 case MAVLINK_MSG_ID_SERVO_OUTPUT_RAW:
600 mavlink_servo_output_raw_t servoOutputRaw;
601 mavlink_msg_servo_output_raw_decode(&message, &servoOutputRaw);
604 const uint16_t rawValues[16] = {
605 servoOutputRaw.servo1_raw,
606 servoOutputRaw.servo2_raw,
607 servoOutputRaw.servo3_raw,
608 servoOutputRaw.servo4_raw,
609 servoOutputRaw.servo5_raw,
610 servoOutputRaw.servo6_raw,
611 servoOutputRaw.servo7_raw,
612 servoOutputRaw.servo8_raw,
613 servoOutputRaw.servo9_raw,
614 servoOutputRaw.servo10_raw,
615 servoOutputRaw.servo11_raw,
616 servoOutputRaw.servo12_raw,
617 servoOutputRaw.servo13_raw,
618 servoOutputRaw.servo14_raw,
619 servoOutputRaw.servo15_raw,
620 servoOutputRaw.servo16_raw
623 for (
int servoIndex = 0; servoIndex <
_servoOutputRawValues.size() && servoIndex < 16; servoIndex++) {
624 _servoOutputRawValues[servoIndex] = (rawValues[servoIndex] == UINT16_MAX) ? -1 : static_cast<int>(rawValues[servoIndex]);
630 case MAVLINK_MSG_ID_BATTERY_STATUS:
631 _handleBatteryStatus(message);
633 case MAVLINK_MSG_ID_SYS_STATUS:
634 _handleSysStatus(message);
636 case MAVLINK_MSG_ID_EXTENDED_SYS_STATE:
637 _handleExtendedSysState(message);
639 case MAVLINK_MSG_ID_COMMAND_ACK:
640 _handleCommandAck(message);
642 case MAVLINK_MSG_ID_LOGGING_DATA:
643 _handleMavlinkLoggingData(message);
645 case MAVLINK_MSG_ID_LOGGING_DATA_ACKED:
646 _handleMavlinkLoggingDataAcked(message);
648 case MAVLINK_MSG_ID_GPS_RAW_INT:
649 _handleGpsRawInt(message);
651 case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
652 _handleGlobalPositionInt(message);
654 case MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED:
655 _handleCameraImageCaptured(message);
657 case MAVLINK_MSG_ID_ADSB_VEHICLE:
660 case MAVLINK_MSG_ID_HIGH_LATENCY:
661 _handleHighLatency(message);
663 case MAVLINK_MSG_ID_HIGH_LATENCY2:
664 _handleHighLatency2(message);
666 case MAVLINK_MSG_ID_STATUSTEXT:
669 case MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS:
670 _handleOrbitExecutionStatus(message);
672 case MAVLINK_MSG_ID_PING:
673 _handlePing(link, message);
675 case MAVLINK_MSG_ID_OBSTACLE_DISTANCE:
676 _handleObstacleDistance(message);
678 case MAVLINK_MSG_ID_FENCE_STATUS:
679 _handleFenceStatus(message);
682 case MAVLINK_MSG_ID_EVENT:
683 case MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE:
684 case MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR:
685 _handleEventMessage(message);
688 case MAVLINK_MSG_ID_SERIAL_CONTROL:
690 mavlink_serial_control_t ser;
691 mavlink_msg_serial_control_decode(&message, &ser);
692 if (
static_cast<size_t>(ser.count) >
sizeof(ser.data)) {
693 qCWarning(VehicleLog) <<
"Invalid count for SERIAL_CONTROL, discarding." << ser.count;
696 QByteArray(
reinterpret_cast<const char*
>(ser.data), ser.count));
700 case MAVLINK_MSG_ID_AVAILABLE_MODES_MONITOR:
704 mavlink_available_modes_monitor_t availableModesMonitor;
705 mavlink_msg_available_modes_monitor_decode(&message, &availableModesMonitor);
710 case MAVLINK_MSG_ID_CURRENT_MODE:
711 _handleCurrentMode(message);
715#if !defined(QGC_NO_ARDUPILOT_DIALECT)
716 case MAVLINK_MSG_ID_CAMERA_FEEDBACK:
717 _handleCameraFeedback(message);
720 case MAVLINK_MSG_ID_LOG_ENTRY:
722 mavlink_log_entry_t log{};
723 mavlink_msg_log_entry_decode(&message, &log);
724 emit
logEntry(log.time_utc, log.size, log.id, log.num_logs, log.last_log_num);
727 case MAVLINK_MSG_ID_LOG_DATA:
729 mavlink_log_data_t log{};
730 mavlink_msg_log_data_decode(&message, &log);
731 if (
static_cast<size_t>(log.count) >
sizeof(log.data)) {
732 qCWarning(VehicleLog) <<
"Invalid count for LOG_DATA, discarding." << log.count;
734 emit
logData(log.ofs, log.id, log.count, log.data);
738 case MAVLINK_MSG_ID_MESSAGE_INTERVAL:
743 case MAVLINK_MSG_ID_CONTROL_STATUS:
744 _handleControlStatus(message);
746 case MAVLINK_MSG_ID_COMMAND_LONG:
747 _handleCommandLong(message);
756#if !defined(QGC_NO_ARDUPILOT_DIALECT)
761 if (_cameraImageCapturedMessageAvailable) {
765 mavlink_camera_feedback_t feedback;
767 mavlink_msg_camera_feedback_decode(&message, &feedback);
769 QGeoCoordinate imageCoordinate((
double)feedback.lat / qPow(10.0, 7.0), (
double)feedback.lng / qPow(10.0, 7.0), feedback.alt_msl);
770 qCDebug(VehicleLog) <<
"_handleCameraFeedback coord:index" << imageCoordinate << feedback.img_idx;
777 mavlink_orbit_execution_status_t orbitStatus;
779 mavlink_msg_orbit_execution_status_decode(&message, &orbitStatus);
781 double newRadius = qAbs(
static_cast<double>(orbitStatus.radius));
782 if (!
QGC::fuzzyCompare(_orbitMapCircle->radius()->rawValue().toDouble(), newRadius)) {
783 _orbitMapCircle->radius()->setRawValue(newRadius);
786 bool newOrbitClockwise = orbitStatus.radius > 0 ? true :
false;
787 if (_orbitMapCircle->clockwiseRotation() != newOrbitClockwise) {
788 _orbitMapCircle->setClockwiseRotation(newOrbitClockwise);
791 QGeoCoordinate newCenter(
static_cast<double>(orbitStatus.x) / qPow(10.0, 7.0),
static_cast<double>(orbitStatus.y) / qPow(10.0, 7.0));
792 if (_orbitMapCircle->center() != newCenter) {
793 _orbitMapCircle->setCenter(newCenter);
798 _orbitMapCircle->setShowRotation(
true);
802 _orbitTelemetryTimer.start(_orbitTelemetryTimeoutMsecs);
805void Vehicle::_orbitTelemetryTimeout()
807 _orbitActive =
false;
813 mavlink_camera_image_captured_t feedback;
815 mavlink_msg_camera_image_captured_decode(&message, &feedback);
817 if (!_cameraImageCapturedMessageAvailable) {
818 _cameraImageCapturedMessageAvailable =
true;
820 if (_cameraTriggerPoints->count() > 0) {
825 QGeoCoordinate imageCoordinate((
double)feedback.lat / qPow(10.0, 7.0), (
double)feedback.lon / qPow(10.0, 7.0), feedback.alt);
826 qCDebug(VehicleLog) <<
"_handleCameraFeedback coord:index" << imageCoordinate << feedback.image_index << feedback.capture_result;
827 if (feedback.capture_result == 1) {
835 if (message.compid != _defaultComponentId) {
839 mavlink_gps_raw_int_t gpsRawInt;
840 mavlink_msg_gps_raw_int_decode(&message, &gpsRawInt);
842 _gpsRawIntMessageAvailable =
true;
844 if (gpsRawInt.fix_type >= GPS_FIX_TYPE_3D_FIX) {
845 if (!_globalPositionIntMessageAvailable) {
846 QGeoCoordinate newPosition(gpsRawInt.lat / (
double)1E7, gpsRawInt.lon / (
double)1E7, gpsRawInt.alt / 1000.0);
847 if (newPosition != _coordinate) {
848 _coordinate = newPosition;
861 if (message.compid != _defaultComponentId) {
865 mavlink_global_position_int_t globalPositionInt;
866 mavlink_msg_global_position_int_decode(&message, &globalPositionInt);
875 if (globalPositionInt.lat == 0 && globalPositionInt.lon == 0) {
879 _globalPositionIntMessageAvailable =
true;
880 QGeoCoordinate newPosition(globalPositionInt.lat / (
double)1E7, globalPositionInt.lon / (
double)1E7, globalPositionInt.alt / 1000.0);
881 if (newPosition != _coordinate) {
882 _coordinate = newPosition;
890 mavlink_high_latency_t highLatency;
891 mavlink_msg_high_latency_decode(&message, &highLatency);
893 QString previousFlightMode;
894 if (_base_mode != 0 || _custom_mode != 0){
899 _base_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
906 if (_armed !=
true) {
914 const double altitude;
916 highLatency.latitude / (double)1E7,
917 highLatency.longitude / (
double)1E7,
918 static_cast<double>(highLatency.altitude_amsl)
922 _coordinate.setLongitude(
coordinate.longitude);
938 mavlink_msg_high_latency2_decode(&message, &highLatency2);
940 QString previousFlightMode;
941 if (_base_mode != 0 || _custom_mode != 0){
947 if (highLatency2.autopilot == MAV_AUTOPILOT_ARDUPILOTMEGA) {
948 _base_mode = (uint8_t)highLatency2.custom0;
950 _base_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
957 if (highLatency2.autopilot == MAV_AUTOPILOT_ARDUPILOTMEGA) {
958 if ((uint8_t)highLatency2.custom0 & MAV_MODE_FLAG_SAFETY_ARMED && _armed !=
true) {
961 }
else if (!((uint8_t)highLatency2.custom0 & MAV_MODE_FLAG_SAFETY_ARMED) && _armed !=
false) {
967 if (_armed !=
true) {
973 _coordinate.setLatitude(highLatency2.latitude / (
double)1E7);
974 _coordinate.setLongitude(highLatency2.longitude / (
double)1E7);
975 _coordinate.setAltitude(highLatency2.altitude);
987 if (newOnboardControlSensorsEnabled != _onboardControlSensorsEnabled) {
988 _onboardControlSensorsEnabled = newOnboardControlSensorsEnabled;
989 _onboardControlSensorsPresent = newOnboardControlSensorsEnabled;
990 _onboardControlSensorsUnhealthy = 0;
994void Vehicle::_setCapabilities(uint64_t capabilityBits)
997 _capabilityBitsKnown =
true;
1002 QString doesNotSupport(
"does not support");
1004 qCDebug(VehicleLog) << QString(
"Vehicle %1 Mavlink 2.0").arg(_capabilityBits & MAV_PROTOCOL_CAPABILITY_MAVLINK2 ?
supports : doesNotSupport);
1005 qCDebug(VehicleLog) << QString(
"Vehicle %1 MISSION_ITEM_INT").arg(_capabilityBits & MAV_PROTOCOL_CAPABILITY_MISSION_INT ?
supports : doesNotSupport);
1006 qCDebug(VehicleLog) << QString(
"Vehicle %1 MISSION_COMMAND_INT").arg(_capabilityBits & MAV_PROTOCOL_CAPABILITY_COMMAND_INT ?
supports : doesNotSupport);
1007 qCDebug(VehicleLog) << QString(
"Vehicle %1 GeoFence").arg(_capabilityBits & MAV_PROTOCOL_CAPABILITY_MISSION_FENCE ?
supports : doesNotSupport);
1008 qCDebug(VehicleLog) << QString(
"Vehicle %1 RallyPoints").arg(_capabilityBits & MAV_PROTOCOL_CAPABILITY_MISSION_RALLY ?
supports : doesNotSupport);
1009 qCDebug(VehicleLog) << QString(
"Vehicle %1 Terrain").arg(_capabilityBits & MAV_PROTOCOL_CAPABILITY_TERRAIN ?
supports : doesNotSupport);
1015 uint8_t* pUid = (uint8_t*)(
void*)&_uid;
1016 uid = uid.asprintf(
"%02X:%02X:%02X:%02X:%02X:%02X:%02X:%02X",
1030 if (message.compid != _defaultComponentId) {
1034 mavlink_extended_sys_state_t extendedState;
1035 mavlink_msg_extended_sys_state_decode(&message, &extendedState);
1037 switch (extendedState.landed_state) {
1038 case MAV_LANDED_STATE_ON_GROUND:
1042 case MAV_LANDED_STATE_TAKEOFF:
1043 case MAV_LANDED_STATE_IN_AIR:
1047 case MAV_LANDED_STATE_LANDING:
1064bool Vehicle::_apmArmingNotRequired()
1066 QString armingRequireParam(
"ARMING_REQUIRE");
1073 if (message.compid != _defaultComponentId) {
1077 mavlink_sys_status_t sysStatus;
1078 mavlink_msg_sys_status_decode(&message, &sysStatus);
1080 _sysStatusSensorInfo->update(sysStatus);
1082 if (sysStatus.onboard_control_sensors_enabled & MAV_SYS_STATUS_PREARM_CHECK) {
1083 if (!_readyToFlyAvailable) {
1084 _readyToFlyAvailable =
true;
1088 bool newReadyToFly = sysStatus.onboard_control_sensors_health & MAV_SYS_STATUS_PREARM_CHECK;
1089 if (newReadyToFly != _readyToFly) {
1090 _readyToFly = newReadyToFly;
1095 bool newAllSensorsHealthy = (sysStatus.onboard_control_sensors_enabled & sysStatus.onboard_control_sensors_health) == sysStatus.onboard_control_sensors_enabled;
1096 if (newAllSensorsHealthy != _allSensorsHealthy) {
1097 _allSensorsHealthy = newAllSensorsHealthy;
1101 if (_onboardControlSensorsPresent != sysStatus.onboard_control_sensors_present) {
1102 _onboardControlSensorsPresent = sysStatus.onboard_control_sensors_present;
1106 if (_onboardControlSensorsEnabled != sysStatus.onboard_control_sensors_enabled) {
1107 _onboardControlSensorsEnabled = sysStatus.onboard_control_sensors_enabled;
1110 if (_onboardControlSensorsHealth != sysStatus.onboard_control_sensors_health) {
1111 _onboardControlSensorsHealth = sysStatus.onboard_control_sensors_health;
1119 _updateArmed(_onboardControlSensorsEnabled & MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS);
1122 uint32_t newSensorsUnhealthy = _onboardControlSensorsEnabled & ~_onboardControlSensorsHealth;
1123 if (newSensorsUnhealthy != _onboardControlSensorsUnhealthy) {
1124 _onboardControlSensorsUnhealthy = newSensorsUnhealthy;
1131 mavlink_battery_status_t batteryStatus;
1132 mavlink_msg_battery_status_decode(&message, &batteryStatus);
1138 QString batteryMessage;
1140 switch (batteryStatus.charge_state) {
1141 case MAV_BATTERY_CHARGE_STATE_OK:
1144 case MAV_BATTERY_CHARGE_STATE_LOW:
1147 batteryMessage = tr(
"battery %1 level low");
1150 case MAV_BATTERY_CHARGE_STATE_CRITICAL:
1153 batteryMessage = tr(
"battery %1 level is critical");
1156 case MAV_BATTERY_CHARGE_STATE_EMERGENCY:
1159 batteryMessage = tr(
"battery %1 level emergency");
1162 case MAV_BATTERY_CHARGE_STATE_FAILED:
1165 batteryMessage = tr(
"battery %1 failed");
1168 case MAV_BATTERY_CHARGE_STATE_UNHEALTHY:
1171 batteryMessage = tr(
"battery %1 unhealthy");
1176 if (!batteryMessage.isEmpty()) {
1177 QString batteryIdStr(
"%1");
1179 batteryIdStr = batteryIdStr.arg(batteryStatus.id);
1181 batteryIdStr = batteryIdStr.arg(
"");
1183 _say(tr(
"warning"));
1184 _say(QStringLiteral(
"%1 %2 ").arg(_vehicleIdSpeech()).arg(batteryMessage.arg(batteryIdStr)));
1190 if (homeCoord != _homePosition) {
1191 _homePosition = homeCoord;
1192 qCDebug(VehicleLog) <<
"new home location set at coordinate: " << homeCoord;
1199 if (message.compid != _defaultComponentId) {
1203 mavlink_home_position_t homePos;
1205 mavlink_msg_home_position_decode(&message, &homePos);
1207 QGeoCoordinate newHomePosition (homePos.latitude / 10000000.0,
1208 homePos.longitude / 10000000.0,
1209 homePos.altitude / 1000.0);
1213void Vehicle::_updateArmed(
bool armed)
1215 if (_armed !=
armed) {
1220 _trajectoryPoints->
start();
1221 _flightTimerStart();
1222 _clearCameraTriggerPoints();
1226 _trajectoryPoints->
stop();
1241 qCDebug(VehicleLog) <<
"_handlePing: primary link gone!";
1245 mavlink_ping_t ping;
1248 mavlink_msg_ping_decode(&message, &ping);
1250 if ((ping.target_system == 0) && (ping.target_component == 0)) {
1255 sharedLink->mavlinkChannel(),
1266 const QString &metadataJsonFileName)
1276 if (message.compid != _defaultComponentId) {
1280 mavlink_heartbeat_t heartbeat;
1282 mavlink_msg_heartbeat_decode(&message, &heartbeat);
1284 bool newArmed = heartbeat.base_mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY;
1290 if (!_apmArmingNotRequired() || !(_onboardControlSensorsPresent & MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS)) {
1292 _updateArmed(newArmed);
1296 _updateArmed(newArmed);
1299 if (heartbeat.base_mode != _base_mode || heartbeat.custom_mode != _custom_mode) {
1300 QString previousFlightMode;
1301 if (_base_mode != 0 || _custom_mode != 0){
1306 _base_mode = heartbeat.base_mode;
1307 _custom_mode = heartbeat.custom_mode;
1316 if (message.compid != _defaultComponentId) {
1320 mavlink_current_mode_t currentMode;
1321 mavlink_msg_current_mode_decode(&message, ¤tMode);
1322 if (currentMode.intended_custom_mode != 0) {
1323 _has_custom_mode_user_intention =
true;
1325 bool changed = _custom_mode_user_intention != currentMode.intended_custom_mode;
1326 _custom_mode_user_intention = currentMode.intended_custom_mode;
1327 if (changed && previousFlightMode !=
flightMode()) {
1335 mavlink_rc_channels_t channels;
1337 mavlink_msg_rc_channels_decode(&message, &channels);
1339 QVector<uint16_t> rawChannelValues({
1349 channels.chan10_raw,
1350 channels.chan11_raw,
1351 channels.chan12_raw,
1352 channels.chan13_raw,
1353 channels.chan14_raw,
1354 channels.chan15_raw,
1355 channels.chan16_raw,
1356 channels.chan17_raw,
1357 channels.chan18_raw,
1361 int validChannelCount = 0;
1362 int firstUnusedChannelIndex = -1;
1363 for (
int i=0; i<rawChannelValues.size(); i++) {
1364 if (rawChannelValues[i] != UINT16_MAX) {
1365 validChannelCount++;
1366 }
else if (firstUnusedChannelIndex == -1) {
1367 firstUnusedChannelIndex = i;
1370 if (firstUnusedChannelIndex != -1 && firstUnusedChannelIndex != validChannelCount) {
1371 qCWarning(VehicleLog) <<
"Non-contiguous RC channels detected. Not publishing data from RC_CHANNELS.";
1375 QVector<int> channelValues(validChannelCount);
1376 QVector<int> clampedValues(validChannelCount);
1377 for (
int channelIndex = 0; channelIndex < validChannelCount; ++channelIndex) {
1378 channelValues[channelIndex] = rawChannelValues[channelIndex];
1379 clampedValues[channelIndex] = std::clamp(channelValues[channelIndex], 1000, 2000);
1392 qCDebug(VehicleLog) <<
"sendMessageOnLinkThreadSafe" << link <<
"not connected!";
1400 uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
1401 int len = mavlink_msg_to_send_buffer(buffer, &message);
1412 uint8_t frameType = 0;
1413 if (_vehicleType == MAV_TYPE_SUBMARINE) {
1429void Vehicle::_activeVehicleChanged(
Vehicle *newActiveVehicle)
1431 _isActiveVehicle = newActiveVehicle ==
this;
1436 return _homePosition;
1443 MAV_CMD_COMPONENT_ARM_DISARM,
1445 armed ? 1.0f : 0.0f);
1451 MAV_CMD_COMPONENT_ARM_DISARM,
1470 return _firmwarePlugin->
flightMode(_base_mode, _custom_mode);
1473bool Vehicle::setFlightModeCustom(
const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode)
1481 uint32_t custom_mode;
1483 if (setFlightModeCustom(
flightMode, &base_mode, &custom_mode)) {
1486 qCDebug(VehicleLog) <<
"setFlightMode: primary link gone!";
1490 uint8_t newBaseMode = _base_mode & ~MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE;
1494 newBaseMode |= base_mode;
1498 MAV_CMD_DO_SET_MODE,
1500 MAV_MODE_FLAG_CUSTOM_MODE_ENABLED,
1506 sharedLink->mavlinkChannel(),
1514 qCWarning(VehicleLog) <<
"FirmwarePlugin::setFlightMode failed, flightMode:" <<
flightMode;
1519QVariantList Vehicle::links()
const {
1522 for(
const auto &item: _links )
1523 ret << QVariant::fromValue(item);
1533 qCDebug(VehicleLog) <<
"requestDataStream: primary link gone!";
1538 mavlink_request_data_stream_t dataStream;
1540 memset(&dataStream, 0,
sizeof(dataStream));
1542 dataStream.req_stream_id = stream;
1543 dataStream.req_message_rate = rate;
1544 dataStream.start_stop = 1;
1545 dataStream.target_system =
id();
1546 dataStream.target_component = _defaultComponentId;
1550 sharedLink->mavlinkChannel(),
1562void Vehicle::_sendMessageMultipleNext()
1564 if (_nextSendMessageMultipleIndex < _sendMessageMultipleList.count()) {
1565 uint32_t msgId = _sendMessageMultipleList[_nextSendMessageMultipleIndex].message.msgid;
1566 const mavlink_message_info_t* info = mavlink_get_message_info_by_id(msgId);
1567 QString msgName = info ? info->name : QString::number(msgId);
1568 qCDebug(VehicleLog) <<
"_sendMessageMultipleNext:" << msgName;
1575 if (--_sendMessageMultipleList[_nextSendMessageMultipleIndex].retryCount <= 0) {
1576 _sendMessageMultipleList.removeAt(_nextSendMessageMultipleIndex);
1578 _nextSendMessageMultipleIndex++;
1582 if (_nextSendMessageMultipleIndex >= _sendMessageMultipleList.count()) {
1583 _nextSendMessageMultipleIndex = 0;
1589 SendMessageMultipleInfo_t info;
1591 info.message = message;
1592 info.retryCount = _sendMessageMultipleRetries;
1594 _sendMessageMultipleList.append(info);
1597void Vehicle::_missionManagerError(
int errorCode,
const QString& errorMsg)
1599 Q_UNUSED(errorCode);
1603void Vehicle::_geoFenceManagerError(
int errorCode,
const QString& errorMsg)
1605 Q_UNUSED(errorCode);
1609void Vehicle::_rallyPointManagerError(
int errorCode,
const QString& errorMsg)
1611 Q_UNUSED(errorCode);
1615void Vehicle::_clearCameraTriggerPoints()
1617 _cameraImageCapturedMessageAvailable =
false;
1618 _cameraTriggerPoints->clearAndDeleteContents();
1621void Vehicle::_flightTimerStart()
1623 _flightTimer.start();
1624 _flightTimeUpdater.start();
1629void Vehicle::_flightTimerStop()
1631 _flightTimeUpdater.stop();
1634void Vehicle::_updateFlightTime()
1639void Vehicle::_gotProgressUpdate(
float progressValue)
1645 progressValue = 0.f;
1647 _loadProgress = progressValue;
1651void Vehicle::_firstMissionLoadComplete()
1656void Vehicle::_firstGeoFenceLoadComplete()
1661void Vehicle::_firstRallyPointLoadComplete()
1664 _initialPlanRequestComplete =
true;
1668void Vehicle::_parametersReady(
bool parametersReady)
1670 qCDebug(VehicleLog) <<
"_parametersReady" << parametersReady;
1673 _sendQGCTimeToVehicle();
1675 _sendQGCTimeToVehicle();
1676 if (parametersReady) {
1678 _setupAutoDisarmSignalling();
1688void Vehicle::_sendQGCTimeToVehicle()
1692 qCDebug(VehicleLog) <<
"_sendQGCTimeToVehicle: primary link gone!";
1697 mavlink_system_time_t cmd;
1700 cmd.time_unix_usec = QDateTime::currentDateTime().currentMSecsSinceEpoch()*1000;
1702 cmd.time_boot_ms = 0;
1705 sharedLink->mavlinkChannel(),
1717 if (!joystickEnabled) {
1719 static_cast<float>(
roll),
1720 static_cast<float>(
pitch),
1721 static_cast<float>(yaw),
1722 static_cast<float>(thrust),
1724 NAN, NAN, NAN, NAN, NAN, NAN, NAN, NAN);
1728void Vehicle::_say(
const QString& text)
1779QString Vehicle::_vehicleIdSpeech()
1782 return tr(
"Vehicle %1 ").arg(
id());
1788void Vehicle::_handleFlightModeChanged(
const QString& flightMode)
1790 if (
flightMode != _lastAnnouncedFlightMode) {
1792 _say(tr(
"%1 %2 flight mode").arg(_vehicleIdSpeech()).arg(
flightMode));
1797void Vehicle::_announceArmedChanged(
bool armed)
1799 _say(QString(
"%1 %2").arg(_vehicleIdSpeech()).arg(
armed ? tr(
"armed") : tr(
"disarmed")));
1802 _armedPosition = _coordinate;
1902 if (!gotoCoord.isValid()) {
1906 if (
coordinate().distanceTo(gotoCoord) > maxDistance) {
1955 static_cast<float>(radius),
1956 static_cast<float>(qQNaN()),
1957 static_cast<float>(ORBIT_YAW_BEHAVIOUR_UNCHANGED),
1958 static_cast<float>(qQNaN()),
1959 centerCoord.latitude(), centerCoord.longitude(),
static_cast<float>(amslAltitude));
1965 static_cast<float>(radius),
1966 static_cast<float>(qQNaN()),
1967 static_cast<float>(ORBIT_YAW_BEHAVIOUR_UNCHANGED),
1968 static_cast<float>(qQNaN()),
1969 static_cast<float>(centerCoord.latitude()),
1970 static_cast<float>(centerCoord.longitude()),
1971 static_cast<float>(amslAltitude));
1977 if (!centerCoord.isValid()) {
1980 if (!_vehicleSupports->
roiMode()) {
1993 if ((centerCoord.altitude() >= 83000) || (centerCoord.altitude() <= -83000)) {
2005 if (!_vehicleSupports->
roiMode()) {
2012 MAV_CMD_DO_SET_ROI_NONE,
2015 static_cast<float>(qQNaN()),
2016 static_cast<float>(qQNaN()),
2017 static_cast<float>(qQNaN()),
2018 static_cast<float>(qQNaN()),
2019 static_cast<double>(qQNaN()),
2020 static_cast<double>(qQNaN()),
2021 static_cast<float>(qQNaN()));
2025 MAV_CMD_DO_SET_ROI_NONE,
2027 static_cast<float>(qQNaN()),
2028 static_cast<float>(qQNaN()),
2029 static_cast<float>(qQNaN()),
2030 static_cast<float>(qQNaN()),
2031 static_cast<float>(qQNaN()),
2032 static_cast<float>(qQNaN()),
2033 static_cast<float>(qQNaN()));
2060 MAV_CMD_DO_GO_AROUND,
2062 static_cast<float>(climbOutAltitude));
2084 _defaultComponentId,
2085 MAV_CMD_COMPONENT_ARM_DISARM,
2095 MAV_CMD_AIRFRAME_CONFIGURATION,
2105 MAV_CMD_AIRFRAME_CONFIGURATION,
2122 qCDebug(VehicleLog) <<
"setCurrentMissionSequence: primary link gone!";
2129 mavlink_msg_mission_set_current_pack_chan(
2132 sharedLink->mavlinkChannel(),
2134 static_cast<uint8_t
>(
id()),
2136 static_cast<uint16_t
>(seq));
2140 MAV_CMD_DO_SET_MISSION_CURRENT,
2142 static_cast<uint16_t
>(seq)
2146void Vehicle::sendMavCommand(
int compId, MAV_CMD command,
bool showError,
float param1,
float param2,
float param3,
float param4,
float param5,
float param6,
float param7)
2148 _mavCmdQueue->
sendCommand(
compId, command, showError, param1, param2, param3, param4, param5, param6, param7);
2151void Vehicle::sendMavCommandDelayed(
int compId, MAV_CMD command,
bool showError,
int milliseconds,
float param1,
float param2,
float param3,
float param4,
float param5,
float param6,
float param7)
2153 _mavCmdQueue->
sendCommandDelayed(
compId, command, showError, milliseconds, param1, param2, param3, param4, param5, param6, param7);
2156void Vehicle::sendCommand(
int compId,
int command,
bool showError,
double param1,
double param2,
double param3,
double param4,
double param5,
double param6,
double param7)
2159 compId,
static_cast<MAV_CMD
>(command),
2161 static_cast<float>(param1),
2162 static_cast<float>(param2),
2163 static_cast<float>(param3),
2164 static_cast<float>(param4),
2165 static_cast<float>(param5),
2166 static_cast<float>(param6),
2167 static_cast<float>(param7));
2175void Vehicle::sendMavCommandInt(
int compId, MAV_CMD command, MAV_FRAME frame,
bool showError,
float param1,
float param2,
float param3,
float param4,
double param5,
double param6,
float param7)
2177 _mavCmdQueue->
sendCommandInt(
compId, command, frame, showError, param1, param2, param3, param4, param5, param6, param7);
2180void Vehicle::sendMavCommandIntWithHandler(
const MavCmdAckHandlerInfo_t* ackHandlerInfo,
int compId, MAV_CMD command, MAV_FRAME frame,
float param1,
float param2,
float param3,
float param4,
double param5,
double param6,
float param7)
2182 _mavCmdQueue->
sendCommandIntWithHandler(ackHandlerInfo,
compId, command, frame, param1, param2, param3, param4, param5, param6, param7);
2185void Vehicle::sendMavCommandWithLambdaFallback(std::function<
void()> lambda,
int compId, MAV_CMD command,
bool showError,
float param1,
float param2,
float param3,
float param4,
float param5,
float param6,
float param7)
2187 _mavCmdQueue->
sendCommandWithLambdaFallback(std::move(lambda),
compId, command, showError, param1, param2, param3, param4, param5, param6, param7);
2192 return _mavCmdQueue->
isPending(targetCompId, command);
2208 mavlink_msg_command_ack_decode(&message, &ack);
2211 QString logMsg = QStringLiteral(
"_handleCommandAck command(%1) result(%2)").arg(rawCommandName).arg(
QGCMAVLink::mavResultToString(
static_cast<MAV_RESULT
>(ack.result)));
2214 if (ack.command == MAV_CMD_REQUEST_MESSAGE) {
2215 const int entryIndex = _mavCmdQueue->
findEntryIndex(message.compid,
static_cast<MAV_CMD
>(ack.command));
2216 if (entryIndex != -1) {
2219 logMsg += QStringLiteral(
" (entry=%1)").arg(entryIndex);
2223 qCDebug(VehicleLog) << logMsg;
2226 if (ack.command == MAV_CMD_DO_SET_ROI_LOCATION && ack.result == MAV_RESULT_ACCEPTED) {
2227 _isROIEnabled =
true;
2230 if (ack.command == MAV_CMD_DO_SET_ROI_NONE && ack.result == MAV_RESULT_ACCEPTED) {
2231 _isROIEnabled =
false;
2234 if (ack.command == MAV_CMD_PREFLIGHT_STORAGE) {
2237#if !defined(QGC_NO_ARDUPILOT_DIALECT)
2238 if (ack.command == MAV_CMD_FLASH_BOOTLOADER && ack.result == MAV_RESULT_ACCEPTED) {
2247 if (ack.command == MAV_CMD_SET_MESSAGE_INTERVAL) {
2248 _mavlinkStreamConfig->gotSetMessageIntervalAck();
2252void Vehicle::requestMessage(RequestMessageResultHandler resultHandler,
void* resultHandlerData,
int compId,
int messageId,
float param1,
float param2,
float param3,
float param4,
float param5)
2254 _reqMsgCoord->
requestMessage(resultHandler, resultHandlerData,
compId, messageId, param1, param2, param3, param4, param5);
2262 if (!_prearmError.isEmpty()) {
2263 _prearmErrorTimer.start();
2267void Vehicle::_prearmErrorTimeout()
2274 _firmwareMajorVersion = majorVersion;
2275 _firmwareMinorVersion = minorVersion;
2276 _firmwarePatchVersion = patchVersion;
2277 _firmwareVersionType = versionType;
2283 _firmwareCustomMajorVersion = majorVersion;
2284 _firmwareCustomMinorVersion = minorVersion;
2285 _firmwareCustomPatchVersion = patchVersion;
2294void Vehicle::_rebootCommandResultHandler(
void* resultHandlerData,
int ,
const mavlink_command_ack_t& ack, MavCmdResultFailureCode_t failureCode)
2298 if (ack.result != MAV_RESULT_ACCEPTED) {
2299 switch (failureCode) {
2301 qCDebug(VehicleLog) << QStringLiteral(
"MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN error(%1)").arg(ack.result);
2304 qCDebug(VehicleLog) <<
"MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN failed: no response from vehicle";
2307 qCDebug(VehicleLog) <<
"MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN failed: duplicate command";
2329 qCDebug(VehicleLog) <<
"startCalibration: primary link gone!";
2395 sharedLink->mavlinkChannel(),
2399 MAV_CMD_PREFLIGHT_CALIBRATION,
2401 param1, param2, param3, param4, param5, param6, param7);
2408 MAV_CMD_PREFLIGHT_CALIBRATION,
2422 MAV_CMD_PREFLIGHT_UAVCAN,
2430 MAV_CMD_PREFLIGHT_UAVCAN,
2445 sendMavCommand(_defaultComponentId, MAV_CMD_DO_MOTOR_TEST, showError, motor, MOTOR_TEST_THROTTLE_PERCENT, percent, timeoutSecs, 0, MOTOR_TEST_ORDER_BOARD);
2450 if (_offlineEditingVehicle) {
2453 qCWarning(VehicleLog) <<
"Call to Vehicle::setOfflineEditingDefaultComponentId on vehicle which is not offline";
2461 MAV_CMD_DO_VTOL_TRANSITION,
2470 sendMavCommand(_defaultComponentId, MAV_CMD_LOGGING_START,
false );
2475 sendMavCommand(_defaultComponentId, MAV_CMD_LOGGING_STOP,
false );
2478void Vehicle::_ackMavlinkLogData(uint16_t sequence)
2482 qCDebug(VehicleLog) <<
"_ackMavlinkLogData: primary link gone!";
2487 mavlink_logging_ack_t ack;
2489 memset(&ack, 0,
sizeof(ack));
2490 ack.sequence = sequence;
2491 ack.target_component = _defaultComponentId;
2492 ack.target_system =
id();
2493 mavlink_msg_logging_ack_encode_chan(
2496 sharedLink->mavlinkChannel(),
2504 mavlink_logging_data_t log;
2505 mavlink_msg_logging_data_decode(&message, &log);
2506 if (
static_cast<size_t>(log.length) >
sizeof(log.data)) {
2507 qWarning() <<
"Invalid length for LOGGING_DATA, discarding." << log.length;
2509 emit
mavlinkLogData(
this, log.target_system, log.target_component, log.sequence,
2510 log.first_message_offset, QByteArray((
const char*)log.data, log.length),
false);
2516 mavlink_logging_data_acked_t log;
2517 mavlink_msg_logging_data_acked_decode(&message, &log);
2518 _ackMavlinkLogData(log.sequence);
2519 if (
static_cast<size_t>(log.length) >
sizeof(log.data)) {
2520 qWarning() <<
"Invalid length for LOGGING_DATA_ACKED, discarding." << log.length;
2522 emit
mavlinkLogData(
this, log.target_system, log.target_component, log.sequence,
2523 log.first_message_offset, QByteArray((
const char*)log.data, log.length),
false);
2596 if(_firmwarePlugin) {
2599 static QVariantList emptyList;
2603void Vehicle::_setupAutoDisarmSignalling()
2620 return fact->
rawValue().toDouble() > 0;
2626void Vehicle::_updateDistanceHeadingHome()
2644void Vehicle::_updateHeadingToNextWP()
2649 if(llist.size()>currentIndex && currentIndex!=-1
2650 && llist[currentIndex]->coordinate().longitude()!=0.0
2660void Vehicle::_updateMissionItemIndex()
2664 unsigned offset = 0;
2672void Vehicle::_updateDistanceHeadingGCS()
2675 if (
coordinate().isValid() && gcsPosition.isValid()) {
2684void Vehicle::_updateHomepoint()
2688 if(setHomeCmdSupported && updateHomeActivated){
2690 if (
coordinate().isValid() && gcsPosition.isValid()) {
2692 MAV_CMD_DO_SET_HOME,
false,
2695 static_cast<float>(gcsPosition.latitude()) ,
2696 static_cast<float>(gcsPosition.longitude()),
2697 static_cast<float>(gcsPosition.altitude()));
2702void Vehicle::_updateHobbsMeter()
2709 _initialPlanRequestComplete =
true;
2723void Vehicle::_vehicleParamLoaded(
bool ready)
2732void Vehicle::_mavlinkMessageStatus(
int uasId, uint64_t totalSent, uint64_t totalReceived, uint64_t totalLoss,
float lossPercent)
2734 if(uasId == _systemID) {
2735 _mavlinkSentCount = totalSent;
2736 _mavlinkReceivedCount = totalReceived;
2737 _mavlinkLossCount = totalLoss;
2738 _mavlinkLossPercent = lossPercent;
2750 return _firmwarePlugin->
versionCompare(
this, major, minor, patch);
2763 _mavlinkStreamConfig->restoreDefaults();
2766 _mavlinkStreamConfig->setHighRateRateAndAttitude();
2769 _mavlinkStreamConfig->setHighRateVelAndPos();
2772 _mavlinkStreamConfig->setHighRateAltAirspeed();
2783void Vehicle::_setMessageInterval(
int messageId,
int rate)
2786 MAV_CMD_SET_MESSAGE_INTERVAL,
2792QString Vehicle::_formatMavCommand(MAV_CMD command,
float param1)
2796 if (command == MAV_CMD_REQUEST_MESSAGE && param1 > 0) {
2797 const mavlink_message_info_t* info = mavlink_get_message_info_by_id(
static_cast<uint32_t
>(param1));
2798 QString param1Str = info ? QString(
"%1(%2)").arg(param1).arg(info->name) : QString::number(param1);
2799 return QString(
"%1: %2").arg(commandName).arg(param1Str);
2801 return QString(
"%1: %2").arg(commandName).arg(param1);
2809void Vehicle::_initializeCsv()
2814 QString now = QDateTime::currentDateTime().toString(
"yyyy-MM-dd hh-mm-ss");
2815 QString fileName = QString(
"%1 vehicle%2.csv").arg(now).arg(_systemID);
2817 _csvLogFile.setFileName(saveDir.absoluteFilePath(fileName));
2819 if (!_csvLogFile.open(QIODevice::Append)) {
2820 qCWarning(VehicleLog) <<
"unable to open file for csv logging, Stopping csv logging!";
2824 QTextStream stream(&_csvLogFile);
2825 QStringList allFactNames;
2829 allFactNames << QString(
"%1.%2").arg(groupName, factName);
2832 qCDebug(VehicleLog) <<
"Facts logged to csv:" << allFactNames;
2833 stream <<
"Timestamp," << allFactNames.join(
",") <<
"\n";
2836void Vehicle::_writeCsvLine()
2839 if(!_csvLogFile.isOpen() &&
2844 if(!_csvLogFile.isOpen()){
2848 QStringList allFactValues;
2849 QTextStream stream(&_csvLogFile);
2852 allFactValues << QDateTime::currentDateTime().toString(QStringLiteral(
"yyyy-MM-dd hh:mm:ss.zzz"));
2854 for (
const QString& factName :
factNames()) {
2864 stream << allFactValues.join(
",") <<
"\n";
2875 mavlink_msg_obstacle_distance_decode(&message, &o);
2876 _objectAvoidance->
update(&o);
2881 mavlink_fence_status_t fenceStatus;
2883 mavlink_msg_fence_status_decode(&message, &fenceStatus);
2885 qCDebug(VehicleLog) <<
"_handleFenceStatus breach_status" << fenceStatus.breach_status;
2887 static qint64 lastUpdate = 0;
2888 qint64 now = QDateTime::currentMSecsSinceEpoch();
2889 if (fenceStatus.breach_status == 1) {
2890 if (now - lastUpdate > 3000) {
2892 QString breachTypeStr;
2893 switch (fenceStatus.breach_type) {
2894 case FENCE_BREACH_NONE:
2896 case FENCE_BREACH_MINALT:
2897 breachTypeStr = tr(
"minimum altitude");
2899 case FENCE_BREACH_MAXALT:
2900 breachTypeStr = tr(
"maximum altitude");
2902 case FENCE_BREACH_BOUNDARY:
2903 breachTypeStr = tr(
"boundary");
2909 _say(breachTypeStr +
" " + tr(
"fence breached"));
2921void Vehicle::sendParamMapRC(
const QString& paramName,
double scale,
double centerValue,
int tuningID,
double minValue,
double maxValue)
2925 qCDebug(VehicleLog) <<
"sendParamMapRC: primary link gone!";
2931 char param_id_cstr[MAVLINK_MSG_PARAM_MAP_RC_FIELD_PARAM_ID_LEN] = {};
2933 for (
unsigned int i = 0; i <
sizeof(param_id_cstr); i++) {
2934 if ((
int)i < paramName.length()) {
2935 param_id_cstr[i] = paramName.toLatin1()[i];
2941 sharedLink->mavlinkChannel(),
2944 MAV_COMP_ID_AUTOPILOT1,
2947 static_cast<uint8_t
>(tuningID),
2948 static_cast<float>(centerValue),
2949 static_cast<float>(scale),
2950 static_cast<float>(minValue),
2951 static_cast<float>(maxValue));
2959 qCDebug(VehicleLog)<<
"clearAllParamMapRC: primary link gone!";
2963 char param_id_cstr[MAVLINK_MSG_PARAM_MAP_RC_FIELD_PARAM_ID_LEN] = {};
2965 for (
int i = 0; i < 3; i++) {
2969 sharedLink->mavlinkChannel(),
2972 MAV_COMP_ID_AUTOPILOT1,
2981void Vehicle::sendJoystickDataThreadSafe(
float roll,
float pitch,
float yaw,
float thrust, quint16 buttons, quint16 buttons2,
float pitchExtension,
float rollExtension,
float aux1,
float aux2,
float aux3,
float aux4,
float aux5,
float aux6)
2985 qCDebug(VehicleLog)<<
"sendJoystickDataThreadSafe: primary link gone!";
2989 if (sharedLink->linkConfiguration()->isHighLatency()) {
2995 float axesScaling = 1.0 * 1000.0;
2996 uint8_t extensions = 0;
2999 float newRollCommand =
roll * axesScaling;
3000 float newPitchCommand =
pitch * axesScaling;
3001 float newYawCommand = yaw * axesScaling;
3002 float newThrustCommand = thrust * axesScaling;
3005 float incomingExtensionValues[] = { pitchExtension, rollExtension, aux1, aux2, aux3, aux4, aux5, aux6 };
3006 int16_t outgoingExtensionValues[std::size(incomingExtensionValues)];
3007 for (
size_t i = 0; i < std::size(incomingExtensionValues); i++) {
3008 int16_t scaledValue = 0;
3009 if (!qIsNaN(incomingExtensionValues[i])) {
3010 scaledValue =
static_cast<int16_t
>(incomingExtensionValues[i] * axesScaling);
3011 extensions |= (1 << i);
3013 outgoingExtensionValues[i] = scaledValue;
3015 mavlink_msg_manual_control_pack_chan(
3018 sharedLink->mavlinkChannel(),
3020 static_cast<uint8_t
>(_systemID),
3021 static_cast<int16_t
>(newPitchCommand),
3022 static_cast<int16_t
>(newRollCommand),
3023 static_cast<int16_t
>(newThrustCommand),
3024 static_cast<int16_t
>(newYawCommand),
3027 outgoingExtensionValues[0],
3028 outgoingExtensionValues[1],
3029 outgoingExtensionValues[2],
3030 outgoingExtensionValues[3],
3031 outgoingExtensionValues[4],
3032 outgoingExtensionValues[5],
3033 outgoingExtensionValues[6],
3034 outgoingExtensionValues[7]
3045 qCDebug(VehicleLog) <<
"sendJoystickAuxRcOverrideThreadSafe: primary link gone!";
3049 if (sharedLink->linkConfiguration()->isHighLatency()) {
3053 bool anyEnabledChannel =
false;
3054 for (
bool enabled : channelEnabled) {
3056 anyEnabledChannel =
true;
3061 if (!useRcOverride || !anyEnabledChannel) {
3063 bool expected =
true;
3064 if (!_joystickAuxRcOverrideActive.compare_exchange_strong(expected,
false)) {
3069 mavlink_msg_rc_channels_override_pack_chan(
3072 sharedLink->mavlinkChannel(),
3074 static_cast<uint8_t
>(_systemID),
3075 static_cast<uint8_t
>(_defaultComponentId),
3084 static_cast<uint16_t
>(UINT16_MAX - 1),
3085 static_cast<uint16_t
>(UINT16_MAX - 1),
3099 mavlink_msg_rc_channels_override_pack_chan(
3102 sharedLink->mavlinkChannel(),
3104 static_cast<uint8_t
>(_systemID),
3105 static_cast<uint8_t
>(_defaultComponentId),
3110 channelEnabled[0] ? channelValues[0] :
static_cast<uint16_t
>(0),
3111 channelEnabled[1] ? channelValues[1] :
static_cast<uint16_t
>(0),
3112 channelEnabled[2] ? channelValues[2] :
static_cast<uint16_t
>(0),
3113 channelEnabled[3] ? channelValues[3] :
static_cast<uint16_t
>(0),
3114 channelEnabled[4] ? channelValues[4] :
static_cast<uint16_t
>(UINT16_MAX - 1),
3115 channelEnabled[5] ? channelValues[5] :
static_cast<uint16_t
>(UINT16_MAX - 1),
3125 _joystickAuxRcOverrideActive =
true;
3131 MAV_CMD_DO_DIGICAM_CONTROL,
3140 _defaultComponentId,
3151 qCDebug(VehicleLog) <<
"setEstimatorOrigin: primary link gone!";
3156 mavlink_msg_set_gps_global_origin_pack_chan(
3159 sharedLink->mavlinkChannel(),
3162 centerCoord.latitude() * 1e7,
3163 centerCoord.longitude() * 1e7,
3164 centerCoord.altitude() * 1e3,
3165 static_cast<float>(qQNaN())
3173 MAV_CMD_START_RX_PAIR,
3181 _timerRevertAllowTakeover.stop();
3182 _timerRevertAllowTakeover.setSingleShot(
true);
3183 _timerRevertAllowTakeover.setInterval(operatorControlTakeoverTimeoutMsecs());
3185 disconnect(&_timerRevertAllowTakeover, &QTimer::timeout,
nullptr,
nullptr);
3187 connect(&_timerRevertAllowTakeover, &QTimer::timeout,
this, [
this](){
3192 _timerRevertAllowTakeover.start();
3197 int safeRequestTimeoutSecs;
3200 if (requestTimeoutSecs >= requestTimeoutSecsMin && requestTimeoutSecs <= requestTimeoutSecsMax) {
3201 safeRequestTimeoutSecs = requestTimeoutSecs;
3207 const MavCmdAckHandlerInfo_t handlerInfo = {&Vehicle::_requestOperatorControlAckHandler,
this,
nullptr,
nullptr};
3210 _defaultComponentId,
3211 MAV_CMD_REQUEST_OPERATOR_CONTROL,
3214 allowOverride ? 1 : 0,
3215 safeRequestTimeoutSecs
3219 if (requestTimeoutSecs > 0) {
3220 requestOperatorControlStartTimer(requestTimeoutSecs * 1000);
3224void Vehicle::_requestOperatorControlAckHandler(
void* resultHandlerData,
int compId,
const mavlink_command_ack_t& ack, MavCmdResultFailureCode_t failureCode)
3230 switch (failureCode) {
3246 if (ack.result == MAV_RESULT_ACCEPTED) {
3247 qCDebug(VehicleLog) <<
"Operator control request accepted";
3249 qCDebug(VehicleLog) <<
"Operator control request rejected";
3253void Vehicle::requestOperatorControlStartTimer(
int requestTimeoutMsecs)
3256 _sendControlRequestAllowed =
false;
3259 _timerRequestOperatorControl.stop();
3260 _timerRequestOperatorControl.setSingleShot(
true);
3261 _timerRequestOperatorControl.setInterval(requestTimeoutMsecs);
3263 disconnect(&_timerRequestOperatorControl, &QTimer::timeout,
nullptr,
nullptr);
3264 connect(&_timerRequestOperatorControl, &QTimer::timeout,
this, [
this](){
3265 _sendControlRequestAllowed =
true;
3268 _timerRequestOperatorControl.start();
3273 mavlink_control_status_t controlStatus;
3274 mavlink_msg_control_status_decode(&message, &controlStatus);
3276 bool updateControlStatusSignals =
false;
3277 if (_gcsControlStatusFlags != controlStatus.flags) {
3278 _gcsControlStatusFlags = controlStatus.flags;
3279 _gcsControlStatusFlags_SystemManager = controlStatus.flags & GCS_CONTROL_STATUS_FLAGS_SYSTEM_MANAGER;
3280 _gcsControlStatusFlags_TakeoverAllowed = controlStatus.flags & GCS_CONTROL_STATUS_FLAGS_TAKEOVER_ALLOWED;
3281 updateControlStatusSignals =
true;
3284 if (_sysid_in_control != controlStatus.sysid_in_control) {
3285 _sysid_in_control = controlStatus.sysid_in_control;
3286 updateControlStatusSignals =
true;
3289 if (!_firstControlStatusReceived) {
3290 _firstControlStatusReceived =
true;
3291 updateControlStatusSignals =
true;
3294 if (updateControlStatusSignals) {
3300 if (!sendControlRequestAllowed() && _gcsControlStatusFlags_TakeoverAllowed) {
3301 disconnect(&_timerRequestOperatorControl, &QTimer::timeout,
nullptr,
nullptr);
3302 _sendControlRequestAllowed =
true;
3315 mavlink_msg_command_long_decode(&message, &commandLong);
3320 if (commandLong.command == MAV_CMD_REQUEST_OPERATOR_CONTROL) {
3321 _handleCommandRequestOperatorControl(commandLong);
3325int Vehicle::operatorControlTakeoverTimeoutMsecs()
const
3364 MAV_CMD_FLASH_BOOTLOADER,
3376 MAV_CMD_DO_AUX_FUNCTION,
3379 enable ? MAV_CMD_DO_AUX_FUNCTION_SWITCH_LEVEL_HIGH : MAV_CMD_DO_AUX_FUNCTION_SWITCH_LEVEL_LOW);
3398void Vehicle::_createStatusTextHandler()
3408void Vehicle::_onStatusTextFromEvent(uint8_t compid,
int severity,
const QString &text,
const QString &description)
3411 static_cast<MAV_SEVERITY
>(severity), text, description);
3414void Vehicle::_textMessageReceived(MAV_COMPONENT componentid, MAV_SEVERITY severity, QString text, QString description)
3418 qCDebug(VehicleLog) <<
"Dropping message (expected as event):" << text;
3422 bool skipSpoken =
false;
3423 const bool ardupilotPrearm = text.startsWith(QStringLiteral(
"PreArm"));
3424 const bool px4Prearm = text.startsWith(QStringLiteral(
"preflight"), Qt::CaseInsensitive) && (severity >= MAV_SEVERITY::MAV_SEVERITY_CRITICAL);
3425 if (ardupilotPrearm || px4Prearm) {
3426 if (_healthAndArmingChecksSupported(componentid)) {
3427 qCDebug(VehicleLog) <<
"Dropping preflight message (expected as event):" << text;
3432 if (_noisySpokenPrearmMap.contains(text) && _noisySpokenPrearmMap.value(text).msecsTo(QTime::currentTime()) < (10 * 1000)) {
3435 (void) _noisySpokenPrearmMap.insert(text, QTime::currentTime());
3440 bool readAloud =
false;
3442 if (text.startsWith(
"#")) {
3443 (void) text.remove(0, 1);
3445 }
else if (severity <= MAV_SEVERITY::MAV_SEVERITY_NOTICE) {
3449 if (readAloud && !skipSpoken) {
3457void Vehicle::_errorMessageReceived(QString message)
3459 QString vehicleIdPrefix;
3462 vehicleIdPrefix = tr(
"Vehicle %1: ").arg(
id());
3472void Vehicle::_createSigningController()
3482void Vehicle::_createImageProtocolManager()
3487 qgcApp()->qgcImageProvider()->setImage(image, _systemID);
3493 return (_imageProtocolManager ? _imageProtocolManager->
flowImageIndex() : 0);
3501void Vehicle::_createMAVLinkLogManager()
3508 return _mavlinkLogManager;
3516void Vehicle::_createCameraManager()
3518 if (!_cameraManager && _firmwarePlugin) {
3526 if (_cameraManager) {
3530 static QVariantList emptyCameraList;
3531 return emptyCameraList;
3539void Vehicle::_createMAVLinkEventManager()
3541 _eventManager = std::make_unique<MAVLinkEventManager>(
this);
3548 _eventManager->handleEventMessage(msg);
3551bool Vehicle::_healthAndArmingChecksSupported(uint8_t compid)
3553 return _eventManager->healthAndArmingChecksSupported(compid);
3558 return _eventManager->healthAndArmingCheckReport();
3563 _eventManager->setMetadata(compid, metadataJsonFileName);
3565 sendMavCommand(_defaultComponentId, MAV_CMD_RUN_PREARM_CHECKS,
false);
static const QString guided_mode_not_supported_by_vehicle
std::shared_ptr< LinkInterface > SharedLinkInterfacePtr
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
struct __mavlink_command_ack_t mavlink_command_ack_t
struct __mavlink_high_latency2_t mavlink_high_latency2_t
struct __mavlink_command_long_t mavlink_command_long_t
struct __mavlink_obstacle_distance_t mavlink_obstacle_distance_t
#define REQUEST_OPERATOR_CONTROL_ALLOW_TAKEOVER_TIMEOUT_MSECS
const QString guided_mode_not_supported_by_vehicle
void mavlinkMessageReceived(const mavlink_message_t &message)
static ADSBVehicleManager * instance()
void load(const QString &json_file)
void say(const QString &text, TextMods textMods=TextMod::None)
static AudioOutput * instance()
void handleMessageForFactGroupCreation(Vehicle *vehicle, const mavlink_message_t &message)
Allows for creation/updating of dynamic FactGroups based on incoming messages.
Used to group Facts together into an object hierarachy.
const QMap< QString, FactGroup * > & factGroups() const
Q_INVOKABLE Fact * getFact(const QString &name) const
QStringList factNames() const
void _addFactGroup(FactGroup *factGroup, const QString &name)
Q_INVOKABLE FactGroup * getFactGroup(const QString &name) const
QStringList factGroupNames() const
Q_INVOKABLE void setLiveUpdates(bool liveUpdates)
Turning on live updates will allow value changes to flow through as they are received.
A Fact is used to hold a single value within the system.
FactMetaData * metaData()
void rawValueChanged(const QVariant &value)
void setRawValue(const QVariant &value)
QString cookedValueString() const
QVariant rawValue() const
Value after translation.
FirmwarePlugin * firmwarePluginForAutopilot(MAV_AUTOPILOT firmwareType, MAV_TYPE vehicleType)
static FirmwarePluginManager * instance()
virtual QString motorDetectionFlightMode() const
Returns the flight mode for Motor Detection.
virtual QString pauseFlightMode() const
Returns The flight mode which indicates the vehicle is paused.
virtual void guidedModeChangeEquivalentAirspeedMetersSecond(Vehicle *vehicle, double airspeed_equiv) const
virtual void guidedModeChangeAltitude(Vehicle *vehicle, double altitudeChange, bool pauseVehicle)
virtual void startMission(Vehicle *vehicle) const
Command the vehicle to start the mission.
virtual bool multiRotorCoaxialMotors(Vehicle *) const
virtual double minimumEquivalentAirspeed(Vehicle *) const
virtual const QVariantList & toolIndicators(const Vehicle *vehicle)
virtual void guidedModeChangeGroundSpeedMetersSecond(Vehicle *vehicle, double groundspeed) const
virtual bool setFlightMode(const QString &flightMode, uint8_t *base_mode, uint32_t *custom_mode) const
@ SetFlightModeCapability
FirmwarePlugin::setFlightMode method is supported.
virtual QString vehicleImageOutline(const Vehicle *) const
Return the resource file which contains the vehicle icon used in the flight view when the view is lig...
virtual void guidedModeTakeoff(Vehicle *vehicle, double takeoffAltRel) const
Command vehicle to takeoff from current location to the specified height.
virtual bool isCapable(const Vehicle *, FirmwareCapabilities) const
virtual double maximumEquivalentAirspeed(Vehicle *) const
virtual QString missionFlightMode() const
Returns the flight mode for running missions.
virtual void adjustMetaData(MAV_TYPE, FactMetaData *)
virtual bool adjustIncomingMavlinkMessage(Vehicle *, mavlink_message_t *)
virtual bool fixedWingAirSpeedLimitsAvailable(Vehicle *) const
virtual void guidedModeChangeHeading(Vehicle *vehicle, const QGeoCoordinate &headingCoord) const
Command vehicle to rotate towards specified location.
virtual QString smartRTLFlightMode() const
Returns the flight mode for Smart RTL.
virtual bool guidedModeGotoLocation(Vehicle *vehicle, const QGeoCoordinate &gotoCoord, double forwardFlightLoiterRadius=0.0) const
virtual bool multiRotorXConfig(Vehicle *) const
virtual QString takeControlFlightMode() const
Returns the flight mode to use when the operator wants to take back control from autonomouse flight.
virtual QString flightMode(uint8_t base_mode, uint32_t custom_mode) const
virtual QString vehicleImageOpaque(const Vehicle *) const
Return the resource file which contains the vehicle icon used in the flight view when the view is dar...
virtual void startTakeoff(Vehicle *vehicle) const
Command the vehicle to start a takeoff.
virtual void pauseVehicle(Vehicle *vehicle) const
virtual QVariant expandedToolbarIndicatorSource(const Vehicle *, const QString &) const
virtual bool mulirotorSpeedLimitsAvailable(Vehicle *) const
int versionCompare(const Vehicle *vehicle, const QString &compare) const
virtual bool hasGripper(const Vehicle *) const
virtual QString landFlightMode() const
Returns the flight mode for Land.
virtual QString gotoFlightMode() const
Returns the flight mode which the vehicle will be in if it is performing a goto location.
virtual Autotune * createAutotune(Vehicle *vehicle) const
Creates Autotune object.
virtual QStringList flightModes(Vehicle *) const
virtual AutoPilotPlugin * autopilotPlugin(Vehicle *vehicle) const
virtual void guidedModeRTL(Vehicle *vehicle, bool smartRTL) const
Command vehicle to return to launch.
virtual QList< MAV_CMD > supportedMissionCommands(QGCMAVLinkTypes::VehicleClass_t) const
List of supported mission commands. Empty list for all commands supported.
virtual QString autoDisarmParameter(Vehicle *) const
virtual QString stabilizedFlightMode() const
Returns the flight mode for Stabilized.
virtual void adjustOutgoingMavlinkMessageThreadSafe(Vehicle *, LinkInterface *, mavlink_message_t *)
void toolIndicatorsChanged()
virtual void setGuidedMode(Vehicle *vehicle, bool guidedMode) const
Set guided flight mode.
virtual QString followFlightMode() const
Returns the flight mode which the vehicle will be for follow me.
virtual uint32_t highLatencyCustomModeTo32Bits(uint16_t hlCustomMode) const
Convert from HIGH_LATENCY2.custom_mode value to correct 32 bit value.
virtual QGCCameraManager * createCameraManager(Vehicle *vehicle) const
Creates vehicle camera manager.
virtual QMap< QString, FactGroup * > * factGroups()
Returns a pointer to a dictionary of firmware-specific FactGroups.
virtual void initializeVehicle(Vehicle *)
Called when Vehicle is first created to perform any firmware specific setup.
virtual bool MAV_CMD_DO_SET_MODE_is_supported() const
returns true if this flight stack supports MAV_CMD_DO_SET_MODE
virtual QString rtlFlightMode() const
Returns the flight mode for RTL.
virtual double maximumHorizontalSpeedMultirotorMetersSecond(Vehicle *) const
virtual void guidedModeLand(Vehicle *vehicle) const
Command vehicle to land at current location.
virtual bool sendHomePositionToVehicle() const
virtual bool isGuidedMode(const Vehicle *) const
Returns whether the vehicle is in guided mode or not.
virtual double minimumTakeoffAltitudeMeters(Vehicle *) const
virtual QString getHobbsMeter(Vehicle *vehicle) const
gets hobbs meter from autopilot. This should be reimplmeented for each firmware
This is the base class for firmware specific geofence managers.
void error(int errorCode, const QString &errorMsg)
Supports the Mavlink image transmission protocol (https://mavlink.io/en/services/image_transmission....
uint32_t flowImageIndex() const
void flowImageIndexChanged(uint32_t index)
void imageReady(const QImage &image)
bool activeJoystickEnabledForActiveVehicle() const
static JoystickManager * instance()
The link interface defines the interface for all links used to communicate with the ground station ap...
virtual bool isConnected() const =0
void writeBytesThreadSafe(const char *bytes, int length)
void statusTextMessageFromEvent(uint8_t compid, int severity, const QString &text, const QString &description)
static int getComponentId()
void mavlinkMessageStatus(int sysid, uint64_t totalSent, uint64_t totalReceived, uint64_t totalLoss, float lossPercent)
void messageReceived(LinkInterface *link, const mavlink_message_t &message)
static MAVLinkProtocol * instance()
Allows to configure a set of mavlink streams to a specific rate, and restore back to default.
Owns the COMMAND_LONG / COMMAND_INT send/retry/ack pipeline for a single Vehicle.
void sendCommandInt(int compId, MAV_CMD command, MAV_FRAME frame, bool showError, float param1, float param2, float param3, float param4, double param5, double param6, float param7)
static QString failureCodeToString(MavCmdResultFailureCode_t failureCode)
void commandResult(int vehicleId, int targetComponent, int command, int ackResult, int failureCode)
Emitted for every terminal ack that has no user-provided resultHandler.
void sendCommandIntWithHandler(const MavCmdAckHandlerInfo_t *ackHandlerInfo, int compId, MAV_CMD command, MAV_FRAME frame, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, double param5=0.0, double param6=0.0, float param7=0.0f)
void sendCommandWithHandler(const MavCmdAckHandlerInfo_t *ackHandlerInfo, int compId, MAV_CMD command, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, float param5=0.0f, float param6=0.0f, float param7=0.0f)
void handleCommandAck(const mavlink_message_t &message, const mavlink_command_ack_t &ack)
Process a COMMAND_ACK — match it to a pending entry and fire callbacks.
void sendCommandDelayed(int compId, MAV_CMD command, bool showError, int milliseconds, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, float param5=0.0f, float param6=0.0f, float param7=0.0f)
bool isPending(int targetCompId, MAV_CMD command) const
True if a matching (targetCompId, command) is already queued or awaiting ack.
static void showCommandAckError(const mavlink_command_ack_t &ack)
void sendCommand(int compId, MAV_CMD command, bool showError, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, float param5=0.0f, float param6=0.0f, float param7=0.0f)
int findEntryIndex(int targetCompId, MAV_CMD command) const
Index of a matching entry in the pending queue, or -1. Exposed for test use.
void sendCommandWithLambdaFallback(std::function< void()> lambda, int compId, MAV_CMD command, bool showError, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, float param5=0.0f, float param6=0.0f, float param7=0.0f)
Tracks per-component MAVLink message intervals and mediates SET_MESSAGE_INTERVAL commands plus MESSAG...
void handleMessageInterval(const mavlink_message_t &message)
void mavlinkMsgIntervalsChanged(uint8_t compid, uint16_t msgId, int32_t rate)
void setMessageRate(uint8_t compId, uint16_t msgId, int32_t rate)
int32_t getMessageRate(uint8_t compId, uint16_t msgId)
static MissionCommandTree * instance()
QString rawName(MAV_CMD command) const
Returns the raw name for the specified command.
int currentIndex(void) const
Current mission item as reported by MISSION_CURRENT.
static MultiVehicleManager * instance()
Vehicle * activeVehicle() const
void parameterReadyVehicleAvailableChanged(bool parameterReadyVehicleAvailable)
void activeVehicleChanged(Vehicle *activeVehicle)
Fact * getParameter(int componentId, const QString ¶mName)
void parametersReadyChanged(bool parametersReady)
static constexpr int defaultComponentId
void loadProgressChanged(float value)
void currentIndexChanged(int currentIndex)
void sendComplete(bool error)
void newMissionItemsAvailable(bool removeAllRequested)
const QList< MissionItem * > & missionItems(void)
void error(int errorCode, const QString &errorMsg)
static void sendPlanToVehicle(Vehicle *vehicle, const QString &filename)
const QVariantList & cameraList() const
void showAdvancedUIChanged(bool showAdvancedUI)
static QGCCorePlugin * instance()
static bool isMultiRotor(MAV_TYPE mavType)
static uint32_t highLatencyFailuresToMavSysStatus(mavlink_high_latency2_t &highLatency2)
static QString mavTypeToString(MAV_TYPE mavType)
static int motorCount(MAV_TYPE mavType, uint8_t frameType=0)
static bool isAirship(MAV_TYPE mavType)
@ CalibrationAPMPressureAirspeed
@ CalibrationAPMAccelSimple
@ CalibrationAPMCompassMot
@ CalibrationAPMPreFlight
static bool isSpacecraft(MAV_TYPE mavType)
static QString firmwareClassToString(FirmwareClass_t firmwareClass)
static bool isVTOL(MAV_TYPE mavType)
static QString firmwareVersionTypeToString(FIRMWARE_VERSION_TYPE firmwareVersionType)
static bool isFixedWing(MAV_TYPE mavType)
static QString mavResultToString(uint8_t result)
static bool isSub(MAV_TYPE mavType)
static QString vehicleClassToInternalString(VehicleClass_t vehicleClass)
static bool isRoverBoat(MAV_TYPE mavType)
The QGCMapCircle represents a circular area which can be displayed on a Map control.
static QGCPositionManager * instance()
QGeoCoordinate gcsPosition() const
void gcsPositionChanged(QGeoCoordinate gcsPosition)
This is a QGeoCoordinate within a QObject such that it can be used on a QmlObjectListModel.
static QGCPressure * instance()
void progressUpdate(float progress)
int count() const override final
Radio link telemetry decoded from MAVLINK_MSG_ID_RADIO_STATUS.
This is the base class for firmware specific rally point managers. A rally point manager is responsib...
void error(int errorCode, const QString &errorMsg)
void mavlinkMessageReceived(mavlink_message_t &message)
Coordinates MAV_CMD_REQUEST_MESSAGE workflows: per-component queueing, ack/message correlation,...
void handleReceivedMessage(const mavlink_message_t &message)
static QString failureCodeToString(RequestMessageResultHandlerFailureCode_t failureCode)
void requestMessage(RequestMessageResultHandler resultHandler, void *resultHandlerData, int compId, int messageId, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, float param5=0.0f)
void stop()
Clear pending state without firing callbacks (used during vehicle shutdown).
Provides access to all app settings.
static SettingsManager * instance()
VideoSettings * videoSettings() const
FlyViewSettings * flyViewSettings() const
MavlinkSettings * mavlinkSettings() const
void availableModesMonitorReceived(uint8_t seq)
bool messageTypeNone() const
bool messageTypeError() const
void handleHTMLEscapedTextMessage(MAV_COMPONENT componentid, MAV_SEVERITY severity, const QString &text, const QString &description)
bool messageTypeNormal() const
void newErrorMessage(QString message)
void resetErrorLevelMessages()
void mavlinkMessageReceived(const mavlink_message_t &message)
void messageCountChanged(uint32_t newCount)
void textMessageReceived(MAV_COMPONENT componentid, MAV_SEVERITY severity, QString text, QString description)
uint32_t messageCount() const
void newFormattedMessage(QString message)
QString formattedMessages() const
void messageTypeChanged()
bool messageTypeWarning() const
Class which represents sensor info from the SYS_STATUS mavlink message.
bool mavlinkMessageReceived(const mavlink_message_t &message)
Coordinates the three terrain-query workflows attached to a Vehicle:
void updateAltAboveTerrain()
void roiWithTerrain(const QGeoCoordinate &coord)
void sendROICommand(const QGeoCoordinate &coord, MAV_FRAME frame, float altitude)
void doSetHomeWithTerrain(const QGeoCoordinate &coord)
Fact _headingFromHomeFact
Fact * altitudeRelative()
Fact _altitudeRelativeFact
void handleMessage(Vehicle *vehicle, const mavlink_message_t &message) override
Allows a FactGroup to parse incoming messages and fill in values.
void updateRCRSSI(uint8_t rssi)
Fact _missionItemIndexFact
Fact _altitudeTuningSetpointFact
Fact _headingToNextWPFact
bool _altitudeMessageAvailable
void bindToGps(VehicleGPSFactGroup *gps1, VehicleGPSFactGroup *gps2)
WeakLinkInterfacePtr primaryLink() const
void mavlinkMessageReceived(LinkInterface *link, const mavlink_message_t &message)
bool containsLink(LinkInterface *link)
void update(mavlink_obstacle_distance_t *message)
Per-vehicle signing facade. Owns the wiring between Vehicle and the active SigningController (which l...
bool changeHeading() const
bool pauseVehicle() const
Q_INVOKABLE void triggerSimpleCamera(void)
Trigger camera using MAV_CMD_DO_DIGICAM_CONTROL command.
bool isInitialConnectComplete() const
Q_INVOKABLE void guidedModeChangeAltitude(double altitudeChange, bool pauseVehicle)
void _setLanding(bool landing)
Vehicle(LinkInterface *link, int vehicleId, int defaultComponentId, MAV_AUTOPILOT firmwareType, MAV_TYPE vehicleType, QObject *parent=nullptr)
Q_INVOKABLE void motorInterlock(bool enable)
Command vehicle to Enable/Disable Motor Interlock.
Q_INVOKABLE void virtualTabletJoystickValue(double roll, double pitch, double yaw, double thrust)
int32_t getMessageRate(uint8_t compId, uint16_t msgId)
VehicleDistanceSensorFactGroup * _distanceSensorFactGroup
TerrainProtocolHandler * _terrainProtocolHandler
void firmwareTypeChanged()
QGCMAVLink::VehicleClass_t vehicleClass(void) const
void setInitialGCSPressure(qreal pressure)
Q_INVOKABLE void flashBootloader()
void sensorsPresentBitsChanged(int sensorsPresentBits)
void defaultHoverSpeedChanged(double hoverSpeed)
friend class InitialConnectStateMachine
const QString _vibrationFactGroupName
bool _multirotor_speed_limits_available
void gcsControlStatusChanged()
void defaultCruiseSpeedChanged(double cruiseSpeed)
bool messageTypeError() const
const QString _gpsFactGroupName
FactGroup * localPositionFactGroup()
void haveMRSpeedLimChanged()
FactGroup * vibrationFactGroup()
void sendMavCommandWithLambdaFallback(std::function< void()> lambda, int compId, MAV_CMD command, bool showError, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, float param5=0.0f, float param6=0.0f, float param7=0.0f)
BatteryFactGroupListModel * _batteryFactGroupListModel
void sendMavCommand(int compId, MAV_CMD command, bool showError, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, float param5=0.0f, float param6=0.0f, float param7=0.0f)
VehicleLocalPositionFactGroup * _localPositionFactGroup
const QString _hygrometerFactGroupName
void messagesLostChanged()
Q_INVOKABLE void rebootVehicle()
Reboot vehicle.
FactGroup * gpsAggregateFactGroup()
VehicleRPMFactGroup * _rpmFactGroup
const QString _localPositionFactGroupName
void vtolInFwdFlightChanged(bool vtolInFwdFlight)
QString missionFlightMode() const
void readyToFlyAvailableChanged(bool readyToFlyAvailable)
void forceInitialPlanRequestComplete()
void isROIEnabledChanged()
Q_INVOKABLE void guidedModeOrbit(const QGeoCoordinate ¢erCoord, double radius, double amslAltitude)
const QString _terrainFactGroupName
const QString _temperatureFactGroupName
void _offlineVehicleTypeSettingChanged(QVariant varVehicleType)
Q_INVOKABLE void guidedModeTakeoff(double altitudeRelative)
Command vehicle to takeoff from current location.
Q_INVOKABLE void sendGripperAction(GRIPPER_ACTIONS gripperOption)
QString flightMode() const
static QString mavCmdResultFailureCodeToString(MavCmdResultFailureCode_t failureCode)
QString stabilizedFlightMode() const
const QVariantList & staticCameraList() const
void requestOperatorControlReceived(int sysIdRequestingControl, int allowTakeover, int requestTimeoutSecs)
Q_INVOKABLE QVariant expandedToolbarIndicatorSource(const QString &indicatorName)
void sendJoystickAuxRcOverrideThreadSafe(const std::array< uint16_t, kAuxRcOverrideChannelCount > &channelValues, const std::array< bool, kAuxRcOverrideChannelCount > &channelEnabled, bool useRcOverride)
void setActuatorsMetadata(uint8_t compid, const QString &metadataJsonFileName)
void setSoloFirmware(bool soloFirmware)
void requestDataStream(MAV_DATA_STREAM stream, uint16_t rate, bool sendMultiple=true)
FactGroup * rpmFactGroup()
QGeoCoordinate homePosition()
const QString _estimatorStatusFactGroupName
const QString _radioStatusFactGroupName
QString vehicleImageOutline() const
MissionManager * _missionManager
VehicleLocalPositionSetpointFactGroup * _localPositionSetpointFactGroup
void textMessageReceived(int sysid, int componentid, int severity, QString text, QString description)
void initialPlanRequestCompleteChanged(bool initialPlanRequestComplete)
Q_INVOKABLE double minimumEquivalentAirspeed()
const QString _clockFactGroupName
Q_INVOKABLE void stopGuidedModeROI()
void firmwareCustomVersionChanged()
QString pauseFlightMode() const
QString prearmError() const
EscStatusFactGroupListModel * _escStatusFactGroupListModel
Q_INVOKABLE void guidedModeROI(const QGeoCoordinate ¢erCoord)
const QString _efiFactGroupName
void inFwdFlightChanged()
void flyingChanged(bool flying)
void setFirmwarePluginInstanceData(FirmwarePluginInstanceData *firmwarePluginInstanceData)
Q_INVOKABLE double maximumHorizontalSpeedMultirotorMetersSecond()
void sendMessageMultiple(mavlink_message_t message)
void capabilityBitsChanged(uint64_t capabilityBits)
bool messageTypeNone() const
void _setHomePosition(QGeoCoordinate &homeCoord)
VehicleClockFactGroup * _clockFactGroup
uint64_t capabilityBits() const
Q_INVOKABLE void abortLanding(double climbOutAltitude)
Command vehicle to abort landing.
void setGuidedMode(bool guidedMode)
void readyToFlyChanged(bool readyToFy)
QString firmwareVersionTypeString() const
QString landFlightMode() const
static void showCommandAckError(const mavlink_command_ack_t &ack)
void newFormattedMessage(QString formattedMessage)
MAV_TYPE vehicleType() const
VehicleLinkManager * vehicleLinkManager()
void cameraManagerChanged()
Q_INVOKABLE void sendParamMapRC(const QString ¶mName, double scale, double centerValue, int tuningID, double minValue, double maxValue)
Sends PARAM_MAP_RC message to vehicle.
HealthAndArmingCheckReport * healthAndArmingCheckReport()
void armedChanged(bool armed)
void firmwareVersionChanged()
FactGroup * distanceSensorFactGroup()
void logEntry(uint32_t time_utc, uint32_t size, uint16_t id, uint16_t num_logs, uint16_t last_log_num)
void sendControlRequestAllowedChanged(bool sendControlRequestAllowed)
FactGroup * generatorFactGroup()
void rcChannelsRawChanged(QVector< int > channelValues)
FirmwarePlugin * firmwarePlugin()
Provides access to the Firmware Plugin for this Vehicle.
void sendMavCommandInt(int compId, MAV_CMD command, MAV_FRAME frame, bool showError, float param1, float param2, float param3, float param4, double param5, double param6, float param7)
Q_INVOKABLE double minimumTakeoffAltitudeMeters()
InitialConnectStateMachine * _initialConnectStateMachine
void sensorsParametersResetAck(bool success)
void sendMavCommandDelayed(int compId, MAV_CMD command, bool showError, int milliseconds, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, float param5=0.0f, float param6=0.0f, float param7=0.0f)
const QString _distanceSensorFactGroupName
Q_INVOKABLE double maximumEquivalentAirspeed()
@ ModeAltitudeAndAirspeed
@ ModeVelocityAndPosition
void setPrearmError(const QString &prearmError)
VehicleVibrationFactGroup * _vibrationFactGroup
void setFirmwareCustomVersion(int majorVersion, int minorVersion, int patchVersion)
Q_INVOKABLE void startTimerRevertAllowTakeover()
VehicleGeneratorFactGroup * _generatorFactGroup
const QString _generatorFactGroupName
void messagesSentChanged()
Q_INVOKABLE void sendPlan(QString planFile)
bool vtolInFwdFlight() const
Q_INVOKABLE void startMission()
bool isMavCommandPending(int targetCompId, MAV_CMD command)
isMavCommandPending Query whether the specified MAV_CMD is in queue to be sent or has already been se...
void capabilitiesKnownChanged(bool capabilitiesKnown)
Q_INVOKABLE void requestOperatorControl(bool allowOverride, int requestTimeoutSecs=0)
void rcChannelsClampedChanged(QVector< int > channelValues)
VehicleEstimatorStatusFactGroup * _estimatorStatusFactGroup
VehicleTemperatureFactGroup * _temperatureFactGroup
bool soloFirmware() const
void coordinateChanged(QGeoCoordinate coordinate)
QString vehicleImageOpaque() const
float _altitudeTuningOffset
Q_INVOKABLE void setPIDTuningTelemetryMode(PIDTuningTelemetryMode mode)
void mavlinkLogData(Vehicle *vehicle, uint8_t target_system, uint8_t target_component, uint16_t sequence, uint8_t first_message, QByteArray data, bool acked)
Q_INVOKABLE void emergencyStop()
Command vehicle to kill all motors no matter what state.
void updateFlightDistance(double distance)
const QString _gpsAggregateFactGroupName
Q_INVOKABLE bool guidedModeGotoLocation(const QGeoCoordinate &gotoCoord, double forwardFlightLoiterRadius=0.0f)
void pairRX(int rxType, int rxSubType)
const QString _setpointFactGroupName
Q_INVOKABLE void setCurrentMissionSequence(int seq)
Alter the current mission item on the vehicle.
FactGroup * gps2FactGroup()
void toolIndicatorsChanged()
void sensorsUnhealthyBitsChanged(int sensorsUnhealthyBits)
void landingChanged(bool landing)
bool sendMessageOnLinkThreadSafe(LinkInterface *link, mavlink_message_t message)
VehicleWindFactGroup * _windFactGroup
const QString _rpmFactGroupName
FactGroup * hygrometerFactGroup()
static const MAV_AUTOPILOT MAV_AUTOPILOT_TRACK
Q_INVOKABLE void startTakeoff()
Q_INVOKABLE void resetAllMessages()
VehicleHygrometerFactGroup * _hygrometerFactGroup
void setFlightMode(const QString &flightMode)
bool messageTypeWarning() const
Q_INVOKABLE void sendCommand(int compId, int command, bool showError, double param1=0.0, double param2=0.0, double param3=0.0, double param4=0.0, double param5=0.0, double param6=0.0, double param7=0.0)
Same as sendMavCommand but available from Qml.
void loadProgressChanged(float value)
QString smartRTLFlightMode() const
QString followFlightMode() const
bool _fixed_wing_airspeed_limits_available
Q_INVOKABLE void motorTest(int motor, int percent, int timeoutSecs, bool showError)
void mavlinkMessageReceived(const mavlink_message_t &message)
void setMessageRate(uint8_t compId, uint16_t msgId, int32_t rate)
Q_INVOKABLE void resetCounters()
< Flight mode vehicle is in while performing goto
const QVariantList & toolIndicators()
void _offlineFirmwareTypeSettingChanged(QVariant varFirmwareType)
FactGroup * localPositionSetpointFactGroup()
Q_INVOKABLE void guidedModeChangeEquivalentAirspeedMetersSecond(double airspeed)
QmlObjectListModel * escs()
void guidedModeChanged(bool guidedMode)
FactGroup * efiFactGroup()
void setEventsMetadata(uint8_t compid, const QString &metadataJsonFileName)
QString formattedMessages() const
int _findMavCommandListEntryIndex(int targetCompId, MAV_CMD command)
Test-only helper: forwards to MavCommandQueue::findEntryIndex.
QObject * sysStatusSensorInfo()
QString motorDetectionFlightMode() const
Q_INVOKABLE void resetErrorLevelMessages()
void orbitActiveChanged(bool orbitActive)
bool messageTypeNormal() const
void allSensorsHealthyChanged(bool allSensorsHealthy)
Q_INVOKABLE void guidedModeRTL(bool smartRTL)
Command vehicle to return to launch.
VehicleGPS2FactGroup * _gps2FactGroup
void trackFirmwareVehicleTypeChanges(void)
Q_INVOKABLE void landingGearDeploy()
Command vichecle to deploy landing gear.
void armedPositionChanged()
VehicleEFIFactGroup * _efiFactGroup
static QString requestMessageResultHandlerFailureCodeToString(RequestMessageResultHandlerFailureCode_t failureCode)
RemoteIDManager * _remoteIDManager
Q_INVOKABLE void doSetHome(const QGeoCoordinate &coord)
Set home from flight map coordinate.
void stopUAVCANBusConfig(void)
void soloFirmwareChanged(bool soloFirmware)
uint32_t flowImageIndex() const
void homePositionChanged(const QGeoCoordinate &homePosition)
QMap< uint8_t, uint8_t > _lowestBatteryChargeStateAnnouncedMap
FactGroup * radioStatusFactGroup()
Q_INVOKABLE void pauseVehicle()
void stopTrackingFirmwareVehicleTypeChanges(void)
FactGroup * windFactGroup()
void flightModesChanged()
const QString _gps2FactGroupName
FactGroup * temperatureFactGroup()
Q_INVOKABLE void closeVehicle()
Removes the vehicle from the system.
void flightModeChanged(const QString &flightMode)
void flowImageIndexChanged()
void roiCoordChanged(const QGeoCoordinate ¢erCoord)
Q_INVOKABLE void clearAllParamMapRC(void)
Clears all PARAM_MAP_RC settings from vehicle.
void messageTypeChanged()
FactGroup * estimatorStatusFactGroup()
Q_INVOKABLE void setEstimatorOrigin(const QGeoCoordinate ¢erCoord)
void setVtolInFwdFlight(bool vtolInFwdFlight)
Q_INVOKABLE void guidedModeChangeGroundSpeedMetersSecond(double groundspeed)
int defaultComponentId() const
void setInitialGCSTemperature(qreal temperature)
void mavlinkStatusChanged()
MAVLinkLogManager * mavlinkLogManager() const
Q_INVOKABLE void clearMessages()
FactGroup * setpointFactGroup()
void sendJoystickDataThreadSafe(float roll, float pitch, float yaw, float thrust, quint16 buttons, quint16 buttons2, float pitchExtension, float rollExtension, float aux1, float aux2, float aux3, float aux4, float aux5, float aux6)
QmlObjectListModel * cameraTriggerPoints()
GeoFenceManager * _geoFenceManager
bool flightModeSetAvailable()
ParameterManager * parameterManager()
VehicleGPSFactGroup * _gpsFactGroup
void sensorsHealthBitsChanged(int sensorsHealthBits)
void _setFlying(bool flying)
Q_INVOKABLE void guidedModeChangeHeading(const QGeoCoordinate &headingCoord)
QString takeControlFlightMode() const
void messagesReceivedChanged()
const QString _localPositionSetpointFactGroupName
void setOfflineEditingDefaultComponentId(int defaultComponentId)
Sets the default component id for an offline editing vehicle.
void setFirmwareVersion(int majorVersion, int minorVersion, int patchVersion, FIRMWARE_VERSION_TYPE versionType=FIRMWARE_VERSION_TYPE_OFFICIAL)
QString rtlFlightMode() const
void requestMessage(RequestMessageResultHandler resultHandler, void *resultHandlerData, int compId, int messageId, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, float param5=0.0f)
QGeoCoordinate coordinate()
void startCalibration(QGCMAVLink::CalibrationType calType)
QVector< int > _servoOutputRawValues
QString firmwareTypeString() const
FactGroup * clockFactGroup()
void stopCalibration(bool showError)
void messageCountChanged()
friend class VehicleLinkManager
QmlObjectListModel * batteries()
void haveFWSpeedLimChanged()
RallyPointManager * _rallyPointManager
void startUAVCANBusConfig(void)
RadioStatusFactGroup * _radioStatusFactGroup
QString gotoFlightMode() const
void sendMavCommandIntWithHandler(const MavCmdAckHandlerInfo_t *ackHandlerInfo, int compId, MAV_CMD command, MAV_FRAME frame, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, double param5=0.0f, double param6=0.0f, float param7=0.0f)
Q_INVOKABLE void landingGearRetract()
Command vichecle to retract landing gear.
VehicleSupports * supports()
const QString _windFactGroupName
void mavCommandResult(int vehicleId, int targetComponent, int command, int ackResult, int failureCode)
VehicleGPSAggregateFactGroup * _gpsAggregateFactGroup
FactGroup * gpsFactGroup()
void sensorsEnabledBitsChanged(int sensorsEnabledBits)
class FirmwarePluginInstanceData * firmwarePluginInstanceData()
VehicleSetpointFactGroup * _setpointFactGroup
Q_INVOKABLE int versionCompare(const QString &compare) const
Used to check if running current version is equal or higher than the one being compared.
TerrainFactGroup * _terrainFactGroup
Q_INVOKABLE void forceArm()
void requiresGpsFixChanged()
void setArmed(bool armed, bool showError)
QStringList flightModes()
void mavlinkMsgIntervalsChanged(uint8_t compid, uint16_t msgId, int32_t rate)
FactGroup * terrainFactGroup()
void mavlinkSerialControl(uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, QByteArray data)
Q_INVOKABLE QString vehicleClassInternalName() const
VehicleLinkManager * _vehicleLinkManager
void servoOutputsChanged(QVector< int > servoValues)
TerrainQueryCoordinator * _terrainQueryCoordinator
void prearmErrorChanged(const QString &prearmError)
void vehicleTypeChanged()
Q_INVOKABLE void guidedModeLand()
Command vehicle to land at current location.
void sendMavCommandWithHandler(const MavCmdAckHandlerInfo_t *ackHandlerInfo, int compId, MAV_CMD command, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, float param5=0.0f, float param6=0.0f, float param7=0.0f)
Sends the command and calls the callback with the result.
StandardModes * _standardModes
friend class GimbalController
QString vehicleTypeString() const
void logData(uint32_t ofs, uint16_t id, uint8_t count, const uint8_t *data)
static VideoManager * instance()
Q_INVOKABLE void stopVideo()
static constexpr const char * videoSourceUDPH264
static constexpr const char * videoDisabled
bool fuzzyCompare(double value1, double value2)
Returns true if the two values are equal or close. Correctly handles 0 and NaN values.
void showCriticalVehicleMessage(const QString &message)
void showAppMessage(const QString &message, const QString &title)
Modal application message. Queued if the UI isn't ready yet.
Callback info bundle for sendMavCommandWithHandler.
MavCmdResultHandler resultHandler
nullptr for no handler
MavCmdResultFailureCode_t
@ MavCmdResultFailureDuplicateCommand
Unable to send command since duplicate is already being waited on for response.
@ MavCmdResultCommandResultOnly
commandResult specifies full success/fail info
@ MavCmdResultFailureNoResponseToCommand
No response from vehicle to command.
RequestMessageResultHandlerFailureCode_t