Commit 30bcc904 authored by ChukRhodes's avatar ChukRhodes

Merge remote-tracking branch 'refs/remotes/mavlink/master'

parents c1591744 e5a83d8d
<?xml version='1.0' encoding='UTF-8'?> <?xml version='1.0' encoding='UTF-8'?>
<airframes> <airframes>
<version>1</version> <version>1</version>
<airframe_group image="" name="Coaxial Helicopter">
<airframe id="15001" maintainer="Emmanuel Roussel" name="Coaxial Helicopter (such as Esky Lama v4 or Esky Big Lama)">
<maintainer>Emmanuel Roussel</maintainer>
<type>Coaxial Helicopter</type>
<output name="MAIN1">Left swashplate servomotor, pitch axis</output>
<output name="MAIN2">Right swashplate servomotor, roll axis</output>
<output name="MAIN3">Upper rotor (CCW)</output>
<output name="MAIN4">Lower rotor (CW)</output>
</airframe>
</airframe_group>
<airframe_group image="AirframeFlyingWing.png" name="Flying Wing"> <airframe_group image="AirframeFlyingWing.png" name="Flying Wing">
<airframe id="3030" maintainer="Simon Wilks &lt;simon@px4.io&gt;" name="IO Camflyer"> <airframe id="3030" maintainer="Simon Wilks &lt;simon@px4.io&gt;" name="IO Camflyer">
<maintainer>Simon Wilks &lt;simon@px4.io&gt;</maintainer> <maintainer>Simon Wilks &lt;simon@px4.io&gt;</maintainer>
...@@ -160,6 +170,13 @@ ...@@ -160,6 +170,13 @@
<maintainer>Lorenz Meier &lt;lorenz@px4.io&gt;</maintainer> <maintainer>Lorenz Meier &lt;lorenz@px4.io&gt;</maintainer>
<type>Quadrotor x</type> <type>Quadrotor x</type>
</airframe> </airframe>
<airframe id="4009" maintainer="Mark Whitehorn &lt;kd0aij@gmail.com&gt;" name="Lumenier QAV250">
<maintainer>Mark Whitehorn &lt;kd0aij@gmail.com&gt;</maintainer>
<type>Quadrotor x</type>
<output name="AUX1">feed-through of RC AUX1 channel</output>
<output name="AUX2">feed-through of RC AUX2 channel</output>
<output name="AUX3">feed-through of RC AUX3 channel</output>
</airframe>
<airframe id="4010" maintainer="Lorenz Meier &lt;lorenz@px4.io&gt;" name="DJI Flame Wheel F330"> <airframe id="4010" maintainer="Lorenz Meier &lt;lorenz@px4.io&gt;" name="DJI Flame Wheel F330">
<maintainer>Lorenz Meier &lt;lorenz@px4.io&gt;</maintainer> <maintainer>Lorenz Meier &lt;lorenz@px4.io&gt;</maintainer>
<type>Quadrotor x</type> <type>Quadrotor x</type>
...@@ -182,6 +199,10 @@ ...@@ -182,6 +199,10 @@
<maintainer>Thomas Gubler &lt;thomas@px4.io&gt;</maintainer> <maintainer>Thomas Gubler &lt;thomas@px4.io&gt;</maintainer>
<type>Quadrotor x</type> <type>Quadrotor x</type>
</airframe> </airframe>
<airframe id="4030" maintainer="Andreas Antener &lt;andreas@uaventure.com&gt;" name="Generic Quadrotor X config">
<maintainer>Andreas Antener &lt;andreas@uaventure.com&gt;</maintainer>
<type>Quadrotor x</type>
</airframe>
</airframe_group> </airframe_group>
<airframe_group image="" name="Rover"> <airframe_group image="" name="Rover">
<airframe id="50001" maintainer="John Doe &lt;john@example.com&gt;" name="Axial Racing AX10"> <airframe id="50001" maintainer="John Doe &lt;john@example.com&gt;" name="Axial Racing AX10">
...@@ -227,8 +248,8 @@ ...@@ -227,8 +248,8 @@
<output name="AUX3">feed-through of RC AUX3 channel</output> <output name="AUX3">feed-through of RC AUX3 channel</output>
<output name="MAIN1">aileron</output> <output name="MAIN1">aileron</output>
<output name="MAIN2">elevator</output> <output name="MAIN2">elevator</output>
<output name="MAIN3">throttle</output> <output name="MAIN3">rudder</output>
<output name="MAIN4">rudder</output> <output name="MAIN4">throttle</output>
<output name="MAIN5">flaps</output> <output name="MAIN5">flaps</output>
</airframe> </airframe>
<airframe id="2102" maintainer="Lorenz Meier &lt;lorenz@px4.io&gt;" name="Skywalker (3DR Aero)"> <airframe id="2102" maintainer="Lorenz Meier &lt;lorenz@px4.io&gt;" name="Skywalker (3DR Aero)">
...@@ -265,9 +286,38 @@ ...@@ -265,9 +286,38 @@
<output name="MAIN4">rudder</output> <output name="MAIN4">rudder</output>
<output name="MAIN5">flaps</output> <output name="MAIN5">flaps</output>
</airframe> </airframe>
<airframe id="2105" maintainer="Andreas Antener &lt;andreas@uaventure.com&gt;" name="Bormatec Maja">
<maintainer>Andreas Antener &lt;andreas@uaventure.com&gt;</maintainer>
<type>Standard Plane</type>
<output name="AUX1">feed-through of RC AUX1 channel</output>
<output name="AUX2">feed-through of RC AUX2 channel</output>
<output name="AUX3">feed-through of RC AUX3 channel</output>
<output name="MAIN1">aileron</output>
<output name="MAIN2">aileron</output>
<output name="MAIN3">elevator</output>
<output name="MAIN4">rudder</output>
<output name="MAIN5">throttle</output>
<output name="MAIN6">wheel</output>
<output name="MAIN7">flaps</output>
</airframe>
<airframe id="2106" maintainer="Andreas Antener &lt;andreas@uaventure.com&gt;" name="Applied Aeronautics Albatross">
<maintainer>Andreas Antener &lt;andreas@uaventure.com&gt;</maintainer>
<type>Standard Plane</type>
<output name="AUX1">feed-through of RC AUX1 channel</output>
<output name="AUX2">feed-through of RC AUX2 channel</output>
<output name="AUX3">feed-through of RC AUX3 channel</output>
<output name="MAIN1">aileron right</output>
<output name="MAIN2">aileron left</output>
<output name="MAIN3">v-tail right</output>
<output name="MAIN4">v-tail left</output>
<output name="MAIN5">throttle</output>
<output name="MAIN6">wheel</output>
<output name="MAIN7">flaps right</output>
<output name="MAIN8">flaps left</output>
</airframe>
</airframe_group> </airframe_group>
<airframe_group image="" name="Standard VTOL"> <airframe_group image="" name="Standard VTOL">
<airframe id="13005" maintainer="Simon Wilks &lt;simon@uaventure.com&gt;" name="Generic AAERT tailplane airframe with Quad VTOL."> <airframe id="13005" maintainer="Simon Wilks &lt;simon@uaventure.com&gt;" name="Fun Cub Quad VTOL.">
<maintainer>Simon Wilks &lt;simon@uaventure.com&gt;</maintainer> <maintainer>Simon Wilks &lt;simon@uaventure.com&gt;</maintainer>
<type>Standard VTOL</type> <type>Standard VTOL</type>
</airframe> </airframe>
...@@ -275,6 +325,10 @@ ...@@ -275,6 +325,10 @@
<maintainer>Simon Wilks &lt;simon@uaventure.com&gt;</maintainer> <maintainer>Simon Wilks &lt;simon@uaventure.com&gt;</maintainer>
<type>Standard VTOL</type> <type>Standard VTOL</type>
</airframe> </airframe>
<airframe id="13007" maintainer="Sander Smeets &lt;sander@droneslab.com&gt;" name="Generic AAVVT v-tail plane airframe with Quad VTOL.">
<maintainer>Sander Smeets &lt;sander@droneslab.com&gt;</maintainer>
<type>Standard VTOL</type>
</airframe>
</airframe_group> </airframe_group>
<airframe_group image="" name="Tricopter Y+"> <airframe_group image="" name="Tricopter Y+">
<airframe id="14001" maintainer="Trent Lukaczyk &lt;aerialhedgehog@gmail.com&gt;" name="Generic Tricopter Y+ Geometry"> <airframe id="14001" maintainer="Trent Lukaczyk &lt;aerialhedgehog@gmail.com&gt;" name="Generic Tricopter Y+ Geometry">
......
...@@ -43,7 +43,7 @@ MapQuickItem { ...@@ -43,7 +43,7 @@ MapQuickItem {
MissionItemIndexLabel { MissionItemIndexLabel {
id: _label id: _label
isCurrentItem: missionItem.isCurrentItem isCurrentItem: missionItem.isCurrentItem
label: missionItem.sequenceNumber label: missionItem.sequenceNumber == 0 ? "H" : missionItem.sequenceNumber
onClicked: _item.clicked() onClicked: _item.clicked()
} }
} }
...@@ -219,6 +219,7 @@ QGCView { ...@@ -219,6 +219,7 @@ QGCView {
//offlineHomePosition = coordinate //offlineHomePosition = coordinate
} else if (addMissionItemsButton.checked) { } else if (addMissionItemsButton.checked) {
var index = controller.addMissionItem(coordinate) var index = controller.addMissionItem(coordinate)
addMissionItemsButtonAutoOffTimer.stop()
addMissionItemsButtonAutoOffTimer.start() addMissionItemsButtonAutoOffTimer.start()
setCurrentItem(index) setCurrentItem(index)
} else { } else {
......
...@@ -594,7 +594,7 @@ ...@@ -594,7 +594,7 @@
"friendlyName": "VTOL Transition", "friendlyName": "VTOL Transition",
"description": "Perform flight mode transition", "description": "Perform flight mode transition",
"category": "Basic", "category": "Basic",
"param7": { "param1": {
"label": "Mode:", "label": "Mode:",
"default": 3, "default": 3,
"decimalPlaces": 0, "decimalPlaces": 0,
......
...@@ -484,19 +484,22 @@ void MissionController::_initAllMissionItems(void) ...@@ -484,19 +484,22 @@ void MissionController::_initAllMissionItems(void)
} }
homeItem->setHomePositionSpecialCase(true); homeItem->setHomePositionSpecialCase(true);
if (_activeVehicle) { if (_activeVehicle) {
homeItem->setCoordinate(_activeVehicle->homePosition());
homeItem->setHomePositionValid(_activeVehicle->homePositionAvailable()); homeItem->setHomePositionValid(_activeVehicle->homePositionAvailable());
if (homeItem->homePositionValid()) {
homeItem->setCoordinate(_activeVehicle->homePosition());
}
} else { } else {
homeItem->setHomePositionValid(false); homeItem->setHomePositionValid(false);
} }
homeItem->setCommand(MAV_CMD_NAV_WAYPOINT); homeItem->setCommand(MAV_CMD_NAV_WAYPOINT);
homeItem->setFrame(MAV_FRAME_GLOBAL); homeItem->setFrame(MAV_FRAME_GLOBAL);
if (!homeItem->homePositionValid()) { if (!homeItem->homePositionValid()) {
QGeoCoordinate homeCoord = homeItem->coordinate(); // Set a bogus home position, the important value is 0.0 Altitude
homeCoord.setAltitude(0.0); homeItem->setCoordinate(QGeoCoordinate(37.803784, -122.462276, 0.0));
homeItem->setCoordinate(homeCoord);
} }
qDebug() << "home item" << homeItem->homePositionValid() << homeItem->coordinate();
for (int i=0; i<_missionItems->count(); i++) { for (int i=0; i<_missionItems->count(); i++) {
_initMissionItem(qobject_cast<MissionItem*>(_missionItems->get(i))); _initMissionItem(qobject_cast<MissionItem*>(_missionItems->get(i)));
} }
......
...@@ -94,7 +94,7 @@ QGCView { ...@@ -94,7 +94,7 @@ QGCView {
//-- Have we received this entry already? //-- Have we received this entry already?
if(controller.model.get(styleData.row).received) { if(controller.model.get(styleData.row).received) {
var d = controller.model.get(styleData.row).time var d = controller.model.get(styleData.row).time
if(d.getUTCFullYear() < 1980) if(d.getUTCFullYear() < 2010)
return "Date Unknown" return "Date Unknown"
else else
return d.toLocaleString() return d.toLocaleString()
......
...@@ -67,6 +67,7 @@ LogDownloadController::LogDownloadController(void) ...@@ -67,6 +67,7 @@ LogDownloadController::LogDownloadController(void)
, _requestingLogEntries(false) , _requestingLogEntries(false)
, _downloadingLogs(false) , _downloadingLogs(false)
, _retries(0) , _retries(0)
, _apmOneBased(0)
{ {
MultiVehicleManager *manager = qgcApp()->toolbox()->multiVehicleManager(); MultiVehicleManager *manager = qgcApp()->toolbox()->multiVehicleManager();
connect(manager, &MultiVehicleManager::activeVehicleChanged, this, &LogDownloadController::_setActiveVehicle); connect(manager, &MultiVehicleManager::activeVehicleChanged, this, &LogDownloadController::_setActiveVehicle);
...@@ -114,6 +115,11 @@ LogDownloadController::_logEntry(UASInterface* uas, uint32_t time_utc, uint32_t ...@@ -114,6 +115,11 @@ LogDownloadController::_logEntry(UASInterface* uas, uint32_t time_utc, uint32_t
} }
//-- If this is the first, pre-fill it //-- If this is the first, pre-fill it
if(!_logEntriesModel.count() && num_logs > 0) { 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++) { for(int i = 0; i < num_logs; i++) {
QGCLogEntry *entry = new QGCLogEntry(i); QGCLogEntry *entry = new QGCLogEntry(i);
_logEntriesModel.append(entry); _logEntriesModel.append(entry);
...@@ -121,14 +127,18 @@ LogDownloadController::_logEntry(UASInterface* uas, uint32_t time_utc, uint32_t ...@@ -121,14 +127,18 @@ LogDownloadController::_logEntry(UASInterface* uas, uint32_t time_utc, uint32_t
} }
//-- Update this log record //-- Update this log record
if(num_logs > 0) { if(num_logs > 0) {
if(id < _logEntriesModel.count()) { //-- Skip if empty (APM first packet)
QGCLogEntry* entry = _logEntriesModel[id]; if(size) {
entry->setSize(size); id -= _apmOneBased;
entry->setTime(QDateTime::fromTime_t(time_utc)); if(id < _logEntriesModel.count()) {
entry->setReceived(true); QGCLogEntry* entry = _logEntriesModel[id];
entry->setStatus(QString("Available")); entry->setSize(size);
} else { entry->setTime(QDateTime::fromTime_t(time_utc));
qWarning() << "Received log entry for out-of-bound index:" << id; entry->setReceived(true);
entry->setStatus(QString("Available"));
} else {
qWarning() << "Received log entry for out-of-bound index:" << id;
}
} }
} else { } else {
//-- No logs to list //-- No logs to list
...@@ -164,13 +174,18 @@ LogDownloadController::_entriesComplete() ...@@ -164,13 +174,18 @@ LogDownloadController::_entriesComplete()
//---------------------------------------------------------------------------------------- //----------------------------------------------------------------------------------------
void void
LogDownloadController::_resetSelection() LogDownloadController::_resetSelection(bool canceled)
{ {
int num_logs = _logEntriesModel.count(); int num_logs = _logEntriesModel.count();
for(int i = 0; i < num_logs; i++) { for(int i = 0; i < num_logs; i++) {
QGCLogEntry* entry = _logEntriesModel[i]; QGCLogEntry* entry = _logEntriesModel[i];
if(entry) { if(entry) {
entry->setSelected(false); if(entry->selected()) {
if(canceled) {
entry->setStatus(QString("Canceled"));
}
entry->setSelected(false);
}
} }
} }
emit selectionChanged(); emit selectionChanged();
...@@ -227,6 +242,9 @@ LogDownloadController::_findMissingEntries() ...@@ -227,6 +242,9 @@ LogDownloadController::_findMissingEntries()
if(end < 0) { if(end < 0) {
end = start; end = start;
} }
//-- APM "Fix"
start += _apmOneBased;
end += _apmOneBased;
//-- Request these entries again //-- Request these entries again
_requestLogList((uint32_t)start, (uint32_t) end); _requestLogList((uint32_t)start, (uint32_t) end);
} else { } else {
...@@ -241,6 +259,8 @@ LogDownloadController::_logData(UASInterface* uas, uint32_t ofs, uint16_t id, ui ...@@ -241,6 +259,8 @@ LogDownloadController::_logData(UASInterface* uas, uint32_t ofs, uint16_t id, ui
if(!_uas || uas != _uas || !_downloadData) { if(!_uas || uas != _uas || !_downloadData) {
return; return;
} }
//-- APM "Fix"
id -= _apmOneBased;
if(_downloadData->ID != id) { if(_downloadData->ID != id) {
qWarning() << "Received log data for wrong log"; qWarning() << "Received log data for wrong log";
return; return;
...@@ -360,6 +380,8 @@ void ...@@ -360,6 +380,8 @@ void
LogDownloadController::_requestLogData(uint8_t id, uint32_t offset, uint32_t count) LogDownloadController::_requestLogData(uint8_t id, uint32_t offset, uint32_t count)
{ {
if(_vehicle) { if(_vehicle) {
//-- APM "Fix"
id += _apmOneBased;
qCDebug(LogDownloadLog) << "Request log data (id:" << id << "offset:" << offset << "size:" << count << ")"; qCDebug(LogDownloadLog) << "Request log data (id:" << id << "offset:" << offset << "size:" << count << ")";
mavlink_message_t msg; mavlink_message_t msg;
mavlink_msg_log_request_data_pack( mavlink_msg_log_request_data_pack(
...@@ -423,6 +445,16 @@ LogDownloadController::download(void) ...@@ -423,6 +445,16 @@ LogDownloadController::download(void)
if(!_downloadPath.isEmpty()) { if(!_downloadPath.isEmpty()) {
if(!_downloadPath.endsWith(QDir::separator())) if(!_downloadPath.endsWith(QDir::separator()))
_downloadPath += 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 //-- Start download process
_downloadingLogs = true; _downloadingLogs = true;
emit downloadingLogsChanged(); emit downloadingLogsChanged();
...@@ -464,13 +496,18 @@ LogDownloadController::_prepareLogDownload() ...@@ -464,13 +496,18 @@ LogDownloadController::_prepareLogDownload()
emit selectionChanged(); emit selectionChanged();
bool result = false; bool result = false;
QString ftime; QString ftime;
if(entry->time().date().year() < 1980) { if(entry->time().date().year() < 2010) {
ftime = "UnknownDate"; ftime = "UnknownDate";
} else { } else {
ftime = entry->time().toString("yyyy-M-d-hh-mm-ss"); ftime = entry->time().toString("yyyy-M-d-hh-mm-ss");
} }
_downloadData = new LogDownloadData(entry); _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); _downloadData->file.setFileName(_downloadPath + _downloadData->filename);
//-- Append a number to the end if the filename already exists //-- Append a number to the end if the filename already exists
if (_downloadData->file.exists()){ if (_downloadData->file.exists()){
...@@ -539,7 +576,7 @@ LogDownloadController::cancel(void) ...@@ -539,7 +576,7 @@ LogDownloadController::cancel(void)
delete _downloadData; delete _downloadData;
_downloadData = 0; _downloadData = 0;
} }
_resetSelection(); _resetSelection(true);
_downloadingLogs = false; _downloadingLogs = false;
emit downloadingLogsChanged(); emit downloadingLogsChanged();
} }
......
...@@ -171,7 +171,7 @@ private: ...@@ -171,7 +171,7 @@ private:
void _findMissingEntries(); void _findMissingEntries();
void _receivedAllEntries(); void _receivedAllEntries();
void _receivedAllData (); void _receivedAllData ();
void _resetSelection (); void _resetSelection (bool canceled = false);
void _findMissingData (); void _findMissingData ();
void _requestLogList (uint32_t start = 0, uint32_t end = 0xFFFF); void _requestLogList (uint32_t start = 0, uint32_t end = 0xFFFF);
void _requestLogData (uint8_t id, uint32_t offset = 0, uint32_t count = 0xFFFFFFFF); void _requestLogData (uint8_t id, uint32_t offset = 0, uint32_t count = 0xFFFFFFFF);
...@@ -187,6 +187,7 @@ private: ...@@ -187,6 +187,7 @@ private:
bool _requestingLogEntries; bool _requestingLogEntries;
bool _downloadingLogs; bool _downloadingLogs;
int _retries; int _retries;
int _apmOneBased;
QString _downloadPath; QString _downloadPath;
}; };
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment