diff --git a/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml b/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml index 020a0fd8217c04f50ceb7031a1ed32d9a03c4515..6e721a2e416e4101caf1efbd326b9824bc345439 100644 --- a/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml +++ b/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml @@ -1,6 +1,16 @@ 1 + + + Emmanuel Roussel + Coaxial Helicopter + Left swashplate servomotor, pitch axis + Right swashplate servomotor, roll axis + Upper rotor (CCW) + Lower rotor (CW) + + Simon Wilks <simon@px4.io> @@ -160,6 +170,13 @@ Lorenz Meier <lorenz@px4.io> Quadrotor x + + Mark Whitehorn <kd0aij@gmail.com> + Quadrotor x + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + feed-through of RC AUX3 channel + Lorenz Meier <lorenz@px4.io> Quadrotor x @@ -182,6 +199,10 @@ Thomas Gubler <thomas@px4.io> Quadrotor x + + Andreas Antener <andreas@uaventure.com> + Quadrotor x + @@ -227,8 +248,8 @@ feed-through of RC AUX3 channel aileron elevator - throttle - rudder + rudder + throttle flaps @@ -265,9 +286,38 @@ rudder flaps + + Andreas Antener <andreas@uaventure.com> + Standard Plane + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + feed-through of RC AUX3 channel + aileron + aileron + elevator + rudder + throttle + wheel + flaps + + + Andreas Antener <andreas@uaventure.com> + Standard Plane + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + feed-through of RC AUX3 channel + aileron right + aileron left + v-tail right + v-tail left + throttle + wheel + flaps right + flaps left + - + Simon Wilks <simon@uaventure.com> Standard VTOL @@ -275,6 +325,10 @@ Simon Wilks <simon@uaventure.com> Standard VTOL + + Sander Smeets <sander@droneslab.com> + Standard VTOL + diff --git a/src/FlightMap/MapItems/MissionItemIndicator.qml b/src/FlightMap/MapItems/MissionItemIndicator.qml index 9610a4507e5ce006333eff4c851633f800e3c461..4b5d8e9800e8eb03676c5dcb219f2cfd6a796325 100644 --- a/src/FlightMap/MapItems/MissionItemIndicator.qml +++ b/src/FlightMap/MapItems/MissionItemIndicator.qml @@ -43,7 +43,7 @@ MapQuickItem { MissionItemIndexLabel { id: _label isCurrentItem: missionItem.isCurrentItem - label: missionItem.sequenceNumber + label: missionItem.sequenceNumber == 0 ? "H" : missionItem.sequenceNumber onClicked: _item.clicked() } } diff --git a/src/MissionEditor/MissionEditor.qml b/src/MissionEditor/MissionEditor.qml index efe6cc0692624f8b927ed1a81e7ef6b90c0f26b0..822122e2d325ff339cf6562abdafc728ab2d21c4 100644 --- a/src/MissionEditor/MissionEditor.qml +++ b/src/MissionEditor/MissionEditor.qml @@ -219,6 +219,7 @@ QGCView { //offlineHomePosition = coordinate } else if (addMissionItemsButton.checked) { var index = controller.addMissionItem(coordinate) + addMissionItemsButtonAutoOffTimer.stop() addMissionItemsButtonAutoOffTimer.start() setCurrentItem(index) } else { diff --git a/src/MissionManager/MavCmdInfo.json b/src/MissionManager/MavCmdInfo.json index c2c28512c562b388a6aa8c8de5f8bfef803b5845..961d35a38885d70cc057c446d378e5fa7fa81caa 100644 --- a/src/MissionManager/MavCmdInfo.json +++ b/src/MissionManager/MavCmdInfo.json @@ -594,7 +594,7 @@ "friendlyName": "VTOL Transition", "description": "Perform flight mode transition", "category": "Basic", - "param7": { + "param1": { "label": "Mode:", "default": 3, "decimalPlaces": 0, diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc index cc0573a47f13d115736c1179a481551c02396fac..9382bef4d03c07ed27508804d58c6f0624f0197d 100644 --- a/src/MissionManager/MissionController.cc +++ b/src/MissionManager/MissionController.cc @@ -484,19 +484,22 @@ void MissionController::_initAllMissionItems(void) } homeItem->setHomePositionSpecialCase(true); if (_activeVehicle) { - homeItem->setCoordinate(_activeVehicle->homePosition()); homeItem->setHomePositionValid(_activeVehicle->homePositionAvailable()); + if (homeItem->homePositionValid()) { + homeItem->setCoordinate(_activeVehicle->homePosition()); + } } else { homeItem->setHomePositionValid(false); } homeItem->setCommand(MAV_CMD_NAV_WAYPOINT); homeItem->setFrame(MAV_FRAME_GLOBAL); if (!homeItem->homePositionValid()) { - QGeoCoordinate homeCoord = homeItem->coordinate(); - homeCoord.setAltitude(0.0); - homeItem->setCoordinate(homeCoord); + // Set a bogus home position, the important value is 0.0 Altitude + homeItem->setCoordinate(QGeoCoordinate(37.803784, -122.462276, 0.0)); } + qDebug() << "home item" << homeItem->homePositionValid() << homeItem->coordinate(); + for (int i=0; i<_missionItems->count(); i++) { _initMissionItem(qobject_cast(_missionItems->get(i))); } diff --git a/src/ViewWidgets/LogDownload.qml b/src/ViewWidgets/LogDownload.qml index e6092351eeeda32a31f074b1abf96bec91f06771..5dc2b3023888df5850b370bee52fec398396d9df 100644 --- a/src/ViewWidgets/LogDownload.qml +++ b/src/ViewWidgets/LogDownload.qml @@ -94,7 +94,7 @@ QGCView { //-- Have we received this entry already? if(controller.model.get(styleData.row).received) { var d = controller.model.get(styleData.row).time - if(d.getUTCFullYear() < 1980) + if(d.getUTCFullYear() < 2010) return "Date Unknown" else return d.toLocaleString() diff --git a/src/ViewWidgets/LogDownloadController.cc b/src/ViewWidgets/LogDownloadController.cc index 445d946eedf1293a87c0d4057c512b3569cd59eb..2aace6f7bcb10359eff2fce53f8412553b73367b 100644 --- a/src/ViewWidgets/LogDownloadController.cc +++ b/src/ViewWidgets/LogDownloadController.cc @@ -67,6 +67,7 @@ LogDownloadController::LogDownloadController(void) , _requestingLogEntries(false) , _downloadingLogs(false) , _retries(0) + , _apmOneBased(0) { MultiVehicleManager *manager = qgcApp()->toolbox()->multiVehicleManager(); connect(manager, &MultiVehicleManager::activeVehicleChanged, this, &LogDownloadController::_setActiveVehicle); @@ -114,6 +115,11 @@ LogDownloadController::_logEntry(UASInterface* uas, uint32_t time_utc, uint32_t } //-- If this is the first, pre-fill it if(!_logEntriesModel.count() && num_logs > 0) { + //-- Is this APM? They send a first entry with bogus ID and only the + // count is valid. From now on, all entries are 1-based. + if(_vehicle->firmwareType() == MAV_AUTOPILOT_ARDUPILOTMEGA) { + _apmOneBased = 1; + } for(int i = 0; i < num_logs; i++) { QGCLogEntry *entry = new QGCLogEntry(i); _logEntriesModel.append(entry); @@ -121,14 +127,18 @@ LogDownloadController::_logEntry(UASInterface* uas, uint32_t time_utc, uint32_t } //-- Update this log record if(num_logs > 0) { - if(id < _logEntriesModel.count()) { - QGCLogEntry* entry = _logEntriesModel[id]; - entry->setSize(size); - entry->setTime(QDateTime::fromTime_t(time_utc)); - entry->setReceived(true); - entry->setStatus(QString("Available")); - } else { - qWarning() << "Received log entry for out-of-bound index:" << id; + //-- Skip if empty (APM first packet) + if(size) { + id -= _apmOneBased; + if(id < _logEntriesModel.count()) { + QGCLogEntry* entry = _logEntriesModel[id]; + entry->setSize(size); + entry->setTime(QDateTime::fromTime_t(time_utc)); + entry->setReceived(true); + entry->setStatus(QString("Available")); + } else { + qWarning() << "Received log entry for out-of-bound index:" << id; + } } } else { //-- No logs to list @@ -164,13 +174,18 @@ LogDownloadController::_entriesComplete() //---------------------------------------------------------------------------------------- void -LogDownloadController::_resetSelection() +LogDownloadController::_resetSelection(bool canceled) { int num_logs = _logEntriesModel.count(); for(int i = 0; i < num_logs; i++) { QGCLogEntry* entry = _logEntriesModel[i]; if(entry) { - entry->setSelected(false); + if(entry->selected()) { + if(canceled) { + entry->setStatus(QString("Canceled")); + } + entry->setSelected(false); + } } } emit selectionChanged(); @@ -227,6 +242,9 @@ LogDownloadController::_findMissingEntries() if(end < 0) { end = start; } + //-- APM "Fix" + start += _apmOneBased; + end += _apmOneBased; //-- Request these entries again _requestLogList((uint32_t)start, (uint32_t) end); } else { @@ -241,6 +259,8 @@ LogDownloadController::_logData(UASInterface* uas, uint32_t ofs, uint16_t id, ui if(!_uas || uas != _uas || !_downloadData) { return; } + //-- APM "Fix" + id -= _apmOneBased; if(_downloadData->ID != id) { qWarning() << "Received log data for wrong log"; return; @@ -360,6 +380,8 @@ void LogDownloadController::_requestLogData(uint8_t id, uint32_t offset, uint32_t count) { if(_vehicle) { + //-- APM "Fix" + id += _apmOneBased; qCDebug(LogDownloadLog) << "Request log data (id:" << id << "offset:" << offset << "size:" << count << ")"; mavlink_message_t msg; mavlink_msg_log_request_data_pack( @@ -423,6 +445,16 @@ LogDownloadController::download(void) if(!_downloadPath.isEmpty()) { if(!_downloadPath.endsWith(QDir::separator())) _downloadPath += QDir::separator(); + //-- Iterate selected entries and shown them as waiting + int num_logs = _logEntriesModel.count(); + for(int i = 0; i < num_logs; i++) { + QGCLogEntry* entry = _logEntriesModel[i]; + if(entry) { + if(entry->selected()) { + entry->setStatus(QString("Waiting")); + } + } + } //-- Start download process _downloadingLogs = true; emit downloadingLogsChanged(); @@ -464,13 +496,18 @@ LogDownloadController::_prepareLogDownload() emit selectionChanged(); bool result = false; QString ftime; - if(entry->time().date().year() < 1980) { + if(entry->time().date().year() < 2010) { ftime = "UnknownDate"; } else { ftime = entry->time().toString("yyyy-M-d-hh-mm-ss"); } _downloadData = new LogDownloadData(entry); - _downloadData->filename = QString("log_") + QString::number(entry->id()) + "_" + ftime + ".txt"; + _downloadData->filename = QString("log_") + QString::number(entry->id()) + "_" + ftime; + if(_vehicle->firmwareType() == MAV_AUTOPILOT_PX4) { + _downloadData->filename += ".px4log"; + } else { + _downloadData->filename += ".bin"; + } _downloadData->file.setFileName(_downloadPath + _downloadData->filename); //-- Append a number to the end if the filename already exists if (_downloadData->file.exists()){ @@ -539,7 +576,7 @@ LogDownloadController::cancel(void) delete _downloadData; _downloadData = 0; } - _resetSelection(); + _resetSelection(true); _downloadingLogs = false; emit downloadingLogsChanged(); } diff --git a/src/ViewWidgets/LogDownloadController.h b/src/ViewWidgets/LogDownloadController.h index 3c29836f6ac311c0458f42ddb510db14ee917f9a..21010acc13c08b53fc6e36112d9cfab3031b7c60 100644 --- a/src/ViewWidgets/LogDownloadController.h +++ b/src/ViewWidgets/LogDownloadController.h @@ -171,7 +171,7 @@ private: void _findMissingEntries(); void _receivedAllEntries(); void _receivedAllData (); - void _resetSelection (); + void _resetSelection (bool canceled = false); void _findMissingData (); void _requestLogList (uint32_t start = 0, uint32_t end = 0xFFFF); void _requestLogData (uint8_t id, uint32_t offset = 0, uint32_t count = 0xFFFFFFFF); @@ -187,6 +187,7 @@ private: bool _requestingLogEntries; bool _downloadingLogs; int _retries; + int _apmOneBased; QString _downloadPath; };