Commit 315d2732 authored by Lorenz Meier's avatar Lorenz Meier

Merge branch 'master' of github.com:mavlink/qgroundcontrol

parents b4089ad9 ca990ff6
......@@ -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 {
......
......@@ -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.
......
......@@ -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.
......
......@@ -6,7 +6,7 @@
<output>
<line_separator>newline</line_separator>
<var_separator>tab</var_separator>
<chunk>
<name>time (sec)</name>
<type>float</type>
......@@ -46,7 +46,7 @@
<node>/orientation/roll-deg</node>
<factor>0.01745329251994329576</factor> <!-- degrees to radians -->
</chunk>
<chunk>
<name>pitch angle (rad)</name>
<type>float</type>
......@@ -54,7 +54,7 @@
<node>/orientation/pitch-deg</node>
<factor>0.01745329251994329576</factor> <!-- degrees to radians -->
</chunk>
<chunk>
<name>yaw angle</name>
<type>float</type>
......@@ -109,7 +109,7 @@
</chunk>
<!-- Velocities -->
<chunk>
<name>Velocity North ("vn" mps)</name>
<type>float</type>
......@@ -176,7 +176,16 @@
<node>/environment/pressure-inhg</node>
<factor>33.86389</factor> <!-- inhg to hpa -->
</chunk>
<!-- Altitude AGL -->
<chunk>
<name>Altitude AGL (m)</name>
<type>float</type>
<format>%.5f</format>
<node>/position/altitude-agl-ft</node>
<factor>0.3048</factor> <!-- feet to meter -->
</chunk>
</output>
<input>
......@@ -195,13 +204,13 @@
<type>float</type>
<node>/controls/flight/elevator</node>
</chunk>
<chunk>
<name>rudder</name>
<type>float</type>
<node>/controls/flight/rudder</node>
</chunk>
<chunk>
<name>running</name>
<type>bool</type>
......@@ -213,7 +222,7 @@
<type>float</type>
<node>/controls/engines/engine/throttle</node>
</chunk>
</input>
......
......@@ -223,7 +223,7 @@ namespace core {
qlonglong id=++ConnCounter;
Mcounter.unlock();
#ifdef DEBUG_PUREIMAGECACHE
qDebug()<<"Cache dir="<<dir<<" Try to GET:"<<pos.X()+","+pos.Y();
qDebug()<<"Cache dir="<<dir<<" Try to GET:"<<pos.X()<<","<<pos.Y();
#endif //DEBUG_PUREIMAGECACHE
QString db=dir+"Data.qmdb";
......
......@@ -349,7 +349,7 @@ void QwtPlotCurve::drawSeries( QPainter *painter,
const QwtScaleMap &xMap, const QwtScaleMap &yMap,
const QRectF &canvasRect, int from, int to ) const
{
const size_t numSamples = dataSize();
const int numSamples = static_cast<int>(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<int>(dataSize()) - 1;
}
drawLines( painter, xMap, yMap, canvasRect, from, to );
break;
......
......@@ -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<int>(size) );
::memcpy( d_x.data(), x, size * sizeof( double ) );
d_y.resize( size );
d_y.resize(static_cast<int>(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<uint>(index) );
const double yValue = y( xValue );
return QPointF( xValue, yValue );
......
......@@ -78,7 +78,7 @@ QRectF qwtBoundingRectT(
from = 0;
if ( to < 0 )
to = series.size() - 1;
to = static_cast<int>(series.size()) - 1;
if ( to < from )
return boundingRect;
......
......@@ -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
}
......@@ -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<uint16_t>(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<uint16_t>(waypoints_receive_buffer->size()) - 1;
}
// switch the waypoints list
......
......@@ -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)
{
......
......@@ -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);
......
This diff is collapsed.
......@@ -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
......@@ -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; }
......
......@@ -31,6 +31,7 @@
/// @author Don Gagne <don@thegagnes.com>
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));
......
......@@ -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;
......
This diff is collapsed.
......@@ -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 <path> from <offset>
kCmdOpen, ///> opens <path> for reading, returns <session>
kCmdRead, ///> reads <size> bytes from <offset> in <session>
kCmdCreate, ///> creates <path> for writing, returns <session>
kCmdWrite, ///> appends <size> bytes at <offset> in <session>
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 <path> from <offset>
kCmdOpenFile, ///< Opens file at <path> for reading, returns <session>
kCmdReadFile, ///< Reads <size> bytes from <offset> in <session>
kCmdCreateFile, ///< Creates file at <path> for writing, returns <session>
kCmdWriteFile, ///< Appends <size> bytes to file in <session>
kCmdRemoveFile, ///< Remove file at <path>
kCmdCreateDirectory, ///< Creates directory at <path>
kCmdRemoveDirectory, ///< Removes Directory at <path>, 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.
......
......@@ -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
......
......@@ -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<QAction*> actions; ///< A list of actions that this UAS can perform.
......
......@@ -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;
......
......@@ -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
{
......
......@@ -7,7 +7,7 @@
#include <QDesktopWidget>
JoystickWidget::JoystickWidget(JoystickInput* joystick, QWidget *parent) :
QDialog(parent),
QWidget(parent),
joystick(joystick),
m_ui(new Ui::JoystickWidget)
{
......
......@@ -31,7 +31,7 @@ This file is part of the PIXHAWK project
#ifndef JOYSTICKWIDGET_H
#define JOYSTICKWIDGET_H
#include <QDialog>
#include <QWidget>
#include <QLabel>
#include <QMap>
#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)
......
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>JoystickWidget</class>
<widget class="QDialog" name="JoystickWidget">
<widget class="QWidget" name="JoystickWidget">
<property name="geometry">
<rect>
<x>0</x>
......@@ -30,7 +30,7 @@
<number>8</number>
</property>
<property name="sizeConstraint">
<enum>QLayout::SetFixedSize</enum>
<enum>QLayout::SetDefaultConstraint</enum>
</property>
<property name="leftMargin">
<number>8</number>
......@@ -50,7 +50,7 @@
<bool>true</bool>
</property>
<property name="text">
<string>Enable joysticks</string>
<string>Enable controllers</string>
</property>
</widget>