Newer
Older
_altitudeAMSLFact.setRawValue(altitudeAMSL);
_altitudeRelativeFact.setRawValue(altitudeRelative);
_climbRateFact.setRawValue(climbRate);
}
void Vehicle::_updateNavigationControllerErrors(UASInterface*, double altitudeError, double speedError, double xtrackError) {
_navigationAltitudeError = altitudeError;
_navigationSpeedError = speedError;
_navigationCrosstrackError = xtrackError;
}
void Vehicle::_updateNavigationControllerData(UASInterface *uas, float, float, float, float targetBearing, float) {
if (_mav == uas) {
_navigationTargetBearing = targetBearing;
}
}
1019
1020
1021
1022
1023
1024
1025
1026
1027
1028
1029
1030
1031
1032
1033
1034
1035
1036
1037
1038
1039
1040
1041
1042
1043
1044
1045
1046
1047
1048
1049
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
*/
void Vehicle::_checkUpdate()
{
// Update current location
if(_mav) {
if(latitude() != _mav->getLatitude()) {
setLatitude(_mav->getLatitude());
if(longitude() != _mav->getLongitude()) {
setLongitude(_mav->getLongitude());
}
}
}
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, qgcApp()->toolbox()->uasMessageHandler()->messages()) {
messages += message->getFormatedText();
}
return messages;
}
void Vehicle::clearMessages()
{
qgcApp()->toolbox()->uasMessageHandler()->clearMessages();
}
void Vehicle::_handletextMessageReceived(UASMessage* message)
{
if(message)
{
_formatedMessage = message->getFormatedText();
emit formatedMessageChanged();
}
}
1099
1100
1101
1102
1103
1104
1105
1106
1107
1108
1109
1110
1111
1112
1113
1114
1115
1116
1117
1118
1119
1120
1121
void Vehicle::_updateState(UASInterface*, QString name, QString)
{
if (_currentState != name) {
_currentState = name;
emit currentStateChanged();
}
}
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 = qgcApp()->toolbox()->uasMessageHandler();
1124
1125
1126
1127
1128
1129
1130
1131
1132
1133
1134
1135
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
1167
1168
1169
1170
1171
1172
1173
1174
1175
1176
1177
1178
1179
1180
1181
1182
1183
1184
1185
1186
1187
1188
1189
Q_ASSERT(pMh);
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)
{
QSettings settings;
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 (qgcApp()->toolbox()->joystickManager()->joysticks().count()) {
_joystickEnabled = 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 (qgcApp()->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)
{
_active = active;
bool Vehicle::homePositionAvailable(void)
{
return _homePositionAvailable;
}
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.
mavlink_message_t msg;
mavlink_command_long_t cmd;
cmd.command = (uint16_t)MAV_CMD_COMPONENT_ARM_DISARM;
cmd.confirmation = 0;
cmd.param1 = armed ? 1.0f : 0.0f;
cmd.param2 = 0.0f;
cmd.param3 = 0.0f;
cmd.param4 = 0.0f;
cmd.param5 = 0.0f;
cmd.param6 = 0.0f;
cmd.param7 = 0.0f;
cmd.target_system = id();
cmd.target_component = defaultComponentId();
mavlink_msg_command_long_encode_chan(_mavlink->getSystemId(),
_mavlink->getComponentId(),
priorityLink()->mavlinkChannel(),
&msg,
&cmd);
sendMessageOnLink(priorityLink(), msg);
}
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(QString("Error during Mission communication with Vehicle: %1").arg(errorMsg));
void Vehicle::_geoFenceManagerError(int errorCode, const QString& errorMsg)
{
Q_UNUSED(errorCode);
qgcApp()->showMessage(QString("Error during GeoFence communication with Vehicle: %1").arg(errorMsg));
}
void Vehicle::_rallyPointManagerError(int errorCode, const QString& errorMsg)
{
Q_UNUSED(errorCode);
qgcApp()->showMessage(QString("Error during Rally Point communication with Vehicle: %1").arg(errorMsg));
void Vehicle::_addNewMapTrajectoryPoint(void)
{
if (_mapTrajectoryHaveFirstCoordinate) {
// Keep three minutes of trajectory
if (_mapTrajectoryList.count() * _mapTrajectoryMsecsBetweenPoints > 3 * 1000 * 60) {
_mapTrajectoryList.removeAt(0)->deleteLater();
}
_mapTrajectoryList.append(new CoordinateVector(_mapTrajectoryLastCoordinate, _coordinate, this));
}
_mapTrajectoryHaveFirstCoordinate = true;
_mapTrajectoryLastCoordinate = _coordinate;
}
void Vehicle::_mapTrajectoryStart(void)
{
_mapTrajectoryHaveFirstCoordinate = false;
_mapTrajectoryList.clear();
_mapTrajectoryTimer.start();
}
void Vehicle::_mapTrajectoryStop()
{
_mapTrajectoryTimer.stop();
}
void Vehicle::_parametersReady(bool parametersReady)
{
if (parametersReady && !_missionManagerInitialRequestSent) {
_missionManagerInitialRequestSent = true;
_missionManager->requestMissionItems();
}
if (parametersReady) {
setJoystickEnabled(_joystickEnabled);
}
// Vehicle is no longer communicating with us, disconnect all links
LinkManager* linkMgr = qgcApp()->toolbox()->linkManager();
for (int i=0; i<_links.count(); i++) {
// FIXME: This linkInUse check is a hack fix for multiple vehicles on the same link.
// The real fix requires significant restructuring which will come later.
if (!qgcApp()->toolbox()->multiVehicleManager()->linkInUse(_links[i], this)) {
linkMgr->disconnectLink(_links[i]);
}
void Vehicle::_imageReady(UASInterface*)
{
if(_uas)
{
QImage img = _uas->getImage();
qgcApp()->toolbox()->imageProvider()->setImage(&img, _id);
_flowImageIndex++;
emit flowImageIndexChanged();
}
}
void Vehicle::_remoteControlRSSIChanged(uint8_t rssi)
{
if (_rcRSSIstore < 0 || _rcRSSIstore > 100) {
_rcRSSIstore = rssi;
}
// Low pass to git rid of jitter
_rcRSSIstore = (_rcRSSIstore * 0.9f) + ((float)rssi * 0.1);
uint8_t filteredRSSI = (uint8_t)ceil(_rcRSSIstore);
if(_rcRSSIstore < 0.1) {
filteredRSSI = 0;
}
if(_rcRSSI != filteredRSSI) {
_rcRSSI = filteredRSSI;
emit rcRSSIChanged(_rcRSSI);
}
}
void Vehicle::virtualTabletJoystickValue(double roll, double pitch, double yaw, double thrust)
{
// The following if statement prevents the virtualTabletJoystick from sending values if the standard joystick is enabled
if ( !_joystickEnabled ) {
_uas->setExternalControlSetpoint(roll, pitch, yaw, thrust, 0, JoystickModeRC);
}
void Vehicle::setConnectionLostEnabled(bool connectionLostEnabled)
{
if (_connectionLostEnabled != connectionLostEnabled) {
_connectionLostEnabled = connectionLostEnabled;
emit connectionLostEnabledChanged(_connectionLostEnabled);
}
}
void Vehicle::_connectionLostTimeout(void)
{
if (_connectionLostEnabled && !_connectionLost) {
_connectionLost = true;
_heardFrom = false;
_say(QString("%1 communication lost").arg(_vehicleIdSpeech()));
if (_autoDisconnect) {
disconnectInactiveVehicle();
}
}
}
void Vehicle::_connectionActive(void)
{
_connectionLostTimer.start();
if (_connectionLost) {
_connectionLost = false;
emit connectionLostChanged(false);
_say(QString("%1 communication regained").arg(_vehicleIdSpeech()));
qgcApp()->toolbox()->audioOutput()->say(text.toLower());
bool Vehicle::fixedWing(void) const
{
return QGCMAVLink::isFixedWing(vehicleType());
return QGCMAVLink::isRover(vehicleType());
bool Vehicle::sub(void) const
{
return QGCMAVLink::isSub(vehicleType());
bool Vehicle::multiRotor(void) const
{
return QGCMAVLink::isMultiRotor(vehicleType());
bool Vehicle::vtol(void) const
{
switch (vehicleType()) {
case MAV_TYPE_VTOL_DUOROTOR:
case MAV_TYPE_VTOL_QUADROTOR:
case MAV_TYPE_VTOL_TILTROTOR:
case MAV_TYPE_VTOL_RESERVED2:
case MAV_TYPE_VTOL_RESERVED3:
case MAV_TYPE_VTOL_RESERVED4:
case MAV_TYPE_VTOL_RESERVED5:
return true;
default:
return false;
}
}
bool Vehicle::supportsManualControl(void) const
{
return _firmwarePlugin->supportsManualControl();
}
bool Vehicle::supportsThrottleModeCenterZero(void) const
{
return _firmwarePlugin->supportsThrottleModeCenterZero();
}
bool Vehicle::supportsRadio(void) const
{
return _firmwarePlugin->supportsRadio();
}
bool Vehicle::supportsJSButton(void) const
{
return _firmwarePlugin->supportsJSButton();
}
void Vehicle::_setCoordinateValid(bool coordinateValid)
{
if (coordinateValid != _coordinateValid) {
_coordinateValid = coordinateValid;
emit coordinateValidChanged(_coordinateValid);
}
}
1658
1659
1660
1661
1662
1663
1664
1665
1666
1667
1668
1669
1670
1671
1672
1673
1674
1675
1676
1677
1678
1679
1680
1681
1682
1683
1684
1685
1686
1687
1688
1689
1690
1691
QString Vehicle::vehicleTypeName() const {
static QMap<int, QString> typeNames = {
{ MAV_TYPE_GENERIC, tr("Generic micro air vehicle" )},
{ MAV_TYPE_FIXED_WING, tr("Fixed wing aircraft")},
{ MAV_TYPE_QUADROTOR, tr("Quadrotor")},
{ MAV_TYPE_COAXIAL, tr("Coaxial helicopter")},
{ MAV_TYPE_HELICOPTER, tr("Normal helicopter with tail rotor.")},
{ MAV_TYPE_ANTENNA_TRACKER, tr("Ground installation")},
{ MAV_TYPE_GCS, tr("Operator control unit / ground control station")},
{ MAV_TYPE_AIRSHIP, tr("Airship, controlled")},
{ MAV_TYPE_FREE_BALLOON, tr("Free balloon, uncontrolled")},
{ MAV_TYPE_ROCKET, tr("Rocket")},
{ MAV_TYPE_GROUND_ROVER, tr("Ground rover")},
{ MAV_TYPE_SURFACE_BOAT, tr("Surface vessel, boat, ship")},
{ MAV_TYPE_SUBMARINE, tr("Submarine")},
{ MAV_TYPE_HEXAROTOR, tr("Hexarotor")},
{ MAV_TYPE_OCTOROTOR, tr("Octorotor")},
{ MAV_TYPE_TRICOPTER, tr("Octorotor")},
{ MAV_TYPE_FLAPPING_WING, tr("Flapping wing")},
{ MAV_TYPE_KITE, tr("Flapping wing")},
{ MAV_TYPE_ONBOARD_CONTROLLER, tr("Onboard companion controller")},
{ MAV_TYPE_VTOL_DUOROTOR, tr("Two-rotor VTOL using control surfaces in vertical operation in addition. Tailsitter")},
{ MAV_TYPE_VTOL_QUADROTOR, tr("Quad-rotor VTOL using a V-shaped quad config in vertical operation. Tailsitter")},
{ MAV_TYPE_VTOL_TILTROTOR, tr("Tiltrotor VTOL")},
{ MAV_TYPE_VTOL_RESERVED2, tr("VTOL reserved 2")},
{ MAV_TYPE_VTOL_RESERVED3, tr("VTOL reserved 3")},
{ MAV_TYPE_VTOL_RESERVED4, tr("VTOL reserved 4")},
{ MAV_TYPE_VTOL_RESERVED5, tr("VTOL reserved 5")},
{ MAV_TYPE_GIMBAL, tr("Onboard gimbal")},
{ MAV_TYPE_ADSB, tr("Onboard ADSB peripheral")},
};
return typeNames[_vehicleType];
}
/// Returns the string to speak to identify the vehicle
QString Vehicle::_vehicleIdSpeech(void)
{
if (qgcApp()->toolbox()->multiVehicleManager()->vehicles()->count() > 1) {
return QString("vehicle %1").arg(id());
} else {
void Vehicle::_handleFlightModeChanged(const QString& flightMode)
_say(QString("%1 %2 flight mode").arg(_vehicleIdSpeech()).arg(flightMode));
emit guidedModeChanged(_firmwarePlugin->isGuidedMode(this));
}
void Vehicle::_announceArmedChanged(bool armed)
{
_say(QString("%1 %2").arg(_vehicleIdSpeech()).arg(armed ? QStringLiteral("armed") : QStringLiteral("disarmed")));
void Vehicle::clearTrajectoryPoints(void)
{
_mapTrajectoryList.clearAndDeleteContents();
}
void Vehicle::setFlying(bool flying)
{
if (armed() && _flying != flying) {
_flying = flying;
emit flyingChanged(flying);
}
}
bool Vehicle::guidedModeSupported(void) const
{
return _firmwarePlugin->isCapable(this, FirmwarePlugin::GuidedModeCapability);
}
bool Vehicle::pauseVehicleSupported(void) const
{
return _firmwarePlugin->isCapable(this, FirmwarePlugin::PauseVehicleCapability);
}
bool Vehicle::orbitModeSupported() const
{
return _firmwarePlugin->isCapable(this, FirmwarePlugin::OrbitModeCapability);
}
void Vehicle::guidedModeRTL(void)
{
if (!guidedModeSupported()) {
qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
return;
}
_firmwarePlugin->guidedModeRTL(this);
}
void Vehicle::guidedModeLand(void)
{
if (!guidedModeSupported()) {
qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
return;
}
_firmwarePlugin->guidedModeLand(this);
}
void Vehicle::guidedModeTakeoff(double altitudeRel)
{
if (!guidedModeSupported()) {
qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
return;
}
setGuidedMode(true);
_firmwarePlugin->guidedModeTakeoff(this, altitudeRel);
}
void Vehicle::guidedModeGotoLocation(const QGeoCoordinate& gotoCoord)
{
if (!guidedModeSupported()) {
qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
return;
}
_firmwarePlugin->guidedModeGotoLocation(this, gotoCoord);
}
void Vehicle::guidedModeChangeAltitude(double altitudeRel)
{
if (!guidedModeSupported()) {
qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
return;
}
_firmwarePlugin->guidedModeChangeAltitude(this, altitudeRel);
}
void Vehicle::guidedModeOrbit(const QGeoCoordinate& centerCoord, double radius, double velocity, double altitude)
{
if (!orbitModeSupported()) {
qgcApp()->showMessage(QStringLiteral("Orbit mode not supported by Vehicle."));
return;
}
_firmwarePlugin->guidedModeOrbit(this, centerCoord, radius, velocity, altitude);
}
1796
1797
1798
1799
1800
1801
1802
1803
1804
1805
1806
1807
1808
1809
1810
1811
1812
1813
1814
1815
1816
1817
1818
1819
1820
1821
1822
1823
1824
1825
1826
1827
1828
1829
void Vehicle::pauseVehicle(void)
{
if (!pauseVehicleSupported()) {
qgcApp()->showMessage(QStringLiteral("Pause not supported by vehicle."));
return;
}
_firmwarePlugin->pauseVehicle(this);
}
bool Vehicle::guidedMode(void) const
{
return _firmwarePlugin->isGuidedMode(this);
}
void Vehicle::setGuidedMode(bool guidedMode)
{
return _firmwarePlugin->setGuidedMode(this, guidedMode);
}
void Vehicle::emergencyStop(void)
{
mavlink_message_t msg;
mavlink_command_long_t cmd;
cmd.command = (uint16_t)MAV_CMD_COMPONENT_ARM_DISARM;
cmd.confirmation = 0;
cmd.param1 = 0.0f;
cmd.param2 = 21196.0f; // Magic number for emergency stop
cmd.param3 = 0.0f;
cmd.param4 = 0.0f;
cmd.param5 = 0.0f;
cmd.param6 = 0.0f;
cmd.param7 = 0.0f;
cmd.target_system = id();
cmd.target_component = defaultComponentId();
mavlink_msg_command_long_encode_chan(_mavlink->getSystemId(),
_mavlink->getComponentId(),
priorityLink()->mavlinkChannel(),
&msg,
&cmd);
sendMessageOnLink(priorityLink(), msg);
void Vehicle::setCurrentMissionSequence(int seq)
{
if (!_firmwarePlugin->sendHomePositionToVehicle()) {
seq--;
}
mavlink_message_t msg;
mavlink_msg_mission_set_current_pack_chan(_mavlink->getSystemId(),
_mavlink->getComponentId(),
priorityLink()->mavlinkChannel(),
&msg,
id(),
_compID,
seq);
sendMessageOnLink(priorityLink(), msg);
void Vehicle::doCommandLong(int component, MAV_CMD command, float param1, float param2, float param3, float param4, float param5, float param6, float param7)
{
mavlink_message_t msg;
mavlink_command_long_t cmd;
cmd.command = command;
cmd.confirmation = 0;
cmd.param1 = param1;
cmd.param2 = param2;
cmd.param3 = param3;
cmd.param4 = param4;
cmd.param5 = param5;
cmd.param6 = param6;
cmd.param7 = param7;
cmd.target_system = id();
cmd.target_component = component;
mavlink_msg_command_long_encode_chan(_mavlink->getSystemId(),
_mavlink->getComponentId(),
priorityLink()->mavlinkChannel(),
&msg,
&cmd);
sendMessageOnLink(priorityLink(), msg);
void Vehicle::setPrearmError(const QString& prearmError)
{
_prearmError = prearmError;
emit prearmErrorChanged(_prearmError);
if (!_prearmError.isEmpty()) {
_prearmErrorTimer.start();
}
}
void Vehicle::_prearmErrorTimeout(void)
{
setPrearmError(QString());
}
void Vehicle::setFirmwareVersion(int majorVersion, int minorVersion, int patchVersion, FIRMWARE_VERSION_TYPE versionType)
{
_firmwareMajorVersion = majorVersion;
_firmwareMinorVersion = minorVersion;
_firmwarePatchVersion = patchVersion;
1900
1901
1902
1903
1904
1905
1906
1907
1908
1909
1910
1911
1912
1913
1914
1915
1916
1917
1918
1919
1920
1921
_firmwareVersionType = versionType;
emit firmwareMajorVersionChanged(_firmwareMajorVersion);
emit firmwareMinorVersionChanged(_firmwareMinorVersion);
emit firmwarePatchVersionChanged(_firmwarePatchVersion);
emit firmwareVersionTypeChanged(_firmwareVersionType);
}
QString Vehicle::firmwareVersionTypeString(void) const
{
switch (_firmwareVersionType) {
case FIRMWARE_VERSION_TYPE_DEV:
return QStringLiteral("dev");
case FIRMWARE_VERSION_TYPE_ALPHA:
return QStringLiteral("alpha");
case FIRMWARE_VERSION_TYPE_BETA:
return QStringLiteral("beta");
case FIRMWARE_VERSION_TYPE_RC:
return QStringLiteral("rc");
case FIRMWARE_VERSION_TYPE_OFFICIAL:
default:
return QStringLiteral("");
}
doCommandLong(defaultComponentId(), MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, 1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f);
return _parameterManager->defaultComponentId();
void Vehicle::setSoloFirmware(bool soloFirmware)
{
if (soloFirmware != _soloFirmware) {
_soloFirmware = soloFirmware;
emit soloFirmwareChanged(soloFirmware);
}
}
#if 0
// Temporarily removed, waiting for new command implementation
void Vehicle::motorTest(int motor, int percent, int timeoutSecs)
{
doCommandLong(defaultComponentId(), MAV_CMD_DO_MOTOR_TEST, motor, MOTOR_TEST_THROTTLE_PERCENT, percent, timeoutSecs);
}
void Vehicle::_newMissionItemsAvailable(void)
{
// After the initial mission request complets we ask for the geofence
if (!_geoFenceManagerInitialRequestSent) {
_geoFenceManagerInitialRequestSent = true;
void Vehicle::_newGeoFenceAvailable(void)
{
// After the initial mission request complets we ask for the geofence
if (!_rallyPointManagerInitialRequestSent) {
_rallyPointManagerInitialRequestSent = true;
_rallyPointManager->loadFromVehicle();
}
}
QString Vehicle::brandImage(void) const
{
return _firmwarePlugin->brandImage(this);
}
1973
1974
1975
1976
1977
1978
1979
1980
1981
1982
1983
1984
1985
1986
1987
1988
1989
1990
1991
1992
1993
1994
1995
1996
1997
1998
1999
2000
QStringList Vehicle::unhealthySensors(void) const
{
QStringList sensorList;
struct sensorInfo_s {
uint32_t bit;
const char* sensorName;
};
static const sensorInfo_s rgSensorInfo[] = {
{ MAV_SYS_STATUS_SENSOR_3D_GYRO, "Gyro" },
{ MAV_SYS_STATUS_SENSOR_3D_ACCEL, "Accelerometer" },
{ MAV_SYS_STATUS_SENSOR_3D_MAG, "Magnetometer" },
{ MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE, "Absolute pressure" },
{ MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE, "Differential pressure" },
{ MAV_SYS_STATUS_SENSOR_GPS, "GPS" },
{ MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW, "Optical flow" },
{ MAV_SYS_STATUS_SENSOR_VISION_POSITION, "Computer vision position" },
{ MAV_SYS_STATUS_SENSOR_LASER_POSITION, "Laser based position" },
{ MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH, "External ground truth" },
{ MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL, "Angular rate control" },
{ MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION, "Attitude stabilization" },
{ MAV_SYS_STATUS_SENSOR_YAW_POSITION, "Yaw position" },
{ MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL, "Z/altitude control" },
{ MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL, "X/Y position control" },
{ MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS, "Motor outputs / control" },
{ MAV_SYS_STATUS_SENSOR_RC_RECEIVER, "RC receiver" },
{ MAV_SYS_STATUS_SENSOR_3D_GYRO2, "Gyro 2" },