QGCMAVLink.h 5.74 KB
Newer Older
1 2
/****************************************************************************
 *
Gus Grubba's avatar
Gus Grubba committed
3
 * (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
4 5 6 7 8
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/
pixhawk's avatar
pixhawk committed
9

10
#pragma once
pixhawk's avatar
pixhawk committed
11

12 13
#include <QString>

14 15 16
#define MAVLINK_USE_MESSAGE_INFO
#define MAVLINK_EXTERNAL_RX_STATUS  // Single m_mavlink_status instance is in QGCApplication.cc
#include <stddef.h>                 // Hack workaround for Mav 2.0 header problem with respect to offsetof usage
17 18

// Ignore warnings from mavlink headers for both GCC/Clang and MSVC
19
#ifdef __GNUC__
20 21

#if __GNUC__ > 8
22 23
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Waddress-of-packed-member"
24 25 26 27 28
#else
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wall"
#endif

29
#else
30
#pragma warning(push, 0)
31
#endif
32

33 34
#include <mavlink_types.h>
extern mavlink_status_t m_mavlink_status[MAVLINK_COMM_NUM_BUFFERS];
35
#include <mavlink.h>
36

37
#ifdef __GNUC__
38
#pragma GCC diagnostic pop
39
#else
40
#pragma warning(pop, 0)
41
#endif
42

43 44 45 46 47 48
#ifdef __GNUC__
#define PACKED_STRUCT( __Declaration__ ) __Declaration__ __attribute__((packed))
#else
#define PACKED_STRUCT( __Declaration__ ) __pragma( pack(push, 1) ) __Declaration__ __pragma( pack(pop) )
#endif

Don Gagne's avatar
Don Gagne committed
49 50
class QGCMAVLink {
public:
51 52 53 54 55 56
    static bool     isFixedWing         (MAV_TYPE mavType);
    static bool     isRover             (MAV_TYPE mavType);
    static bool     isSub               (MAV_TYPE mavType);
    static bool     isMultiRotor        (MAV_TYPE mavType);
    static bool     isVTOL              (MAV_TYPE mavType);
    static QString  mavResultToString   (MAV_RESULT result);
Don Gagne's avatar
Don Gagne committed
57 58
};

59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84
class MavlinkFTP {
public:
    /// This is the fixed length portion of the protocol data.
    /// This needs to be packed, because it's typecasted from mavlink_file_transfer_protocol_t.payload, which starts
    /// at a 3 byte offset, causing an unaligned access to seq_number and offset
    PACKED_STRUCT(
            typedef struct RequestHeader {
                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     burstComplete;  ///< Only used if req_opcode=kCmdBurstReadFile - 1: set of burst packets complete, 0: More burst packets coming.
                uint8_t     paddng;        ///< 32 bit aligment padding
                uint32_t    offset;         ///< Offsets for List and Read commands
            }) RequestHeader;

    PACKED_STRUCT(
            typedef struct Request{
                RequestHeader hdr;

                // 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 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_file_transfer_protocol_t*)0)->payload) - sizeof(RequestHeader)];
85

86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133
                    // File length returned by Open command
                    uint32_t openFileLength;

                    // Length of file chunk written by write command
                    uint32_t writeFileLength;
                };
            }) Request;

    typedef enum {
        kCmdNone = 0,           ///< ignored, always acked
        kCmdTerminateSession,	///< Terminates open Read session
        kCmdResetSessions,		///< Terminates all open Read sessions
        kCmdListDirectory,		///< List files in <path> from <offset>
        kCmdOpenFileRO,			///< 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,			///< Writes <size> bytes to <offset> in <session>
        kCmdRemoveFile,			///< Remove file at <path>
        kCmdCreateDirectory,	///< Creates directory at <path>
        kCmdRemoveDirectory,	///< Removes Directory at <path>, must be empty
        kCmdOpenFileWO,			///< Opens file at <path> for writing, returns <session>
        kCmdTruncateFile,		///< Truncate file at <path> to <offset> length
        kCmdRename,				///< Rename <path1> to <path2>
        kCmdCalcFileCRC32,		///< Calculate CRC32 for file at <path>
        kCmdBurstReadFile,      ///< Burst download session file

        kRspAck = 128,          ///< Ack response
        kRspNak,                ///< Nak response
    } OpCode_t;

    /// @brief Error codes returned in Nak response PayloadHeader.data[0].
   typedef enum {
        kErrNone = 0,
        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
        kErrFailFileExists,         ///< File exists already
        kErrFailFileProtected,      ///< File is write protected
        kErrFailFileNotFound
    } ErrorCode_t;

    static QString opCodeToString   (OpCode_t opCode);
    static QString errorCodeToString(ErrorCode_t errorCode);
};