Newer
Older
bool Vehicle::sendMessageOnLinkThreadSafe(LinkInterface* link, mavlink_message_t message)
// Give the plugin a chance to adjust
_firmwarePlugin->adjustOutgoingMavlinkMessageThreadSafe(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);
_messagesSent++;
emit messagesSentChanged();
void Vehicle::_updatePriorityLink(bool updateActive, bool sendCommand)
// if the priority link is commanded and still active don't change anything
if (_priorityLinkCommanded) {
if (_priorityLink.data()->link_active(_id)) {
return;
} else {
_priorityLinkCommanded = false;
}
}
LinkInterface* newPriorityLink = nullptr;
// This routine specifically 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 nullptr pointer crashes where priorityLink() is still called during shutdown sequence.
if (_links.count() == 0) {
return;
}
// Check for the existing priority link to still be valid
for (int i=0; i<_links.count(); i++) {
if (_priorityLink.data() == _links[i]) {
if (!_priorityLink.data()->highLatency() && _priorityLink->link_active(_id)) {
// Link is still valid. Continue to use it unless it is high latency. In that case we still look for a better
// link to use as priority link.
return;
}
}
}
// The previous priority link is no longer valid. We must no find the best link available in this priority order:
// First active direct USB connection
// Any active non high latency link
// An active high latency link
// Any link
#ifndef NO_SERIAL_LINK
// Search for an active direct usb connection
for (int i=0; i<_links.count(); i++) {
LinkInterface* link = _links[i];
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 && link->link_active(_id)) {
// Search for an active non-high latency link
for (int i=0; i<_links.count(); i++) {
LinkInterface* link = _links[i];
if (!link->highLatency() && link->link_active(_id)) {
newPriorityLink = link;
break;
}
}
}
if (!newPriorityLink) {
// Search for an active high latency link
for (int i=0; i<_links.count(); i++) {
LinkInterface* link = _links[i];
if (link->highLatency() && link->link_active(_id)) {
newPriorityLink = link;
break;
}
}
if (!newPriorityLink) {
// Use any link
newPriorityLink = _links[0];
if (_priorityLink.data() != newPriorityLink) {
qgcApp()->showAppMessage((tr("switch to %2 as priority link")).arg(newPriorityLink->getName()));
_priorityLink = _toolbox->linkManager()->sharedLinkInterfacePointerForLink(newPriorityLink);
_updateHighLatencyLink(sendCommand);
emit priorityLinkNameChanged(_priorityLink->getName());
if (updateActive) {
_linkActiveChanged(_priorityLink.data(), _priorityLink->link_active(_id), _id);
{
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;
2140
2141
2142
2143
2144
2145
2146
2147
2148
2149
2150
2151
2152
2153
2154
2155
2156
2157
2158
2159
2160
2161
2162
2163
2164
2165
2166
2167
2168
2169
2170
2171
2172
2173
2174
2175
2176
2177
2178
2179
2180
case MAV_TYPE_SUBMARINE:
{
// Supported frame types
enum {
SUB_FRAME_BLUEROV1,
SUB_FRAME_VECTORED,
SUB_FRAME_VECTORED_6DOF,
SUB_FRAME_VECTORED_6DOF_90DEG,
SUB_FRAME_SIMPLEROV_3,
SUB_FRAME_SIMPLEROV_4,
SUB_FRAME_SIMPLEROV_5,
SUB_FRAME_CUSTOM
};
uint8_t frameType = parameterManager()->getParameter(_compID, "FRAME_CONFIG")->rawValue().toInt();
switch (frameType) { // ardupilot/libraries/AP_Motors/AP_Motors6DOF.h sub_frame_t
case SUB_FRAME_BLUEROV1:
case SUB_FRAME_VECTORED:
return 6;
case SUB_FRAME_SIMPLEROV_3:
return 3;
case SUB_FRAME_SIMPLEROV_4:
return 4;
case SUB_FRAME_SIMPLEROV_5:
return 5;
case SUB_FRAME_VECTORED_6DOF:
case SUB_FRAME_VECTORED_6DOF_90DEG:
case SUB_FRAME_CUSTOM:
return 8;
default:
return -1;
}
}
{
return _firmwarePlugin->multiRotorCoaxialMotors(this);
}
{
return _firmwarePlugin->multiRotorXConfig(this);
}
QString Vehicle::formatedMessages()
{
QString messages;
for(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();
2236
2237
2238
2239
2240
2241
2242
2243
2244
2245
2246
2247
2248
2249
2250
2251
2252
2253
2254
2255
2256
2257
2258
2259
2260
2261
2262
2263
2264
2265
2266
2267
2268
2269
2270
2271
2272
2273
2274
2275
2276
2277
2278
2279
2280
2281
2282
2283
2284
2285
2286
2287
2288
2289
2290
2291
2292
2293
2294
2295
2296
2297
2298
2299
2300
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();
}
}
if (!_active) {
return;
}
QSettings settings;
settings.beginGroup(QString(_settingsGroup).arg(_id));
// 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());
nanthony21
committed
_startJoystick(true);
{
QSettings settings;
settings.beginGroup(QString(_settingsGroup).arg(_id));
// 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);
}
{
return _joystickEnabled;
}
void Vehicle::setJoystickEnabled(bool enabled)
{
_joystickEnabled = enabled;
_startJoystick(_joystickEnabled);
emit joystickEnabledChanged(_joystickEnabled);
}
void Vehicle::_startJoystick(bool start)
{
Joystick* joystick = _joystickManager->activeJoystick();
nanthony21
committed
joystick->startPolling(this);
} else {
joystick->stopPolling();
}
}
}
{
return _active;
}
void Vehicle::setActive(bool active)
{
if (_active != active) {
_active = active;
nanthony21
committed
_startJoystick(false);
emit activeChanged(_active);
}
QGeoCoordinate Vehicle::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()
return _firmwarePlugin->isCapable(this, FirmwarePlugin::SetFlightModeCapability);
QStringList Vehicle::flightModes()
QStringList Vehicle::extraJoystickFlightModes()
{
return _firmwarePlugin->extraJoystickFlightModes(this);
}
QString Vehicle::flightMode() const
{
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);
qWarning() << "FirmwarePlugin::setFlightMode failed, flightMode:" << flightMode;
QString Vehicle::priorityLinkName() const
}
return "none";
QVariantList Vehicle::links() const {
for( const auto &item: _links )
ret << QVariant::fromValue(item);
return ret;
}
void Vehicle::setPriorityLinkByName(const QString& priorityLinkName)
{
if (!_priorityLink) {
return;
}
if (priorityLinkName == _priorityLink->getName()) {
// The link did not change
return;
}
LinkInterface* newPriorityLink = nullptr;
for (int i=0; i<_links.count(); i++) {
if (_links[i]->getName() == priorityLinkName) {
newPriorityLink = _links[i];
}
}
if (newPriorityLink) {
_priorityLinkCommanded = true;
_priorityLink = _toolbox->linkManager()->sharedLinkInterfacePointerForLink(newPriorityLink);
_updateHighLatencyLink(true);
emit priorityLinkNameChanged(_priorityLink->getName());
_linkActiveChanged(_priorityLink.data(), _priorityLink->link_active(_id), _id);
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 {
void Vehicle::_sendMessageMultipleNext()
{
if (_nextSendMessageMultipleIndex < _sendMessageMultipleList.count()) {
qCDebug(VehicleLog) << "_sendMessageMultipleNext:" << _sendMessageMultipleList[_nextSendMessageMultipleIndex].message.msgid;
sendMessageOnLinkThreadSafe(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()->showAppMessage(tr("Mission transfer failed. Error: %1").arg(errorMsg));
void Vehicle::_geoFenceManagerError(int errorCode, const QString& errorMsg)
{
Q_UNUSED(errorCode);
qgcApp()->showAppMessage(tr("GeoFence transfer failed. Error: %1").arg(errorMsg));
}
void Vehicle::_rallyPointManagerError(int errorCode, const QString& errorMsg)
{
Q_UNUSED(errorCode);
qgcApp()->showAppMessage(tr("Rally Point transfer failed. Error: %1").arg(errorMsg));
void Vehicle::_clearCameraTriggerPoints()
{
_cameraTriggerPoints.clearAndDeleteContents();
_flightDistanceFact.setRawValue(0);
{
_flightTimeFact.setRawValue((double)_flightTimer.elapsed() / 1000.0);
}
disconnect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &Vehicle::_firstMissionLoadComplete);
disconnect(_geoFenceManager, &GeoFenceManager::loadComplete, this, &Vehicle::_firstGeoFenceLoadComplete);
disconnect(_rallyPointManager, &RallyPointManager::loadComplete, this, &Vehicle::_firstRallyPointLoadComplete);
_initialPlanRequestComplete = true;
emit initialPlanRequestCompleteChanged(true);
void Vehicle::_parametersReady(bool parametersReady)
{
// Try to set current unix time to the vehicle
_sendQGCTimeToVehicle();
// Send time twice, more likely to get to the vehicle on a noisy link
_sendQGCTimeToVehicle();
disconnect(_parameterManager, &ParameterManager::parametersReadyChanged, this, &Vehicle::_parametersReady);
void Vehicle::_sendQGCTimeToVehicle()
{
mavlink_message_t msg;
mavlink_system_time_t cmd;
// Timestamp of the master clock in microseconds since UNIX epoch.
cmd.time_unix_usec = QDateTime::currentDateTime().currentMSecsSinceEpoch()*1000;
// Timestamp of the component clock since boot time in milliseconds (Not necessary).
cmd.time_boot_ms = 0;
mavlink_msg_system_time_encode_chan(_mavlink->getSystemId(),
_mavlink->getComponentId(),
priorityLink()->mavlinkChannel(),
&msg,
&cmd);
void Vehicle::disconnectInactiveVehicle()
// Vehicle is no longer communicating with us, disconnect all links
LinkManager* linkMgr = _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 (!_toolbox->multiVehicleManager()->linkInUse(_links[i], this)) {
linkMgr->disconnectLink(_links[i]);
}
void Vehicle::_imageReady(UASInterface*)
{
if(_uas)
{
QImage img = _uas->getImage();
_toolbox->imageProvider()->setImage(&img, _id);
_flowImageIndex++;
emit flowImageIndexChanged();
}
}
void Vehicle::_remoteControlRSSIChanged(uint8_t rssi)
{
//-- 0 <= rssi <= 100 - 255 means "invalid/unknown"
if(rssi > 100) { // Anything over 100 doesn't make sense
if(_rcRSSI != 255) {
_rcRSSI = 255;
emit rcRSSIChanged(_rcRSSI);
}
return;
}
//-- Initialize it
if(_rcRSSIstore == 255.) {
_rcRSSIstore = (double)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
static_cast<float>(roll),
static_cast<float>(pitch),
static_cast<float>(yaw),
static_cast<float>(thrust),
0);
void Vehicle::setConnectionLostEnabled(bool connectionLostEnabled)
{
if (_connectionLostEnabled != connectionLostEnabled) {
_connectionLostEnabled = connectionLostEnabled;
emit connectionLostEnabledChanged(_connectionLostEnabled);
}
}
void Vehicle::_linkActiveChanged(LinkInterface *link, bool active, int vehicleID)
// only continue if the vehicle id is correct
if (vehicleID != _id) {
Lorenz Meier
committed
bool communicationLost = false;
bool communicationRegained = false;
if (link == _priorityLink) {
if (active && _connectionLost) {
// communication to priority link regained
_connectionLost = false;
emit connectionLostChanged(false);
if (_priorityLink->highLatency()) {
_setMaxProtoVersion(100);
Lorenz Meier
committed
}
} else if (!active && !_connectionLost) {
_updatePriorityLink(false /* updateActive */, false /* sendCommand */);
if (link == _priorityLink) {
_connectionLost = true;
communicationLost = true;
_heardFrom = false;
emit connectionLostChanged(true);
if (_autoDisconnect) {
// Reset link state
for (int i = 0; i < _links.length(); i++) {
_mavlink->resetMetadataForLink(_links.at(i));
}
}
}
} else {
qgcApp()->showAppMessage((tr("%1 communication to auxiliary link %2 %3")).arg(_vehicleIdSpeech()).arg(link->getName()).arg(active ? "regained" : "lost"));
_updatePriorityLink(false /* updateActive */, true /* sendCommand */);
QString commSpeech;
bool multiVehicle = _toolbox->multiVehicleManager()->vehicles()->count() > 1;
if (communicationRegained) {
commSpeech = tr("Communication regained");
if (_links.count() > 1) {
qgcApp()->showAppMessage(tr("Communication regained to vehicle %1 on %2 link %3").arg(_id).arg(_links.count() > 1 ? tr("priority") : tr("auxiliary")).arg(link->getName()));
qgcApp()->showAppMessage(tr("Communication regained to vehicle %1").arg(_id));
}
}
if (communicationLost) {
commSpeech = tr("Communication lost");
if (_links.count() > 1) {
qgcApp()->showAppMessage(tr("Communication lost to vehicle %1 on %2 link %3").arg(_id).arg(_links.count() > 1 ? tr("priority") : tr("auxiliary")).arg(link->getName()));
qgcApp()->showAppMessage(tr("Communication lost to vehicle %1").arg(_id));
}
}
if (multiVehicle && (communicationLost || communicationRegained)) {
commSpeech.append(tr(" to vehicle %1").arg(_id));
}
if (!commSpeech.isEmpty()) {
_say(commSpeech);
}
_toolbox->audioOutput()->say(text.toLower());
return QGCMAVLink::isFixedWing(vehicleType());
return QGCMAVLink::isSub(vehicleType());
return QGCMAVLink::isMultiRotor(vehicleType());
bool Vehicle::supportsThrottleModeCenterZero() const
{
return _firmwarePlugin->supportsThrottleModeCenterZero();
}
bool Vehicle::supportsNegativeThrust()
Gus Grubba
committed
return _firmwarePlugin->supportsNegativeThrust(this);
bool Vehicle::supportsRadio() const
{
return _firmwarePlugin->supportsRadio();
}
bool Vehicle::supportsJSButton() const
{
return _firmwarePlugin->supportsJSButton();
}
bool Vehicle::supportsMotorInterference() const
{
return _firmwarePlugin->supportsMotorInterference();
}
bool Vehicle::supportsTerrainFrame() const
2829
2830
2831
2832
2833
2834
2835
2836
2837
2838
2839
2840
2841
2842
2843
2844
2845
2846
2847
2848
2849
2850
2851
2852
2853
2854
2855
2856
2857
2858
2859
2860
2861
2862
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()
if (_toolbox->multiVehicleManager()->vehicles()->count() > 1) {
return tr("vehicle %1").arg(id());
void Vehicle::_handleFlightModeChanged(const QString& flightMode)
_say(tr("%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 ? tr("armed") : tr("disarmed")));
if(armed) {
//-- Keep track of armed coordinates
_armedPosition = _coordinate;
emit armedPositionChanged();
}
void Vehicle::_setFlying(bool flying)
_flying = flying;
emit flyingChanged(flying);
}
}
void Vehicle::_setLanding(bool landing)
{
if (armed() && _landing != landing) {
_landing = landing;
emit landingChanged(landing);
}
}
bool Vehicle::guidedModeSupported() const
return _firmwarePlugin->isCapable(this, FirmwarePlugin::GuidedModeCapability);
bool Vehicle::pauseVehicleSupported() const
return _firmwarePlugin->isCapable(this, FirmwarePlugin::PauseVehicleCapability);
}
bool Vehicle::orbitModeSupported() const
{
return _firmwarePlugin->isCapable(this, FirmwarePlugin::OrbitModeCapability);
bool Vehicle::roiModeSupported() const
{
return _firmwarePlugin->isCapable(this, FirmwarePlugin::ROIModeCapability);
}
bool Vehicle::takeoffVehicleSupported() const
{
return _firmwarePlugin->isCapable(this, FirmwarePlugin::TakeoffVehicleCapability);
}
QString Vehicle::gotoFlightMode() const
{
return _firmwarePlugin->gotoFlightMode();
}
return;
}
_firmwarePlugin->guidedModeLand(this);
}
void Vehicle::guidedModeTakeoff(double altitudeRelative)
_firmwarePlugin->guidedModeTakeoff(this, altitudeRelative);
double Vehicle::minimumTakeoffAltitude()
{
return _firmwarePlugin->minimumTakeoffAltitude(this);
}
{
_firmwarePlugin->startMission(this);
}
void Vehicle::guidedModeGotoLocation(const QGeoCoordinate& gotoCoord)
{
if (!guidedModeSupported()) {
if (!coordinate().isValid()) {
return;
}
double maxDistance = _settingsManager->flyViewSettings()->maxGoToLocationDistance()->rawValue().toDouble();
if (coordinate().distanceTo(gotoCoord) > maxDistance) {
qgcApp()->showAppMessage(QString("New location is too far. Must be less than %1 %2.").arg(qRound(FactMetaData::metersToAppSettingsHorizontalDistanceUnits(maxDistance).toDouble())).arg(FactMetaData::appSettingsHorizontalDistanceUnitsString()));
_firmwarePlugin->guidedModeGotoLocation(this, gotoCoord);
}
void Vehicle::guidedModeChangeAltitude(double altitudeChange)
_firmwarePlugin->guidedModeChangeAltitude(this, altitudeChange);
void Vehicle::guidedModeOrbit(const QGeoCoordinate& centerCoord, double radius, double amslAltitude)