diff --git a/QGCInstaller.pri b/QGCInstaller.pri
index 72c19f498951e2468362712f8c5089d9663d7b8a..d7a335ef9f972ed3c19f5395eafaa5c907de1d56 100644
--- a/QGCInstaller.pri
+++ b/QGCInstaller.pri
@@ -19,7 +19,8 @@
installer {
MacBuild {
- QMAKE_POST_LINK += && $$dirname(QMAKE_QMAKE)/macdeployqt $${DESTDIR}/qgroundcontrol.app -dmg
+ QMAKE_POST_LINK += && $$dirname(QMAKE_QMAKE)/macdeployqt $${DESTDIR}/qgroundcontrol.app
+ QMAKE_POST_LINK += && hdiutil create -layout SPUD -srcfolder $${DESTDIR}/qgroundcontrol.app -volname QGroundControl $${DESTDIR}/qgroundcontrol.dmg
}
WindowsBuild {
diff --git a/QGCSetup.pri b/QGCSetup.pri
index c99a7c09719b050063a8a88c0108b8b58f37f4b7..861859f17bd6c8243c0935491bca89ea6398ba90 100644
--- a/QGCSetup.pri
+++ b/QGCSetup.pri
@@ -197,7 +197,8 @@ WindowsBuild {
QMAKE_POST_LINK += $$escape_expand(\\n) mkdir release\\platforms
QMAKE_POST_LINK += $$escape_expand(\\n) $$QMAKE_COPY \"$$PLUGINS_DIR_WIN\\platforms\\qwindows$${DLL_QT_DEBUGCHAR}.dll\" \"$$DESTDIR_WIN\\platforms\\qwindows$${DLL_QT_DEBUGCHAR}.dll\"
QMAKE_POST_LINK += $$escape_expand(\\n) $$QMAKE_COPY_DIR \"$$PLUGINS_DIR_WIN\\imageformats\" \"$$DESTDIR_WIN\\imageformats\"
-
+ QMAKE_POST_LINK += $$escape_expand(\\n) $$QMAKE_COPY_DIR \"$$PLUGINS_DIR_WIN\\sqldrivers\" \"$$DESTDIR_WIN\\sqldrivers\"
+
ReleaseBuild {
# Copy Visual Studio DLLs
# Note that this is only done for release because the debugging versions of these DLLs cannot be redistributed.
diff --git a/README.md b/README.md
index 1b854bf070bac42a887147592376d904192aacc1..a40c36063dc3c909cdd8e7de370508df08ecb557 100644
--- a/README.md
+++ b/README.md
@@ -141,7 +141,7 @@ Only compilation using Visual Studio 2010, 2012, and 2013 are supported.
3. **[OPTIONAL]** Go to the QGroundControl folder and then to libs/thirdParty/libxbee and build it following the instructions in win32.README.txt
-4. Open the Qt Command Prompt program from the Start Menu, navigate to the source folder of QGroundControl, and create the Visual Studio project by typing `qmake -tp vc qgroundcontrol.pro`
+4. Open the Qt Command Prompt program from the Start Menu, navigate to the source folder of QGroundControl, and create the Visual Studio project by typing `qmake -tp vc qgroundcontrol.pro`. To build a "Release" only build which does not contain unit tests, add the options 'CONFIG-=debug_and_release CONFIG+=release'.
5. Now open the generated `qgroundcontrol.vcxproj` file.
diff --git a/files/flightgear/Protocol/qgroundcontrol-fixed-wing.xml b/files/flightgear/Protocol/qgroundcontrol-fixed-wing.xml
index 0ecbf20d5dde9d6a742eef9a2d37f9bf318d8fc5..5ecb9966bc1e3283c91b3c1d961ba1a57dda120c 100644
--- a/files/flightgear/Protocol/qgroundcontrol-fixed-wing.xml
+++ b/files/flightgear/Protocol/qgroundcontrol-fixed-wing.xml
@@ -6,7 +6,7 @@
@@ -195,13 +204,13 @@
float/controls/flight/elevator
-
+
rudderfloat/controls/flight/rudder
-
+
runningbool
@@ -213,7 +222,7 @@
float/controls/engines/engine/throttle
-
+
diff --git a/libs/opmapcontrol/src/core/pureimagecache.cpp b/libs/opmapcontrol/src/core/pureimagecache.cpp
index efda4187547e4e685477fcb7e00203dd2e6409f5..8562fcaeea3306b51ba8aeb38da763e2fc3255da 100644
--- a/libs/opmapcontrol/src/core/pureimagecache.cpp
+++ b/libs/opmapcontrol/src/core/pureimagecache.cpp
@@ -223,7 +223,7 @@ namespace core {
qlonglong id=++ConnCounter;
Mcounter.unlock();
#ifdef DEBUG_PUREIMAGECACHE
- qDebug()<<"Cache dir="<
(dataSize());
if ( !painter || numSamples <= 0 )
return;
@@ -405,7 +405,7 @@ void QwtPlotCurve::drawCurve( QPainter *painter, int style,
// we always need the complete
// curve for fitting
from = 0;
- to = dataSize() - 1;
+ to = static_cast(dataSize()) - 1;
}
drawLines( painter, xMap, yMap, canvasRect, from, to );
break;
diff --git a/libs/qwt/qwt_point_data.cpp b/libs/qwt/qwt_point_data.cpp
index d4eeaaabb32490634dd2d19a44a2659039a0ce14..4743d179c71c57ad483478609a6657f66c2fc9e0 100644
--- a/libs/qwt/qwt_point_data.cpp
+++ b/libs/qwt/qwt_point_data.cpp
@@ -37,10 +37,10 @@ QwtPointArrayData::QwtPointArrayData(
QwtPointArrayData::QwtPointArrayData( const double *x,
const double *y, size_t size )
{
- d_x.resize( size );
+ d_x.resize( static_cast(size) );
::memcpy( d_x.data(), x, size * sizeof( double ) );
- d_y.resize( size );
+ d_y.resize(static_cast(size));
::memcpy( d_y.data(), y, size * sizeof( double ) );
}
@@ -273,7 +273,7 @@ QPointF QwtSyntheticPointData::sample( size_t index ) const
if ( index >= d_size )
return QPointF( 0, 0 );
- const double xValue = x( index );
+ const double xValue = x( static_cast(index) );
const double yValue = y( xValue );
return QPointF( xValue, yValue );
diff --git a/libs/qwt/qwt_series_data.cpp b/libs/qwt/qwt_series_data.cpp
index 319af41ff955a5089c49c74220b6dad6d6248003..f5c7618e031f6e0d9764b79d923733be393de039 100644
--- a/libs/qwt/qwt_series_data.cpp
+++ b/libs/qwt/qwt_series_data.cpp
@@ -78,7 +78,7 @@ QRectF qwtBoundingRectT(
from = 0;
if ( to < 0 )
- to = series.size() - 1;
+ to = static_cast(series.size()) - 1;
if ( to < from )
return boundingRect;
diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro
index cd7c6c79060a5d346458e5c2f5baf822fe91dc1c..ee921d15d194a26e8b6cbf4e3b38251706de3203 100644
--- a/qgroundcontrol.pro
+++ b/qgroundcontrol.pro
@@ -73,6 +73,11 @@ CONFIG(debug, debug|release) {
error(Unsupported build flavor)
}
+# Need to special case Windows debug_and_release since VS Project creation in this case does strange things [QTBUG-40351]
+win32:debug_and_release {
+ CONFIG += WindowsDebugAndRelease
+}
+
# Setup our build directories
BASEDIR = $${IN_PWD}
@@ -744,8 +749,15 @@ SOURCES += \
#
# Unit Test specific configuration goes here
-# We'd ideally only build this code as part of a Debug build, but qmake doesn't allow
-# for Debug-only files when generating Visual Studio projects [QTBUG-40351]
+#
+# We have to special case Windows debug_and_release builds because you can't have files
+# which are only in the debug variant [QTBUG-40351]. So in this case we include unit tests
+# even in the release variant. If you want a Windows release build with no unit tests run
+# qmake with CONFIG-=debug_and_release CONFIG+=release.
+#
+
+DebugBuild|WindowsDebugAndRelease {
+
INCLUDEPATH += \
src/qgcunittest
@@ -778,3 +790,5 @@ SOURCES += \
src/qgcunittest/TCPLoopBackServer.cc \
src/qgcunittest/QGCUASFileManagerTest.cc \
src/qgcunittest/PX4RCCalibrationTest.cc
+
+}
diff --git a/src/comm/MAVLinkSimulationWaypointPlanner.cc b/src/comm/MAVLinkSimulationWaypointPlanner.cc
index c4cc5fee3beb2e965945b74da0e574afb2df62dd..aa6384166c947a50cb5761233cbcbeaf72f56efe 100644
--- a/src/comm/MAVLinkSimulationWaypointPlanner.cc
+++ b/src/comm/MAVLinkSimulationWaypointPlanner.cc
@@ -890,7 +890,7 @@ void MAVLinkSimulationWaypointPlanner::mavlink_handler (const mavlink_message_t*
} else {
if (verbose) qDebug("Got MAVLINK_MSG_ID_MISSION_ITEM_REQUEST_LIST from %u but have no waypoints, staying in \n", msg->sysid);
}
- protocol_current_count = waypoints->size();
+ protocol_current_count = static_cast(waypoints->size());
send_waypoint_count(msg->sysid,msg->compid, protocol_current_count);
} else {
if (verbose) qDebug("Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST_LIST because i'm doing something else already (state=%i).\n", current_state);
@@ -999,7 +999,7 @@ void MAVLinkSimulationWaypointPlanner::mavlink_handler (const mavlink_message_t*
send_waypoint_ack(protocol_current_partner_systemid, protocol_current_partner_compid, 0);
if (current_active_wp_id > waypoints_receive_buffer->size()-1) {
- current_active_wp_id = waypoints_receive_buffer->size() - 1;
+ current_active_wp_id = static_cast(waypoints_receive_buffer->size()) - 1;
}
// switch the waypoints list
diff --git a/src/comm/QGCFlightGearLink.cc b/src/comm/QGCFlightGearLink.cc
index f570adf5ef99fb0472f66900d15db368302c9cad..9bc8a7aa2ac4c1c01117eda863413f35145a295c 100644
--- a/src/comm/QGCFlightGearLink.cc
+++ b/src/comm/QGCFlightGearLink.cc
@@ -99,6 +99,8 @@ void QGCFlightGearLink::run()
mav, SLOT(sendHilGps(quint64, double, double, double, int, float, float, float, float, float, float, float, int)));
connect(this, SIGNAL(sensorHilRawImuChanged(quint64,float,float,float,float,float,float,float,float,float,float,float,float,float,quint32)),
mav, SLOT(sendHilSensors(quint64,float,float,float,float,float,float,float,float,float,float,float,float,float,quint32)));
+ connect(this, SIGNAL(sensorHilOpticalFlowChanged(quint64, qint16, qint16, float,float, quint8, float)),
+ mav, SLOT(sendHilOpticalFlow(quint64, qint16, qint16, float, float, quint8, float)));
// Start a new QProcess to run FlightGear in
_fgProcess = new QProcess(this);
@@ -298,7 +300,7 @@ void QGCFlightGearLink::readBytes()
QStringList values = state.split("\t");
// Check length
- const int nValues = 21;
+ const int nValues = 22;
if (values.size() != nValues)
{
qDebug() << "RETURN LENGTH MISMATCHING EXPECTED" << nValues << "BUT GOT" << values.size();
@@ -316,6 +318,7 @@ void QGCFlightGearLink::readBytes()
float temperature;
float abs_pressure;
float mag_variation, mag_dip, xmag_ned, ymag_ned, zmag_ned, xmag_body, ymag_body, zmag_body;
+ float alt_agl;
lat = values.at(1).toDouble();
@@ -345,6 +348,8 @@ void QGCFlightGearLink::readBytes()
abs_pressure = values.at(20).toFloat() * 1e2f; //convert to Pa from hPa
abs_pressure += barometerOffsetkPa * 1e3f; //add offset, convert from kPa to Pa
+ alt_agl = values.at(21).toFloat();
+
//calculate differential pressure
const float air_gas_constant = 287.1f; // J/(kg * K)
const float absolute_null_celsius = -273.15f; // °C
@@ -424,8 +429,16 @@ void QGCFlightGearLink::readBytes()
int satellites = 8;
emit sensorHilGpsChanged(QGC::groundTimeUsecs(), lat, lon, alt, gps_fix_type, eph, epv, vel, vx, vy, vz, cog, satellites);
-
// qDebug() << "sensorHilGpsChanged " << lat << lon << alt << vel;
+
+ // Send Optical Flow message. For now we set the flow quality to 0 and just write the ground_distance field
+ float distanceMeasurement = -1.0; // -1 means invalid value
+ if (fabsf(roll) < 0.87 && fabsf(pitch) < 0.87) // return a valid value only for decent angles
+ {
+ distanceMeasurement = fabsf((float)(1.0/cosPhi * 1.0/cosThe * alt_agl)); // assuming planar ground
+ }
+ emit sensorHilOpticalFlowChanged(QGC::groundTimeUsecs(), 0, 0, 0.0f,
+ 0.0f, 0.0f, distanceMeasurement);
} else {
emit hilStateChanged(QGC::groundTimeUsecs(), roll, pitch, yaw, rollspeed,
pitchspeed, yawspeed, lat, lon, alt,
@@ -470,6 +483,8 @@ bool QGCFlightGearLink::disconnectSimulation()
disconnect(this, SIGNAL(hilStateChanged(quint64, float, float, float, float,float, float, double, double, double, float, float, float, float, float, float, float, float)), mav, SLOT(sendHilState(quint64, float, float, float, float,float, float, double, double, double, float, float, float, float, float, float, float, float)));
disconnect(this, SIGNAL(sensorHilGpsChanged(quint64, double, double, double, int, float, float, float, float, float, float, float, int)), mav, SLOT(sendHilGps(quint64, double, double, double, int, float, float, float, float, float, float, float, int)));
disconnect(this, SIGNAL(sensorHilRawImuChanged(quint64,float,float,float,float,float,float,float,float,float,float,float,float,float,quint32)), mav, SLOT(sendHilSensors(quint64,float,float,float,float,float,float,float,float,float,float,float,float,float,quint32)));
+ disconnect(this, SIGNAL(sensorHilOpticalFlowChanged(quint64, qint16, qint16, float,float, quint8, float)),
+ mav, SLOT(sendHilOpticalFlow(quint64, qint16, qint16, float, float, quint8, float)));
if (_fgProcess)
{
diff --git a/src/comm/QGCHilLink.h b/src/comm/QGCHilLink.h
index 0c2a08f4f518a59a0ffbeac7c677dea9b4d2429a..ed83adafe11ff428249968bba952eceba9cdfe43 100644
--- a/src/comm/QGCHilLink.h
+++ b/src/comm/QGCHilLink.h
@@ -105,6 +105,9 @@ signals:
float abs_pressure, float diff_pressure,
float pressure_alt, float temperature,
quint32 fields_updated);
+
+ void sensorHilOpticalFlowChanged(quint64 time_us, qint16 flow_x, qint16 flow_y, float flow_comp_m_x,
+ float flow_comp_m_y, quint8 quality, float ground_distance);
/** @brief Remote host and port changed */
void remoteChanged(const QString& hostPort);
diff --git a/src/qgcunittest/MockMavlinkFileServer.cc b/src/qgcunittest/MockMavlinkFileServer.cc
index b4945b3b015cf72aab58221f9b87dc9042934e00..87f8016d7d233ddba31fb51e00ec5d348bc942e4 100644
--- a/src/qgcunittest/MockMavlinkFileServer.cc
+++ b/src/qgcunittest/MockMavlinkFileServer.cc
@@ -28,7 +28,6 @@ const MockMavlinkFileServer::ErrorMode_t MockMavlinkFileServer::rgFailureModes[]
MockMavlinkFileServer::errModeNakResponse,
MockMavlinkFileServer::errModeNoSecondResponse,
MockMavlinkFileServer::errModeNakSecondResponse,
- MockMavlinkFileServer::errModeBadCRC,
MockMavlinkFileServer::errModeBadSequence,
};
const size_t MockMavlinkFileServer::cFailureModes = sizeof(MockMavlinkFileServer::rgFailureModes) / sizeof(MockMavlinkFileServer::rgFailureModes[0]);
@@ -45,8 +44,10 @@ const MockMavlinkFileServer::FileTestCase MockMavlinkFileServer::rgFileTestCases
// We only support a single fixed session
const uint8_t MockMavlinkFileServer::_sessionId = 1;
-MockMavlinkFileServer::MockMavlinkFileServer(void) :
- _errMode(errModeNone)
+MockMavlinkFileServer::MockMavlinkFileServer(uint8_t systemIdQGC, uint8_t systemIdServer) :
+ _errMode(errModeNone),
+ _systemIdServer(systemIdServer),
+ _systemIdQGC(systemIdQGC)
{
}
@@ -64,7 +65,7 @@ void MockMavlinkFileServer::_listCommand(QGCUASFileManager::Request* request, ui
// We only support root path
path = (char *)&request->data[0];
if (!path.isEmpty() && path != "/") {
- _sendNak(QGCUASFileManager::kErrNotDir, outgoingSeqNumber);
+ _sendNak(QGCUASFileManager::kErrFail, outgoingSeqNumber);
return;
}
@@ -74,7 +75,6 @@ void MockMavlinkFileServer::_listCommand(QGCUASFileManager::Request* request, ui
return;
}
- ackResponse.hdr.magic = 'f';
ackResponse.hdr.opcode = QGCUASFileManager::kRspAck;
ackResponse.hdr.session = 0;
ackResponse.hdr.offset = request->hdr.offset;
@@ -86,8 +86,8 @@ void MockMavlinkFileServer::_listCommand(QGCUASFileManager::Request* request, ui
char *bufPtr = (char *)&ackResponse.data[0];
for (int i=0; i<_fileList.size(); i++) {
strcpy(bufPtr, _fileList[i].toStdString().c_str());
- size_t cchFilename = strlen(bufPtr);
- Q_ASSERT(cchFilename);
+ uint8_t cchFilename = static_cast(strlen(bufPtr));
+ Q_ASSERT(cchFilename);
ackResponse.hdr.size += cchFilename + 1;
bufPtr += cchFilename + 1;
}
@@ -95,7 +95,7 @@ void MockMavlinkFileServer::_listCommand(QGCUASFileManager::Request* request, ui
_emitResponse(&ackResponse, outgoingSeqNumber);
} else if (_errMode == errModeNakSecondResponse) {
// Nak error all subsequent requests
- _sendNak(QGCUASFileManager::kErrPerm, outgoingSeqNumber);
+ _sendNak(QGCUASFileManager::kErrFail, outgoingSeqNumber);
return;
} else if (_errMode == errModeNoSecondResponse) {
// No response for all subsequent requests
@@ -129,11 +129,10 @@ void MockMavlinkFileServer::_openCommand(QGCUASFileManager::Request* request, ui
}
}
if (!found) {
- _sendNak(QGCUASFileManager::kErrNotFile, outgoingSeqNumber);
+ _sendNak(QGCUASFileManager::kErrFail, outgoingSeqNumber);
return;
}
- response.hdr.magic = 'f';
response.hdr.opcode = QGCUASFileManager::kRspAck;
response.hdr.session = _sessionId;
@@ -151,7 +150,7 @@ void MockMavlinkFileServer::_readCommand(QGCUASFileManager::Request* request, ui
uint16_t outgoingSeqNumber = _nextSeqNumber(seqNumber);
if (request->hdr.session != _sessionId) {
- _sendNak(QGCUASFileManager::kErrNoSession, outgoingSeqNumber);
+ _sendNak(QGCUASFileManager::kErrFail, outgoingSeqNumber);
return;
}
@@ -162,7 +161,7 @@ void MockMavlinkFileServer::_readCommand(QGCUASFileManager::Request* request, ui
// If we get here it means the client is requesting additional data past the first request
if (_errMode == errModeNakSecondResponse) {
// Nak error all subsequent requests
- _sendNak(QGCUASFileManager::kErrPerm, outgoingSeqNumber);
+ _sendNak(QGCUASFileManager::kErrFail, outgoingSeqNumber);
return;
} else if (_errMode == errModeNoSecondResponse) {
// No rsponse for all subsequent requests
@@ -183,7 +182,6 @@ void MockMavlinkFileServer::_readCommand(QGCUASFileManager::Request* request, ui
// We should always have written something, otherwise there is something wrong with the code above
Q_ASSERT(cDataBytes);
- response.hdr.magic = 'f';
response.hdr.session = _sessionId;
response.hdr.size = cDataBytes;
response.hdr.offset = request->hdr.offset;
@@ -198,7 +196,7 @@ void MockMavlinkFileServer::_terminateCommand(QGCUASFileManager::Request* reques
uint16_t outgoingSeqNumber = _nextSeqNumber(seqNumber);
if (request->hdr.session != _sessionId) {
- _sendNak(QGCUASFileManager::kErrNoSession, outgoingSeqNumber);
+ _sendNak(QGCUASFileManager::kErrInvalidSession, outgoingSeqNumber);
return;
}
@@ -214,15 +212,15 @@ void MockMavlinkFileServer::sendMessage(mavlink_message_t message)
{
QGCUASFileManager::Request ackResponse;
- Q_ASSERT(message.msgid == MAVLINK_MSG_ID_ENCAPSULATED_DATA);
+ Q_ASSERT(message.msgid == MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL);
- mavlink_encapsulated_data_t requestEncapsulatedData;
- mavlink_msg_encapsulated_data_decode(&message, &requestEncapsulatedData);
- QGCUASFileManager::Request* request = (QGCUASFileManager::Request*)&requestEncapsulatedData.data[0];
+ mavlink_file_transfer_protocol_t requestFileTransferProtocol;
+ mavlink_msg_file_transfer_protocol_decode(&message, &requestFileTransferProtocol);
+ QGCUASFileManager::Request* request = (QGCUASFileManager::Request*)&requestFileTransferProtocol.payload[0];
- Q_ASSERT(request->hdr.magic == QGCUASFileManager::kProtocolMagic);
-
- uint16_t incomingSeqNumber = requestEncapsulatedData.seqnr;
+ Q_ASSERT(requestFileTransferProtocol.target_system == _systemIdServer);
+
+ uint16_t incomingSeqNumber = request->hdr.seqNumber;
uint16_t outgoingSeqNumber = _nextSeqNumber(incomingSeqNumber);
if (_errMode == errModeNoResponse) {
@@ -230,58 +228,43 @@ void MockMavlinkFileServer::sendMessage(mavlink_message_t message)
return;
} else if (_errMode == errModeNakResponse) {
// Nak all requests, the actual error send back doesn't really matter as long as it's an error
- _sendNak(QGCUASFileManager::kErrPerm, outgoingSeqNumber);
+ _sendNak(QGCUASFileManager::kErrFail, outgoingSeqNumber);
return;
}
- // Validate CRC
- if (request->hdr.crc32 != QGCUASFileManager::crc32(request)) {
- _sendNak(QGCUASFileManager::kErrCrc, outgoingSeqNumber);
- }
-
switch (request->hdr.opcode) {
case QGCUASFileManager::kCmdTestNoAck:
// ignored, ack not sent back, for testing only
break;
- case QGCUASFileManager::kCmdReset:
+ case QGCUASFileManager::kCmdResetSessions:
// terminates all sessions
// Fall through to send back Ack
case QGCUASFileManager::kCmdNone:
// ignored, always acked
- ackResponse.hdr.magic = 'f';
ackResponse.hdr.opcode = QGCUASFileManager::kRspAck;
ackResponse.hdr.session = 0;
- ackResponse.hdr.crc32 = 0;
ackResponse.hdr.size = 0;
_emitResponse(&ackResponse, outgoingSeqNumber);
break;
- case QGCUASFileManager::kCmdList:
+ case QGCUASFileManager::kCmdListDirectory:
_listCommand(request, incomingSeqNumber);
break;
- case QGCUASFileManager::kCmdOpen:
+ case QGCUASFileManager::kCmdOpenFile:
_openCommand(request, incomingSeqNumber);
break;
- case QGCUASFileManager::kCmdRead:
+ case QGCUASFileManager::kCmdReadFile:
_readCommand(request, incomingSeqNumber);
break;
- case QGCUASFileManager::kCmdTerminate:
+ case QGCUASFileManager::kCmdTerminateSession:
_terminateCommand(request, incomingSeqNumber);
break;
- // Remainder of commands are NYI
-
- case QGCUASFileManager::kCmdCreate:
- // creates for writing, returns
- case QGCUASFileManager::kCmdWrite:
- // appends bytes at in
- case QGCUASFileManager::kCmdRemove:
- // remove file (only if created by server?)
default:
// nack for all NYI opcodes
_sendNak(QGCUASFileManager::kErrUnknownCommand, outgoingSeqNumber);
@@ -294,7 +277,6 @@ void MockMavlinkFileServer::_sendAck(uint16_t seqNumber)
{
QGCUASFileManager::Request ackResponse;
- ackResponse.hdr.magic = 'f';
ackResponse.hdr.opcode = QGCUASFileManager::kRspAck;
ackResponse.hdr.session = 0;
ackResponse.hdr.size = 0;
@@ -307,7 +289,6 @@ void MockMavlinkFileServer::_sendNak(QGCUASFileManager::ErrorCode error, uint16_
{
QGCUASFileManager::Request nakResponse;
- nakResponse.hdr.magic = 'f';
nakResponse.hdr.opcode = QGCUASFileManager::kRspNak;
nakResponse.hdr.session = 0;
nakResponse.hdr.size = 1;
@@ -321,14 +302,15 @@ void MockMavlinkFileServer::_emitResponse(QGCUASFileManager::Request* request, u
{
mavlink_message_t mavlinkMessage;
- request->hdr.magic = QGCUASFileManager::kProtocolMagic;
- request->hdr.crc32 = QGCUASFileManager::crc32(request);
- if (_errMode == errModeBadCRC) {
- // Return a bad CRC
- request->hdr.crc32++;
- }
+ request->hdr.seqNumber = seqNumber;
- mavlink_msg_encapsulated_data_pack(250, 50, &mavlinkMessage, seqNumber, (uint8_t*)request);
+ mavlink_msg_file_transfer_protocol_pack(_systemIdServer, // System ID
+ 0, // Component ID
+ &mavlinkMessage, // Mavlink Message to pack into
+ 0, // Target network
+ _systemIdQGC, // QGC Target System ID
+ 0, // Target component
+ (uint8_t*)request); // Payload
emit messageReceived(NULL, mavlinkMessage);
}
diff --git a/src/qgcunittest/MockMavlinkFileServer.h b/src/qgcunittest/MockMavlinkFileServer.h
index c3cd78208874277962fe16196f112cc6d08d2b3e..7e4e303b1ba5c63135786846f2ae4691e76a4fa0 100644
--- a/src/qgcunittest/MockMavlinkFileServer.h
+++ b/src/qgcunittest/MockMavlinkFileServer.h
@@ -40,7 +40,10 @@ class MockMavlinkFileServer : public MockMavlinkInterface
Q_OBJECT
public:
- MockMavlinkFileServer(void);
+ /// @brief Constructor for MockMavlinkFileServer
+ /// @param System ID for QGroundControl App
+ /// @pqram System ID for this Server
+ MockMavlinkFileServer(uint8_t systemIdQGC, uint8_t systemIdServer);
/// @brief Sets the list of files returned by the List command. Prepend names with F or D
/// to indicate (F)ile or (D)irectory.
@@ -53,7 +56,6 @@ public:
errModeNakResponse, ///< Nak all requests
errModeNoSecondResponse, ///< No response to subsequent request to initial command
errModeNakSecondResponse, ///< Nak subsequent request to initial command
- errModeBadCRC, ///< Return response with bad CRC
errModeBadSequence ///< Return response with bad sequence number
} ErrorMode_t;
@@ -103,6 +105,8 @@ private:
static const uint8_t _sessionId;
uint8_t _readFileLength; ///< Length of active file being read
ErrorMode_t _errMode; ///< Currently set error mode, as specified by setErrorMode
+ const uint8_t _systemIdServer; ///< System ID for server
+ const uint8_t _systemIdQGC; ///< QGC System ID
};
#endif
diff --git a/src/qgcunittest/MockUAS.h b/src/qgcunittest/MockUAS.h
index fc3b0cece36dcc25143448e008ca5c1534cd981b..a153a234b2cde6f3beb76ebefed0c192afdc5694 100644
--- a/src/qgcunittest/MockUAS.h
+++ b/src/qgcunittest/MockUAS.h
@@ -166,6 +166,9 @@ public slots:
{ Q_UNUSED(time_us); Q_UNUSED(xacc); Q_UNUSED(yacc); Q_UNUSED(zacc); Q_UNUSED(rollspeed); Q_UNUSED(pitchspeed); Q_UNUSED(yawspeed); Q_UNUSED(xmag); Q_UNUSED(ymag); Q_UNUSED(zmag); Q_UNUSED(abs_pressure); Q_UNUSED(diff_pressure); Q_UNUSED(pressure_alt); Q_UNUSED(temperature); Q_UNUSED(fields_changed); Q_ASSERT(false); };
virtual void sendHilGps(quint64 time_us, double lat, double lon, double alt, int fix_type, float eph, float epv, float vel, float vn, float ve, float vd, float cog, int satellites)
{ Q_UNUSED(time_us); Q_UNUSED(lat); Q_UNUSED(lon); Q_UNUSED(alt); Q_UNUSED(fix_type); Q_UNUSED(eph); Q_UNUSED(epv); Q_UNUSED(vel); Q_UNUSED(vn); Q_UNUSED(ve); Q_UNUSED(vd); Q_UNUSED(cog); Q_UNUSED(satellites); Q_ASSERT(false); };
+ virtual void sendHilOpticalFlow(quint64 time_us, qint16 flow_x, qint16 flow_y, float flow_comp_m_x,
+ float flow_comp_m_y, quint8 quality, float ground_distance)
+ { Q_UNUSED(time_us); Q_UNUSED(flow_x); Q_UNUSED(flow_y); Q_UNUSED(flow_comp_m_x); Q_UNUSED(flow_comp_m_y); Q_UNUSED(quality); Q_UNUSED(ground_distance); Q_ASSERT(false);};
virtual bool isRotaryWing() { Q_ASSERT(false); return false; }
virtual bool isFixedWing() { Q_ASSERT(false); return false; }
diff --git a/src/qgcunittest/QGCUASFileManagerTest.cc b/src/qgcunittest/QGCUASFileManagerTest.cc
index 0e83d47f95a0312966af001cfe0f98b1ddab73bb..40d0ae20f7505f66e6f7047596878c0804fe93c3 100644
--- a/src/qgcunittest/QGCUASFileManagerTest.cc
+++ b/src/qgcunittest/QGCUASFileManagerTest.cc
@@ -31,6 +31,7 @@
/// @author Don Gagne
QGCUASFileManagerUnitTest::QGCUASFileManagerUnitTest(void) :
+ _mockFileServer(_systemIdQGC, _systemIdServer),
_fileManager(NULL),
_multiSpy(NULL)
{
@@ -40,6 +41,7 @@ QGCUASFileManagerUnitTest::QGCUASFileManagerUnitTest(void) :
// Called once before all test cases are run
void QGCUASFileManagerUnitTest::initTestCase(void)
{
+ _mockUAS.setMockSystemId(_systemIdServer);
_mockUAS.setMockMavlinkPlugin(&_mockFileServer);
}
@@ -48,19 +50,16 @@ void QGCUASFileManagerUnitTest::init(void)
{
Q_ASSERT(_multiSpy == NULL);
- _fileManager = new QGCUASFileManager(NULL, &_mockUAS);
+ _fileManager = new QGCUASFileManager(NULL, &_mockUAS, _systemIdQGC);
Q_CHECK_PTR(_fileManager);
// Reset any internal state back to normal
_mockFileServer.setErrorMode(MockMavlinkFileServer::errModeNone);
_fileListReceived.clear();
- bool connected = connect(&_mockFileServer, SIGNAL(messageReceived(LinkInterface*, mavlink_message_t)), _fileManager, SLOT(receiveMessage(LinkInterface*, mavlink_message_t)));
- Q_ASSERT(connected);
- Q_UNUSED(connected); // Silent release build compiler warning
+ connect(&_mockFileServer, &MockMavlinkFileServer::messageReceived, _fileManager, &QGCUASFileManager::receiveMessage);
- connected = connect(_fileManager, SIGNAL(listEntry(const QString&)), this, SLOT(listEntry(const QString&)));
- Q_ASSERT(connected);
+ connect(_fileManager, &QGCUASFileManager::listEntry, this, &QGCUASFileManagerUnitTest::listEntry);
_rgSignals[listEntrySignalIndex] = SIGNAL(listEntry(const QString&));
_rgSignals[listCompleteSignalIndex] = SIGNAL(listComplete(void));
diff --git a/src/qgcunittest/QGCUASFileManagerTest.h b/src/qgcunittest/QGCUASFileManagerTest.h
index fc7d0063eeff36c8f17015a7cad8516e700d69ca..9b241747d3129c6154552ba8c54937e94ebc97ac 100644
--- a/src/qgcunittest/QGCUASFileManagerTest.h
+++ b/src/qgcunittest/QGCUASFileManagerTest.h
@@ -80,6 +80,10 @@ private:
downloadFileCompleteSignalMask = 1 << downloadFileCompleteSignalIndex,
errorMessageSignalMask = 1 << errorMessageSignalIndex,
};
+
+ static const uint8_t _systemIdQGC = 255;
+ static const uint8_t _systemIdServer = 128;
+
MockUAS _mockUAS;
MockMavlinkFileServer _mockFileServer;
diff --git a/src/uas/QGCUASFileManager.cc b/src/uas/QGCUASFileManager.cc
index 354a437f7401decd3af8392c7d3f7076765d531c..ed459d2368de9609c64ac47d829b9a1b10f1f616 100644
--- a/src/uas/QGCUASFileManager.cc
+++ b/src/uas/QGCUASFileManager.cc
@@ -24,79 +24,27 @@
#include "QGCUASFileManager.h"
#include "QGC.h"
#include "MAVLinkProtocol.h"
+#include "MainWindow.h"
#include
#include
#include
-static const quint32 crctab[] =
-{
- 0x00000000, 0x77073096, 0xee0e612c, 0x990951ba, 0x076dc419, 0x706af48f, 0xe963a535, 0x9e6495a3,
- 0x0edb8832, 0x79dcb8a4, 0xe0d5e91e, 0x97d2d988, 0x09b64c2b, 0x7eb17cbd, 0xe7b82d07, 0x90bf1d91,
- 0x1db71064, 0x6ab020f2, 0xf3b97148, 0x84be41de, 0x1adad47d, 0x6ddde4eb, 0xf4d4b551, 0x83d385c7,
- 0x136c9856, 0x646ba8c0, 0xfd62f97a, 0x8a65c9ec, 0x14015c4f, 0x63066cd9, 0xfa0f3d63, 0x8d080df5,
- 0x3b6e20c8, 0x4c69105e, 0xd56041e4, 0xa2677172, 0x3c03e4d1, 0x4b04d447, 0xd20d85fd, 0xa50ab56b,
- 0x35b5a8fa, 0x42b2986c, 0xdbbbc9d6, 0xacbcf940, 0x32d86ce3, 0x45df5c75, 0xdcd60dcf, 0xabd13d59,
- 0x26d930ac, 0x51de003a, 0xc8d75180, 0xbfd06116, 0x21b4f4b5, 0x56b3c423, 0xcfba9599, 0xb8bda50f,
- 0x2802b89e, 0x5f058808, 0xc60cd9b2, 0xb10be924, 0x2f6f7c87, 0x58684c11, 0xc1611dab, 0xb6662d3d,
- 0x76dc4190, 0x01db7106, 0x98d220bc, 0xefd5102a, 0x71b18589, 0x06b6b51f, 0x9fbfe4a5, 0xe8b8d433,
- 0x7807c9a2, 0x0f00f934, 0x9609a88e, 0xe10e9818, 0x7f6a0dbb, 0x086d3d2d, 0x91646c97, 0xe6635c01,
- 0x6b6b51f4, 0x1c6c6162, 0x856530d8, 0xf262004e, 0x6c0695ed, 0x1b01a57b, 0x8208f4c1, 0xf50fc457,
- 0x65b0d9c6, 0x12b7e950, 0x8bbeb8ea, 0xfcb9887c, 0x62dd1ddf, 0x15da2d49, 0x8cd37cf3, 0xfbd44c65,
- 0x4db26158, 0x3ab551ce, 0xa3bc0074, 0xd4bb30e2, 0x4adfa541, 0x3dd895d7, 0xa4d1c46d, 0xd3d6f4fb,
- 0x4369e96a, 0x346ed9fc, 0xad678846, 0xda60b8d0, 0x44042d73, 0x33031de5, 0xaa0a4c5f, 0xdd0d7cc9,
- 0x5005713c, 0x270241aa, 0xbe0b1010, 0xc90c2086, 0x5768b525, 0x206f85b3, 0xb966d409, 0xce61e49f,
- 0x5edef90e, 0x29d9c998, 0xb0d09822, 0xc7d7a8b4, 0x59b33d17, 0x2eb40d81, 0xb7bd5c3b, 0xc0ba6cad,
- 0xedb88320, 0x9abfb3b6, 0x03b6e20c, 0x74b1d29a, 0xead54739, 0x9dd277af, 0x04db2615, 0x73dc1683,
- 0xe3630b12, 0x94643b84, 0x0d6d6a3e, 0x7a6a5aa8, 0xe40ecf0b, 0x9309ff9d, 0x0a00ae27, 0x7d079eb1,
- 0xf00f9344, 0x8708a3d2, 0x1e01f268, 0x6906c2fe, 0xf762575d, 0x806567cb, 0x196c3671, 0x6e6b06e7,
- 0xfed41b76, 0x89d32be0, 0x10da7a5a, 0x67dd4acc, 0xf9b9df6f, 0x8ebeeff9, 0x17b7be43, 0x60b08ed5,
- 0xd6d6a3e8, 0xa1d1937e, 0x38d8c2c4, 0x4fdff252, 0xd1bb67f1, 0xa6bc5767, 0x3fb506dd, 0x48b2364b,
- 0xd80d2bda, 0xaf0a1b4c, 0x36034af6, 0x41047a60, 0xdf60efc3, 0xa867df55, 0x316e8eef, 0x4669be79,
- 0xcb61b38c, 0xbc66831a, 0x256fd2a0, 0x5268e236, 0xcc0c7795, 0xbb0b4703, 0x220216b9, 0x5505262f,
- 0xc5ba3bbe, 0xb2bd0b28, 0x2bb45a92, 0x5cb36a04, 0xc2d7ffa7, 0xb5d0cf31, 0x2cd99e8b, 0x5bdeae1d,
- 0x9b64c2b0, 0xec63f226, 0x756aa39c, 0x026d930a, 0x9c0906a9, 0xeb0e363f, 0x72076785, 0x05005713,
- 0x95bf4a82, 0xe2b87a14, 0x7bb12bae, 0x0cb61b38, 0x92d28e9b, 0xe5d5be0d, 0x7cdcefb7, 0x0bdbdf21,
- 0x86d3d2d4, 0xf1d4e242, 0x68ddb3f8, 0x1fda836e, 0x81be16cd, 0xf6b9265b, 0x6fb077e1, 0x18b74777,
- 0x88085ae6, 0xff0f6a70, 0x66063bca, 0x11010b5c, 0x8f659eff, 0xf862ae69, 0x616bffd3, 0x166ccf45,
- 0xa00ae278, 0xd70dd2ee, 0x4e048354, 0x3903b3c2, 0xa7672661, 0xd06016f7, 0x4969474d, 0x3e6e77db,
- 0xaed16a4a, 0xd9d65adc, 0x40df0b66, 0x37d83bf0, 0xa9bcae53, 0xdebb9ec5, 0x47b2cf7f, 0x30b5ffe9,
- 0xbdbdf21c, 0xcabac28a, 0x53b39330, 0x24b4a3a6, 0xbad03605, 0xcdd70693, 0x54de5729, 0x23d967bf,
- 0xb3667a2e, 0xc4614ab8, 0x5d681b02, 0x2a6f2b94, 0xb40bbe37, 0xc30c8ea1, 0x5a05df1b, 0x2d02ef8d
-};
-
-
-QGCUASFileManager::QGCUASFileManager(QObject* parent, UASInterface* uas) :
+
+QGCUASFileManager::QGCUASFileManager(QObject* parent, UASInterface* uas, uint8_t unitTestSystemIdQGC) :
QObject(parent),
_currentOperation(kCOIdle),
_mav(uas),
_lastOutgoingSeqNumber(0),
- _activeSession(0)
-{
- bool connected = connect(&_ackTimer, SIGNAL(timeout()), this, SLOT(_ackTimeout()));
- Q_ASSERT(connected);
- Q_UNUSED(connected); // Silence retail unused variable error
-}
-
-/// @brief Calculates a 32 bit CRC for the specified request.
-/// @param request Request to calculate CRC for. request->size must be set correctly.
-/// @param state previous crc state
-/// @return Calculated CRC
-quint32 QGCUASFileManager::crc32(Request* request, unsigned state)
+ _activeSession(0),
+ _systemIdQGC(unitTestSystemIdQGC)
{
- uint8_t* data = (uint8_t*)request;
- size_t cbData = sizeof(RequestHeader) + request->hdr.size;
-
- // Always calculate CRC with 0 initial CRC value
- quint32 crcSave = request->hdr.crc32;
- request->hdr.crc32 = 0;
-
- for (size_t i=0; i < cbData; i++)
- state = crctab[(state ^ data[i]) & 0xff] ^ (state >> 8);
-
- request->hdr.crc32 = crcSave;
-
- return state;
+ connect(&_ackTimer, &QTimer::timeout, this, &QGCUASFileManager::_ackTimeout);
+
+ _systemIdServer = _mav->getUASID();
+
+ // Make sure we don't have bad structure packing
+ Q_ASSERT(sizeof(RequestHeader) == 12);
}
/// @brief Respond to the Ack associated with the Open command with the next Read command.
@@ -116,7 +64,7 @@ void QGCUASFileManager::_openAckResponse(Request* openAck)
Request request;
request.hdr.session = _activeSession;
- request.hdr.opcode = kCmdRead;
+ request.hdr.opcode = kCmdReadFile;
request.hdr.offset = _readOffset;
request.hdr.size = sizeof(request.data);
@@ -180,8 +128,9 @@ void QGCUASFileManager::_readAckResponse(Request* readAck)
Request request;
request.hdr.session = _activeSession;
- request.hdr.opcode = kCmdRead;
+ request.hdr.opcode = kCmdReadFile;
request.hdr.offset = _readOffset;
+ request.hdr.size = 0;
_sendRequest(&request);
} else {
@@ -210,8 +159,8 @@ void QGCUASFileManager::_listAckResponse(Request* listAck)
// get the length of the name
uint8_t cBytesLeft = cBytes - offset;
- size_t nlen = strnlen(ptr, cBytesLeft);
- if (nlen < 2) {
+ uint8_t nlen = static_cast(strnlen(ptr, cBytesLeft));
+ if ((*ptr == 'S' && nlen > 1) || (*ptr != 'S' && nlen < 2)) {
_currentOperation = kCOIdle;
_emitErrorMessage(tr("Incorrectly formed list entry: '%1'").arg(ptr));
return;
@@ -221,10 +170,12 @@ void QGCUASFileManager::_listAckResponse(Request* listAck)
return;
}
- // Returned names are prepended with D for directory, F for file, U for unknown
+ // Returned names are prepended with D for directory, F for file, S for skip
if (*ptr == 'F' || *ptr == 'D') {
// put it in the view
_emitListEntry(ptr);
+ } else if (*ptr == 'S') {
+ // do nothing
} else {
qDebug() << "unknown entry" << ptr;
}
@@ -252,37 +203,25 @@ void QGCUASFileManager::receiveMessage(LinkInterface* link, mavlink_message_t me
{
Q_UNUSED(link);
- if (message.msgid != MAVLINK_MSG_ID_ENCAPSULATED_DATA) {
- // wtf, not for us
- return;
- }
-
- // XXX: hack to prevent files from videostream to interfere
- // FIXME: magic number
- if (message.compid != 50) {
+ // receiveMessage is signalled will all mavlink messages so we need to filter everything else out but ours.
+ if (message.msgid != MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL) {
return;
}
-
- mavlink_encapsulated_data_t data;
- mavlink_msg_encapsulated_data_decode(&message, &data);
- Request* request = (Request*)&data.data[0];
- if (request->hdr.magic != kProtocolMagic) {
+ mavlink_file_transfer_protocol_t data;
+ mavlink_msg_file_transfer_protocol_decode(&message, &data);
+
+ // Make sure we are the target system
+ if (data.target_system != _systemIdQGC) {
+ qDebug() << "Received MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL with possibly incorrect system id" << _systemIdQGC;
return;
}
-
- _clearAckTimeout();
- uint16_t incomingSeqNumber = data.seqnr;
+ Request* request = (Request*)&data.payload[0];
- // Make sure we have a good CRC
- quint32 expectedCRC = crc32(request);
- quint32 receivedCRC = request->hdr.crc32;
- if (receivedCRC != expectedCRC) {
- _currentOperation = kCOIdle;
- _emitErrorMessage(tr("Bad CRC on received message: expected(%1) received(%2)").arg(expectedCRC).arg(receivedCRC));
- return;
- }
+ _clearAckTimeout();
+
+ uint16_t incomingSeqNumber = request->hdr.seqNumber;
// Make sure we have a good sequence number
uint16_t expectedSeqNumber = _lastOutgoingSeqNumber + 1;
@@ -325,11 +264,13 @@ void QGCUASFileManager::receiveMessage(LinkInterface* link, mavlink_message_t me
break;
}
} else if (request->hdr.opcode == kRspNak) {
- Q_ASSERT(request->hdr.size == 1); // Should only have one byte of error code
OperationState previousOperation = _currentOperation;
uint8_t errorCode = request->data[0];
+ // Nak's normally have 1 byte of data for error code, except for kErrFailErrno which has additional byte for errno
+ Q_ASSERT((errorCode == kErrFailErrno && request->hdr.size == 2) || request->hdr.size == 1);
+
_currentOperation = kCOIdle;
if (previousOperation == kCOList && errorCode == kErrEOF) {
@@ -374,17 +315,17 @@ void QGCUASFileManager::listDirectory(const QString& dirPath)
void QGCUASFileManager::_fillRequestWithString(Request* request, const QString& str)
{
strncpy((char *)&request->data[0], str.toStdString().c_str(), sizeof(request->data));
- request->hdr.size = strnlen((const char *)&request->data[0], sizeof(request->data));
+ request->hdr.size = static_cast(strnlen((const char *)&request->data[0], sizeof(request->data)));
}
void QGCUASFileManager::_sendListCommand(void)
{
Request request;
- request.hdr.magic = 'f';
request.hdr.session = 0;
- request.hdr.opcode = kCmdList;
+ request.hdr.opcode = kCmdListDirectory;
request.hdr.offset = _listOffset;
+ request.hdr.size = 0;
_fillRequestWithString(&request, _listPath);
@@ -416,10 +357,10 @@ void QGCUASFileManager::downloadPath(const QString& from, const QDir& downloadDi
_currentOperation = kCOOpen;
Request request;
- request.hdr.magic = 'f';
request.hdr.session = 0;
- request.hdr.opcode = kCmdOpen;
+ request.hdr.opcode = kCmdOpenFile;
request.hdr.offset = 0;
+ request.hdr.size = 0;
_fillRequestWithString(&request, from);
_sendRequest(&request);
}
@@ -427,34 +368,24 @@ void QGCUASFileManager::downloadPath(const QString& from, const QDir& downloadDi
QString QGCUASFileManager::errorString(uint8_t errorCode)
{
switch(errorCode) {
- case kErrNone:
- return QString("no error");
- case kErrNoRequest:
- return QString("bad request");
- case kErrNoSession:
- return QString("bad session");
- case kErrSequence:
- return QString("bad sequence number");
- case kErrNotDir:
- return QString("not a directory");
- case kErrNotFile:
- return QString("not a file");
- case kErrEOF:
- return QString("read beyond end of file");
- case kErrNotAppend:
- return QString("write not at end of file");
- case kErrTooBig:
- return QString("file too big");
- case kErrIO:
- return QString("device I/O error");
- case kErrPerm:
- return QString("permission denied");
- case kErrUnknownCommand:
- return QString("unknown command");
- case kErrCrc:
- return QString("bad crc");
- default:
- return QString("unknown error code");
+ case kErrNone:
+ return QString("no error");
+ case kErrFail:
+ return QString("unknown error");
+ case kErrEOF:
+ return QString("read beyond end of file");
+ case kErrUnknownCommand:
+ return QString("unknown command");
+ case kErrFailErrno:
+ return QString("command failed");
+ case kErrInvalidDataSize:
+ return QString("invalid data size");
+ case kErrInvalidSession:
+ return QString("invalid session");
+ case kErrNoSessionsAvailable:
+ return QString("no sessions availble");
+ default:
+ return QString("unknown error code");
}
}
@@ -470,7 +401,6 @@ bool QGCUASFileManager::_sendOpcodeOnlyCmd(uint8_t opcode, OperationState newOpS
}
Request request;
- request.hdr.magic = 'f';
request.hdr.session = 0;
request.hdr.opcode = opcode;
request.hdr.offset = 0;
@@ -522,7 +452,8 @@ void QGCUASFileManager::_sendTerminateCommand(void)
{
Request request;
request.hdr.session = _activeSession;
- request.hdr.opcode = kCmdTerminate;
+ request.hdr.opcode = kCmdTerminateSession;
+ request.hdr.size = 0;
_sendRequest(&request);
}
@@ -547,10 +478,20 @@ void QGCUASFileManager::_sendRequest(Request* request)
_lastOutgoingSeqNumber++;
- request->hdr.magic = kProtocolMagic;
- request->hdr.crc32 = crc32(request);
- // FIXME: Send correct system id instead of harcoded 250
- // FIXME: What about the component id? Should it be set to something specific.
- mavlink_msg_encapsulated_data_pack(250, 0, &message, _lastOutgoingSeqNumber, (uint8_t*)request);
+ request->hdr.seqNumber = _lastOutgoingSeqNumber;
+
+ if (_systemIdQGC == 0) {
+ _systemIdQGC = MainWindow::instance()->getMAVLink()->getSystemId();
+ }
+
+ Q_ASSERT(_mav);
+ mavlink_msg_file_transfer_protocol_pack(_systemIdQGC, // QGC System ID
+ 0, // QGC Component ID
+ &message, // Mavlink Message to pack into
+ 0, // Target network
+ _systemIdServer, // Target system
+ 0, // Target component
+ (uint8_t*)request); // Payload
+
_mav->sendMessage(message);
}
diff --git a/src/uas/QGCUASFileManager.h b/src/uas/QGCUASFileManager.h
index 7fe7f9d9d0dd134401cdce902267c19fff3e8f8d..893ce4e70fa4f3a3c9b53a8ef0a767faeec15f16 100644
--- a/src/uas/QGCUASFileManager.h
+++ b/src/uas/QGCUASFileManager.h
@@ -33,12 +33,12 @@ class QGCUASFileManager : public QObject
{
Q_OBJECT
public:
- QGCUASFileManager(QObject* parent, UASInterface* uas);
+ QGCUASFileManager(QObject* parent, UASInterface* uas, uint8_t unitTestSystemIdQGC = 0);
/// These methods are only used for testing purposes.
bool _sendCmdTestAck(void) { return _sendOpcodeOnlyCmd(kCmdNone, kCOAck); };
bool _sendCmdTestNoAck(void) { return _sendOpcodeOnlyCmd(kCmdTestNoAck, kCOAck); };
- bool _sendCmdReset(void) { return _sendOpcodeOnlyCmd(kCmdReset, kCOAck); };
+ bool _sendCmdReset(void) { return _sendOpcodeOnlyCmd(kCmdResetSessions, kCOAck); };
/// @brief Timeout in msecs to wait for an Ack time come back. This is public so we can write unit tests which wait long enough
/// for the FileManager to timeout.
@@ -74,26 +74,29 @@ public slots:
void downloadPath(const QString& from, const QDir& downloadDir);
protected:
- static const uint8_t kProtocolMagic = 'f';
+
+ /// @brief This is the fixed length portion of the protocol data. Trying to pack structures across differing compilers is
+ /// questionable, so we pad the structure ourselves to 32 bit alignment which should get us what we want.
struct RequestHeader
{
- uint8_t magic; ///> Magic byte 'f' to idenitfy FTP protocol
- uint8_t session; ///> Session id for read and write commands
- uint8_t opcode; ///> Command opcode
- uint8_t size; ///> Size of data
- uint32_t crc32; ///> CRC for entire Request structure, with crc32 set to 0
- uint32_t offset; ///> Offsets for List and Read commands
+ uint16_t seqNumber; ///< sequence number for message
+ uint8_t session; ///< Session id for read and write commands
+ uint8_t opcode; ///< Command opcode
+ uint8_t size; ///< Size of data
+ uint8_t req_opcode; ///< Request opcode returned in kRspAck, kRspNak message
+ uint8_t padding[2]; ///< 32 bit aligment padding
+ uint32_t offset; ///< Offsets for List and Read commands
};
struct Request
{
struct RequestHeader hdr;
- // We use a union here instead of just casting (uint32_t)&data[0] to not break strict aliasing rules
+ // We use a union here instead of just casting (uint32_t)&payload[0] to not break strict aliasing rules
union {
- // The entire Request must fit into the data member of the mavlink_encapsulated_data_t structure. We use as many leftover bytes
+ // The entire Request must fit into the payload member of the mavlink_file_transfer_protocol_t structure. We use as many leftover bytes
// after we use up space for the RequestHeader for the data portion of the Request.
- uint8_t data[sizeof(((mavlink_encapsulated_data_t*)0)->data) - sizeof(RequestHeader)];
+ uint8_t data[sizeof(((mavlink_file_transfer_protocol_t*)0)->payload) - sizeof(RequestHeader)];
// File length returned by Open command
uint32_t openFileLength;
@@ -101,43 +104,38 @@ protected:
};
enum Opcode
- {
- // Commands
- kCmdNone, ///> ignored, always acked
- kCmdTerminate, ///> releases sessionID, closes file
- kCmdReset, ///> terminates all sessions
- kCmdList, ///> list files in from
- kCmdOpen, ///> opens for reading, returns
- kCmdRead, ///> reads bytes from in
- kCmdCreate, ///> creates for writing, returns
- kCmdWrite, ///> appends bytes at in
- kCmdRemove, ///> remove file (only if created by server?)
-
- // Responses
- kRspAck, ///> positive acknowledgement of previous command
- kRspNak, ///> negative acknowledgement of previous command
-
- // Used for testing only, not part of protocol
- kCmdTestNoAck, // ignored, ack not sent back, should timeout waiting for ack
- };
-
- enum ErrorCode
- {
- kErrNone,
- kErrNoRequest,
- kErrNoSession,
- kErrSequence,
- kErrNotDir,
- kErrNotFile,
- kErrEOF,
- kErrNotAppend,
- kErrTooBig,
- kErrIO,
- kErrPerm,
- kErrUnknownCommand,
- kErrCrc
- };
-
+ {
+ kCmdNone, ///< ignored, always acked
+ kCmdTerminateSession, ///< Terminates open Read session
+ kCmdResetSessions, ///< Terminates all open Read sessions
+ kCmdListDirectory, ///< List files in from
+ kCmdOpenFile, ///< Opens file at for reading, returns
+ kCmdReadFile, ///< Reads bytes from in
+ kCmdCreateFile, ///< Creates file at for writing, returns
+ kCmdWriteFile, ///< Appends bytes to file in
+ kCmdRemoveFile, ///< Remove file at
+ kCmdCreateDirectory, ///< Creates directory at
+ kCmdRemoveDirectory, ///< Removes Directory at , must be empty
+
+ kRspAck = 128, ///< Ack response
+ kRspNak, ///< Nak response
+
+ // Used for testing only, not part of protocol
+ kCmdTestNoAck, ///< ignored, ack not sent back, should timeout waiting for ack
+ };
+
+ /// @brief Error codes returned in Nak response PayloadHeader.data[0].
+ enum ErrorCode
+ {
+ kErrNone,
+ kErrFail, ///< Unknown failure
+ kErrFailErrno, ///< errno sent back in PayloadHeader.data[1]
+ kErrInvalidDataSize, ///< PayloadHeader.size is invalid
+ kErrInvalidSession, ///< Session is not currently open
+ kErrNoSessionsAvailable, ///< All available Sessions in use
+ kErrEOF, ///< Offset past end of file for List and Read commands
+ kErrUnknownCommand ///< Unknown command opcode
+ };
enum OperationState
{
@@ -167,24 +165,26 @@ protected:
void _sendTerminateCommand(void);
void _closeReadSession(bool success);
- static quint32 crc32(Request* request, unsigned state = 0);
static QString errorString(uint8_t errorCode);
- OperationState _currentOperation; ///> Current operation of state machine
- QTimer _ackTimer; ///> Used to signal a timeout waiting for an ack
+ OperationState _currentOperation; ///< Current operation of state machine
+ QTimer _ackTimer; ///< Used to signal a timeout waiting for an ack
UASInterface* _mav;
uint16_t _lastOutgoingSeqNumber; ///< Sequence number sent in last outgoing packet
- unsigned _listOffset; ///> offset for the current List operation
- QString _listPath; ///> path for the current List operation
+ unsigned _listOffset; ///< offset for the current List operation
+ QString _listPath; ///< path for the current List operation
+
+ uint8_t _activeSession; ///< currently active session, 0 for none
+ uint32_t _readOffset; ///< current read offset
+ QByteArray _readFileAccumulator; ///< Holds file being downloaded
+ QDir _readFileDownloadDir; ///< Directory to download file to
+ QString _readFileDownloadFilename; ///< Filename (no path) for download file
- uint8_t _activeSession; ///> currently active session, 0 for none
- uint32_t _readOffset; ///> current read offset
- QByteArray _readFileAccumulator; ///> Holds file being downloaded
- QDir _readFileDownloadDir; ///> Directory to download file to
- QString _readFileDownloadFilename; ///> Filename (no path) for download file
+ uint8_t _systemIdQGC; ///< System ID for QGC
+ uint8_t _systemIdServer; ///< System ID for server
// We give MockMavlinkFileServer friend access so that it can use the data structures and opcodes
// to build a mock mavlink file server for testing.
diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc
index 3fd754b098acdd2d9241a4264fb8c0f0faf7f2b0..692d1b1fab42ee6b13a56609efdb596e0ea2419f 100644
--- a/src/uas/UAS.cc
+++ b/src/uas/UAS.cc
@@ -158,7 +158,8 @@ UAS::UAS(MAVLinkProtocol* protocol, QThread* thread, int id) : UASInterface(),
hilEnabled(false),
sensorHil(false),
lastSendTimeGPS(0),
- lastSendTimeSensors(0)
+ lastSendTimeSensors(0),
+ lastSendTimeOpticalFlow(0)
{
moveToThread(thread);
@@ -1952,7 +1953,7 @@ QImage UAS::getImage()
QString header("P5\n%1 %2\n%3\n");
header = header.arg(imageWidth).arg(imageHeight).arg(imgColors);
- QByteArray tmpImage(header.toStdString().c_str(), header.toStdString().size());
+ QByteArray tmpImage(header.toStdString().c_str(), header.length());
tmpImage.append(imageRecBuffer);
//qDebug() << "IMAGE SIZE:" << tmpImage.size() << "HEADER SIZE: (15):" << header.size() << "HEADER: " << header;
@@ -2416,7 +2417,7 @@ void UAS::setParameter(const int compId, const QString& paramId, const QVariant&
p.param_id[i] = 0;
}
}
- mavlink_msg_param_set_encode(mavlink->getSystemId(), compId, &msg, &p);
+ mavlink_msg_param_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &p);
sendMessage(msg);
}
}
@@ -3147,6 +3148,26 @@ void UAS::sendHilSensors(quint64 time_us, float xacc, float yacc, float zacc, fl
}
}
+void UAS::sendHilOpticalFlow(quint64 time_us, qint16 flow_x, qint16 flow_y, float flow_comp_m_x,
+ float flow_comp_m_y, quint8 quality, float ground_distance)
+{
+ if (this->base_mode & MAV_MODE_FLAG_HIL_ENABLED)
+ {
+ mavlink_message_t msg;
+ mavlink_msg_hil_optical_flow_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg,
+ time_us, 0, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance);
+ sendMessage(msg);
+ lastSendTimeOpticalFlow = QGC::groundTimeMilliseconds();
+ }
+ else
+ {
+ // Attempt to set HIL mode
+ setMode(base_mode | MAV_MODE_FLAG_HIL_ENABLED, custom_mode);
+ qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to enable.";
+ }
+
+}
+
void UAS::sendHilGps(quint64 time_us, double lat, double lon, double alt, int fix_type, float eph, float epv, float vel, float vn, float ve, float vd, float cog, int satellites)
{
// Only send at 10 Hz max rate
diff --git a/src/uas/UAS.h b/src/uas/UAS.h
index 8124847a2671a0cd2701eced5c507f8d42d2587e..9d9681caa6b3429b3bffb3b02cbf9a7f13ed2477 100644
--- a/src/uas/UAS.h
+++ b/src/uas/UAS.h
@@ -813,6 +813,10 @@ public slots:
void sendHilSensors(quint64 time_us, float xacc, float yacc, float zacc, float rollspeed, float pitchspeed, float yawspeed,
float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature, quint32 fields_changed);
+ /** @brief Send Optical Flow sensor message for HIL, (arguments and units accoding to mavlink documentation*/
+ void sendHilOpticalFlow(quint64 time_us, qint16 flow_x, qint16 flow_y, float flow_comp_m_x,
+ float flow_comp_m_y, quint8 quality, float ground_distance);
+
/**
* @param time_us
* @param lat
@@ -1020,7 +1024,8 @@ protected:
bool hilEnabled; ///< Set to true if HIL mode is enabled from GCS (UAS might be in HIL even if this flag is not set, this defines the GCS HIL setting)
bool sensorHil; ///< True if sensor HIL is enabled
quint64 lastSendTimeGPS; ///< Last HIL GPS message sent
- quint64 lastSendTimeSensors;
+ quint64 lastSendTimeSensors; ///< Last HIL Sensors message sent
+ quint64 lastSendTimeOpticalFlow; ///< Last HIL Optical Flow message sent
QList actions; ///< A list of actions that this UAS can perform.
diff --git a/src/uas/UASInterface.h b/src/uas/UASInterface.h
index 0064229d6bb971fe2975512dda82602415fd9209..e15b98949a491993a48fa600f7e4ec1fb4631415 100644
--- a/src/uas/UASInterface.h
+++ b/src/uas/UASInterface.h
@@ -390,6 +390,10 @@ public slots:
/** @brief Send raw GPS for sensor HIL */
virtual void sendHilGps(quint64 time_us, double lat, double lon, double alt, int fix_type, float eph, float epv, float vel, float vn, float ve, float vd, float cog, int satellites) = 0;
+ /** @brief Send Optical Flow sensor message for HIL, (arguments and units accoding to mavlink documentation*/
+ virtual void sendHilOpticalFlow(quint64 time_us, qint16 flow_x, qint16 flow_y, float flow_comp_m_x,
+ float flow_comp_m_y, quint8 quality, float ground_distance) = 0;
+
protected:
QColor color;
diff --git a/src/uas/UASWaypointManager.cc b/src/uas/UASWaypointManager.cc
index 5bb0e891524af88b490510a85e5655d34f22811d..b20067a0a9cfe1953205ef7b81533c9745a59790 100644
--- a/src/uas/UASWaypointManager.cc
+++ b/src/uas/UASWaypointManager.cc
@@ -55,7 +55,7 @@ UASWaypointManager::UASWaypointManager(UAS* _uas)
uasid = uas->getUASID();
connect(&protocol_timer, SIGNAL(timeout()), this, SLOT(timeout()));
connect(uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(handleLocalPositionChanged(UASInterface*,double,double,double,quint64)));
- connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,double,quint64)), this, SLOT(handleGlobalPositionChanged(UASInterface*,double,double,double,double,double,quint64)));
+ connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,double,quint64)), this, SLOT(handleGlobalPositionChanged(UASInterface*,double,double,double,double,quint64)));
}
else
{
diff --git a/src/ui/JoystickWidget.cc b/src/ui/JoystickWidget.cc
index 03df9be2ce40d8844d2ce9cffb4feb405d51309a..541d546c9a6d52ecf49083aa33b7b7b3d9f68d53 100644
--- a/src/ui/JoystickWidget.cc
+++ b/src/ui/JoystickWidget.cc
@@ -7,7 +7,7 @@
#include
JoystickWidget::JoystickWidget(JoystickInput* joystick, QWidget *parent) :
- QDialog(parent),
+ QWidget(parent),
joystick(joystick),
m_ui(new Ui::JoystickWidget)
{
diff --git a/src/ui/JoystickWidget.h b/src/ui/JoystickWidget.h
index 36250decc0ff0e29983c7f0fdacf10cca635ccec..a0d9d9856e98763715f7b8cc3550d261d0a74658 100644
--- a/src/ui/JoystickWidget.h
+++ b/src/ui/JoystickWidget.h
@@ -31,7 +31,7 @@ This file is part of the PIXHAWK project
#ifndef JOYSTICKWIDGET_H
#define JOYSTICKWIDGET_H
-#include
+#include
#include
#include
#include "JoystickInput.h"
@@ -44,7 +44,7 @@ namespace Ui
class JoystickWidget;
}
-class JoystickWidget : public QDialog
+class JoystickWidget : public QWidget
{
Q_OBJECT
Q_DISABLE_COPY(JoystickWidget)
diff --git a/src/ui/JoystickWidget.ui b/src/ui/JoystickWidget.ui
index f33134eb650d3b93031162cec4b22b819a9a1981..a56cc40179a4a56e426c40f6ae10e2ef77722aed 100644
--- a/src/ui/JoystickWidget.ui
+++ b/src/ui/JoystickWidget.ui
@@ -1,7 +1,7 @@
JoystickWidget
-
+ 0
@@ -30,7 +30,7 @@
8
- QLayout::SetFixedSize
+ QLayout::SetDefaultConstraint8
@@ -50,7 +50,7 @@
true
- Enable joysticks
+ Enable controllers
@@ -174,53 +174,8 @@
-
-
-
-
- 0
- 0
-
-
-
-
- 50
- 0
-
-
-
-
- 16777215
- 16777215
-
-
-
- Qt::Horizontal
-
-
- QDialogButtonBox::Ok
-
-
-
-
-
- dialogButtonsBox
- accepted()
- JoystickWidget
- accept()
-
-
- 263
- 438
-
-
- 157
- 274
-
-
-
-
+
diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc
index 50de05b0a092374ed83698fc581d09b1fcca5411..c209145add77fca2e2dda0879ae7b1714c217d1a 100644
--- a/src/ui/MainWindow.cc
+++ b/src/ui/MainWindow.cc
@@ -279,7 +279,6 @@ void MainWindow::init()
// Connect user interface devices
emit initStatusChanged(tr("Initializing joystick interface"), Qt::AlignLeft | Qt::AlignBottom, QColor(62, 93, 141));
- joystickWidget = 0;
joystick = new JoystickInput();
#ifdef QGC_MOUSE_ENABLED_WIN
@@ -1329,9 +1328,6 @@ void MainWindow::connectCommonActions()
// so no ressources spend on this.
ui.actionJoystickSettings->setVisible(true);
- // Configuration
- // Joystick
- connect(ui.actionJoystickSettings, SIGNAL(triggered()), this, SLOT(configure()));
// Application Settings
connect(ui.actionSettings, SIGNAL(triggered()), this, SLOT(showSettings()));
@@ -1380,22 +1376,9 @@ void MainWindow::showRoadMap()
}
}
-void MainWindow::configure()
-{
- if (!joystickWidget)
- {
- if (!joystick->isRunning())
- {
- joystick->start();
- }
- joystickWidget = new JoystickWidget(joystick, this);
- }
- joystickWidget->show();
-}
-
void MainWindow::showSettings()
{
- QGCSettingsWidget* settings = new QGCSettingsWidget(this);
+ QGCSettingsWidget* settings = new QGCSettingsWidget(joystick, this);
settings->show();
}
diff --git a/src/ui/MainWindow.h b/src/ui/MainWindow.h
index 5e65b73073b983df0b1dbd9ca3772e63c5d7c4fa..5cfdec60aa5dcc9596a00284a57e081833c777a5 100644
--- a/src/ui/MainWindow.h
+++ b/src/ui/MainWindow.h
@@ -81,7 +81,6 @@ class QSplashScreen;
class QGCStatusBar;
class Linecharts;
class QGCDataPlot2D;
-class JoystickWidget;
class MenuActionHelper;
class QGCUASFileViewMulti;
@@ -202,7 +201,6 @@ public slots:
LinkInterface* addLink();
void addLink(LinkInterface* link);
bool configLink(LinkInterface *link);
- void configure();
/** @brief Simulate a link */
void simulateLink(bool simulate);
/** @brief Set the currently controlled UAS */
@@ -459,10 +457,7 @@ protected:
QPointer fileWidget;
- // Popup widgets
- JoystickWidget* joystickWidget;
-
- JoystickInput* joystick;
+ JoystickInput* joystick; ///< The joystick manager for QGC
#ifdef QGC_MOUSE_ENABLED_WIN
/** @brief 3d Mouse support (WIN only) */
diff --git a/src/ui/MainWindow.ui b/src/ui/MainWindow.ui
index ea87b9e18ff118a534f903d5da6e0c2ab54acb38..c8c3f1ae14814024a8c34327e8fdb5b71a89a55f 100644
--- a/src/ui/MainWindow.ui
+++ b/src/ui/MainWindow.ui
@@ -62,7 +62,6 @@
-
diff --git a/src/ui/PrimaryFlightDisplay.cc b/src/ui/PrimaryFlightDisplay.cc
index 24348584c5fe110be3d6df3247124e28cba01166..38e0654d9c0b11e7ee4b8c2f8ed02048e6a81c60 100644
--- a/src/ui/PrimaryFlightDisplay.cc
+++ b/src/ui/PrimaryFlightDisplay.cc
@@ -322,7 +322,6 @@ void PrimaryFlightDisplay::updateSpeed(UASInterface* uas, double _groundSpeed, d
void PrimaryFlightDisplay::updateAltitude(UASInterface* uas, double _altitudeAMSL, double _altitudeWGS84, double _altitudeRelative, double _climbRate, quint64 timestamp) {
Q_UNUSED(uas);
Q_UNUSED(timestamp);
- Q_UNUSED(_altitudeWGS84)
if (fabsf(altitudeAMSL - _altitudeAMSL) > 0.5f) {
_valuesChanged = true;
diff --git a/src/ui/QGCMAVLinkInspector.cc b/src/ui/QGCMAVLinkInspector.cc
index 82c6464afa787f5fe870b2bfc0dcbc43db40865b..fe3c6bb49e98e7eea1ce241b69311a747da0fe66 100644
--- a/src/ui/QGCMAVLinkInspector.cc
+++ b/src/ui/QGCMAVLinkInspector.cc
@@ -23,14 +23,11 @@ QGCMAVLinkInspector::QGCMAVLinkInspector(MAVLinkProtocol* protocol, QWidget *par
ui->systemComboBox->addItem(tr("All"), 0);
ui->componentComboBox->addItem(tr("All"), 0);
- // Store metadata for all MAVLink messages.
- mavlink_message_info_t msg_infos[256] = MAVLINK_MESSAGE_INFO;
- memcpy(messageInfo, msg_infos, sizeof(mavlink_message_info_t)*256);
+ // Store metadata for all MAVLink messages.
+ mavlink_message_info_t msg_infos[256] = MAVLINK_MESSAGE_INFO;
+ memcpy(messageInfo, msg_infos, sizeof(mavlink_message_info_t)*256);
- // Initialize the received data for all messages to invalid (0xFF)
- memset(receivedMessages, 0xFF, sizeof(mavlink_message_t)*256);
-
- // Set up the column headers for the message listing
+ // Set up the column headers for the message listing
QStringList header;
header << tr("Name");
header << tr("Value");
@@ -53,7 +50,7 @@ QGCMAVLinkInspector::QGCMAVLinkInspector(MAVLinkProtocol* protocol, QWidget *par
connect(ui->clearButton, SIGNAL(clicked()), this, SLOT(clearView()));
// Connect external connections
-// connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)), this, SLOT(addSystem(UASInterface*)));
+ connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)), this, SLOT(addSystem(UASInterface*)));
connect(protocol, SIGNAL(messageReceived(LinkInterface*,mavlink_message_t)), this, SLOT(receiveMessage(LinkInterface*,mavlink_message_t)));
// Attach the UI's refresh rate to a timer.
@@ -64,6 +61,9 @@ QGCMAVLinkInspector::QGCMAVLinkInspector(MAVLinkProtocol* protocol, QWidget *par
void QGCMAVLinkInspector::addSystem(UASInterface* uas)
{
ui->systemComboBox->addItem(uas->getUASName(), uas->getUASID());
+
+ // Add a tree for a new UAS
+ addUAStoTree(uas->getUASID());
}
void QGCMAVLinkInspector::selectDropDownMenuSystem(int dropdownid)
@@ -95,12 +95,25 @@ void QGCMAVLinkInspector::rebuildComponentList()
components.clear();
ui->componentComboBox->addItem(tr("All"), 0);
+
+ // Fill
+ UASInterface* uas = UASManager::instance()->getUASForId(selectedSystemID);
+ if (uas)
+ {
+ QMap components = uas->getComponents();
+ foreach (int id, components.keys())
+ {
+ QString name = components.value(id);
+ ui->componentComboBox->addItem(name, id);
+ }
+ }
}
void QGCMAVLinkInspector::addComponent(int uas, int component, const QString& name)
{
Q_UNUSED(component);
Q_UNUSED(name);
+
if (uas != selectedSystemID) return;
rebuildComponentList();
@@ -112,52 +125,162 @@ void QGCMAVLinkInspector::addComponent(int uas, int component, const QString& na
*/
void QGCMAVLinkInspector::clearView()
{
- memset(receivedMessages, 0xFF, sizeof(mavlink_message_t)*256);
+ QMap::iterator ite;
+ for(ite=uasMessageStorage.begin(); ite!=uasMessageStorage.end();++ite)
+ {
+ delete ite.value();
+ ite.value() = NULL;
+ }
+ uasMessageStorage.clear();
+
+ QMap* >::iterator iteMsg;
+ for (iteMsg=uasMsgTreeItems.begin(); iteMsg!=uasMsgTreeItems.end();++iteMsg)
+ {
+ QMap* msgTreeItems = iteMsg.value();
+
+ QList groupKeys = msgTreeItems->uniqueKeys();
+ QList::iterator listKeys;
+ for (listKeys=groupKeys.begin();listKeys!=groupKeys.end();++listKeys)
+ {
+ delete msgTreeItems->take(*listKeys);
+ }
+ }
+ uasMsgTreeItems.clear();
+
+ QMap::iterator iteTree;
+ for(iteTree=uasTreeWidgetItems.begin(); iteTree!=uasTreeWidgetItems.end();++iteTree)
+ {
+ delete iteTree.value();
+ iteTree.value() = NULL;
+ }
+ uasTreeWidgetItems.clear();
+
+ QMap* >::iterator iteHz;
+ for (iteHz=uasMessageHz.begin(); iteHz!=uasMessageHz.end();++iteHz)
+ {
+
+ iteHz.value()->clear();
+ delete iteHz.value();
+ iteHz.value() = NULL;
+ }
+ uasMessageHz.clear();
+
+ QMap* >::iterator iteCount;
+ for(iteCount=uasMessageCount.begin(); iteCount!=uasMessageCount.end();++iteCount)
+ {
+ iteCount.value()->clear();
+ delete iteCount.value();
+ iteCount.value() = NULL;
+ }
+ uasMessageCount.clear();
+
+ QMap* >::iterator iteLast;
+ for(iteLast=uasLastMessageUpdate.begin(); iteLast!=uasLastMessageUpdate.end();++iteLast)
+ {
+ iteLast.value()->clear();
+ delete iteLast.value();
+ iteLast.value() = NULL;
+ }
+ uasLastMessageUpdate.clear();
+
onboardMessageInterval.clear();
- lastMessageUpdate.clear();
- messagesHz.clear();
- treeWidgetItems.clear();
+
ui->treeWidget->clear();
ui->rateTreeWidget->clear();
+
}
void QGCMAVLinkInspector::refreshView()
{
- for (int i = 0; i < 256; ++i)//mavlink_message_t msg, receivedMessages)
+ QMap::const_iterator ite;
+
+ for(ite=uasMessageStorage.constBegin(); ite!=uasMessageStorage.constEnd();++ite)
{
- mavlink_message_t* msg = receivedMessages+i;
+
+ mavlink_message_t* msg = ite.value();
// Ignore NULL values
if (msg->msgid == 0xFF) continue;
+
+ // Update the message frenquency
+
+ // Get the previous frequency for low-pass filtering
+ float msgHz = 0.0f;
+ QMap* >::const_iterator iteHz = uasMessageHz.find(msg->sysid);
+ QMap* uasMsgHz = iteHz.value();
+
+ while((iteHz != uasMessageHz.end()) && (iteHz.key() == msg->sysid))
+ {
+ if(iteHz.value()->contains(msg->msgid))
+ {
+ uasMsgHz = iteHz.value();
+ msgHz = iteHz.value()->value(msg->msgid);
+ break;
+ }
+ ++iteHz;
+ }
+
+ // Get the number of message received
+ float msgCount = 0;
+ QMap * >::const_iterator iter = uasMessageCount.find(msg->sysid);
+ QMap* uasMsgCount = iter.value();
+
+ while((iter != uasMessageCount.end()) && (iter.key()==msg->sysid))
+ {
+ if(iter.value()->contains(msg->msgid))
+ {
+ msgCount = (float) iter.value()->value(msg->msgid);
+ uasMsgCount = iter.value();
+ break;
+ }
+ ++iter;
+ }
+
+ // Compute the new low-pass filtered frequency and update the message count
+ msgHz = (1.0f-updateHzLowpass)* msgHz + updateHzLowpass*msgCount/((float)updateInterval/1000.0f);
+ uasMsgHz->insert(msg->msgid,msgHz);
+ uasMsgCount->insert(msg->msgid,(unsigned int) 0);
+
// Update the tree view
QString messageName("%1 (%2 Hz, #%3)");
- float msgHz = (1.0f-updateHzLowpass)*messagesHz.value(msg->msgid, 0) + updateHzLowpass*((float)messageCount.value(msg->msgid, 0))/((float)updateInterval/1000.0f);
- messagesHz.insert(msg->msgid, msgHz);
messageName = messageName.arg(messageInfo[msg->msgid].name).arg(msgHz, 3, 'f', 1).arg(msg->msgid);
- messageCount.insert(msg->msgid, 0);
- if (!treeWidgetItems.contains(msg->msgid))
+
+ addUAStoTree(msg->sysid);
+
+ // Look for the tree for the UAS sysid
+ QMap* msgTreeItems = uasMsgTreeItems.value(msg->sysid);
+ if (!msgTreeItems)
+ {
+ // The UAS tree has not been created yet, no update
+ return;
+ }
+
+ // Add the message with msgid to the tree if not done yet
+ if(!msgTreeItems->contains(msg->msgid))
{
QStringList fields;
fields << messageName;
- QTreeWidgetItem* widget = new QTreeWidgetItem(fields);
- widget->setFirstColumnSpanned(true);
-
+ QTreeWidgetItem* widget = new QTreeWidgetItem();
for (unsigned int i = 0; i < messageInfo[msg->msgid].num_fields; ++i)
{
QTreeWidgetItem* field = new QTreeWidgetItem();
widget->addChild(field);
}
-
- treeWidgetItems.insert(msg->msgid, widget);
- ui->treeWidget->addTopLevelItem(widget);
+ msgTreeItems->insert(msg->msgid,widget);
+ QList groupKeys = msgTreeItems->uniqueKeys();
+ int insertIndex = groupKeys.indexOf(msg->msgid);
+ uasTreeWidgetItems.value(msg->sysid)->insertChild(insertIndex,widget);
}
- // Set Hz
- QTreeWidgetItem* message = treeWidgetItems.value(msg->msgid);
- message->setFirstColumnSpanned(true);
- message->setData(0, Qt::DisplayRole, QVariant(messageName));
- for (unsigned int i = 0; i < messageInfo[msg->msgid].num_fields; ++i)
+ // Update the message
+ QTreeWidgetItem* message = msgTreeItems->value(msg->msgid);
+ if(message)
{
- updateField(msg->msgid, i, message->child(i));
+ message->setFirstColumnSpanned(true);
+ message->setData(0, Qt::DisplayRole, QVariant(messageName));
+ for (unsigned int i = 0; i < messageInfo[msg->msgid].num_fields; ++i)
+ {
+ updateField(msg->sysid,msg->msgid, i, message->child(i));
+ }
}
}
@@ -170,7 +293,7 @@ void QGCMAVLinkInspector::refreshView()
{
const char* msgname = messageInfo[i].name;
- int namelen = strnlen(msgname, 5);
+ size_t namelen = strnlen(msgname, 5);
if (namelen < 3) {
continue;
@@ -201,39 +324,145 @@ void QGCMAVLinkInspector::refreshView()
}
}
+void QGCMAVLinkInspector::addUAStoTree(int sysId)
+{
+ if(!uasTreeWidgetItems.contains(sysId))
+ {
+ // Add the UAS to the main tree after it has been created
+ UASInterface* uas = UASManager::instance()->getUASForId(sysId);
+
+ if (uas)
+ {
+ QStringList idstring;
+ if (uas->getUASName() == "")
+ {
+ idstring << tr("UAS ") + QString::number(uas->getUASID());
+ }
+ else
+ {
+ idstring << uas->getUASName();
+ }
+ QTreeWidgetItem* uasWidget = new QTreeWidgetItem(idstring);
+ uasWidget->setFirstColumnSpanned(true);
+ uasTreeWidgetItems.insert(sysId,uasWidget);
+ ui->treeWidget->addTopLevelItem(uasWidget);
+ uasMsgTreeItems.insert(sysId,new QMap());
+ }
+ }
+}
+
void QGCMAVLinkInspector::receiveMessage(LinkInterface* link,mavlink_message_t message)
{
Q_UNUSED(link);
+
+ quint64 receiveTime;
+
if (selectedSystemID != 0 && selectedSystemID != message.sysid) return;
if (selectedComponentID != 0 && selectedComponentID != message.compid) return;
- // Only overwrite if system filter is set
- memcpy(receivedMessages+message.msgid, &message, sizeof(mavlink_message_t));
- // Add not yet seen systems / components
- if (!systems.contains(message.sysid)) {
- systems.insert(message.sysid, message.sysid);
- ui->systemComboBox->addItem(tr("MAV%1").arg(message.sysid), message.sysid);
+ // Create dynamically an array to store the messages for each UAS
+ if (!uasMessageStorage.contains(message.sysid))
+ {
+ mavlink_message_t* msg = new mavlink_message_t;
+ *msg = message;
+ uasMessageStorage.insertMulti(message.sysid,msg);
}
- if (!components.contains(message.compid)) {
- components.insert(message.compid, message.compid);
- ui->componentComboBox->addItem(tr("COMP%1").arg(message.compid), message.compid);
+ bool msgFound = false;
+ QMap::const_iterator iteMsg = uasMessageStorage.find(message.sysid);
+ mavlink_message_t* uasMessage = iteMsg.value();
+ while((iteMsg != uasMessageStorage.end()) && (iteMsg.key() == message.sysid))
+ {
+ if (iteMsg.value()->msgid == message.msgid)
+ {
+ msgFound = true;
+ uasMessage = iteMsg.value();
+ break;
+ }
+ ++iteMsg;
}
-
- quint64 receiveTime = QGC::groundTimeMilliseconds();
- if (lastMessageUpdate.contains(message.msgid))
+ if (!msgFound)
+ {
+ mavlink_message_t* msgIdMessage = new mavlink_message_t;
+ *msgIdMessage = message;
+ uasMessageStorage.insertMulti(message.sysid,msgIdMessage);
+ }
+ else
{
- int count = messageCount.value(message.msgid, 0);
- messageCount.insert(message.msgid, count+1);
+ *uasMessage = message;
}
- lastMessageUpdate.insert(message.msgid, receiveTime);
+ // Looking if this message has already been received once
+ msgFound = false;
+ QMap* >::const_iterator ite = uasLastMessageUpdate.find(message.sysid);
+ QMap* lastMsgUpdate = ite.value();
+ while((ite != uasLastMessageUpdate.end()) && (ite.key() == message.sysid))
+ {
+ if(ite.value()->contains(message.msgid))
+ {
+ msgFound = true;
- if (selectedSystemID == 0 || selectedComponentID == 0) {
+ // Point to the found message
+ lastMsgUpdate = ite.value();
+ break;
+ }
+ ++ite;
+ }
+
+ receiveTime = QGC::groundTimeMilliseconds();
+
+ // If the message doesn't exist, create a map for the frequency, message count and time of reception
+ if(!msgFound)
+ {
+ // Create a map for the message frequency
+ QMap* messageHz = new QMap;
+ messageHz->insert(message.msgid,0.0f);
+ uasMessageHz.insertMulti(message.sysid,messageHz);
+
+ // Create a map for the message count
+ QMap* messagesCount = new QMap;
+ messagesCount->insert(message.msgid,0);
+ uasMessageCount.insertMulti(message.sysid,messagesCount);
+
+ // Create a map for the time of reception of the message
+ QMap* lastMessage = new QMap;
+ lastMessage->insert(message.msgid,receiveTime);
+ uasLastMessageUpdate.insertMulti(message.sysid,lastMessage);
+
+ // Point to the created message
+ lastMsgUpdate = lastMessage;
+ }
+ else
+ {
+ // The message has been found/created
+ if ((lastMsgUpdate->contains(message.msgid))&&(uasMessageCount.contains(message.sysid)))
+ {
+ // Looking for and updating the message count
+ unsigned int count = 0;
+ QMap* >::const_iterator iter = uasMessageCount.find(message.sysid);
+ QMap * uasMsgCount = iter.value();
+ while((iter != uasMessageCount.end()) && (iter.key() == message.sysid))
+ {
+ if(iter.value()->contains(message.msgid))
+ {
+ uasMsgCount = iter.value();
+ count = uasMsgCount->value(message.msgid,0);
+ uasMsgCount->insert(message.msgid,count+1);
+ break;
+ }
+ ++iter;
+ }
+ }
+ lastMsgUpdate->insert(message.msgid,receiveTime);
+ }
+
+ if (selectedSystemID == 0 || selectedComponentID == 0)
+ {
return;
}
- switch (message.msgid) {
+ switch (message.msgid)
+ {
case MAVLINK_MSG_ID_DATA_STREAM:
{
mavlink_data_stream_t stream;
@@ -245,7 +474,8 @@ void QGCMAVLinkInspector::receiveMessage(LinkInterface* link,mavlink_message_t m
}
}
-void QGCMAVLinkInspector::changeStreamInterval(int msgid, int interval) {
+void QGCMAVLinkInspector::changeStreamInterval(int msgid, int interval)
+{
//REQUEST_DATA_STREAM
if (selectedSystemID == 0 || selectedComponentID == 0) {
return;
@@ -280,14 +510,37 @@ void QGCMAVLinkInspector::rateTreeItemChanged(QTreeWidgetItem* paramItem, int co
QGCMAVLinkInspector::~QGCMAVLinkInspector()
{
+ clearView();
delete ui;
}
-void QGCMAVLinkInspector::updateField(int msgid, int fieldid, QTreeWidgetItem* item)
+void QGCMAVLinkInspector::updateField(int sysid, int msgid, int fieldid, QTreeWidgetItem* item)
{
// Add field tree widget item
item->setData(0, Qt::DisplayRole, QVariant(messageInfo[msgid].fields[fieldid].name));
- uint8_t* m = ((uint8_t*)(receivedMessages+msgid))+8;
+
+ bool msgFound = false;
+ QMap::const_iterator iteMsg = uasMessageStorage.find(sysid);
+ mavlink_message_t* uasMessage = iteMsg.value();
+ while((iteMsg != uasMessageStorage.end()) && (iteMsg.key() == sysid))
+ {
+ if (iteMsg.value()->msgid == msgid)
+ {
+ msgFound = true;
+ uasMessage = iteMsg.value();
+ break;
+ }
+ ++iteMsg;
+ }
+
+ if (!msgFound)
+ {
+ return;
+ }
+
+ uint8_t* m = ((uint8_t*)uasMessage)+8;
+
+
switch (messageInfo[msgid].fields[fieldid].type)
{
case MAVLINK_TYPE_CHAR:
diff --git a/src/ui/QGCMAVLinkInspector.h b/src/ui/QGCMAVLinkInspector.h
index e4e7820e813b13d134547880adcb7a82193acaee..2c86e0730cb10a5b60ad258c6c706d1107943a92 100644
--- a/src/ui/QGCMAVLinkInspector.h
+++ b/src/ui/QGCMAVLinkInspector.h
@@ -26,9 +26,11 @@ public slots:
void receiveMessage(LinkInterface* link,mavlink_message_t message);
/** @brief Clear all messages */
void clearView();
- /** Update view */
+ /** @brief Update view */
void refreshView();
+ /** @brief Add system to the list */
void addSystem(UASInterface* uas);
+ /** @brief Add component to the list */
void addComponent(int uas, int component, const QString& name);
/** @Brief Select a system through the drop down menu */
void selectDropDownMenuSystem(int dropdownid);
@@ -43,25 +45,32 @@ protected:
int selectedComponentID; ///< Currently selected component
QMap systems; ///< Already observed systems
QMap components; ///< Already observed components
- QMap lastMessageUpdate; ///< Used to switch between highlight and non-highlighting color
- QMap messagesHz; ///< Used to store update rate in Hz
QMap onboardMessageInterval; ///< Stores the onboard selected data rate
- QMap messageCount; ///< Used to store the message count
- mavlink_message_t receivedMessages[256]; ///< Available / known messages
- QMap treeWidgetItems; ///< Available tree widget items
QMap rateTreeWidgetItems; ///< Available rate tree widget items
QTimer updateTimer; ///< Only update at 1 Hz to not overload the GUI
mavlink_message_info_t messageInfo[256]; // Store the metadata for all available MAVLink messages.
- // Update one message field
- void updateField(int msgid, int fieldid, QTreeWidgetItem* item);
+ QMap uasTreeWidgetItems; ///< Tree of available uas with their widget
+ QMap* > uasMsgTreeItems; ///< Stores the widget of the received message for each UAS
+
+ QMap uasMessageStorage; ///< Stores the messages for every UAS
+
+ QMap* > uasMessageHz; ///< Stores the frequency of each message of each UAS
+ QMap* > uasMessageCount; ///< Stores the message count of each message of each UAS
+
+ QMap* > uasLastMessageUpdate; ///< Stores the time of the last message for each message of each UAS
+
+ /* @brief Update one message field */
+ void updateField(int sysid, int msgid, int fieldid, QTreeWidgetItem* item);
/** @brief Rebuild the list of components */
void rebuildComponentList();
/** @brief Change the stream interval */
void changeStreamInterval(int msgid, int interval);
+ /* @brief Create a new tree for a new UAS */
+ void addUAStoTree(int sysId);
- static const unsigned int updateInterval;
- static const float updateHzLowpass;
+ static const unsigned int updateInterval; ///< The update interval of the refresh function
+ static const float updateHzLowpass; ///< The low-pass filter value for the frequency of each message
private:
Ui::QGCMAVLinkInspector *ui;
diff --git a/src/ui/QGCSettingsWidget.cc b/src/ui/QGCSettingsWidget.cc
index c5328b3ad6ecdf0df7ad6b0dbc066255fef531ac..fddf9fe6a389c3fbb01e3d22fc0f3142010745b6 100644
--- a/src/ui/QGCSettingsWidget.cc
+++ b/src/ui/QGCSettingsWidget.cc
@@ -5,14 +5,13 @@
#include "MainWindow.h"
#include "ui_QGCSettingsWidget.h"
+#include "JoystickWidget.h"
#include "LinkManager.h"
#include "MAVLinkProtocol.h"
#include "MAVLinkSettingsWidget.h"
#include "GAudioOutput.h"
-//, Qt::WindowFlags flags
-
-QGCSettingsWidget::QGCSettingsWidget(QWidget *parent, Qt::WindowFlags flags) :
+QGCSettingsWidget::QGCSettingsWidget(JoystickInput *joystick, QWidget *parent, Qt::WindowFlags flags) :
QDialog(parent, flags),
mainWindow((MainWindow*)parent),
ui(new Ui::QGCSettingsWidget)
@@ -24,6 +23,9 @@ QGCSettingsWidget::QGCSettingsWidget(QWidget *parent, Qt::WindowFlags flags) :
position.moveCenter(QApplication::desktop()->availableGeometry().center());
move(position.topLeft());
+ // Add the joystick settings pane
+ ui->tabWidget->addTab(new JoystickWidget(joystick, this), "Controllers");
+
// Add all protocols
QList protocols = LinkManager::instance()->getProtocols();
foreach (ProtocolInterface* protocol, protocols) {
diff --git a/src/ui/QGCSettingsWidget.h b/src/ui/QGCSettingsWidget.h
index b9fa70d7eda4157306f252281e5f7a11af39450c..98851ad67e8451955ec9f35ef0962689a6736797 100644
--- a/src/ui/QGCSettingsWidget.h
+++ b/src/ui/QGCSettingsWidget.h
@@ -14,7 +14,7 @@ class QGCSettingsWidget : public QDialog
Q_OBJECT
public:
- QGCSettingsWidget(QWidget *parent = 0, Qt::WindowFlags flags = Qt::Sheet);
+ QGCSettingsWidget(JoystickInput *joystick, QWidget *parent = 0, Qt::WindowFlags flags = Qt::Sheet);
~QGCSettingsWidget();
public slots:
diff --git a/src/ui/configuration/FlightModeConfig.cc b/src/ui/configuration/FlightModeConfig.cc
index 62a46c7ca818a1624f890414e24aab6d23e8e4e8..7939fac5bf564a22d05ef88b8bb5fac5259f0476 100644
--- a/src/ui/configuration/FlightModeConfig.cc
+++ b/src/ui/configuration/FlightModeConfig.cc
@@ -181,9 +181,9 @@ void FlightModeConfig::activeUASSet(UASInterface *uas)
}
// Set up the combo boxes
- for (size_t i=0; i<_cModes; i++) {
+ for (int i=0; i<_cModes; i++) {
// Fill each combo box with the available flight modes
- for (size_t j=0; j<_cModeInfo; j++) {
+ for (int j=0; j<_cModeInfo; j++) {
_rgCombo[i]->addItem(_rgModeInfo[j].label, QVariant(QChar((char)_rgModeInfo[j].value)));
}
@@ -260,13 +260,13 @@ void FlightModeConfig::parameterChanged(int uas, int component, QString paramete
}
} else {
// Loop over the flight mode params looking for a match
- for (size_t i=0; i<_cModes; i++) {
+ for (int i=0; i<_cModes; i++) {
if (parameterName == _rgModeParam[i]) {
// We found a match, i is now the index of the combo box which displays that mode slot
// Loop over the mode info till we find the matching value, this tells us which row in the
// combo box to select.
QComboBox* combo = _rgCombo[i];
- for (size_t j=0; j<_cModeInfo; j++) {
+ for (int j=0; j<_cModeInfo; j++) {
if (_rgModeInfo[j].value == iValue) {
combo->setCurrentIndex(j);
return;
diff --git a/src/ui/configuration/FlightModeConfig.h b/src/ui/configuration/FlightModeConfig.h
index 27cb23a4796425008596016ef526f2b49dad8ef0..81ee2939fc47d07d75237ef53e0ebf56ff7185ce 100644
--- a/src/ui/configuration/FlightModeConfig.h
+++ b/src/ui/configuration/FlightModeConfig.h
@@ -58,9 +58,9 @@ private:
static const FlightModeInfo_t _rgModeInfoRotor[];
static const FlightModeInfo_t _rgModeInfoRover[];
const FlightModeInfo_t* _rgModeInfo;
- size_t _cModeInfo;
+ int _cModeInfo;
- static const size_t _cModes = 6;
+ static const int _cModes = 6;
static const char* _rgModeParamFixedWing[_cModes];
static const char* _rgModeParamRotor[_cModes];
diff --git a/src/ui/designer/QGCCommandButton.cc b/src/ui/designer/QGCCommandButton.cc
index 78e46d19801d6a8ad8d91f4012b54ee76f02fc09..c002d067defc316fed526e43e0eaaa315b0a5ee4 100644
--- a/src/ui/designer/QGCCommandButton.cc
+++ b/src/ui/designer/QGCCommandButton.cc
@@ -83,6 +83,7 @@ QGCCommandButton::QGCCommandButton(QWidget *parent) :
ui->editCommandComboBox->addItem("MAV_CMD_OVERRIDE_GOTO", MAV_CMD_OVERRIDE_GOTO);
ui->editCommandComboBox->addItem("MAV_CMD_MISSION_START", MAV_CMD_MISSION_START);
ui->editCommandComboBox->addItem("MAV_CMD_COMPONENT_ARM_DISARM", MAV_CMD_COMPONENT_ARM_DISARM);
+ ui->editCommandComboBox->addItem("MAV_CMD_START_RX_PAIR", MAV_CMD_START_RX_PAIR);
ui->editCommandComboBox->addItem("MAV_CMD_DO_FLIGHTTERMINATION", MAV_CMD_DO_FLIGHTTERMINATION);
ui->editCommandComboBox->addItem("MAV_CMD_PAYLOAD_PREPARE_DEPLOY", MAV_CMD_PAYLOAD_PREPARE_DEPLOY);
ui->editCommandComboBox->addItem("MAV_CMD_PAYLOAD_CONTROL_DEPLOY", MAV_CMD_PAYLOAD_CONTROL_DEPLOY);
diff --git a/src/ui/main/QGCViewModeSelection.cc b/src/ui/main/QGCViewModeSelection.cc
index 341b0d724ed9ad00bb440ff3ede8b473c2603e87..68932c7c72e5d15c9f334c3f23ef164f693d5718 100644
--- a/src/ui/main/QGCViewModeSelection.cc
+++ b/src/ui/main/QGCViewModeSelection.cc
@@ -13,11 +13,7 @@ QGCViewModeSelection::QGCViewModeSelection(QWidget *parent) :
connect(ui->viewModeGeneric, SIGNAL(clicked()), this, SLOT(selectGeneric()));
connect(ui->viewModeAR, SIGNAL(clicked()), this, SLOT(selectWifi()));
connect(ui->viewModePX4, SIGNAL(clicked()), this, SLOT(selectPX4()));
- connect(ui->viewModeAPM, SIGNAL(clicked()), this, SLOT(selectAPM()));
connect(ui->notAgainCheckBox, SIGNAL(clicked(bool)), this, SIGNAL(settingsStorageRequested(bool)));
-
- // XXX we need to revive the APM support or remove it completely
- ui->viewModeAPM->hide();
}
QGCViewModeSelection::~QGCViewModeSelection()
@@ -49,9 +45,3 @@ void QGCViewModeSelection::selectPX4() {
mode = MainWindow::CUSTOM_MODE_PX4;
selected = true;
}
-
-void QGCViewModeSelection::selectAPM() {
- emit customViewModeSelected(MainWindow::CUSTOM_MODE_APM);
- mode = MainWindow::CUSTOM_MODE_APM;
- selected = true;
-}
diff --git a/src/ui/main/QGCViewModeSelection.h b/src/ui/main/QGCViewModeSelection.h
index 9a3f5826efeebaad0e00f57ebd355fe29e03d7d2..1d1e81d702b64c063a8c32c97c3a7cfd35742255 100644
--- a/src/ui/main/QGCViewModeSelection.h
+++ b/src/ui/main/QGCViewModeSelection.h
@@ -22,7 +22,6 @@ public slots:
void selectGeneric();
void selectPX4();
- void selectAPM();
void selectWifi();
signals:
diff --git a/src/ui/main/QGCViewModeSelection.ui b/src/ui/main/QGCViewModeSelection.ui
index b45aa7813db071c7d7f30d7eec4581e0c1444b53..968a888a602639cda4616dca15cb9bfb1dd952a5 100644
--- a/src/ui/main/QGCViewModeSelection.ui
+++ b/src/ui/main/QGCViewModeSelection.ui
@@ -67,13 +67,6 @@
-
-
-
- APM Autopilot
-
-
-
@@ -81,23 +74,6 @@
-
-
-
-
-
-
-
- :/files/images/actions/qgroundcontrol-apm.svg:/files/images/actions/qgroundcontrol-apm.svg
-
-
-
- 120
- 120
-
-
-
-
diff --git a/src/ui/map/QGCMapWidget.cc b/src/ui/map/QGCMapWidget.cc
index a01796e46256496dc4d08958ec88511e81471070..99969c492e3b936db1c66c657dda8edf2563a01c 100644
--- a/src/ui/map/QGCMapWidget.cc
+++ b/src/ui/map/QGCMapWidget.cc
@@ -421,9 +421,10 @@ void QGCMapWidget::activeUASSet(UASInterface* uas)
* @param alt Altitude over mean sea level
* @param usec Timestamp of the position message in milliseconds FIXME will move to microseconds
*/
-void QGCMapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lon, double alt, quint64 usec)
+void QGCMapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lon, double altAMSL, double altWGS84, quint64 usec)
{
Q_UNUSED(usec);
+ Q_UNUSED(altAMSL);
// Immediate update
if (maxUpdateInterval == 0)
@@ -452,7 +453,7 @@ void QGCMapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lo
// Set new lat/lon position of UAV icon
internals::PointLatLng pos_lat_lon = internals::PointLatLng(lat, lon);
- uav->SetUAVPos(pos_lat_lon, alt);
+ uav->SetUAVPos(pos_lat_lon, altWGS84);
// Follow status
if (followUAVEnabled && uas->getUASID() == followUAVID) SetCurrentPosition(pos_lat_lon);
// Convert from radians to degrees and apply
diff --git a/src/ui/map/QGCMapWidget.h b/src/ui/map/QGCMapWidget.h
index 6fc17c6b32816687106c12f12be1b3b468787643..1550c7effc8ada58a56a1fa85ae843b74718ab25 100644
--- a/src/ui/map/QGCMapWidget.h
+++ b/src/ui/map/QGCMapWidget.h
@@ -56,7 +56,7 @@ public slots:
/** @brief Add system to map view */
void addUAS(UASInterface* uas);
/** @brief Update the global position of a system */
- void updateGlobalPosition(UASInterface* uas, double lat, double lon, double alt, quint64 usec);
+ void updateGlobalPosition(UASInterface* uas, double lat, double lon, double altAMSL, double altWGS84, quint64 usec);
/** @brief Update the global position of all systems */
void updateGlobalPosition();
/** @brief Update the local position and draw it converted to GPS reference */
diff --git a/src/ui/uas/UASView.cc b/src/ui/uas/UASView.cc
index 4d5e1765d3e9ebcfca42b336d87275371678ddfe..ab86b3175b631dca611098caca76d421f61d8067 100644
--- a/src/ui/uas/UASView.cc
+++ b/src/ui/uas/UASView.cc
@@ -396,13 +396,14 @@ void UASView::updateLocalPosition(UASInterface* uas, double x, double y, double
localFrame = true;
}
-void UASView::updateGlobalPosition(UASInterface* uas, double lon, double lat, double alt, quint64 usec)
+void UASView::updateGlobalPosition(UASInterface* uas, double lon, double lat, double altAMSL, double altWGS84, quint64 usec)
{
Q_UNUSED(uas);
Q_UNUSED(usec);
+ Q_UNUSED(altAMSL);
this->lon = lon;
this->lat = lat;
- this->alt = alt;
+ this->alt = altWGS84;
globalFrameKnown = true;
}
diff --git a/src/ui/uas/UASView.h b/src/ui/uas/UASView.h
index 218f3a89584cee8fe0864bf976c197c55007d6be..c536d5be78fa7d2420fe2d64c0178cb898ae0298 100644
--- a/src/ui/uas/UASView.h
+++ b/src/ui/uas/UASView.h
@@ -58,7 +58,7 @@ public slots:
void updateThrust(UASInterface* uas, double thrust);
void updateBattery(UASInterface* uas, double voltage, double current, double percent, int seconds);
void updateLocalPosition(UASInterface*, double x, double y, double z, quint64 usec);
- void updateGlobalPosition(UASInterface*, double lon, double lat, double alt, quint64 usec);
+ void updateGlobalPosition(UASInterface*, double lon, double lat, double altAMSL, double altWGS84, quint64 usec);
void updateSpeed(UASInterface*, double x, double y, double z, quint64 usec);
void updateState(UASInterface*, QString uasState, QString stateDescription);
/** @brief Update the MAV mode */