Newer
Older
Lorenz Meier
committed
void Vehicle::_handleCommandLong(mavlink_message_t& message)
{
#ifdef NO_SERIAL_LINK
// If not using serial link, bail out.
Lorenz Meier
committed
mavlink_command_long_t cmd;
mavlink_msg_command_long_decode(&message, &cmd);
switch (cmd.command) {
// Other component on the same system
// requests that QGC frees up the serial port of the autopilot
case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
if (cmd.param6 > 0) {
// disconnect the USB link if its a direct connection to a Pixhawk
for (int i = 0; i < _links.length(); i++) {
SerialLink *sl = qobject_cast<SerialLink*>(_links.at(i));
if (sl && sl->getSerialConfig()->usbDirect()) {
qDebug() << "Disconnecting:" << _links.at(i)->getName();
qgcApp()->toolbox()->linkManager()->disconnectLink(_links.at(i));
Lorenz Meier
committed
}
}
Lorenz Meier
committed
break;
}
Lorenz Meier
committed
}
void Vehicle::_handleExtendedSysState(mavlink_message_t& message)
{
mavlink_extended_sys_state_t extendedState;
mavlink_msg_extended_sys_state_decode(&message, &extendedState);
switch (extendedState.landed_state) {
case MAV_LANDED_STATE_ON_GROUND:
_setFlying(false);
_setLanding(false);
case MAV_LANDED_STATE_TAKEOFF:
_setFlying(true);
_setLanding(false);
break;
case MAV_LANDED_STATE_LANDING:
_setFlying(true);
_setLanding(true);
break;
default:
break;
bool vtolInFwdFlight = extendedState.vtol_state == MAV_VTOL_STATE_FW;
if (vtolInFwdFlight != _vtolInFwdFlight) {
_vtolInFwdFlight = vtolInFwdFlight;
emit vtolInFwdFlightChanged(vtolInFwdFlight);
}
void Vehicle::_handleVibration(mavlink_message_t& message)
{
mavlink_vibration_t vibration;
mavlink_msg_vibration_decode(&message, &vibration);
_vibrationFactGroup.xAxis()->setRawValue(vibration.vibration_x);
_vibrationFactGroup.yAxis()->setRawValue(vibration.vibration_y);
_vibrationFactGroup.zAxis()->setRawValue(vibration.vibration_z);
_vibrationFactGroup.clipCount1()->setRawValue(vibration.clipping_0);
_vibrationFactGroup.clipCount2()->setRawValue(vibration.clipping_1);
_vibrationFactGroup.clipCount3()->setRawValue(vibration.clipping_2);
}
void Vehicle::_handleWindCov(mavlink_message_t& message)
{
mavlink_wind_cov_t wind;
mavlink_msg_wind_cov_decode(&message, &wind);
float direction = qRadiansToDegrees(qAtan2(wind.wind_y, wind.wind_x));
float speed = qSqrt(qPow(wind.wind_x, 2) + qPow(wind.wind_y, 2));
_windFactGroup.direction()->setRawValue(direction);
_windFactGroup.speed()->setRawValue(speed);
_windFactGroup.verticalSpeed()->setRawValue(0);
}
Gus Grubba
committed
#if !defined(NO_ARDUPILOT_DIALECT)
void Vehicle::_handleWind(mavlink_message_t& message)
{
mavlink_wind_t wind;
mavlink_msg_wind_decode(&message, &wind);
_windFactGroup.direction()->setRawValue(wind.direction);
_windFactGroup.speed()->setRawValue(wind.speed);
_windFactGroup.verticalSpeed()->setRawValue(wind.speed_z);
}
Gus Grubba
committed
#endif
void Vehicle::_handleSysStatus(mavlink_message_t& message)
{
mavlink_sys_status_t sysStatus;
mavlink_msg_sys_status_decode(&message, &sysStatus);
if (sysStatus.current_battery == -1) {
_batteryFactGroup.current()->setRawValue(VehicleBatteryFactGroup::_currentUnavailable);
} else {
// Current is in Amps, current_battery is 10 * milliamperes (1 = 10 milliampere)
_batteryFactGroup.current()->setRawValue((float)sysStatus.current_battery / 100.0f);
}
if (sysStatus.voltage_battery == UINT16_MAX) {
_batteryFactGroup.voltage()->setRawValue(VehicleBatteryFactGroup::_voltageUnavailable);
} else {
_batteryFactGroup.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)
_batteryFactGroup.instantPower()->setRawValue((float)(sysStatus.current_battery*sysStatus.voltage_battery)/(100000.0));
}
_batteryFactGroup.percentRemaining()->setRawValue(sysStatus.battery_remaining);
if (sysStatus.battery_remaining > 0) {
if (sysStatus.battery_remaining < _settingsManager->appSettings()->batteryPercentRemainingAnnounce()->rawValue().toInt() &&
sysStatus.battery_remaining < _lastAnnouncedLowBatteryPercent) {
_say(QString(tr("%1 low battery: %2 percent remaining")).arg(_vehicleIdSpeech()).arg(sysStatus.battery_remaining));
_lastAnnouncedLowBatteryPercent = sysStatus.battery_remaining;
_onboardControlSensorsPresent = sysStatus.onboard_control_sensors_present;
_onboardControlSensorsEnabled = sysStatus.onboard_control_sensors_enabled;
_onboardControlSensorsHealth = sysStatus.onboard_control_sensors_health;
uint32_t newSensorsUnhealthy = _onboardControlSensorsEnabled & ~_onboardControlSensorsHealth;
if (newSensorsUnhealthy != _onboardControlSensorsUnhealthy) {
_onboardControlSensorsUnhealthy = newSensorsUnhealthy;
emit unhealthySensorsChanged();
}
1136
1137
1138
1139
1140
1141
1142
1143
1144
1145
1146
1147
1148
1149
1150
1151
1152
1153
1154
1155
1156
1157
1158
1159
1160
1161
1162
1163
1164
1165
1166
}
void Vehicle::_handleBatteryStatus(mavlink_message_t& message)
{
mavlink_battery_status_t bat_status;
mavlink_msg_battery_status_decode(&message, &bat_status);
if (bat_status.temperature == INT16_MAX) {
_batteryFactGroup.temperature()->setRawValue(VehicleBatteryFactGroup::_temperatureUnavailable);
} else {
_batteryFactGroup.temperature()->setRawValue((double)bat_status.temperature / 100.0);
}
if (bat_status.current_consumed == -1) {
_batteryFactGroup.mahConsumed()->setRawValue(VehicleBatteryFactGroup::_mahConsumedUnavailable);
} else {
_batteryFactGroup.mahConsumed()->setRawValue(bat_status.current_consumed);
}
int cellCount = 0;
for (int i=0; i<10; i++) {
if (bat_status.voltages[i] != UINT16_MAX) {
cellCount++;
}
}
if (cellCount == 0) {
cellCount = -1;
}
_batteryFactGroup.cellCount()->setRawValue(cellCount);
}
void Vehicle::_setHomePosition(QGeoCoordinate& homeCoord)
{
if (homeCoord != _homePosition) {
_homePosition = homeCoord;
emit homePositionChanged(_homePosition);
}
}
void Vehicle::_handleHomePosition(mavlink_message_t& message)
{
mavlink_home_position_t homePos;
mavlink_msg_home_position_decode(&message, &homePos);
QGeoCoordinate newHomePosition (homePos.latitude / 10000000.0,
homePos.longitude / 10000000.0,
homePos.altitude / 1000.0);
}
void Vehicle::_handleHeartbeat(mavlink_message_t& message)
{
if (message.compid != _defaultComponentId) {
return;
}
mavlink_msg_heartbeat_decode(&message, &heartbeat);
bool newArmed = heartbeat.base_mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY;
if (_armed != newArmed) {
_armed = newArmed;
emit armedChanged(_armed);
// We are transitioning to the armed state, begin tracking trajectory points for the map
if (_armed) {
_mapTrajectoryStart();
_clearCameraTriggerPoints();
// Also handle Video Streaming
if(_settingsManager->videoSettings()->disableWhenDisarmed()->rawValue().toBool()) {
_settingsManager->videoSettings()->streamEnabled()->setRawValue(false);
qgcApp()->toolbox()->videoManager()->videoReceiver()->stop();
}
}
if (heartbeat.base_mode != _base_mode || heartbeat.custom_mode != _custom_mode) {
QString previousFlightMode;
if (_base_mode != 0 || _custom_mode != 0){
// Vehicle is initialized with _base_mode=0 and _custom_mode=0. Don't pass this to flightMode() since it will complain about
// bad modes while unit testing.
previousFlightMode = flightMode();
}
_base_mode = heartbeat.base_mode;
_custom_mode = heartbeat.custom_mode;
if (previousFlightMode != flightMode()) {
emit flightModeChanged(flightMode());
}
void Vehicle::_handleRadioStatus(mavlink_message_t& message)
{
Lorenz Meier
committed
//-- Process telemetry status message
mavlink_radio_status_t rstatus;
mavlink_msg_radio_status_decode(&message, &rstatus);
Lorenz Meier
committed
int rssi = rstatus.rssi;
int remrssi = rstatus.remrssi;
int lnoise = (int)(int8_t)rstatus.noise;
int rnoise = (int)(int8_t)rstatus.remnoise;
//-- 3DR Si1k radio needs rssi fields to be converted to dBm
if (message.sysid == '3' && message.compid == 'D') {
/* Per the Si1K datasheet figure 23.25 and SI AN474 code
* samples the relationship between the RSSI register
* and received power is as follows:
*
* 10
* inputPower = rssi * ------ 127
* 19
*
* Additionally limit to the only realistic range [-120,0] dBm
*/
rssi = qMin(qMax(qRound(static_cast<qreal>(rssi) / 1.9 - 127.0), - 120), 0);
remrssi = qMin(qMax(qRound(static_cast<qreal>(remrssi) / 1.9 - 127.0), - 120), 0);
} else {
rssi = (int)(int8_t)rstatus.rssi;
remrssi = (int)(int8_t)rstatus.remrssi;
1260
1261
1262
1263
1264
1265
1266
1267
1268
1269
1270
1271
1272
1273
1274
1275
1276
1277
1278
1279
1280
1281
}
//-- Check for changes
if(_telemetryLRSSI != rssi) {
_telemetryLRSSI = rssi;
emit telemetryLRSSIChanged(_telemetryLRSSI);
}
if(_telemetryRRSSI != remrssi) {
_telemetryRRSSI = remrssi;
emit telemetryRRSSIChanged(_telemetryRRSSI);
}
if(_telemetryRXErrors != rstatus.rxerrors) {
_telemetryRXErrors = rstatus.rxerrors;
emit telemetryRXErrorsChanged(_telemetryRXErrors);
}
if(_telemetryFixed != rstatus.fixed) {
_telemetryFixed = rstatus.fixed;
emit telemetryFixedChanged(_telemetryFixed);
}
if(_telemetryTXBuffer != rstatus.txbuf) {
_telemetryTXBuffer = rstatus.txbuf;
emit telemetryTXBufferChanged(_telemetryTXBuffer);
}
if(_telemetryLNoise != lnoise) {
_telemetryLNoise = lnoise;
emit telemetryLNoiseChanged(_telemetryLNoise);
}
if(_telemetryRNoise != rnoise) {
_telemetryRNoise = rnoise;
emit telemetryRNoiseChanged(_telemetryRNoise);
}
}
1292
1293
1294
1295
1296
1297
1298
1299
1300
1301
1302
1303
1304
1305
1306
1307
1308
1309
1310
1311
1312
1313
1314
1315
1316
1317
1318
1319
1320
1321
1322
1323
1324
1325
1326
1327
1328
1329
1330
1331
1332
1333
1334
1335
1336
1337
1338
1339
1340
1341
1342
1343
1344
1345
1346
1347
1348
1349
1350
1351
1352
1353
1354
1355
1356
void Vehicle::_handleRCChannels(mavlink_message_t& message)
{
mavlink_rc_channels_t channels;
mavlink_msg_rc_channels_decode(&message, &channels);
uint16_t* _rgChannelvalues[cMaxRcChannels] = {
&channels.chan1_raw,
&channels.chan2_raw,
&channels.chan3_raw,
&channels.chan4_raw,
&channels.chan5_raw,
&channels.chan6_raw,
&channels.chan7_raw,
&channels.chan8_raw,
&channels.chan9_raw,
&channels.chan10_raw,
&channels.chan11_raw,
&channels.chan12_raw,
&channels.chan13_raw,
&channels.chan14_raw,
&channels.chan15_raw,
&channels.chan16_raw,
&channels.chan17_raw,
&channels.chan18_raw,
};
int pwmValues[cMaxRcChannels];
for (int i=0; i<cMaxRcChannels; i++) {
uint16_t channelValue = *_rgChannelvalues[i];
if (i < channels.chancount) {
pwmValues[i] = channelValue == UINT16_MAX ? -1 : channelValue;
} else {
pwmValues[i] = -1;
}
}
emit remoteControlRSSIChanged(channels.rssi);
emit rcChannelsChanged(channels.chancount, pwmValues);
}
void Vehicle::_handleRCChannelsRaw(mavlink_message_t& message)
{
// We handle both RC_CHANNLES and RC_CHANNELS_RAW since different firmware will only
// send one or the other.
mavlink_rc_channels_raw_t channels;
mavlink_msg_rc_channels_raw_decode(&message, &channels);
uint16_t* _rgChannelvalues[cMaxRcChannels] = {
&channels.chan1_raw,
&channels.chan2_raw,
&channels.chan3_raw,
&channels.chan4_raw,
&channels.chan5_raw,
&channels.chan6_raw,
&channels.chan7_raw,
&channels.chan8_raw,
};
int pwmValues[cMaxRcChannels];
int channelCount = 0;
for (int i=0; i<cMaxRcChannels; i++) {
pwmValues[i] = -1;
}
for (int i=0; i<8; i++) {
uint16_t channelValue = *_rgChannelvalues[i];
if (channelValue == UINT16_MAX) {
pwmValues[i] = -1;
} else {
pwmValues[i] = channelValue;
}
}
for (int i=9; i<18; i++) {
pwmValues[i] = -1;
}
emit remoteControlRSSIChanged(channels.rssi);
emit rcChannelsChanged(channelCount, pwmValues);
}
void Vehicle::_handleScaledPressure(mavlink_message_t& message) {
mavlink_scaled_pressure_t pressure;
mavlink_msg_scaled_pressure_decode(&message, &pressure);
_temperatureFactGroup.temperature1()->setRawValue(pressure.temperature / 100.0);
}
void Vehicle::_handleScaledPressure2(mavlink_message_t& message) {
mavlink_scaled_pressure2_t pressure;
mavlink_msg_scaled_pressure2_decode(&message, &pressure);
_temperatureFactGroup.temperature2()->setRawValue(pressure.temperature / 100.0);
}
void Vehicle::_handleScaledPressure3(mavlink_message_t& message) {
mavlink_scaled_pressure3_t pressure;
mavlink_msg_scaled_pressure3_decode(&message, &pressure);
_temperatureFactGroup.temperature3()->setRawValue(pressure.temperature / 100.0);
}
bool Vehicle::_containsLink(LinkInterface* link)
{
}
void Vehicle::_addLink(LinkInterface* link)
{
if (!_containsLink(link)) {
qCDebug(VehicleLog) << "_addLink:" << QString("%1").arg((ulong)link, 0, 16);
_links += link;
_updatePriorityLink();
connect(_toolbox->linkManager(), &LinkManager::linkInactive, this, &Vehicle::_linkInactiveOrDeleted);
connect(_toolbox->linkManager(), &LinkManager::linkDeleted, this, &Vehicle::_linkInactiveOrDeleted);
connect(link, &LinkInterface::highLatencyChanged, this, &Vehicle::_updateHighLatencyLink);
void Vehicle::_linkInactiveOrDeleted(LinkInterface* link)
qCDebug(VehicleLog) << "_linkInactiveOrDeleted linkCount" << _links.count();
_updatePriorityLink();
// Make sure to not send this more than one time
_allLinksInactiveSent = true;
emit allLinksInactive(this);
bool Vehicle::sendMessageOnLink(LinkInterface* link, mavlink_message_t message)
{
if (!link || !_links.contains(link) || !link->isConnected()) {
return false;
}
emit _sendMessageOnLinkOnThread(link, message);
return true;
}
void Vehicle::_sendMessageOnLink(LinkInterface* link, mavlink_message_t message)
{
// Make sure this is still a good link
if (!link || !_links.contains(link) || !link->isConnected()) {
return;
}
#if 0
// Leaving in for ease in Mav 2.0 testing
mavlink_status_t* mavlinkStatus = mavlink_get_channel_status(link->mavlinkChannel());
qDebug() << "_sendMessageOnLink" << mavlinkStatus << link->mavlinkChannel() << mavlinkStatus->flags << message.magic;
#endif
// Give the plugin a chance to adjust
_firmwarePlugin->adjustOutgoingMavlinkMessage(this, link, &message);
// Write message into buffer, prepending start sign
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
int len = mavlink_msg_to_send_buffer(buffer, &message);
link->writeBytesSafe((const char*)buffer, len);
_messagesSent++;
emit messagesSentChanged();
void Vehicle::_updatePriorityLink(void)
LinkInterface* newPriorityLink = NULL;
// Note that this routine specificallty does not clear _priorityLink when there are no links remaining.
// By doing this we hold a reference on the last link as the Vehicle shuts down. Thus preventing shutdown
// ordering NULL pointer crashes where priorityLink() is still called during shutdown sequence.
for (int i=0; i<_links.count(); i++) {
LinkInterface* link = _links[i];
if (link->isConnected()) {
SerialLink* pSerialLink = qobject_cast<SerialLink*>(link);
if (pSerialLink) {
LinkConfiguration* config = pSerialLink->getLinkConfiguration();
if (config) {
SerialConfiguration* pSerialConfig = qobject_cast<SerialConfiguration*>(config);
if (pSerialConfig && pSerialConfig->usbDirect()) {
if (_priorityLink.data() != link) {
newPriorityLink = link;
break;
}
return;
if (!newPriorityLink && !_priorityLink.data() && _links.count()) {
newPriorityLink = _links[0];
}
if (newPriorityLink) {
_priorityLink = _toolbox->linkManager()->sharedLinkInterfacePointerForLink(newPriorityLink);
void Vehicle::_updateAttitude(UASInterface*, double roll, double pitch, double yaw, quint64)
{
if (qIsInf(pitch)) {
if (yaw < 0.0) yaw += 360.0;
// truncate to integer so widget never displays 360
_headingFact.setRawValue(trunc(yaw));
}
}
void Vehicle::_updateAttitude(UASInterface* uas, int, double roll, double pitch, double yaw, quint64 timestamp)
{
_updateAttitude(uas, roll, pitch, yaw, timestamp);
}
1532
1533
1534
1535
1536
1537
1538
1539
1540
1541
1542
1543
1544
1545
1546
1547
1548
1549
1550
1551
1552
1553
1554
1555
1556
1557
1558
1559
1560
1561
1562
int Vehicle::motorCount(void)
{
switch (_vehicleType) {
case MAV_TYPE_HELICOPTER:
return 1;
case MAV_TYPE_VTOL_DUOROTOR:
return 2;
case MAV_TYPE_TRICOPTER:
return 3;
case MAV_TYPE_QUADROTOR:
case MAV_TYPE_VTOL_QUADROTOR:
return 4;
case MAV_TYPE_HEXAROTOR:
return 6;
case MAV_TYPE_OCTOROTOR:
return 8;
default:
return -1;
}
}
bool Vehicle::coaxialMotors(void)
{
return _firmwarePlugin->multiRotorCoaxialMotors(this);
}
bool Vehicle::xConfigMotors(void)
{
return _firmwarePlugin->multiRotorXConfig(this);
}
/*
* Internal
*/
QString Vehicle::getMavIconColor()
{
// TODO: Not using because not only the colors are ghastly, it doesn't respect dark/light palette
if(_mav)
return _mav->getColor().name();
else
return QString("black");
}
QString Vehicle::formatedMessages()
{
QString messages;
foreach(UASMessage* message, _toolbox->uasMessageHandler()->messages()) {
messages += message->getFormatedText();
}
return messages;
}
_toolbox->uasMessageHandler()->clearMessages();
void Vehicle::_handletextMessageReceived(UASMessage* message)
{
if(message)
{
_formatedMessage = message->getFormatedText();
emit formatedMessageChanged();
}
}
void Vehicle::_handleTextMessage(int newCount)
{
// Reset?
if(!newCount) {
_currentMessageCount = 0;
_currentNormalCount = 0;
_currentWarningCount = 0;
_currentErrorCount = 0;
_messageCount = 0;
_currentMessageType = MessageNone;
emit newMessageCountChanged();
emit messageTypeChanged();
emit messageCountChanged();
return;
}
UASMessageHandler* pMh = _toolbox->uasMessageHandler();
1616
1617
1618
1619
1620
1621
1622
1623
1624
1625
1626
1627
1628
1629
1630
1631
1632
1633
1634
1635
1636
1637
1638
1639
1640
1641
1642
1643
1644
1645
1646
1647
1648
1649
1650
1651
1652
1653
1654
1655
1656
1657
1658
1659
1660
1661
1662
1663
1664
1665
1666
1667
1668
1669
1670
1671
1672
1673
1674
1675
1676
1677
1678
1679
1680
MessageType_t type = newCount ? _currentMessageType : MessageNone;
int errorCount = _currentErrorCount;
int warnCount = _currentWarningCount;
int normalCount = _currentNormalCount;
//-- Add current message counts
errorCount += pMh->getErrorCount();
warnCount += pMh->getWarningCount();
normalCount += pMh->getNormalCount();
//-- See if we have a higher level
if(errorCount != _currentErrorCount) {
_currentErrorCount = errorCount;
type = MessageError;
}
if(warnCount != _currentWarningCount) {
_currentWarningCount = warnCount;
if(_currentMessageType != MessageError) {
type = MessageWarning;
}
}
if(normalCount != _currentNormalCount) {
_currentNormalCount = normalCount;
if(_currentMessageType != MessageError && _currentMessageType != MessageWarning) {
type = MessageNormal;
}
}
int count = _currentErrorCount + _currentWarningCount + _currentNormalCount;
if(count != _currentMessageCount) {
_currentMessageCount = count;
// Display current total new messages count
emit newMessageCountChanged();
}
if(type != _currentMessageType) {
_currentMessageType = type;
// Update message level
emit messageTypeChanged();
}
// Update message count (all messages)
if(newCount != _messageCount) {
_messageCount = newCount;
emit messageCountChanged();
}
QString errMsg = pMh->getLatestError();
if(errMsg != _latestError) {
_latestError = errMsg;
emit latestErrorChanged();
}
}
void Vehicle::resetMessages()
{
// Reset Counts
int count = _currentMessageCount;
MessageType_t type = _currentMessageType;
_currentErrorCount = 0;
_currentWarningCount = 0;
_currentNormalCount = 0;
_currentMessageCount = 0;
_currentMessageType = MessageNone;
if(count != _currentMessageCount) {
emit newMessageCountChanged();
}
if(type != _currentMessageType) {
emit messageTypeChanged();
}
}
int Vehicle::manualControlReservedButtonCount(void)
{
return _firmwarePlugin->manualControlReservedButtonCount();
}
void Vehicle::_loadSettings(void)
{
if (!_active) {
return;
}
settings.beginGroup(QString(_settingsGroup).arg(_id));
_joystickMode = (JoystickMode_t)settings.value(_joystickModeSettingsKey, JoystickModeRC).toInt(&convertOk);
if (!convertOk) {
_joystickMode = JoystickModeRC;
}
// Joystick enabled is a global setting so first make sure there are any joysticks connected
if (_toolbox->joystickManager()->joysticks().count()) {
setJoystickEnabled(settings.value(_joystickEnabledSettingsKey, false).toBool());
}
void Vehicle::_saveSettings(void)
{
QSettings settings;
settings.beginGroup(QString(_settingsGroup).arg(_id));
settings.setValue(_joystickModeSettingsKey, _joystickMode);
// The joystick enabled setting should only be changed if a joystick is present
// since the checkbox can only be clicked if one is present
if (_toolbox->joystickManager()->joysticks().count()) {
settings.setValue(_joystickEnabledSettingsKey, _joystickEnabled);
}
}
int Vehicle::joystickMode(void)
{
return _joystickMode;
}
void Vehicle::setJoystickMode(int mode)
{
if (mode < 0 || mode >= JoystickModeMax) {
qCWarning(VehicleLog) << "Invalid joystick mode" << mode;
return;
}
_joystickMode = (JoystickMode_t)mode;
_saveSettings();
emit joystickModeChanged(mode);
}
QStringList Vehicle::joystickModes(void)
{
QStringList list;
list << "Normal" << "Attitude" << "Position" << "Force" << "Velocity";
bool Vehicle::joystickEnabled(void)
{
return _joystickEnabled;
}
void Vehicle::setJoystickEnabled(bool enabled)
{
_joystickEnabled = enabled;
_startJoystick(_joystickEnabled);
_saveSettings();
emit joystickEnabledChanged(_joystickEnabled);
}
void Vehicle::_startJoystick(bool start)
{
Joystick* joystick = _joystickManager->activeJoystick();
if (joystick) {
if (start) {
if (_joystickEnabled) {
joystick->startPolling(this);
}
} else {
joystick->stopPolling();
}
}
}
bool Vehicle::active(void)
{
return _active;
}
void Vehicle::setActive(bool active)
{
if (_active != active) {
_active = active;
emit activeChanged(_active);
}
QGeoCoordinate Vehicle::homePosition(void)
{
return _homePosition;
}
void Vehicle::setArmed(bool armed)
{
// We specifically use COMMAND_LONG:MAV_CMD_COMPONENT_ARM_DISARM since it is supported by more flight stacks.
MAV_CMD_COMPONENT_ARM_DISARM,
true, // show error if fails
armed ? 1.0f : 0.0f);
}
bool Vehicle::flightModeSetAvailable(void)
{
return _firmwarePlugin->isCapable(this, FirmwarePlugin::SetFlightModeCapability);
}
QStringList Vehicle::flightModes(void)
{
{
return _firmwarePlugin->flightMode(_base_mode, _custom_mode);
}
void Vehicle::setFlightMode(const QString& flightMode)
{
uint8_t base_mode;
uint32_t custom_mode;
if (_firmwarePlugin->setFlightMode(flightMode, &base_mode, &custom_mode)) {
// setFlightMode will only set MAV_MODE_FLAG_CUSTOM_MODE_ENABLED in base_mode, we need to move back in the existing
// states.
uint8_t newBaseMode = _base_mode & ~MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE;
newBaseMode |= base_mode;
mavlink_message_t msg;
mavlink_msg_set_mode_pack_chan(_mavlink->getSystemId(),
_mavlink->getComponentId(),
priorityLink()->mavlinkChannel(),
&msg,
id(),
newBaseMode,
custom_mode);
sendMessageOnLink(priorityLink(), msg);
qWarning() << "FirmwarePlugin::setFlightMode failed, flightMode:" << flightMode;
}
}
bool Vehicle::hilMode(void)
{
return _base_mode & MAV_MODE_FLAG_HIL_ENABLED;
}
void Vehicle::setHilMode(bool hilMode)
{
mavlink_message_t msg;
uint8_t newBaseMode = _base_mode & ~MAV_MODE_FLAG_DECODE_POSITION_HIL;
if (hilMode) {
newBaseMode |= MAV_MODE_FLAG_HIL_ENABLED;
}
mavlink_msg_set_mode_pack_chan(_mavlink->getSystemId(),
_mavlink->getComponentId(),
priorityLink()->mavlinkChannel(),
&msg,
id(),
newBaseMode,
_custom_mode);
sendMessageOnLink(priorityLink(), msg);
void Vehicle::requestDataStream(MAV_DATA_STREAM stream, uint16_t rate, bool sendMultiple)
{
mavlink_message_t msg;
mavlink_request_data_stream_t dataStream;
dataStream.req_stream_id = stream;
dataStream.req_message_rate = rate;
dataStream.start_stop = 1; // start
dataStream.target_system = id();
dataStream.target_component = _defaultComponentId;
mavlink_msg_request_data_stream_encode_chan(_mavlink->getSystemId(),
_mavlink->getComponentId(),
priorityLink()->mavlinkChannel(),
&msg,
&dataStream);
if (sendMultiple) {
// We use sendMessageMultiple since we really want these to make it to the vehicle
sendMessageMultiple(msg);
} else {
sendMessageOnLink(priorityLink(), msg);
}
void Vehicle::_sendMessageMultipleNext(void)
{
if (_nextSendMessageMultipleIndex < _sendMessageMultipleList.count()) {
qCDebug(VehicleLog) << "_sendMessageMultipleNext:" << _sendMessageMultipleList[_nextSendMessageMultipleIndex].message.msgid;
sendMessageOnLink(priorityLink(), _sendMessageMultipleList[_nextSendMessageMultipleIndex].message);
if (--_sendMessageMultipleList[_nextSendMessageMultipleIndex].retryCount <= 0) {
_sendMessageMultipleList.removeAt(_nextSendMessageMultipleIndex);
} else {
_nextSendMessageMultipleIndex++;
}
}
if (_nextSendMessageMultipleIndex >= _sendMessageMultipleList.count()) {
_nextSendMessageMultipleIndex = 0;
}
}
void Vehicle::sendMessageMultiple(mavlink_message_t message)
{
SendMessageMultipleInfo_t info;
info.message = message;
info.retryCount = _sendMessageMultipleRetries;
_sendMessageMultipleList.append(info);
}
void Vehicle::_missionManagerError(int errorCode, const QString& errorMsg)
{
Q_UNUSED(errorCode);
qgcApp()->showMessage(tr("Mission transfer failed. Retry transfer. Error: %1").arg(errorMsg));
void Vehicle::_geoFenceManagerError(int errorCode, const QString& errorMsg)
{
Q_UNUSED(errorCode);
qgcApp()->showMessage(tr("GeoFence transfer failed. Retry transfer. Error: %1").arg(errorMsg));
}
void Vehicle::_rallyPointManagerError(int errorCode, const QString& errorMsg)
{
Q_UNUSED(errorCode);
qgcApp()->showMessage(tr("Rally Point transfer failed. Retry transfer. Error: %1").arg(errorMsg));
void Vehicle::_addNewMapTrajectoryPoint(void)
{
if (_mapTrajectoryHaveFirstCoordinate) {
// Keep three minutes of trajectory on mobile due to perf impact of lines
#ifdef __mobile__
if (_mapTrajectoryList.count() * _mapTrajectoryMsecsBetweenPoints > 3 * 1000 * 60) {
_mapTrajectoryList.removeAt(0)->deleteLater();
}
_mapTrajectoryList.append(new CoordinateVector(_mapTrajectoryLastCoordinate, _coordinate, this));
_flightDistanceFact.setRawValue(_flightDistanceFact.rawValue().toDouble() + _mapTrajectoryLastCoordinate.distanceTo(_coordinate));
}
_mapTrajectoryHaveFirstCoordinate = true;
_mapTrajectoryLastCoordinate = _coordinate;
_flightTimeFact.setRawValue((double)_flightTimer.elapsed() / 1000.0);
void Vehicle::_clearTrajectoryPoints(void)
{
_mapTrajectoryList.clearAndDeleteContents();
}
void Vehicle::_clearCameraTriggerPoints(void)
{
_cameraTriggerPoints.clearAndDeleteContents();
}
void Vehicle::_mapTrajectoryStart(void)
{
_mapTrajectoryHaveFirstCoordinate = false;
_clearTrajectoryPoints();
_flightDistanceFact.setRawValue(0);
}
void Vehicle::_mapTrajectoryStop()
{
_mapTrajectoryTimer.stop();
}
if (_missionManagerInitialRequestSent) {
return;
}
if (_parameterManager->parametersReady() && _vehicleCapabilitiesKnown) {
_missionManagerInitialRequestSent = true;
if (_settingsManager->appSettings()->autoLoadMissions()->rawValue().toBool()) {
QString missionAutoLoadDirPath = _settingsManager->appSettings()->missionSavePath();
if (!missionAutoLoadDirPath.isEmpty()) {
QDir missionAutoLoadDir(missionAutoLoadDirPath);
QString autoloadFilename = missionAutoLoadDir.absoluteFilePath(tr("AutoLoad%1.%2").arg(_id).arg(AppSettings::planFileExtension));
if (QFile(autoloadFilename).exists()) {
_initialPlanRequestComplete = true; // We aren't going to load from the vehicle, so we are done