Commit b485d7f6 authored by Lorenz Meier's avatar Lorenz Meier

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

parents 03ced70a a1cc1b5e
......@@ -103,11 +103,11 @@
</ground_reactions>
<!-- the front and rear motors spin clockwise, and the left and right motors spin counter-clockwise. -->
<propulsion>
<engine file="a2830-12" name="front">
<engine file="a2830-12" name="right">
<location unit="M">
<x> -0.283 </x>
<y> 0.00 </y>
<z> 0.00 </z>
<x> 0.000 </x>
<y> 0.283 </y>
<z> 0.000 </z>
</location>
<orient unit="DEG">
<pitch> 90.00 </pitch>
......@@ -117,8 +117,8 @@
<feed>0</feed>
<thruster file="prop10x4.5">
<location unit="M">
<x> -0.283 </x>
<y> 0.00 </y>
<x> 0.000 </x>
<y> 0.283 </y>
<z> 0.125 </z>
</location>
<orient unit="DEG">
......@@ -130,11 +130,12 @@
<p_factor> 10 </p_factor>
</thruster>
</engine>
<engine file="a2830-12" name="rear">
<engine file="a2830-12" name="left">
<location unit="M">
<x> 0.283 </x>
<y> 0.000 </y>
<z> 0.000 </z>
<x> 0.00 </x>
<y> -0.283 </y>
<z> 0.00 </z>
</location>
<orient unit="DEG">
<pitch> 90.00 </pitch>
......@@ -144,8 +145,8 @@
<feed>0</feed>
<thruster file="prop10x4.5">
<location unit="M">
<x> 0.283 </x>
<y> 0.000 </y>
<x> 0.00 </x>
<y> -0.283 </y>
<z> 0.125 </z>
</location>
<orient unit="DEG">
......@@ -157,11 +158,12 @@
<p_factor> 10 </p_factor>
</thruster>
</engine>
<engine file="a2830-12" name="left">
<engine file="a2830-12" name="front">
<location unit="M">
<x> 0.00 </x>
<y> 0.283 </y>
<z> 0.00 </z>
<x> -0.283 </x>
<y> 0.00 </y>
<z> 0.00 </z>
</location>
<orient unit="DEG">
<pitch> 90.00 </pitch>
......@@ -171,8 +173,8 @@
<feed>0</feed>
<thruster file="prop10x4.5">
<location unit="M">
<x> 0.00 </x>
<y> 0.283 </y>
<x> -0.283 </x>
<y> 0.00 </y>
<z> 0.125 </z>
</location>
<orient unit="DEG">
......@@ -184,10 +186,11 @@
<p_factor> 10 </p_factor>
</thruster>
</engine>
<engine file="a2830-12" name="right">
<engine file="a2830-12" name="rear">
<location unit="M">
<x> 0.000 </x>
<y> -0.283 </y>
<x> 0.283 </x>
<y> 0.000 </y>
<z> 0.000 </z>
</location>
<orient unit="DEG">
......@@ -198,8 +201,8 @@
<feed>0</feed>
<thruster file="prop10x4.5">
<location unit="M">
<x> 0.000 </x>
<y> -0.283 </y>
<x> 0.283 </x>
<y> 0.000 </y>
<z> 0.125 </z>
</location>
<orient unit="DEG">
......@@ -211,6 +214,7 @@
<p_factor> 10 </p_factor>
</thruster>
</engine>
<tank type="FUEL" number="0">
<location unit="M">
<x> 0.00 </x>
......@@ -222,6 +226,7 @@
<contents unit="KG"> 0.0 </contents>
</tank>
</propulsion>
<aerodynamics>
<axis name="LIFT">
</axis>
......
......@@ -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>
......@@ -141,7 +141,42 @@
<node>/velocities/airspeed-kt</node>
<factor>0.514444444444444</factor> <!-- knots to mps -->
</chunk>
<!-- Magnetometer -->
<chunk>
<name>Magnetic Variation (rad)</name>
<type>float</type>
<format>%.8f</format>
<node>/environment/magnetic-variation-deg</node>
<factor>0.01745329251994329576</factor> <!-- degrees to radians -->
</chunk>
<chunk>
<name>Magnetic Dip (rad)</name>
<type>float</type>
<format>%.8f</format>
<node>/environment/magnetic-dip-deg</node>
<factor>0.01745329251994329576</factor> <!-- degrees to radians -->
</chunk>
<!-- Temperature -->
<chunk>
<name>Temperature (deg C)</name>
<type>float</type>
<format>%.8f</format>
<node>/environment/temperature-degc</node>
<factor>1</factor>
</chunk>
<!-- Pressure -->
<chunk>
<name>Pressure (hPa)</name>
<type>float</type>
<format>%.8f</format>
<node>/environment/pressure-inhg</node>
<factor>33.86389</factor> <!-- inhg to hpa -->
</chunk>
</output>
<input>
......@@ -152,28 +187,33 @@
<!-- motors, in range 0.0 to 1.0 -->
<chunk>
<name>throttle0</name>
<type>double</type>
<type>float</type>
<node>/controls/engines/engine[0]/throttle</node>
</chunk>
</chunk>
<chunk>
<name>throttle1</name>
<type>double</type>
<type>float</type>
<node>/controls/engines/engine[1]/throttle</node>
</chunk>
</chunk>
<chunk>
<name>throttle2</name>
<type>double</type>
<type>float</type>
<node>/controls/engines/engine[2]/throttle</node>
</chunk>
</chunk>
<chunk>
<name>running</name>
<type>bool</type>
<node>/engines/engine/running</node>
</chunk>
<chunk>
<name>throttle3</name>
<type>double</type>
<type>float</type>
<node>/controls/engines/engine[3]/throttle</node>
</chunk>
</chunk>
</input>
</generic>
</PropertyList>
\ No newline at end of file
</PropertyList>
......@@ -73,7 +73,7 @@ static inline uint16_t crc_calculate(const uint8_t* pBuffer, uint16_t length)
* @param data new bytes to hash
* @param crcAccum the already accumulated checksum
**/
static inline void crc_accumulate_buffer(uint16_t *crcAccum, const char *pBuffer, uint8_t length)
static inline void crc_accumulate_buffer(uint16_t *crcAccum, const char *pBuffer, uint16_t length)
{
const uint8_t *p = (const uint8_t *)pBuffer;
while (length--) {
......
......@@ -5,6 +5,10 @@
#ifndef COMMON_H
#define COMMON_H
#ifndef MAVLINK_H
#error Wrong include order: common.h MUST NOT BE DIRECTLY USED. Include mavlink.h from the same directory instead or set all defines from mavlink.h manually.
#endif
#ifdef __cplusplus
extern "C" {
#endif
......
......@@ -73,7 +73,6 @@ MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, ui
#endif
{
// This code part is the same for all messages;
uint16_t checksum;
msg->magic = MAVLINK_STX;
msg->len = length;
msg->sysid = system_id;
......@@ -81,12 +80,13 @@ MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, ui
// One sequence number per component
msg->seq = mavlink_get_channel_status(chan)->current_tx_seq;
mavlink_get_channel_status(chan)->current_tx_seq = mavlink_get_channel_status(chan)->current_tx_seq+1;
checksum = crc_calculate((uint8_t*)&msg->len, length + MAVLINK_CORE_HEADER_LEN);
msg->checksum = crc_calculate(((const uint8_t*)(msg)) + 3, MAVLINK_CORE_HEADER_LEN);
crc_accumulate_buffer(&msg->checksum, _MAV_PAYLOAD(msg), msg->len);
#if MAVLINK_CRC_EXTRA
crc_accumulate(crc_extra, &checksum);
crc_accumulate(crc_extra, &msg->checksum);
#endif
mavlink_ck_a(msg) = (uint8_t)(checksum & 0xFF);
mavlink_ck_b(msg) = (uint8_t)(checksum >> 8);
mavlink_ck_a(msg) = (uint8_t)(msg->checksum & 0xFF);
mavlink_ck_b(msg) = (uint8_t)(msg->checksum >> 8);
return length + MAVLINK_NUM_NON_PAYLOAD_BYTES;
}
......@@ -133,7 +133,7 @@ MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint
buf[4] = mavlink_system.compid;
buf[5] = msgid;
status->current_tx_seq++;
checksum = crc_calculate((uint8_t*)&buf[1], MAVLINK_CORE_HEADER_LEN);
checksum = crc_calculate((const uint8_t*)&buf[1], MAVLINK_CORE_HEADER_LEN);
crc_accumulate_buffer(&checksum, packet, length);
#if MAVLINK_CRC_EXTRA
crc_accumulate(crc_extra, &checksum);
......@@ -158,6 +158,7 @@ MAVLINK_HELPER void _mavlink_resend_uart(mavlink_channel_t chan, const mavlink_m
ck[0] = (uint8_t)(msg->checksum & 0xFF);
ck[1] = (uint8_t)(msg->checksum >> 8);
// XXX use the right sequence here
MAVLINK_START_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + msg->len);
_mavlink_send_uart(chan, (const char *)&msg->magic, MAVLINK_NUM_HEADER_BYTES);
......@@ -172,7 +173,13 @@ MAVLINK_HELPER void _mavlink_resend_uart(mavlink_channel_t chan, const mavlink_m
*/
MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg)
{
memcpy(buffer, (const uint8_t *)&msg->magic, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len);
memcpy(buffer, (const uint8_t *)&msg->magic, MAVLINK_NUM_HEADER_BYTES + (uint16_t)msg->len);
uint8_t *ck = buffer + (MAVLINK_NUM_HEADER_BYTES + (uint16_t)msg->len);
ck[0] = (uint8_t)(msg->checksum & 0xFF);
ck[1] = (uint8_t)(msg->checksum >> 8);
return MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len;
}
......
......@@ -28,6 +28,7 @@
#define MAVLINK_MAX_EXTENDED_PAYLOAD_LEN (MAVLINK_MAX_EXTENDED_PACKET_LEN - MAVLINK_EXTENDED_HEADER_LEN - MAVLINK_NUM_NON_PAYLOAD_BYTES)
#pragma pack(push, 1)
typedef struct param_union {
union {
float param_float;
......@@ -62,13 +63,12 @@ typedef struct __mavlink_message {
uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8];
} mavlink_message_t;
typedef struct __mavlink_extended_message {
mavlink_message_t base_msg;
int32_t extended_payload_len; ///< Length of extended payload if any
uint8_t extended_payload[MAVLINK_MAX_EXTENDED_PAYLOAD_LEN];
} mavlink_extended_message_t;
#pragma pack(pop)
typedef enum {
MAVLINK_TYPE_CHAR = 0,
......
......@@ -186,22 +186,27 @@ DebugBuild {
src/qgcunittest/MockUASManager.h \
src/qgcunittest/MockUAS.h \
src/qgcunittest/MockQGCUASParamManager.h \
src/qgcunittest/MockMavlinkInterface.h \
src/qgcunittest/MockMavlinkFileServer.h \
src/qgcunittest/MultiSignalSpy.h \
src/qgcunittest/FlightModeConfigTest.h \
src/qgcunittest/FlightGearTest.h \
src/qgcunittest/TCPLinkTest.h \
src/qgcunittest/TCPLoopBackServer.h
src/qgcunittest/TCPLoopBackServer.h \
src/qgcunittest/QGCUASFileManagerTest.h
SOURCES += \
src/qgcunittest/UASUnitTest.cc \
src/qgcunittest/MockUASManager.cc \
src/qgcunittest/MockUAS.cc \
src/qgcunittest/MockQGCUASParamManager.cc \
src/qgcunittest/MockMavlinkFileServer.cc \
src/qgcunittest/MultiSignalSpy.cc \
src/qgcunittest/FlightModeConfigTest.cc \
src/qgcunittest/FlightGearTest.cc \
src/qgcunittest/TCPLinkTest.cc \
src/qgcunittest/TCPLoopBackServer.cc
src/qgcunittest/TCPLoopBackServer.cc \
src/qgcunittest/QGCUASFileManagerTest.cc
}
#
......@@ -296,6 +301,7 @@ FORMS += \
src/ui/designer/QGCCommandButton.ui \
src/ui/QGCMAVLinkLogPlayer.ui \
src/ui/QGCWaypointListMulti.ui \
src/ui/QGCUASFileViewMulti.ui \
src/ui/QGCUDPLinkConfiguration.ui \
src/ui/QGCTCPLinkConfiguration.ui \
src/ui/QGCSettingsWidget.ui \
......@@ -373,7 +379,8 @@ FORMS += \
src/ui/px4_configuration/QGCPX4AirframeConfig.ui \
src/ui/px4_configuration/QGCPX4MulticopterConfig.ui \
src/ui/px4_configuration/QGCPX4SensorCalibration.ui \
src/ui/designer/QGCXYPlot.ui
src/ui/designer/QGCXYPlot.ui \
src/ui/QGCUASFileView.ui
HEADERS += \
src/MG.h \
......@@ -461,6 +468,7 @@ HEADERS += \
src/comm/MAVLinkSimulationMAV.h \
src/uas/QGCMAVLinkUASFactory.h \
src/ui/QGCWaypointListMulti.h \
src/ui/QGCUASFileViewMulti.h \
src/ui/QGCUDPLinkConfiguration.h \
src/ui/QGCTCPLinkConfiguration.h \
src/ui/QGCSettingsWidget.h \
......@@ -567,6 +575,8 @@ HEADERS += \
src/ui/menuactionhelper.h \
src/uas/UASManagerInterface.h \
src/uas/QGCUASParamManagerInterface.h \
src/uas/QGCUASFileManager.h \
src/ui/QGCUASFileView.h \
src/uas/QGCUASWorker.h \
src/CmdLineOptParser.h \
src/uas/QGXPX4UAS.h
......@@ -651,6 +661,7 @@ SOURCES += \
src/comm/MAVLinkSimulationMAV.cc \
src/uas/QGCMAVLinkUASFactory.cc \
src/ui/QGCWaypointListMulti.cc \
src/ui/QGCUASFileViewMulti.cc \
src/ui/QGCUDPLinkConfiguration.cc \
src/ui/QGCTCPLinkConfiguration.cc \
src/ui/QGCSettingsWidget.cc \
......@@ -753,6 +764,8 @@ SOURCES += \
src/ui/px4_configuration/QGCPX4SensorCalibration.cc \
src/ui/designer/QGCXYPlot.cc \
src/ui/menuactionhelper.cpp \
src/uas/QGCUASFileManager.cc \
src/ui/QGCUASFileView.cc \
src/uas/QGCUASWorker.cc \
src/CmdLineOptParser.cc \
src/uas/QGXPX4UAS.cc
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
#include "MockMavlinkFileServer.h"
const MockMavlinkFileServer::FileTestCase MockMavlinkFileServer::rgFileTestCases[MockMavlinkFileServer::cFileTestCases] = {
// File fits one Read Ack packet, partially filling data
{ "partial.qgc", sizeof(((QGCUASFileManager::Request*)0)->data) - 1 },
// File fits one Read Ack packet, exactly filling all data
{ "exact.qgc", sizeof(((QGCUASFileManager::Request*)0)->data) },
// File is larger than a single Read Ack packets, requires multiple Reads
{ "multi.qgc", sizeof(((QGCUASFileManager::Request*)0)->data) + 1 },
};
// We only support a single fixed session
const uint8_t MockMavlinkFileServer::_sessionId = 1;
MockMavlinkFileServer::MockMavlinkFileServer(void)
{
}
/// @brief Handles List command requests. Only supports root folder paths.
/// File list returned is set using the setFileList method.
void MockMavlinkFileServer::_listCommand(QGCUASFileManager::Request* request)
{
// FIXME: Does not support directories that span multiple packets
QGCUASFileManager::Request ackResponse;
QString path;
// We only support root path
path = (char *)&request->data[0];
if (!path.isEmpty() && path != "/") {
_sendNak(QGCUASFileManager::kErrNotDir);
return;
}
// Offset requested is past the end of the list
if (request->hdr.offset > (uint32_t)_fileList.size()) {
_sendNak(QGCUASFileManager::kErrEOF);
return;
}
ackResponse.hdr.magic = 'f';
ackResponse.hdr.opcode = QGCUASFileManager::kRspAck;
ackResponse.hdr.session = 0;
ackResponse.hdr.offset = request->hdr.offset;
ackResponse.hdr.size = 0;
if (request->hdr.offset == 0) {
// Requesting first batch of file names
Q_ASSERT(_fileList.size());
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);
ackResponse.hdr.size += cchFilename + 1;
bufPtr += cchFilename + 1;
}
_emitResponse(&ackResponse);
} else {
// FIXME: Does not support directories that span multiple packets
_sendNak(QGCUASFileManager::kErrEOF);
}
}
/// @brief Handles Open command requests.
void MockMavlinkFileServer::_openCommand(QGCUASFileManager::Request* request)
{
QGCUASFileManager::Request response;
QString path;
size_t cchPath = strnlen((char *)request->data, sizeof(request->data));
Q_ASSERT(cchPath != sizeof(request->data));
path = (char *)request->data;
// Check path against one of our known test cases
bool found = false;
for (size_t i=0; i<cFileTestCases; i++) {
if (path == rgFileTestCases[i].filename) {
found = true;
_readFileLength = rgFileTestCases[i].length;
break;
}
}
if (!found) {
_sendNak(QGCUASFileManager::kErrNotFile);
return;
}
response.hdr.magic = 'f';
response.hdr.opcode = QGCUASFileManager::kRspAck;
response.hdr.session = _sessionId;
response.hdr.size = 0;
_emitResponse(&response);
}
/// @brief Handles Read command requests.
void MockMavlinkFileServer::_readCommand(QGCUASFileManager::Request* request)
{
QGCUASFileManager::Request response;
if (request->hdr.session != _sessionId) {
_sendNak(QGCUASFileManager::kErrNoSession);
return;
}
uint32_t readOffset = request->hdr.offset; // offset into file for reading
uint8_t cDataBytes = 0; // current number of data bytes used
if (readOffset >= _readFileLength) {
_sendNak(QGCUASFileManager::kErrEOF);
return;
}
// Write length byte if needed
if (readOffset == 0) {
response.data[0] = _readFileLength;
readOffset++;
cDataBytes++;
}
// Write file bytes. Data is a repeating sequence of 0x00, 0x01, .. 0xFF.
for (; cDataBytes < sizeof(response.data) && readOffset < _readFileLength; readOffset++, cDataBytes++) {
// Subtract one from readOffset to take into account length byte and start file data a 0x00
response.data[cDataBytes] = (readOffset - 1) & 0xFF;
}
// 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;
response.hdr.opcode = QGCUASFileManager::kRspAck;
_emitResponse(&response);
}
/// @brief Handles Terminate commands
void MockMavlinkFileServer::_terminateCommand(QGCUASFileManager::Request* request)
{
if (request->hdr.session != _sessionId) {
_sendNak(QGCUASFileManager::kErrNoSession);
return;
}
_sendAck();
// Let our test harness know that we got a terminate command. This is used to validate the a Terminate is correctly
// sent after an Open.
emit terminateCommandReceived();
}
/// @brief Handles messages sent to the FTP server.
void MockMavlinkFileServer::sendMessage(mavlink_message_t message)
{
QGCUASFileManager::Request ackResponse;
Q_ASSERT(message.msgid == MAVLINK_MSG_ID_ENCAPSULATED_DATA);
mavlink_encapsulated_data_t requestEncapsulatedData;
mavlink_msg_encapsulated_data_decode(&message, &requestEncapsulatedData);
QGCUASFileManager::Request* request = (QGCUASFileManager::Request*)&requestEncapsulatedData.data[0];
// Validate CRC
if (request->hdr.crc32 != QGCUASFileManager::crc32(request)) {
_sendNak(QGCUASFileManager::kErrCrc);
}
switch (request->hdr.opcode) {
case QGCUASFileManager::kCmdTestNoAck:
// ignored, ack not sent back, for testing only
break;
case QGCUASFileManager::kCmdReset:
// 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);
break;
case QGCUASFileManager::kCmdList:
_listCommand(request);
break;
case QGCUASFileManager::kCmdOpen:
_openCommand(request);
break;
case QGCUASFileManager::kCmdRead:
_readCommand(request);
break;
case QGCUASFileManager::kCmdTerminate:
_terminateCommand(request);
break;
// Remainder of commands are NYI
case QGCUASFileManager::kCmdCreate:
// creates <path> for writing, returns <session>
case QGCUASFileManager::kCmdWrite:
// appends <size> bytes at <offset> in <session>
case QGCUASFileManager::kCmdRemove:
// remove file (only if created by server?)
default:
// nack for all NYI opcodes
_sendNak(QGCUASFileManager::kErrUnknownCommand);
break;
}
}
/// @brief Sends an Ack
void MockMavlinkFileServer::_sendAck(void)
{
QGCUASFileManager::Request ackResponse;
ackResponse.hdr.magic = 'f';
ackResponse.hdr.opcode = QGCUASFileManager::kRspAck;
ackResponse.hdr.session = 0;
ackResponse.hdr.size = 0;
_emitResponse(&ackResponse);
}
/// @brief Sends a Nak with the specified error code.
void MockMavlinkFileServer::_sendNak(QGCUASFileManager::ErrorCode error)
{
QGCUASFileManager::Request nakResponse;
nakResponse.hdr.magic = 'f';
nakResponse.hdr.opcode = QGCUASFileManager::kRspNak;
nakResponse.hdr.session = 0;
nakResponse.hdr.size = 1;
nakResponse.data[0] = error;
_emitResponse(&nakResponse);
}
/// @brief Emits a Request through the messageReceived signal.
void MockMavlinkFileServer::_emitResponse(QGCUASFileManager::Request* request)
{
mavlink_message_t mavlinkMessage;
request->hdr.crc32 = QGCUASFileManager::crc32(request);
mavlink_msg_encapsulated_data_pack(250, 0, &mavlinkMessage, 0 /*_encdata_seq*/, (uint8_t*)request);
emit messageReceived(NULL, mavlinkMessage);
}
\ No newline at end of file