msp_msg.hpp
Go to the documentation of this file.
00001 // MSP message definitions
00002 // http://www.multiwii.com/wiki/index.php?title=Multiwii_Serial_Protocol
00003 
00004 #ifndef MSP_MSG_HPP
00005 #define MSP_MSG_HPP
00006 
00007 #include <array>
00008 #include <cassert>
00009 #include <climits>
00010 #include <iomanip>
00011 #include <set>
00012 #include <sstream>
00013 #include <string>
00014 #include <vector>
00015 #include "Message.hpp"
00016 
00017 /*================================================================
00018  * actual messages have id and the relevant encode decode methods
00019  * the logic for encoding and decoding must be within a message-derived class
00020  * non message-derived structs must have pack/unpack subroutines
00021  *
00022  */
00023 
00024 // undefine macros defined by GNU C std library
00025 #undef major
00026 #undef minor
00027 
00028 namespace msp {
00029 
00030 enum class ID : uint16_t {
00031     MSP_API_VERSION                    = 1,
00032     MSP_FC_VARIANT                     = 2,
00033     MSP_FC_VERSION                     = 3,
00034     MSP_BOARD_INFO                     = 4,
00035     MSP_BUILD_INFO                     = 5,
00036     MSP_INAV_PID                       = 6,
00037     MSP_SET_INAV_PID                   = 7,
00038     MSP_NAME                           = 10,  // out message
00039     MSP_SET_NAME                       = 11,  // in message
00040     MSP_NAV_POSHOLD                    = 12,  // only in iNav
00041     MSP_SET_NAV_POSHOLD                = 13,  // only in iNav
00042     MSP_CALIBRATION_DATA               = 14,
00043     MSP_SET_CALIBRATION_DATA           = 15,
00044     MSP_POSITION_ESTIMATION_CONFIG     = 16,
00045     MSP_SET_POSITION_ESTIMATION_CONFIG = 17,
00046     MSP_WP_MISSION_LOAD                = 18,  // Load mission from NVRAM
00047     MSP_WP_MISSION_SAVE                = 19,  // Save mission to NVRAM
00048     MSP_WP_GETINFO                     = 20,
00049     MSP_RTH_AND_LAND_CONFIG            = 21,
00050     MSP_SET_RTH_AND_LAND_CONFIG        = 22,
00051     MSP_FW_CONFIG                      = 23,
00052     MSP_SET_FW_CONFIG                  = 24,
00053     MSP_BATTERY_CONFIG                 = 32,  // not avaialable in iNav
00054     MSP_SET_BATTERY_CONFIG             = 33,  // not avaialable in iNav
00055     MSP_MODE_RANGES                    = 34,
00056     MSP_SET_MODE_RANGE                 = 35,
00057     MSP_FEATURE                        = 36,
00058     MSP_SET_FEATURE                    = 37,
00059     MSP_BOARD_ALIGNMENT                = 38,
00060     MSP_SET_BOARD_ALIGNMENT            = 39,
00061     MSP_CURRENT_METER_CONFIG           = 40,
00062     MSP_SET_CURRENT_METER_CONFIG       = 41,
00063     MSP_MIXER                          = 42,
00064     MSP_SET_MIXER                      = 43,
00065     MSP_RX_CONFIG                      = 44,
00066     MSP_SET_RX_CONFIG                  = 45,
00067     MSP_LED_COLORS                     = 46,
00068     MSP_SET_LED_COLORS                 = 47,
00069     MSP_LED_STRIP_CONFIG               = 48,
00070     MSP_SET_LED_STRIP_CONFIG           = 49,
00071     MSP_RSSI_CONFIG                    = 50,
00072     MSP_SET_RSSI_CONFIG                = 51,
00073     MSP_ADJUSTMENT_RANGES              = 52,
00074     MSP_SET_ADJUSTMENT_RANGE           = 53,
00075     MSP_CF_SERIAL_CONFIG               = 54,
00076     MSP_SET_CF_SERIAL_CONFIG           = 55,
00077     MSP_VOLTAGE_METER_CONFIG           = 56,
00078     MSP_SET_VOLTAGE_METER_CONFIG       = 57,
00079     MSP_SONAR_ALTITUDE                 = 58,
00080     MSP_PID_CONTROLLER                 = 59,
00081     MSP_SET_PID_CONTROLLER             = 60,
00082     MSP_ARMING_CONFIG                  = 61,
00083     MSP_SET_ARMING_CONFIG              = 62,
00084     MSP_RX_MAP                         = 64,
00085     MSP_SET_RX_MAP                     = 65,
00086     MSP_BF_CONFIG                      = 66,  // depricated, out message
00087     MSP_SET_BF_CONFIG                  = 67,  // depricated, in message
00088     MSP_REBOOT                         = 68,
00089     MSP_BF_BUILD_INFO                  = 69,  // depricated, iNav
00090     MSP_DATAFLASH_SUMMARY              = 70,
00091     MSP_DATAFLASH_READ                 = 71,
00092     MSP_DATAFLASH_ERASE                = 72,
00093     MSP_LOOP_TIME                      = 73,  // depricated, iNav
00094     MSP_SET_LOOP_TIME                  = 74,  // depricated, iNav
00095     MSP_FAILSAFE_CONFIG                = 75,
00096     MSP_SET_FAILSAFE_CONFIG            = 76,
00097     MSP_RXFAIL_CONFIG                  = 77,  // depricated, iNav
00098     MSP_SET_RXFAIL_CONFIG              = 78,  // depricated, iNav
00099     MSP_SDCARD_SUMMARY                 = 79,
00100     MSP_BLACKBOX_CONFIG                = 80,
00101     MSP_SET_BLACKBOX_CONFIG            = 81,
00102     MSP_TRANSPONDER_CONFIG             = 82,
00103     MSP_SET_TRANSPONDER_CONFIG         = 83,
00104     MSP_OSD_CONFIG                     = 84,  // out message, betaflight
00105     MSP_SET_OSD_CONFIG                 = 85,  // in message, betaflight
00106     MSP_OSD_CHAR_READ                  = 86,  // out message, betaflight
00107     MSP_OSD_CHAR_WRITE                 = 87,
00108     MSP_VTX_CONFIG                     = 88,
00109     MSP_SET_VTX_CONFIG                 = 89,
00110     MSP_ADVANCED_CONFIG                = 90,
00111     MSP_SET_ADVANCED_CONFIG            = 91,
00112     MSP_FILTER_CONFIG                  = 92,
00113     MSP_SET_FILTER_CONFIG              = 93,
00114     MSP_PID_ADVANCED                   = 94,
00115     MSP_SET_PID_ADVANCED               = 95,
00116     MSP_SENSOR_CONFIG                  = 96,
00117     MSP_SET_SENSOR_CONFIG              = 97,
00118     MSP_CAMERA_CONTROL                 = 98,   // MSP_SPECIAL_PARAMETERS
00119     MSP_SET_ARMING_DISABLED            = 99,   // MSP_SET_SPECIAL_PARAMETERS
00120     MSP_IDENT                          = 100,  // depricated
00121     MSP_STATUS                         = 101,
00122     MSP_RAW_IMU                        = 102,
00123     MSP_SERVO                          = 103,
00124     MSP_MOTOR                          = 104,
00125     MSP_RC                             = 105,
00126     MSP_RAW_GPS                        = 106,
00127     MSP_COMP_GPS                       = 107,
00128     MSP_ATTITUDE                       = 108,
00129     MSP_ALTITUDE                       = 109,
00130     MSP_ANALOG                         = 110,
00131     MSP_RC_TUNING                      = 111,
00132     MSP_PID                            = 112,
00133     MSP_ACTIVEBOXES                    = 113,  // depricated, iNav
00134     MSP_MISC                           = 114,  // depricated, iNav
00135     MSP_MOTOR_PINS                     = 115,  // depricated, iNav
00136     MSP_BOXNAMES                       = 116,
00137     MSP_PIDNAMES                       = 117,
00138     MSP_WP                             = 118,
00139     MSP_BOXIDS                         = 119,
00140     MSP_SERVO_CONF                     = 120,
00141     MSP_NAV_STATUS                     = 121,
00142     MSP_NAV_CONFIG                     = 122,
00143     MSP_MOTOR_3D_CONFIG                = 124,
00144     MSP_RC_DEADBAND                    = 125,
00145     MSP_SENSOR_ALIGNMENT               = 126,
00146     MSP_LED_STRIP_MODECOLOR            = 127,
00147     MSP_VOLTAGE_METERS                 = 128,  // not present in iNav
00148     MSP_CURRENT_METERS                 = 129,  // not present in iNav
00149     MSP_BATTERY_STATE                  = 130,  // not present in iNav
00150     MSP_MOTOR_CONFIG                   = 131,  // out message
00151     MSP_GPS_CONFIG                     = 132,  // out message
00152     MSP_COMPASS_CONFIG                 = 133,  // out message
00153     MSP_ESC_SENSOR_DATA                = 134,  // out message
00154     MSP_STATUS_EX                      = 150,
00155     MSP_SENSOR_STATUS                  = 151,  // only iNav
00156     MSP_UID                            = 160,
00157     MSP_GPSSVINFO                      = 164,
00158     MSP_GPSSTATISTICS                  = 166,
00159     MSP_OSD_VIDEO_CONFIG               = 180,
00160     MSP_SET_OSD_VIDEO_CONFIG           = 181,
00161     MSP_DISPLAYPORT                    = 182,
00162     MSP_COPY_PROFILE                   = 183,  // not in iNav
00163     MSP_BEEPER_CONFIG                  = 184,  // not in iNav
00164     MSP_SET_BEEPER_CONFIG              = 185,  // not in iNav
00165     MSP_SET_TX_INFO                    = 186,  // in message
00166     MSP_TX_INFO                        = 187,  // out message
00167     MSP_SET_RAW_RC                     = 200,
00168     MSP_SET_RAW_GPS                    = 201,
00169     MSP_SET_PID                        = 202,
00170     MSP_SET_BOX                        = 203,  // depricated
00171     MSP_SET_RC_TUNING                  = 204,
00172     MSP_ACC_CALIBRATION                = 205,
00173     MSP_MAG_CALIBRATION                = 206,
00174     MSP_SET_MISC                       = 207,  // depricated
00175     MSP_RESET_CONF                     = 208,
00176     MSP_SET_WP                         = 209,
00177     MSP_SELECT_SETTING                 = 210,
00178     MSP_SET_HEADING                    = 211,
00179     MSP_SET_SERVO_CONF                 = 212,
00180     MSP_SET_MOTOR                      = 214,
00181     MSP_SET_NAV_CONFIG                 = 215,
00182     MSP_SET_MOTOR_3D_CONF              = 217,
00183     MSP_SET_RC_DEADBAND                = 218,
00184     MSP_SET_RESET_CURR_PID             = 219,
00185     MSP_SET_SENSOR_ALIGNMENT           = 220,
00186     MSP_SET_LED_STRIP_MODECOLOR        = 221,
00187     MSP_SET_MOTOR_CONFIG               = 222,  // out message
00188     MSP_SET_GPS_CONFIG                 = 223,  // out message
00189     MSP_SET_COMPASS_CONFIG             = 224,  // out message
00190     MSP_SET_ACC_TRIM                   = 239,  // in message
00191     MSP_ACC_TRIM                       = 240,  // out message
00192     MSP_SERVO_MIX_RULES                = 241,  // out message
00193     MSP_SET_SERVO_MIX_RULE             = 242,  // in message
00194     MSP_PASSTHROUGH_SERIAL             = 244,  // not used in CF, BF, iNav
00195     MSP_SET_4WAY_IF                    = 245,  // in message
00196     MSP_SET_RTC                        = 246,  // in message
00197     MSP_RTC                            = 247,  // out message
00198     MSP_EEPROM_WRITE                   = 250,  // in message
00199     MSP_RESERVE_1                      = 251,  // reserved for system usage
00200     MSP_RESERVE_2                      = 252,  // reserved for system usage
00201     MSP_DEBUGMSG                       = 253,  // out message
00202     MSP_DEBUG                          = 254,  // out message
00203     MSP_V2_FRAME                       = 255,  // MSPv2 over MSPv1
00204 
00205     MSP2_COMMON_TZ               = 0x1001,  // out message, TZ offset
00206     MSP2_COMMON_SET_TZ           = 0x1002,  // in message, sets the TZ offset
00207     MSP2_COMMON_SETTING          = 0x1003,  // in/out message, returns setting
00208     MSP2_COMMON_SET_SETTING      = 0x1004,  // in message, sets a setting value
00209     MSP2_COMMON_MOTOR_MIXER      = 0x1005,
00210     MSP2_COMMON_SET_MOTOR_MIXER  = 0x1006,
00211     MSP2_INAV_STATUS             = 0x2000,
00212     MSP2_INAV_OPTICAL_FLOW       = 0x2001,
00213     MSP2_INAV_ANALOG             = 0x2002,
00214     MSP2_INAV_MISC               = 0x2003,
00215     MSP2_INAV_SET_MISC           = 0x2004,
00216     MSP2_INAV_BATTERY_CONFIG     = 0x2005,
00217     MSP2_INAV_SET_BATTERY_CONFIG = 0x2006,
00218     MSP2_INAV_RATE_PROFILE       = 0x2007,
00219     MSP2_INAV_SET_RATE_PROFILE   = 0x2008,
00220     MSP2_INAV_AIR_SPEED          = 0x2009
00221 };
00222 
00223 enum class ArmingFlags : uint32_t {
00224     ARMED          = (1 << 2),
00225     WAS_EVER_ARMED = (1 << 3),
00226 
00227     ARMING_DISABLED_FAILSAFE_SYSTEM = (1 << 7),
00228 
00229     ARMING_DISABLED_NOT_LEVEL                    = (1 << 8),
00230     ARMING_DISABLED_SENSORS_CALIBRATING          = (1 << 9),
00231     ARMING_DISABLED_SYSTEM_OVERLOADED            = (1 << 10),
00232     ARMING_DISABLED_NAVIGATION_UNSAFE            = (1 << 11),
00233     ARMING_DISABLED_COMPASS_NOT_CALIBRATED       = (1 << 12),
00234     ARMING_DISABLED_ACCELEROMETER_NOT_CALIBRATED = (1 << 13),
00235     ARMING_DISABLED_ARM_SWITCH                   = (1 << 14),
00236     ARMING_DISABLED_HARDWARE_FAILURE             = (1 << 15),
00237     ARMING_DISABLED_BOXFAILSAFE                  = (1 << 16),
00238     ARMING_DISABLED_BOXKILLSWITCH                = (1 << 17),
00239     ARMING_DISABLED_RC_LINK                      = (1 << 18),
00240     ARMING_DISABLED_THROTTLE                     = (1 << 19),
00241     ARMING_DISABLED_CLI                          = (1 << 20),
00242     ARMING_DISABLED_CMS_MENU                     = (1 << 21),
00243     ARMING_DISABLED_OSD_MENU                     = (1 << 22),
00244     ARMING_DISABLED_ROLLPITCH_NOT_CENTERED       = (1 << 23),
00245     ARMING_DISABLED_SERVO_AUTOTRIM               = (1 << 24),
00246     ARMING_DISABLED_OOM                          = (1 << 25),
00247     ARMING_DISABLED_INVALID_SETTING              = (1 << 26),
00248 
00249     ARMING_DISABLED_ALL_FLAGS =
00250         (ARMING_DISABLED_FAILSAFE_SYSTEM | ARMING_DISABLED_NOT_LEVEL |
00251          ARMING_DISABLED_SENSORS_CALIBRATING |
00252          ARMING_DISABLED_SYSTEM_OVERLOADED | ARMING_DISABLED_NAVIGATION_UNSAFE |
00253          ARMING_DISABLED_COMPASS_NOT_CALIBRATED |
00254          ARMING_DISABLED_ACCELEROMETER_NOT_CALIBRATED |
00255          ARMING_DISABLED_ARM_SWITCH | ARMING_DISABLED_HARDWARE_FAILURE |
00256          ARMING_DISABLED_BOXFAILSAFE | ARMING_DISABLED_BOXKILLSWITCH |
00257          ARMING_DISABLED_RC_LINK | ARMING_DISABLED_THROTTLE |
00258          ARMING_DISABLED_CLI | ARMING_DISABLED_CMS_MENU |
00259          ARMING_DISABLED_OSD_MENU | ARMING_DISABLED_ROLLPITCH_NOT_CENTERED |
00260          ARMING_DISABLED_SERVO_AUTOTRIM | ARMING_DISABLED_OOM |
00261          ARMING_DISABLED_INVALID_SETTING)
00262 };
00263 
00264 inline std::string armingFlagToString(uint32_t flag) {
00265     std::string val;
00266     if(flag & (1 << 2)) val += "ARMED ";
00267     if(flag & (1 << 3)) val += "WAS_EVER_ARMED ";
00268     if(flag & (1 << 7)) val += "ARMING_DISABLED_FAILSAFE_SYSTEM ";
00269     if(flag & (1 << 8)) val += "ARMING_DISABLED_NOT_LEVEL ";
00270     if(flag & (1 << 9)) val += "ARMING_DISABLED_SENSORS_CALIBRATING ";
00271     if(flag & (1 << 10)) val += "ARMING_DISABLED_SYSTEM_OVERLOADED ";
00272     if(flag & (1 << 11)) val += "ARMING_DISABLED_NAVIGATION_UNSAFE ";
00273     if(flag & (1 << 12)) val += "ARMING_DISABLED_COMPASS_NOT_CALIBRATED ";
00274     if(flag & (1 << 13)) val += "ARMING_DISABLED_ACCELEROMETER_NOT_CALIBRATED ";
00275     if(flag & (1 << 14)) val += "ARMING_DISABLED_ARM_SWITCH ";
00276     if(flag & (1 << 15)) val += "ARMING_DISABLED_HARDWARE_FAILURE ";
00277     if(flag & (1 << 16)) val += "ARMING_DISABLED_BOXFAILSAFE ";
00278     if(flag & (1 << 17)) val += "ARMING_DISABLED_BOXKILLSWITCH ";
00279     if(flag & (1 << 18)) val += "ARMING_DISABLED_RC_LINK ";
00280     if(flag & (1 << 19)) val += "ARMING_DISABLED_THROTTLE ";
00281     if(flag & (1 << 20)) val += "ARMING_DISABLED_CLI ";
00282     if(flag & (1 << 21)) val += "ARMING_DISABLED_CMS_MENU ";
00283     if(flag & (1 << 22)) val += "ARMING_DISABLED_OSD_MENU ";
00284     if(flag & (1 << 23)) val += "ARMING_DISABLED_ROLLPITCH_NOT_CENTERED ";
00285     if(flag & (1 << 24)) val += "ARMING_DISABLED_SERVO_AUTOTRIM ";
00286     if(flag & (1 << 25)) val += "ARMING_DISABLED_OOM ";
00287     if(flag & (1 << 26)) val += "ARMING_DISABLED_INVALID_SETTING ";
00288     return val;
00289 }
00290 
00291 namespace msg {
00292 
00293 const static size_t N_SERVO = 8;
00294 const static size_t N_MOTOR = 8;
00295 
00296 const static size_t BOARD_IDENTIFIER_LENGTH = 4;
00297 
00298 const static size_t BUILD_DATE_LENGTH         = 11;
00299 const static size_t BUILD_TIME_LENGTH         = 8;
00300 const static size_t GIT_SHORT_REVISION_LENGTH = 7;
00301 
00302 const static size_t MAX_NAME_LENGTH                     = 16;
00303 const static size_t MAX_MODE_ACTIVATION_CONDITION_COUNT = 20;
00304 
00305 const static size_t LED_CONFIGURABLE_COLOR_COUNT = 16;
00306 const static size_t LED_MAX_STRIP_LENGTH         = 32;
00307 
00308 const static size_t MAX_ADJUSTMENT_RANGE_COUNT        = 12;
00309 const static size_t MAX_SIMULTANEOUS_ADJUSTMENT_COUNT = 6;
00310 
00311 const static size_t OSD_ITEM_COUNT = 41;  // manual count from iNav io/osd.h
00312 
00313 const static size_t MAX_MAPPABLE_RX_INPUTS = 4;  // unique to REVO?
00314 
00315 const static size_t LED_MODE_COUNT          = 6;
00316 const static size_t LED_DIRECTION_COUNT     = 6;
00317 const static size_t LED_SPECIAL_COLOR_COUNT = 11;
00318 
00319 enum class MultiType : uint8_t {
00320     TRI = 1,
00321     QUADP,          // 2
00322     QUADX,          // 3
00323     BI,             // 4
00324     GIMBAL,         // 5
00325     Y6,             // 6
00326     HEX6,           // 7
00327     FLYING_WING,    // 8
00328     Y4,             // 9
00329     HEX6X,          // 10
00330     OCTOX8,         // 11
00331     OCTOFLATP,      // 12
00332     OCTOFLATX,      // 13
00333     AIRPLANE,       // 14
00334     HELI_120_CCPM,  // 15
00335     HELI_90_DEG,    // 16
00336     VTAIL4,         // 17
00337     HEX6H,          // 18
00338     DUALCOPTER = 20,
00339     SINGLECOPTER,  // 21
00340 };
00341 
00342 enum class Capability { BIND, DYNBAL, FLAP, NAVCAP, EXTAUX };
00343 
00344 enum class Sensor {
00345     Accelerometer,
00346     Barometer,
00347     Magnetometer,
00348     GPS,
00349     Sonar,
00350     OpticalFlow,
00351     Pitot,
00352     GeneralHealth
00353 };
00354 
00355 const static size_t NAUX = 4;
00356 
00357 enum class SwitchPosition : size_t {
00358     LOW  = 0,
00359     MID  = 1,
00360     HIGH = 2,
00361 };
00362 
00363 static const std::vector<std::string> FEATURES = {"RX_PPM",
00364                                                   "VBAT",
00365                                                   "INFLIGHT_ACC_CAL",
00366                                                   "RX_SERIAL",
00367                                                   "MOTOR_STOP",
00368                                                   "SERVO_TILT",
00369                                                   "SOFTSERIAL",
00370                                                   "GPS",
00371                                                   "FAILSAFE",
00372                                                   "SONAR",
00373                                                   "TELEMETRY",
00374                                                   "AMPERAGE_METER",
00375                                                   "3D",
00376                                                   "RX_PARALLEL_PWM",
00377                                                   "RX_MSP",
00378                                                   "RSSI_ADC",
00379                                                   "LED_STRIP",
00380                                                   "DISPLAY",
00381                                                   "ONESHOT125",
00382                                                   "BLACKBOX",
00383                                                   "CHANNEL_FORWARDING",
00384                                                   "TRANSPONDER",
00385                                                   "OSD"};
00386 
00387 enum class PID_Element : uint8_t {
00388     PID_ROLL = 0,
00389     PID_PITCH,
00390     PID_YAW,
00391     PID_POS_Z,
00392     PID_POS_XY,
00393     PID_VEL_XY,
00394     PID_SURFACE,
00395     PID_LEVEL,
00396     PID_HEADING,
00397     PID_VEL_Z,
00398     PID_ITEM_COUNT
00399 };
00400 
00403 
00404 // MSP_API_VERSION: 1
00405 struct ApiVersion : public Message {
00406     ApiVersion(FirmwareVariant v) : Message(v) {}
00407 
00408     virtual ID id() const override { return ID::MSP_API_VERSION; }
00409 
00410     Value<uint8_t> protocol;
00411     Value<uint8_t> major;
00412     Value<uint8_t> minor;
00413 
00414     virtual bool decode(const ByteVector& data) override {
00415         bool rc = true;
00416         rc &= data.unpack(protocol);
00417         rc &= data.unpack(major);
00418         rc &= data.unpack(minor);
00419         return rc;
00420     }
00421 
00422     virtual std::ostream& print(std::ostream& s) const override {
00423         s << "#Api Version:" << std::endl;
00424         s << " API: " << major << "." << minor << std::endl;
00425         s << " Protocol: " << protocol << std::endl;
00426         return s;
00427     }
00428 };
00429 
00430 // MSP_FC_VARIANT: 2
00431 struct FcVariant : public Message {
00432     FcVariant(FirmwareVariant v) : Message(v) {}
00433 
00434     virtual ID id() const override { return ID::MSP_FC_VARIANT; }
00435 
00436     Value<std::string> identifier;
00437 
00438     virtual bool decode(const ByteVector& data) override {
00439         return data.unpack(identifier, data.size());
00440     }
00441 
00442     virtual std::ostream& print(std::ostream& s) const override {
00443         s << "#FC variant:" << std::endl;
00444         s << " Identifier: " << identifier << std::endl;
00445         return s;
00446     }
00447 };
00448 
00449 // MSP_FC_VERSION: 3
00450 struct FcVersion : public Message {
00451     FcVersion(FirmwareVariant v) : Message(v) {}
00452 
00453     virtual ID id() const override { return ID::MSP_FC_VERSION; }
00454 
00455     Value<uint8_t> major;
00456     Value<uint8_t> minor;
00457     Value<uint8_t> patch_level;
00458 
00459     virtual bool decode(const ByteVector& data) override {
00460         bool rc = true;
00461         rc &= data.unpack(major);
00462         rc &= data.unpack(minor);
00463         rc &= data.unpack(patch_level);
00464         return rc;
00465     }
00466 
00467     virtual std::ostream& print(std::ostream& s) const override {
00468         s << "#FC version:" << std::endl;
00469         s << " Version: " << major << "." << minor << "." << patch_level
00470           << std::endl;
00471         return s;
00472     }
00473 };
00474 
00475 // MSP_BOARD_INFO: 4
00476 struct BoardInfo : public Message {
00477     BoardInfo(FirmwareVariant v) : Message(v) {}
00478 
00479     virtual ID id() const override { return ID::MSP_BOARD_INFO; }
00480 
00481     Value<std::string> identifier;
00482     Value<uint16_t> version;
00483     Value<uint8_t> osd_support;
00484     Value<uint8_t> comms_capabilites;
00485     Value<std::string> name;
00486 
00487     virtual bool decode(const ByteVector& data) override {
00488         bool rc = true;
00489         rc &= data.unpack(identifier, BOARD_IDENTIFIER_LENGTH);
00490         rc &= data.unpack(version);
00491         rc &= data.unpack(osd_support);
00492         rc &= data.unpack(comms_capabilites);
00493         uint8_t name_len = 0;
00494         rc &= data.unpack(name_len);
00495         rc &= data.unpack(name, name_len);
00496         return rc;
00497     }
00498 
00499     virtual std::ostream& print(std::ostream& s) const override {
00500         s << "#Board Info:" << std::endl;
00501         s << " Identifier: " << identifier << std::endl;
00502         s << " Version: " << version << std::endl;
00503         s << " OSD support: " << osd_support << std::endl;
00504         s << " Comms bitmask: " << comms_capabilites << std::endl;
00505         s << " Board Name: " << name << std::endl;
00506         return s;
00507     }
00508 };
00509 
00510 // MSP_BUILD_INFO: 5
00511 struct BuildInfo : public Message {
00512     BuildInfo(FirmwareVariant v) : Message(v) {}
00513 
00514     virtual ID id() const override { return ID::MSP_BUILD_INFO; }
00515 
00516     Value<std::string> buildDate;
00517     Value<std::string> buildTime;
00518     Value<std::string> shortGitRevision;
00519 
00520     virtual bool decode(const ByteVector& data) override {
00521         bool rc = true;
00522         rc &= data.unpack(buildDate, BUILD_DATE_LENGTH);
00523         rc &= data.unpack(buildTime, BUILD_TIME_LENGTH);
00524         rc &= data.unpack(shortGitRevision, GIT_SHORT_REVISION_LENGTH);
00525         return rc;
00526     }
00527 
00528     virtual std::ostream& print(std::ostream& s) const override {
00529         s << "#Build Info:" << std::endl;
00530         s << " Date: " << buildDate << std::endl;
00531         s << " Time: " << buildTime << std::endl;
00532         s << " Git revision: " << shortGitRevision << std::endl;
00533         return s;
00534     }
00535 };
00536 
00537 struct InavPidSettings {
00538     Value<uint8_t> async_mode;
00539     Value<uint16_t> acc_task_frequency;
00540     Value<uint16_t> attitude_task_frequency;
00541     Value<uint8_t> heading_hold_rate_limit;
00542     Value<uint8_t> heading_hold_error_lpf_freq;
00543     Value<uint16_t> yaw_jump_prevention_limit;
00544     Value<uint8_t> gyro_lpf;
00545     Value<uint8_t> acc_soft_lpf_hz;
00546 };
00547 
00548 // MSP_INAV_PID: 6
00549 struct InavPid : public InavPidSettings, public Message {
00550     InavPid(FirmwareVariant v) : Message(v) {}
00551 
00552     virtual ID id() const override { return ID::MSP_INAV_PID; }
00553 
00554     virtual bool decode(const ByteVector& data) override {
00555         bool rc = true;
00556         rc &= data.unpack(async_mode);
00557         rc &= data.unpack(acc_task_frequency);
00558         rc &= data.unpack(attitude_task_frequency);
00559         rc &= data.unpack(heading_hold_rate_limit);
00560         rc &= data.unpack(heading_hold_error_lpf_freq);
00561         rc &= data.unpack(yaw_jump_prevention_limit);
00562         rc &= data.unpack(gyro_lpf);
00563         rc &= data.unpack(acc_soft_lpf_hz);
00564         // read the reserved bytes
00565         rc &= data.consume(4);
00566         return rc;
00567     }
00568 };
00569 
00570 // MSP_SET_INAV_PID: 7
00571 struct SetInavPid : public InavPidSettings, public Message {
00572     SetInavPid(FirmwareVariant v) : Message(v) {}
00573 
00574     virtual ID id() const override { return ID::MSP_SET_INAV_PID; }
00575 
00576     virtual ByteVectorUptr encode() const override {
00577         ByteVectorUptr data = std::make_unique<ByteVector>();
00578         bool rc             = true;
00579         rc &= data->pack(async_mode);
00580         rc &= data->pack(acc_task_frequency);
00581         rc &= data->pack(attitude_task_frequency);
00582         rc &= data->pack(heading_hold_rate_limit);
00583         rc &= data->pack(heading_hold_error_lpf_freq);
00584         rc &= data->pack(yaw_jump_prevention_limit);
00585         rc &= data->pack(gyro_lpf);
00586         rc &= data->pack(acc_soft_lpf_hz);
00587         // write the reserved bytes
00588         rc &= data->pack(uint32_t(0));
00589         if(!rc) data.reset();
00590         return data;
00591     }
00592 };
00593 
00594 // MSP_NAME: 10
00595 struct BoardName : public Message {
00596     BoardName(FirmwareVariant v) : Message(v) {}
00597 
00598     virtual ID id() const override { return ID::MSP_NAME; }
00599 
00600     Value<std::string> name;
00601 
00602     virtual bool decode(const ByteVector& data) override {
00603         return data.unpack(name);
00604     }
00605 };
00606 
00607 // MSP_SET_NAME: 11
00608 struct SetBoardName : public Message {
00609     SetBoardName(FirmwareVariant v) : Message(v) {}
00610 
00611     virtual ID id() const override { return ID::MSP_SET_NAME; }
00612 
00613     Value<std::string> name;
00614 
00615     virtual ByteVectorUptr encode() const override {
00616         ByteVectorUptr data = std::make_unique<ByteVector>();
00617         if(!data->pack(name, MAX_NAME_LENGTH)) data.reset();
00618         return data;
00619     }
00620 };
00621 
00622 struct NavPosHoldSettings {
00623     Value<uint8_t> user_control_mode;
00624     Value<uint16_t> max_auto_speed;
00625     Value<uint16_t> max_auto_climb_rate;
00626     Value<uint16_t> max_manual_speed;
00627     Value<uint16_t> max_manual_climb_rate;
00628     Value<uint8_t> max_bank_angle;
00629     Value<uint8_t> use_thr_mid_for_althold;
00630     Value<uint16_t> hover_throttle;
00631 };
00632 
00633 // MSP_NAV_POSHOLD: 12
00634 struct NavPosHold : public NavPosHoldSettings, public Message {
00635     NavPosHold(FirmwareVariant v) : Message(v) {}
00636 
00637     virtual ID id() const override { return ID::MSP_NAV_POSHOLD; }
00638 
00639     virtual bool decode(const ByteVector& data) override {
00640         bool rc = true;
00641         rc &= data.unpack(user_control_mode);
00642         rc &= data.unpack(max_auto_speed);
00643         rc &= data.unpack(max_auto_climb_rate);
00644         rc &= data.unpack(max_manual_speed);
00645         rc &= data.unpack(max_manual_climb_rate);
00646         rc &= data.unpack(max_bank_angle);
00647         rc &= data.unpack(use_thr_mid_for_althold);
00648         rc &= data.unpack(hover_throttle);
00649         return rc;
00650     }
00651 };
00652 
00653 // MSP_SET_NAV_POSHOLD: 13
00654 struct SetNavPosHold : public NavPosHoldSettings, public Message {
00655     SetNavPosHold(FirmwareVariant v) : Message(v) {}
00656 
00657     virtual ID id() const override { return ID::MSP_SET_NAV_POSHOLD; }
00658 
00659     virtual ByteVectorUptr encode() const override {
00660         ByteVectorUptr data = std::make_unique<ByteVector>();
00661         bool rc             = true;
00662         rc &= data->pack(user_control_mode);
00663         rc &= data->pack(max_auto_speed);
00664         rc &= data->pack(max_auto_climb_rate);
00665         rc &= data->pack(max_manual_speed);
00666         rc &= data->pack(max_manual_climb_rate);
00667         rc &= data->pack(max_bank_angle);
00668         rc &= data->pack(use_thr_mid_for_althold);
00669         rc &= data->pack(hover_throttle);
00670         if(!rc) data.reset();
00671         return data;
00672     }
00673 };
00674 
00675 struct CalibrationDataSettings {
00676     Value<uint16_t> acc_zero_x;
00677     Value<uint16_t> acc_zero_y;
00678     Value<uint16_t> acc_zero_z;
00679     Value<uint16_t> acc_gain_x;
00680     Value<uint16_t> acc_gain_y;
00681     Value<uint16_t> acc_gain_z;
00682 };
00683 
00684 // MSP_CALIBRATION_DATA: 14
00685 struct CalibrationData : public CalibrationDataSettings, public Message {
00686     CalibrationData(FirmwareVariant v) : Message(v) {}
00687 
00688     virtual ID id() const override { return ID::MSP_CALIBRATION_DATA; }
00689 
00690     Value<uint8_t> axis_calibration_flags;
00691 
00692     virtual bool decode(const ByteVector& data) override {
00693         bool rc = true;
00694         rc &= data.unpack(axis_calibration_flags);
00695         rc &= data.unpack(acc_zero_x);
00696         rc &= data.unpack(acc_zero_y);
00697         rc &= data.unpack(acc_zero_z);
00698         rc &= data.unpack(acc_gain_x);
00699         rc &= data.unpack(acc_gain_y);
00700         rc &= data.unpack(acc_gain_z);
00701         return rc;
00702     }
00703 };
00704 
00705 // MSP_SET_CALIBRATION_DATA: 15
00706 struct SetCalibrationData : public CalibrationDataSettings, public Message {
00707     SetCalibrationData(FirmwareVariant v) : Message(v) {}
00708 
00709     virtual ID id() const override { return ID::MSP_SET_CALIBRATION_DATA; }
00710 
00711     virtual ByteVectorUptr encode() const override {
00712         ByteVectorUptr data = std::make_unique<ByteVector>();
00713         bool rc             = true;
00714         rc &= data->pack(acc_zero_x);
00715         rc &= data->pack(acc_zero_y);
00716         rc &= data->pack(acc_zero_z);
00717         rc &= data->pack(acc_gain_x);
00718         rc &= data->pack(acc_gain_y);
00719         rc &= data->pack(acc_gain_z);
00720         if(!rc) data.reset();
00721         return data;
00722     }
00723 };
00724 
00725 struct PositionEstimationConfigSettings {
00726     Value<float> w_z_baro_p;
00727     Value<float> w_z_gps_p;
00728     Value<float> w_z_gps_v;
00729     Value<float> w_xy_gps_p;
00730     Value<float> w_xy_gps_v;
00731     Value<uint8_t> gps_min_sats;
00732     Value<bool> use_gps_vel_NED;
00733 };
00734 
00735 // MSP_POSITION_ESTIMATION_CONFIG: 16
00736 struct PositionEstimationConfig : public PositionEstimationConfigSettings,
00737                                   public Message {
00738     PositionEstimationConfig(FirmwareVariant v) : Message(v) {}
00739 
00740     virtual ID id() const override {
00741         return ID::MSP_POSITION_ESTIMATION_CONFIG;
00742     }
00743 
00744     virtual bool decode(const ByteVector& data) override {
00745         bool rc = true;
00746         rc &= data.unpack<uint16_t>(w_z_baro_p, 0.01);
00747         rc &= data.unpack<uint16_t>(w_z_gps_p, 0.01);
00748         rc &= data.unpack<uint16_t>(w_z_gps_v, 0.01);
00749         rc &= data.unpack<uint16_t>(w_xy_gps_p, 0.01);
00750         rc &= data.unpack<uint16_t>(w_xy_gps_v, 0.01);
00751         rc &= data.unpack(gps_min_sats);
00752         rc &= data.unpack(use_gps_vel_NED);
00753         return rc;
00754     }
00755 };
00756 
00757 // MSP_SET_POSITION_ESTIMATION_CONFIG: 17
00758 struct SetPositionEstimationConfig : public PositionEstimationConfigSettings,
00759                                      public Message {
00760     SetPositionEstimationConfig(FirmwareVariant v) : Message(v) {}
00761 
00762     virtual ID id() const override {
00763         return ID::MSP_SET_POSITION_ESTIMATION_CONFIG;
00764     }
00765 
00766     virtual ByteVectorUptr encode() const override {
00767         ByteVectorUptr data = std::make_unique<ByteVector>();
00768         bool rc             = true;
00769         rc &= data->pack(static_cast<uint16_t>(w_z_baro_p() * 100));
00770         rc &= data->pack(static_cast<uint16_t>(w_z_gps_p() * 100));
00771         rc &= data->pack(static_cast<uint16_t>(w_z_gps_v() * 100));
00772         rc &= data->pack(static_cast<uint16_t>(w_xy_gps_p() * 100));
00773         rc &= data->pack(static_cast<uint16_t>(w_xy_gps_v() * 100));
00774         rc &= data->pack(gps_min_sats);
00775         rc &= data->pack(use_gps_vel_NED);
00776         if(!rc) data.reset();
00777         return data;
00778     }
00779 };
00780 
00781 // MSP_WP_MISSION_LOAD: 18
00782 struct WpMissionLoad : public Message {
00783     WpMissionLoad(FirmwareVariant v) : Message(v) {}
00784 
00785     virtual ID id() const override { return ID::MSP_WP_MISSION_LOAD; }
00786 
00787     virtual ByteVectorUptr encode() const override {
00788         ByteVectorUptr data = std::make_unique<ByteVector>();
00789         if(!data->pack(uint8_t(0))) data.reset();
00790         return data;
00791     }
00792 };
00793 
00794 // MSP_WP_MISSION_SAVE: 19
00795 struct WpMissionSave : public Message {
00796     WpMissionSave(FirmwareVariant v) : Message(v) {}
00797 
00798     virtual ID id() const override { return ID::MSP_WP_MISSION_SAVE; }
00799 
00800     virtual ByteVectorUptr encode() const override {
00801         ByteVectorUptr data = std::make_unique<ByteVector>();
00802         if(!data->pack(uint8_t(0))) data.reset();
00803         return data;
00804     }
00805 };
00806 
00807 // MSP_WP_GETINFO: 20
00808 struct WpGetInfo : public Message {
00809     WpGetInfo(FirmwareVariant v) : Message(v) {}
00810 
00811     virtual ID id() const override { return ID::MSP_WP_GETINFO; }
00812 
00813     Value<uint8_t> wp_capabilites;
00814     Value<uint8_t> max_waypoints;
00815     Value<bool> wp_list_valid;
00816     Value<uint8_t> wp_count;
00817 
00818     virtual bool decode(const ByteVector& data) override {
00819         bool rc = true;
00820         rc &= data.unpack(wp_capabilites);
00821         rc &= data.unpack(max_waypoints);
00822         rc &= data.unpack(wp_list_valid);
00823         rc &= data.unpack(wp_count);
00824         return rc;
00825     }
00826 };
00827 
00828 struct RthAndLandConfigSettings {
00829     Value<uint16_t> min_rth_distance;
00830     Value<uint8_t> rth_climb_first;
00831     Value<uint8_t> rth_climb_ignore_emerg;
00832     Value<uint8_t> rth_tail_first;
00833     Value<uint8_t> rth_allow_landing;
00834     Value<uint8_t> rth_alt_control_mode;
00835     Value<uint16_t> rth_abort_threshold;
00836     Value<uint16_t> rth_altitude;
00837     Value<uint16_t> land_descent_rate;
00838     Value<uint16_t> land_slowdown_minalt;
00839     Value<uint16_t> land_slowdown_maxalt;
00840     Value<uint16_t> emerg_descent_rate;
00841 };
00842 
00843 // MSP_RTH_AND_LAND_CONFIG: 21
00844 struct RthAndLandConfig : public RthAndLandConfigSettings, public Message {
00845     RthAndLandConfig(FirmwareVariant v) : Message(v) {}
00846 
00847     virtual ID id() const override { return ID::MSP_RTH_AND_LAND_CONFIG; }
00848 
00849     virtual bool decode(const ByteVector& data) override {
00850         bool rc = true;
00851         rc &= data.unpack(min_rth_distance);
00852         rc &= data.unpack(rth_climb_first);
00853         rc &= data.unpack(rth_climb_ignore_emerg);
00854         rc &= data.unpack(rth_tail_first);
00855         rc &= data.unpack(rth_allow_landing);
00856         rc &= data.unpack(rth_alt_control_mode);
00857         rc &= data.unpack(rth_abort_threshold);
00858         rc &= data.unpack(rth_altitude);
00859         rc &= data.unpack(land_descent_rate);
00860         rc &= data.unpack(land_slowdown_minalt);
00861         rc &= data.unpack(land_slowdown_maxalt);
00862         rc &= data.unpack(emerg_descent_rate);
00863         return rc;
00864     }
00865 };
00866 
00867 // MSP_SET_RTH_AND_LAND_CONFIG: 22
00868 struct SetRthAndLandConfig : public RthAndLandConfigSettings, public Message {
00869     SetRthAndLandConfig(FirmwareVariant v) : Message(v) {}
00870 
00871     virtual ID id() const override { return ID::MSP_SET_RTH_AND_LAND_CONFIG; }
00872 
00873     virtual ByteVectorUptr encode() const override {
00874         ByteVectorUptr data = std::make_unique<ByteVector>();
00875         bool rc             = true;
00876         rc &= data->pack(min_rth_distance);
00877         rc &= data->pack(rth_climb_first);
00878         rc &= data->pack(rth_climb_ignore_emerg);
00879         rc &= data->pack(rth_tail_first);
00880         rc &= data->pack(rth_allow_landing);
00881         rc &= data->pack(rth_alt_control_mode);
00882         rc &= data->pack(rth_abort_threshold);
00883         rc &= data->pack(rth_altitude);
00884         rc &= data->pack(land_descent_rate);
00885         rc &= data->pack(land_slowdown_minalt);
00886         rc &= data->pack(land_slowdown_maxalt);
00887         rc &= data->pack(emerg_descent_rate);
00888         if(!rc) data.reset();
00889         return data;
00890     }
00891 };
00892 
00893 struct FwConfigSettings {
00894     Value<uint16_t> cruise_throttle;
00895     Value<uint16_t> min_throttle;
00896     Value<uint16_t> max_throttle;
00897     Value<uint8_t> max_bank_angle;
00898     Value<uint8_t> max_climb_angle;
00899     Value<uint8_t> max_dive_angle;
00900     Value<uint8_t> pitch_to_throttle;
00901     Value<uint16_t> loiter_radius;
00902 };
00903 
00904 // MSP_FW_CONFIG: 23
00905 struct FwConfig : public FwConfigSettings, public Message {
00906     FwConfig(FirmwareVariant v) : Message(v) {}
00907 
00908     virtual ID id() const override { return ID::MSP_FW_CONFIG; }
00909 
00910     virtual bool decode(const ByteVector& data) override {
00911         bool rc = true;
00912         rc &= data.unpack(cruise_throttle);
00913         rc &= data.unpack(min_throttle);
00914         rc &= data.unpack(max_throttle);
00915         rc &= data.unpack(max_bank_angle);
00916         rc &= data.unpack(max_climb_angle);
00917         rc &= data.unpack(max_dive_angle);
00918         rc &= data.unpack(pitch_to_throttle);
00919         rc &= data.unpack(loiter_radius);
00920         return rc;
00921     }
00922 };
00923 
00924 // MSP_SET_FW_CONFIG: 24
00925 struct SetFwConfig : public FwConfigSettings, public Message {
00926     SetFwConfig(FirmwareVariant v) : Message(v) {}
00927 
00928     virtual ID id() const override { return ID::MSP_SET_FW_CONFIG; }
00929 
00930     virtual ByteVectorUptr encode() const override {
00931         ByteVectorUptr data = std::make_unique<ByteVector>();
00932         bool rc             = true;
00933         rc &= data->pack(cruise_throttle);
00934         rc &= data->pack(min_throttle);
00935         rc &= data->pack(max_throttle);
00936         rc &= data->pack(max_bank_angle);
00937         rc &= data->pack(max_climb_angle);
00938         rc &= data->pack(max_dive_angle);
00939         rc &= data->pack(pitch_to_throttle);
00940         rc &= data->pack(loiter_radius);
00941         if(!rc) data.reset();
00942         return data;
00943     }
00944 };
00945 
00946 struct BatteryConfigSettings {
00947     Value<uint8_t> vbatmincellvoltage;
00948     Value<uint8_t> vbatmaxcellvoltage;
00949     Value<uint8_t> vbatwarningcellvoltage;
00950     Value<uint16_t> batteryCapacity;
00951     Value<uint8_t> voltageMeterSource;
00952     Value<uint8_t> currentMeterSource;
00953 };
00954 
00955 // MSP_BATTERY_CONFIG: 32
00956 struct BatteryConfig : public BatteryConfigSettings, public Message {
00957     BatteryConfig(FirmwareVariant v) : Message(v) {}
00958 
00959     virtual ID id() const override { return ID::MSP_BATTERY_CONFIG; }
00960 
00961     virtual bool decode(const ByteVector& data) override {
00962         bool rc = true;
00963         rc &= data.unpack(vbatmincellvoltage);
00964         rc &= data.unpack(vbatmaxcellvoltage);
00965         rc &= data.unpack(vbatwarningcellvoltage);
00966         rc &= data.unpack(batteryCapacity);
00967         rc &= data.unpack(voltageMeterSource);
00968         rc &= data.unpack(currentMeterSource);
00969         return rc;
00970     }
00971 };
00972 
00973 // MSP_SET_BATTERY_CONFIG: 33
00974 struct SetBatteryConfig : public BatteryConfigSettings, public Message {
00975     SetBatteryConfig(FirmwareVariant v) : Message(v) {}
00976 
00977     virtual ID id() const override { return ID::MSP_SET_BATTERY_CONFIG; }
00978 
00979     virtual ByteVectorUptr encode() const override {
00980         ByteVectorUptr data = std::make_unique<ByteVector>();
00981         bool rc             = true;
00982         rc &= data->pack(vbatmincellvoltage);
00983         rc &= data->pack(vbatmaxcellvoltage);
00984         rc &= data->pack(vbatwarningcellvoltage);
00985         rc &= data->pack(batteryCapacity);
00986         rc &= data->pack(voltageMeterSource);
00987         rc &= data->pack(currentMeterSource);
00988         if(!rc) data.reset();
00989         return data;
00990     }
00991 };
00992 
00993 struct box_description {
00994     Value<uint8_t> id;
00995     Value<uint8_t> aux_channel_index;
00996     Value<uint8_t> startStep;
00997     Value<uint8_t> endStep;
00998 };
00999 
01000 // MSP_MODE_RANGES: 34
01001 struct ModeRanges : public Message {
01002     ModeRanges(FirmwareVariant v) : Message(v) {}
01003 
01004     virtual ID id() const override { return ID::MSP_MODE_RANGES; }
01005 
01006     std::array<box_description, MAX_MODE_ACTIVATION_CONDITION_COUNT> boxes;
01007 
01008     virtual bool decode(const ByteVector& data) override {
01009         bool rc = true;
01010         for(size_t i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) {
01011             rc &= data.unpack(boxes[i].id);
01012             rc &= data.unpack(boxes[i].aux_channel_index);
01013             rc &= data.unpack(boxes[i].startStep);
01014             rc &= data.unpack(boxes[i].endStep);
01015         }
01016         return rc;
01017     }
01018 };
01019 
01020 // MSP_SET_MODE_RANGE: 35
01021 struct SetModeRange : public Message {
01022     SetModeRange(FirmwareVariant v) : Message(v) {}
01023 
01024     virtual ID id() const override { return ID::MSP_SET_MODE_RANGE; }
01025 
01026     Value<uint8_t> mode_activation_condition_idx;
01027     box_description box;
01028 
01029     virtual ByteVectorUptr encode() const override {
01030         ByteVectorUptr data = std::make_unique<ByteVector>();
01031         bool rc             = true;
01032         rc &= data->pack(mode_activation_condition_idx);
01033         rc &= data->pack(box.id);
01034         rc &= data->pack(box.aux_channel_index);
01035         rc &= data->pack(box.startStep);
01036         rc &= data->pack(box.endStep);
01037         if(!rc) data.reset();
01038         return data;
01039     }
01040 };
01041 
01042 // MSP_FEATURE: 36
01043 struct Feature : public Message {
01044     Feature(FirmwareVariant v) : Message(v) {}
01045 
01046     virtual ID id() const override { return ID::MSP_FEATURE; }
01047 
01048     std::set<std::string> features;
01049 
01050     virtual bool decode(const ByteVector& data) override {
01051         uint32_t mask;
01052         bool rc = data.unpack(mask);
01053         if(!rc) return rc;
01054         features.clear();
01055         for(size_t ifeat(0); ifeat < FEATURES.size(); ifeat++) {
01056             if(mask & (1 << ifeat)) features.insert(FEATURES[ifeat]);
01057         }
01058         return rc;
01059     }
01060 
01061     virtual std::ostream& print(std::ostream& s) const override {
01062         s << "#Features:" << std::endl;
01063         for(const std::string& f : features) {
01064             s << f << std::endl;
01065         }
01066         return s;
01067     }
01068 };
01069 
01070 // MSP_SET_FEATURE: 37
01071 struct SetFeature : public Message {
01072     SetFeature(FirmwareVariant v) : Message(v) {}
01073 
01074     virtual ID id() const override { return ID::MSP_SET_FEATURE; }
01075 
01076     std::set<std::string> features;
01077 
01078     virtual ByteVectorUptr encode() const override {
01079         ByteVectorUptr data = std::make_unique<ByteVector>();
01080         uint32_t mask       = 0;
01081         for(size_t ifeat(0); ifeat < FEATURES.size(); ifeat++) {
01082             if(features.count(FEATURES[ifeat])) mask |= 1 << ifeat;
01083         }
01084         if(!data->pack(mask)) data.reset();
01085         return data;
01086     }
01087 };
01088 
01089 // iNav uses decidegrees, BF/CF use degrees
01090 struct BoardAlignmentSettings {
01091     Value<uint16_t> roll;
01092     Value<uint16_t> pitch;
01093     Value<uint16_t> yaw;
01094 };
01095 
01096 // MSP_BOARD_ALIGNMENT: 38
01097 struct BoardAlignment : public BoardAlignmentSettings, public Message {
01098     BoardAlignment(FirmwareVariant v) : Message(v) {}
01099 
01100     virtual ID id() const override { return ID::MSP_BOARD_ALIGNMENT; }
01101 
01102     virtual bool decode(const ByteVector& data) override {
01103         bool rc = true;
01104         rc &= data.unpack(roll);
01105         rc &= data.unpack(pitch);
01106         rc &= data.unpack(yaw);
01107         return rc;
01108     }
01109 };
01110 
01111 // MSP_SET_BOARD_ALIGNMENT: 39
01112 struct SetBoardAlignment : public BoardAlignmentSettings, public Message {
01113     SetBoardAlignment(FirmwareVariant v) : Message(v) {}
01114 
01115     virtual ID id() const override { return ID::MSP_BOARD_ALIGNMENT; }
01116 
01117     virtual ByteVectorUptr encode() const override {
01118         ByteVectorUptr data = std::make_unique<ByteVector>();
01119         bool rc             = true;
01120         rc &= data->pack(roll);
01121         rc &= data->pack(pitch);
01122         rc &= data->pack(yaw);
01123         if(!rc) data.reset();
01124         return data;
01125     }
01126 };
01127 
01128 struct CurrentMeterConfigSettings {
01129     Value<uint16_t> currnet_scale;
01130     Value<uint16_t> current_offset;
01131     Value<uint8_t> current_type;
01132     Value<uint16_t> capacity;
01133 };
01134 
01135 // MSP_CURRENT_METER_CONFIG: 40 (differs from Cleanflight/BetaFlight)
01136 struct CurrentMeterConfig : public CurrentMeterConfigSettings, public Message {
01137     CurrentMeterConfig(FirmwareVariant v) : Message(v) {}
01138 
01139     virtual ID id() const override { return ID::MSP_CURRENT_METER_CONFIG; }
01140 
01141     virtual bool decode(const ByteVector& data) override {
01142         bool rc = true;
01143         rc &= data.unpack(currnet_scale);
01144         rc &= data.unpack(current_offset);
01145         rc &= data.unpack(current_type);
01146         rc &= data.unpack(capacity);
01147         return rc;
01148     }
01149 };
01150 
01151 // MSP_SET_CURRENT_METER_CONFIG: 41 (differs from Cleanflight/BetaFlight)
01152 struct SetCurrentMeterConfig : public CurrentMeterConfigSettings,
01153                                public Message {
01154     SetCurrentMeterConfig(FirmwareVariant v) : Message(v) {}
01155 
01156     virtual ID id() const override { return ID::MSP_SET_CURRENT_METER_CONFIG; }
01157 
01158     virtual ByteVectorUptr encode() const override {
01159         ByteVectorUptr data = std::make_unique<ByteVector>();
01160         bool rc             = true;
01161         rc &= data->pack(currnet_scale);
01162         rc &= data->pack(current_offset);
01163         rc &= data->pack(current_type);
01164         rc &= data->pack(capacity);
01165         if(!rc) data.reset();
01166         return data;
01167     }
01168 };
01169 
01170 // MSP_MIXER: 42
01171 struct Mixer : public Message {
01172     Mixer(FirmwareVariant v) : Message(v) {}
01173 
01174     virtual ID id() const override { return ID::MSP_MIXER; }
01175 
01176     Value<uint8_t> mode;
01177 
01178     virtual bool decode(const ByteVector& data) override {
01179         return data.unpack(mode);
01180     }
01181 };
01182 
01183 // MSP_SET_MIXER: 43
01184 struct SetMixer : public Message {
01185     SetMixer(FirmwareVariant v) : Message(v) {}
01186 
01187     virtual ID id() const override { return ID::MSP_SET_MIXER; }
01188 
01189     Value<uint8_t> mode;
01190 
01191     virtual ByteVectorUptr encode() const override {
01192         ByteVectorUptr data = std::make_unique<ByteVector>();
01193         if(!data->pack(mode)) data.reset();
01194         return data;
01195     }
01196 };
01197 
01198 struct RxConfigSettings {
01199     size_t valid_data_groups;
01200     // group1
01201     Value<uint8_t> serialrx_provider;
01202     Value<uint16_t> maxcheck;
01203     Value<uint16_t> midrc;
01204     Value<uint16_t> mincheck;
01205     Value<uint8_t> spektrum_sat_bind;
01206     // group 2
01207     Value<uint16_t> rx_min_usec;
01208     Value<uint16_t> rx_max_usec;
01209     // group 3
01210     Value<uint8_t> rcInterpolation;
01211     Value<uint8_t> rcInterpolationInterval;
01212     Value<uint16_t> airModeActivateThreshold;
01213     // group 4
01214     Value<uint8_t> rx_spi_protocol;
01215     Value<uint32_t> rx_spi_id;
01216     Value<uint8_t> rx_spi_rf_channel_count;
01217     // group 5
01218     Value<uint8_t> fpvCamAngleDegrees;
01219     // group 6 - iNav only
01220     Value<uint8_t> receiverType;
01221 
01222     std::ostream& rxConfigPrint(std::ostream& s) const {
01223         s << "#RX configuration:" << std::endl;
01224         s << " serialrx_provider: " << serialrx_provider << std::endl;
01225         s << " maxcheck: " << maxcheck << std::endl;
01226         s << " midrc: " << midrc << std::endl;
01227         s << " mincheck: " << mincheck << std::endl;
01228         s << " spektrum_sat_bind: " << spektrum_sat_bind << std::endl;
01229         s << " rx_min_usec: " << rx_min_usec << std::endl;
01230         s << " rx_max_usec: " << rx_max_usec << std::endl;
01231         s << " rcInterpolation: " << rcInterpolation << std::endl;
01232         s << " rcInterpolationInterval: " << rcInterpolationInterval
01233           << std::endl;
01234         s << " airModeActivateThreshold: " << airModeActivateThreshold
01235           << std::endl;
01236         s << " rx_spi_protocol: " << rx_spi_protocol << std::endl;
01237         s << " rx_spi_id: " << rx_spi_id << std::endl;
01238         s << " rx_spi_rf_channel_count: " << rx_spi_rf_channel_count
01239           << std::endl;
01240         s << " fpvCamAngleDegrees: " << fpvCamAngleDegrees << std::endl;
01241         s << " receiverType: " << receiverType << std::endl;
01242         return s;
01243     }
01244 };
01245 
01246 // MSP_RX_CONFIG: 44
01247 struct RxConfig : public RxConfigSettings, public Message {
01248     RxConfig(FirmwareVariant v) : Message(v) {}
01249 
01250     virtual ID id() const override { return ID::MSP_RX_CONFIG; }
01251 
01252     virtual bool decode(const ByteVector& data) override {
01253         bool rc           = true;
01254         valid_data_groups = 1;
01255         rc &= data.unpack(serialrx_provider);
01256         rc &= data.unpack(maxcheck);
01257         rc &= data.unpack(midrc);
01258         rc &= data.unpack(mincheck);
01259         rc &= data.unpack(spektrum_sat_bind);
01260         if(data.unpacking_remaining() == 0) return rc;
01261 
01262         valid_data_groups += 1;
01263         rc &= data.unpack(rx_min_usec);
01264         rc &= data.unpack(rx_max_usec);
01265         if(data.unpacking_remaining() == 0) return rc;
01266 
01267         valid_data_groups += 1;
01268         rc &= data.unpack(rcInterpolation);
01269         rc &= data.unpack(rcInterpolationInterval);
01270         rc &= data.unpack(airModeActivateThreshold);
01271         if(data.unpacking_remaining() == 0) return rc;
01272 
01273         valid_data_groups += 1;
01274         rc &= data.unpack(rx_spi_protocol);
01275         rc &= data.unpack(rx_spi_id);
01276         rc &= data.unpack(rx_spi_rf_channel_count);
01277         if(data.unpacking_remaining() == 0) return rc;
01278 
01279         valid_data_groups += 1;
01280         rc &= data.unpack(fpvCamAngleDegrees);
01281         if(data.unpacking_remaining() == 0) return rc;
01282 
01283         valid_data_groups += 1;
01284         rc &= data.unpack(receiverType);
01285         return rc;
01286     }
01287 
01288     virtual std::ostream& print(std::ostream& s) const override {
01289         return rxConfigPrint(s);
01290     }
01291 };
01292 
01293 // MSP_SET_RX_CONFIG: 45
01294 struct SetRxConfig : public RxConfigSettings, public Message {
01295     SetRxConfig(FirmwareVariant v) : Message(v) {}
01296 
01297     virtual ID id() const override { return ID::MSP_SET_RX_CONFIG; }
01298 
01299     virtual ByteVectorUptr encode() const override {
01300         ByteVectorUptr data = std::make_unique<ByteVector>();
01301         bool rc             = true;
01302         rc &= data->pack(serialrx_provider);
01303         rc &= data->pack(maxcheck);
01304         rc &= data->pack(midrc);
01305         rc &= data->pack(mincheck);
01306         rc &= data->pack(spektrum_sat_bind);
01307         if(valid_data_groups == 1) goto packing_finished;
01308         rc &= data->pack(rx_min_usec);
01309         rc &= data->pack(rx_max_usec);
01310         if(valid_data_groups == 2) goto packing_finished;
01311         rc &= data->pack(rcInterpolation);
01312         rc &= data->pack(rcInterpolationInterval);
01313         rc &= data->pack(airModeActivateThreshold);
01314         if(valid_data_groups == 3) goto packing_finished;
01315         rc &= data->pack(rx_spi_protocol);
01316         rc &= data->pack(rx_spi_id);
01317         rc &= data->pack(rx_spi_rf_channel_count);
01318         if(valid_data_groups == 4) goto packing_finished;
01319         rc &= data->pack(fpvCamAngleDegrees);
01320         if(valid_data_groups == 5) goto packing_finished;
01321         rc &= data->pack(receiverType);
01322     packing_finished:
01323         if(!rc) data.reset();
01324         return data;
01325     }
01326 
01327     virtual std::ostream& print(std::ostream& s) const override {
01328         return rxConfigPrint(s);
01329     }
01330 };
01331 
01332 struct HsvColor : public Packable {
01333     Value<uint16_t> h;
01334     Value<uint8_t> s;
01335     Value<uint8_t> v;
01336 
01337     bool unpack_from(const ByteVector& data) {
01338         bool rc = true;
01339         rc &= data.unpack(h);
01340         rc &= data.unpack(s);
01341         rc &= data.unpack(v);
01342         return rc;
01343     }
01344 
01345     bool pack_into(ByteVector& data) const {
01346         bool rc = true;
01347         rc &= data.pack(h);
01348         rc &= data.pack(s);
01349         rc &= data.pack(v);
01350         return rc;
01351     }
01352 };
01353 
01354 // MSP_LED_COLORS: 46
01355 struct LedColors : public Message {
01356     LedColors(FirmwareVariant v) : Message(v) {}
01357 
01358     virtual ID id() const override { return ID::MSP_LED_COLORS; }
01359 
01360     std::array<HsvColor, LED_CONFIGURABLE_COLOR_COUNT> colors;
01361 
01362     virtual bool decode(const ByteVector& data) override {
01363         bool rc = true;
01364         for(auto& c : colors) {
01365             rc &= data.unpack(c);
01366         }
01367         return rc;
01368     }
01369 };
01370 
01371 // MSP_SET_LED_COLORS: 47
01372 struct SetLedColors : public Message {
01373     SetLedColors(FirmwareVariant v) : Message(v) {}
01374 
01375     virtual ID id() const override { return ID::MSP_SET_LED_COLORS; }
01376 
01377     std::array<HsvColor, LED_CONFIGURABLE_COLOR_COUNT> colors;
01378 
01379     virtual ByteVectorUptr encode() const override {
01380         ByteVectorUptr data = std::make_unique<ByteVector>();
01381         bool rc             = true;
01382         for(size_t i = 0; i < LED_CONFIGURABLE_COLOR_COUNT; ++i) {
01383             rc &= data->pack(colors[i].h);
01384             rc &= data->pack(colors[i].s);
01385             rc &= data->pack(colors[i].v);
01386         }
01387         if(!rc) data.reset();
01388         return data;
01389     }
01390 };
01391 
01392 // MSP_LED_STRIP_CONFIG: 48
01393 struct LedStripConfigs : public Message {
01394     LedStripConfigs(FirmwareVariant v) : Message(v) {}
01395 
01396     virtual ID id() const override { return ID::MSP_LED_STRIP_CONFIG; }
01397 
01398     std::array<uint32_t, LED_MAX_STRIP_LENGTH> configs;
01399 
01400     virtual bool decode(const ByteVector& data) override {
01401         bool rc = true;
01402         for(size_t i = 0; i < LED_MAX_STRIP_LENGTH; ++i) {
01403             rc &= data.unpack(configs[i]);
01404         }
01405         return rc;
01406     }
01407 };
01408 
01409 // MSP_SET_LED_STRIP_CONFIG: 49
01410 struct SetLedStripConfig : public Message {
01411     SetLedStripConfig(FirmwareVariant v) : Message(v) {}
01412 
01413     virtual ID id() const override { return ID::MSP_SET_LED_STRIP_CONFIG; }
01414 
01415     Value<uint8_t> cfg_index;
01416     Value<uint32_t> config;
01417 
01418     virtual ByteVectorUptr encode() const override {
01419         ByteVectorUptr data = std::make_unique<ByteVector>();
01420         bool rc             = true;
01421         rc &= data->pack(cfg_index);
01422         rc &= data->pack(config);
01423         if(!rc) data.reset();
01424         return data;
01425     }
01426 };
01427 
01428 // MSP_RSSI_CONFIG: 50
01429 struct RssiConfig : public Message {
01430     RssiConfig(FirmwareVariant v) : Message(v) {}
01431 
01432     virtual ID id() const override { return ID::MSP_RSSI_CONFIG; }
01433 
01434     Value<uint8_t> rssi_channel;
01435 
01436     virtual bool decode(const ByteVector& data) override {
01437         return data.unpack(rssi_channel);
01438     }
01439 };
01440 
01441 // MSP_SET_RSSI_CONFIG: 51
01442 struct SetRssiConfig : public Message {
01443     SetRssiConfig(FirmwareVariant v) : Message(v) {}
01444 
01445     virtual ID id() const override { return ID::MSP_SET_RSSI_CONFIG; }
01446 
01447     Value<uint8_t> rssi_channel;
01448 
01449     virtual ByteVectorUptr encode() const override {
01450         ByteVectorUptr data = std::make_unique<ByteVector>();
01451         if(!data->pack(rssi_channel)) data.reset();
01452         return data;
01453     }
01454 };
01455 
01456 struct adjustmentRange {
01457     Value<uint8_t> adjustmentIndex;
01458     Value<uint8_t> auxChannelIndex;
01459     Value<uint8_t> range_startStep;
01460     Value<uint8_t> range_endStep;
01461     Value<uint8_t> adjustmentFunction;
01462     Value<uint8_t> auxSwitchChannelIndex;
01463 };
01464 
01465 // MSP_ADJUSTMENT_RANGES: 52
01466 struct AdjustmentRanges : public Message {
01467     AdjustmentRanges(FirmwareVariant v) : Message(v) {}
01468 
01469     virtual ID id() const override { return ID::MSP_ADJUSTMENT_RANGES; }
01470 
01471     std::array<adjustmentRange, MAX_ADJUSTMENT_RANGE_COUNT> ranges;
01472 
01473     virtual bool decode(const ByteVector& data) override {
01474         bool rc = true;
01475         for(size_t i = 0; i < MAX_ADJUSTMENT_RANGE_COUNT; ++i) {
01476             rc &= data.unpack(ranges[i].adjustmentIndex);
01477             rc &= data.unpack(ranges[i].auxChannelIndex);
01478             rc &= data.unpack(ranges[i].range_startStep);
01479             rc &= data.unpack(ranges[i].range_endStep);
01480             rc &= data.unpack(ranges[i].adjustmentFunction);
01481             rc &= data.unpack(ranges[i].auxSwitchChannelIndex);
01482         }
01483         return rc;
01484     }
01485 };
01486 
01487 // MSP_SET_ADJUSTMENT_RANGE: 53
01488 struct SetAdjustmentRange : public Message {
01489     SetAdjustmentRange(FirmwareVariant v) : Message(v) {}
01490 
01491     virtual ID id() const override { return ID::MSP_SET_ADJUSTMENT_RANGE; }
01492 
01493     Value<uint8_t> range_index;
01494     adjustmentRange range;
01495 
01496     virtual ByteVectorUptr encode() const override {
01497         ByteVectorUptr data = std::make_unique<ByteVector>();
01498         bool rc             = true;
01499         rc &= data->pack(range_index);
01500         rc &= data->pack(range.adjustmentIndex);
01501         rc &= data->pack(range.auxChannelIndex);
01502         rc &= data->pack(range.range_startStep);
01503         rc &= data->pack(range.range_endStep);
01504         rc &= data->pack(range.adjustmentFunction);
01505         rc &= data->pack(range.auxSwitchChannelIndex);
01506         if(!rc) data.reset();
01507         return data;
01508     }
01509 };
01510 
01511 struct CfSerialConfigSettings {
01512     Value<uint8_t> identifier;
01513     Value<uint16_t> functionMask;
01514     Value<uint8_t> mspBaudrateIndx;
01515     Value<uint8_t> gpsBaudrateIndx;
01516     Value<uint8_t> telemetryBaudrateIndx;
01517     Value<uint8_t> peripheralBaudrateIndx;
01518 };
01519 
01520 // MSP_CF_SERIAL_CONFIG: 54
01521 struct CfSerialConfig : public Message {
01522     CfSerialConfig(FirmwareVariant v) : Message(v) {}
01523 
01524     virtual ID id() const override { return ID::MSP_CF_SERIAL_CONFIG; }
01525 
01526     std::vector<CfSerialConfigSettings> configs;
01527 
01528     virtual bool decode(const ByteVector& data) override {
01529         bool rc = true;
01530         do {
01531             CfSerialConfigSettings tmp;
01532             rc &= data.unpack(tmp.identifier);
01533             rc &= data.unpack(tmp.functionMask);
01534             rc &= data.unpack(tmp.mspBaudrateIndx);
01535             rc &= data.unpack(tmp.gpsBaudrateIndx);
01536             rc &= data.unpack(tmp.telemetryBaudrateIndx);
01537             rc &= data.unpack(tmp.peripheralBaudrateIndx);
01538             if(rc) configs.push_back(tmp);
01539         } while(rc);
01540         return configs.size();
01541     }
01542 };
01543 
01544 // MSP_SET_CF_SERIAL_CONFIG: 55
01545 struct SetCfSerialConfig : public Message {
01546     SetCfSerialConfig(FirmwareVariant v) : Message(v) {}
01547 
01548     virtual ID id() const override { return ID::MSP_SET_CF_SERIAL_CONFIG; }
01549 
01550     std::vector<CfSerialConfigSettings> configs;
01551 
01552     virtual ByteVectorUptr encode() const override {
01553         ByteVectorUptr data = std::make_unique<ByteVector>();
01554         bool rc             = true;
01555         for(const auto& config : configs) {
01556             rc &= data->pack(config.identifier);
01557             rc &= data->pack(config.functionMask);
01558             rc &= data->pack(config.mspBaudrateIndx);
01559             rc &= data->pack(config.gpsBaudrateIndx);
01560             rc &= data->pack(config.telemetryBaudrateIndx);
01561             rc &= data->pack(config.peripheralBaudrateIndx);
01562         }
01563         if(!rc) data.reset();
01564         return data;
01565     }
01566 };
01567 
01568 struct VoltageMeterConfigSettings {
01569     Value<uint8_t> scale_dV;
01570     Value<uint8_t> cell_min_dV;
01571     Value<uint8_t> cell_max_dV;
01572     Value<uint8_t> cell_warning_dV;
01573 };
01574 
01575 // MSP_VOLTAGE_METER_CONFIG: 56 (differs from Cleanflight/BetaFlight)
01576 struct VoltageMeterConfig : public VoltageMeterConfigSettings, public Message {
01577     VoltageMeterConfig(FirmwareVariant v) : Message(v) {}
01578 
01579     virtual ID id() const override { return ID::MSP_VOLTAGE_METER_CONFIG; }
01580 
01581     virtual bool decode(const ByteVector& data) override {
01582         bool rc = true;
01583         rc &= data.unpack(scale_dV);
01584         rc &= data.unpack(cell_min_dV);
01585         rc &= data.unpack(cell_max_dV);
01586         rc &= data.unpack(cell_warning_dV);
01587         return rc;
01588     }
01589 };
01590 
01591 // MSP_SET_VOLTAGE_METER_CONFIG: 57 (differs from Cleanflight/BetaFlight)
01592 struct SetVoltageMeterConfig : public VoltageMeterConfigSettings,
01593                                public Message {
01594     SetVoltageMeterConfig(FirmwareVariant v) : Message(v) {}
01595 
01596     virtual ID id() const override { return ID::MSP_SET_VOLTAGE_METER_CONFIG; }
01597 
01598     virtual ByteVectorUptr encode() const override {
01599         ByteVectorUptr data = std::make_unique<ByteVector>();
01600         bool rc             = true;
01601         rc &= data->pack(scale_dV);
01602         rc &= data->pack(cell_min_dV);
01603         rc &= data->pack(cell_max_dV);
01604         rc &= data->pack(cell_warning_dV);
01605         if(!rc) data.reset();
01606         return data;
01607     }
01608 };
01609 
01610 // MSP_SONAR_ALTITUDE: 58
01611 struct SonarAltitude : public Message {
01612     SonarAltitude(FirmwareVariant v) : Message(v) {}
01613 
01614     virtual ID id() const override { return ID::MSP_SONAR_ALTITUDE; }
01615 
01616     Value<uint32_t> altitude_cm;
01617 
01618     virtual bool decode(const ByteVector& data) override {
01619         return data.unpack(altitude_cm);
01620     }
01621 };
01622 
01623 // MSP_PID_CONTROLLER: 59
01624 struct PidController : public Message {
01625     PidController(FirmwareVariant v) : Message(v) {}
01626 
01627     virtual ID id() const override { return ID::MSP_PID_CONTROLLER; }
01628 
01629     Value<uint8_t> controller_id;
01630 
01631     virtual bool decode(const ByteVector& data) override {
01632         return data.unpack(controller_id);
01633     }
01634 };
01635 
01636 // MSP_SET_PID_CONTROLLER: 60
01637 struct SetPidController : public Message {
01638     SetPidController(FirmwareVariant v) : Message(v) {}
01639 
01640     virtual ID id() const override { return ID::MSP_SET_PID_CONTROLLER; }
01641 };
01642 
01643 struct ArmingConfigSettings {
01644     Value<uint8_t> auto_disarm_delay;
01645     Value<uint8_t> disarm_kill_switch;
01646     bool imu_small_angle_valid;
01647     Value<uint8_t> imu_small_angle;
01648 };
01649 
01650 // MSP_ARMING_CONFIG: 61
01651 struct ArmingConfig : public ArmingConfigSettings, public Message {
01652     ArmingConfig(FirmwareVariant v) : Message(v) {}
01653 
01654     virtual ID id() const override { return ID::MSP_ARMING_CONFIG; }
01655 
01656     virtual bool decode(const ByteVector& data) override {
01657         bool rc = true;
01658         rc &= data.unpack(auto_disarm_delay);
01659         rc &= data.unpack(disarm_kill_switch);
01660         if(data.unpack(imu_small_angle)) imu_small_angle_valid = true;
01661         return rc;
01662     }
01663 };
01664 
01665 // MSP_SET_ARMING_CONFIG: 62
01666 struct SetArmingConfig : public ArmingConfigSettings, public Message {
01667     SetArmingConfig(FirmwareVariant v) : Message(v) {}
01668 
01669     virtual ID id() const override { return ID::MSP_SET_ARMING_CONFIG; }
01670 
01671     virtual ByteVectorUptr encode() const override {
01672         ByteVectorUptr data = std::make_unique<ByteVector>();
01673         bool rc             = true;
01674         rc &= data->pack(auto_disarm_delay);
01675         rc &= data->pack(disarm_kill_switch);
01676         if(imu_small_angle_valid) rc &= data->pack(imu_small_angle);
01677         if(!rc) data.reset();
01678         return data;
01679     }
01680 };
01681 
01682 struct RxMapSettings {
01683     std::array<uint8_t, MAX_MAPPABLE_RX_INPUTS> map;
01684 
01685     std::ostream& printRxMapSettings(std::ostream& s) const {
01686         s << "#Channel mapping:" << std::endl;
01687         for(size_t i(0); i < map.size(); i++) {
01688             s << " " << i << ": " << size_t(map[i]) << std::endl;
01689         }
01690         return s;
01691     }
01692 };
01693 
01694 // MSP_RX_MAP: 64
01695 struct RxMap : public RxMapSettings, public Message {
01696     RxMap(FirmwareVariant v) : Message(v) {}
01697 
01698     virtual ID id() const override { return ID::MSP_RX_MAP; }
01699 
01700     virtual bool decode(const ByteVector& data) override {
01701         if(data.size() < MAX_MAPPABLE_RX_INPUTS) return false;
01702         bool rc = true;
01703         for(size_t i = 0; i < MAX_MAPPABLE_RX_INPUTS; ++i) {
01704             rc &= data.unpack(map[i]);
01705         }
01706         return rc;
01707     }
01708 
01709     virtual std::ostream& print(std::ostream& s) const override {
01710         return printRxMapSettings(s);
01711     }
01712 };
01713 
01714 // MSP_SET_RX_MAP: 65
01715 struct SetRxMap : public RxMapSettings, public Message {
01716     SetRxMap(FirmwareVariant v) : Message(v) {}
01717 
01718     virtual ID id() const override { return ID::MSP_SET_RX_MAP; }
01719 
01720     virtual ByteVectorUptr encode() const override {
01721         ByteVectorUptr data = std::make_unique<ByteVector>();
01722         bool rc             = true;
01723         for(const auto& channel : map) {
01724             rc &= data->pack(channel);
01725         }
01726         if(!rc) data.reset();
01727         return data;
01728     }
01729 
01730     virtual std::ostream& print(std::ostream& s) const override {
01731         return printRxMapSettings(s);
01732     }
01733 };
01734 
01735 // iNav uses decidegrees, BF/CF use degrees
01736 struct BfConfigSettings {
01737     Value<uint8_t> mixer_mode;
01738     Value<uint32_t> feature_mask;
01739     Value<uint8_t> serialrx_provider;
01740     Value<uint16_t> roll;
01741     Value<uint16_t> pitch;
01742     Value<uint16_t> yaw;
01743     Value<uint16_t> current_meter_scale;
01744     Value<uint16_t> current_meter_offset;
01745 };
01746 
01747 // MSP_BF_CONFIG: 66, //out message baseflight-specific settings that aren't
01748 // covered elsewhere
01749 struct BfConfig : public BfConfigSettings, public Message {
01750     BfConfig(FirmwareVariant v) : Message(v) {}
01751 
01752     virtual ID id() const override { return ID::MSP_BF_CONFIG; }
01753 
01754     virtual bool decode(const ByteVector& data) override {
01755         bool rc = true;
01756         rc &= data.unpack(mixer_mode);
01757         rc &= data.unpack(feature_mask);
01758         rc &= data.unpack(serialrx_provider);
01759         rc &= data.unpack(roll);
01760         rc &= data.unpack(pitch);
01761         rc &= data.unpack(yaw);
01762         rc &= data.unpack(current_meter_scale);
01763         rc &= data.unpack(current_meter_offset);
01764         return rc;
01765     }
01766 };
01767 
01768 // MSP_SET_BF_CONFIG: 67, //in message baseflight-specific settings save
01769 struct SetBfConfig : public BfConfigSettings, public Message {
01770     SetBfConfig(FirmwareVariant v) : Message(v) {}
01771 
01772     virtual ID id() const override { return ID::MSP_SET_BF_CONFIG; }
01773 
01774     virtual ByteVectorUptr encode() const override {
01775         ByteVectorUptr data = std::make_unique<ByteVector>();
01776         bool rc             = true;
01777         rc &= data->pack(mixer_mode);
01778         rc &= data->pack(feature_mask);
01779         rc &= data->pack(serialrx_provider);
01780         rc &= data->pack(roll);
01781         rc &= data->pack(pitch);
01782         rc &= data->pack(yaw);
01783         rc &= data->pack(current_meter_scale);
01784         rc &= data->pack(current_meter_offset);
01785         if(!rc) data.reset();
01786         return data;
01787     }
01788 };
01789 
01790 // MSP_REBOOT: 68
01791 struct Reboot : public Message {
01792     Reboot(FirmwareVariant v) : Message(v) {}
01793 
01794     virtual ID id() const override { return ID::MSP_REBOOT; }
01795 };
01796 
01797 // MSP_BF_BUILD_INFO: 69
01798 struct BfBuildInfo : public Message {
01799     BfBuildInfo(FirmwareVariant v) : Message(v) {}
01800 
01801     virtual ID id() const override { return ID::MSP_BF_BUILD_INFO; }
01802 
01803     Value<std::string> build_date;
01804     Value<uint32_t> reserved1;
01805     Value<uint32_t> reserved2;
01806 
01807     virtual bool decode(const ByteVector& data) override {
01808         bool rc = true;
01809         rc &= data.unpack(build_date, 11);
01810         rc &= data.unpack(reserved1);
01811         rc &= data.unpack(reserved2);
01812         return rc;
01813     }
01814 };
01815 
01816 // MSP_DATAFLASH_SUMMARY: 70
01817 struct DataflashSummary : public Message {
01818     DataflashSummary(FirmwareVariant v) : Message(v) {}
01819 
01820     virtual ID id() const override { return ID::MSP_DATAFLASH_SUMMARY; }
01821 
01822     bool flash_is_ready;
01823     Value<uint32_t> sectors;
01824     Value<uint32_t> total_size;
01825     Value<uint32_t> offset;
01826 
01827     virtual bool decode(const ByteVector& data) override {
01828         bool rc = true;
01829         rc &= data.unpack(flash_is_ready);
01830         rc &= data.unpack(sectors);
01831         rc &= data.unpack(total_size);
01832         rc &= data.unpack(offset);
01833         return rc;
01834     }
01835 };
01836 
01837 // message format differs between iNav and BF/CF
01838 // MSP_DATAFLASH_READ: 71
01839 struct DataflashRead : public Message {
01840     DataflashRead(FirmwareVariant v) : Message(v) {}
01841 
01842     virtual ID id() const override { return ID::MSP_DATAFLASH_READ; }
01843 
01844     Value<uint32_t> read_address;
01845     Value<uint16_t> read_size;
01846     bool allow_compression;
01847     ByteVector flash_data;
01848 
01849     virtual ByteVectorUptr encode() const override {
01850         ByteVectorUptr data = std::make_unique<ByteVector>();
01851         bool rc             = true;
01852         rc &= data->pack(read_address);
01853         rc &= data->pack(read_size);
01854         rc &= data->pack(allow_compression);
01855         if(!rc) data.reset();
01856         return data;
01857     }
01858 
01859     virtual bool decode(const ByteVector& data) override {
01860         bool rc = true;
01861         rc &= data.unpack(read_address);
01862         flash_data = ByteVector(data.unpacking_iterator(), data.end());
01863         rc &= data.consume(flash_data.size());
01864         return rc;
01865     }
01866 };
01867 
01868 // MSP_DATAFLASH_ERASE: 72
01869 struct DataflashErase : public Message {
01870     DataflashErase(FirmwareVariant v) : Message(v) {}
01871 
01872     virtual ID id() const override { return ID::MSP_DATAFLASH_ERASE; }
01873 
01874     virtual bool decode(const ByteVector& /*data*/) override { return true; }
01875 };
01876 
01877 // MSP_LOOP_TIME: 73
01878 struct LoopTime : public Message {
01879     LoopTime(FirmwareVariant v) : Message(v) {}
01880 
01881     virtual ID id() const override { return ID::MSP_LOOP_TIME; }
01882 
01883     Value<uint16_t> loop_time;
01884 
01885     virtual bool decode(const ByteVector& data) override {
01886         return data.unpack(loop_time);
01887     }
01888 };
01889 
01890 // MSP_SET_LOOP_TIME:74
01891 struct SetLoopTime : public Message {
01892     SetLoopTime(FirmwareVariant v) : Message(v) {}
01893 
01894     virtual ID id() const override { return ID::MSP_SET_LOOP_TIME; }
01895 
01896     Value<uint16_t> loop_time;
01897 
01898     virtual ByteVectorUptr encode() const override {
01899         ByteVectorUptr data = std::make_unique<ByteVector>();
01900         if(!data->pack(loop_time)) data.reset();
01901         return data;
01902     }
01903 };
01904 
01905 struct FailsafeSettings {
01906     bool extended_contents;
01907     Value<uint8_t> delay;
01908     Value<uint8_t> off_delay;
01909     Value<uint16_t> throttle;
01910     Value<uint8_t> kill_switch;
01911     Value<uint16_t> throttle_low_delay;
01912     Value<uint8_t> procedure;
01913     Value<uint8_t> recovery_delay;
01914     Value<uint16_t> fw_roll_angle;
01915     Value<uint16_t> fw_pitch_angle;
01916     Value<uint16_t> fw_yaw_rate;
01917     Value<uint16_t> stick_motion_threshold;
01918     Value<uint16_t> min_distance;
01919     Value<uint8_t> min_distance_procedure;
01920 };
01921 
01922 // MSP_FAILSAFE_CONFIG: 75
01923 struct FailsafeConfig : public FailsafeSettings, public Message {
01924     FailsafeConfig(FirmwareVariant v) : Message(v) {}
01925 
01926     virtual ID id() const override { return ID::MSP_FAILSAFE_CONFIG; }
01927 
01928     virtual bool decode(const ByteVector& data) override {
01929         bool rc           = true;
01930         extended_contents = false;
01931         rc &= data.unpack(delay);
01932         rc &= data.unpack(off_delay);
01933         rc &= data.unpack(throttle);
01934         rc &= data.unpack(kill_switch);
01935         rc &= data.unpack(throttle_low_delay);
01936         rc &= data.unpack(procedure);
01937         if(data.unpacking_remaining() == 0) return rc;
01938         extended_contents = true;
01939         rc &= data.unpack(recovery_delay);
01940         rc &= data.unpack(fw_roll_angle);
01941         rc &= data.unpack(fw_pitch_angle);
01942         rc &= data.unpack(fw_yaw_rate);
01943         rc &= data.unpack(stick_motion_threshold);
01944         rc &= data.unpack(min_distance);
01945         rc &= data.unpack(min_distance_procedure);
01946         return rc;
01947     }
01948 };
01949 
01950 // MSP_SET_FAILSAFE_CONFIG: 76
01951 struct SetFailsafeConfig : public FailsafeSettings, public Message {
01952     SetFailsafeConfig(FirmwareVariant v) : Message(v) {}
01953 
01954     virtual ID id() const override { return ID::MSP_SET_FAILSAFE_CONFIG; }
01955 
01956     virtual ByteVectorUptr encode() const override {
01957         ByteVectorUptr data = std::make_unique<ByteVector>();
01958         bool rc             = true;
01959         rc &= data->pack(delay);
01960         rc &= data->pack(off_delay);
01961         rc &= data->pack(throttle);
01962         rc &= data->pack(kill_switch);
01963         rc &= data->pack(throttle_low_delay);
01964         rc &= data->pack(procedure);
01965         if(extended_contents) {
01966             rc &= data->pack(recovery_delay);
01967             rc &= data->pack(fw_roll_angle);
01968             rc &= data->pack(fw_pitch_angle);
01969             rc &= data->pack(fw_yaw_rate);
01970             rc &= data->pack(stick_motion_threshold);
01971             rc &= data->pack(min_distance);
01972             rc &= data->pack(min_distance_procedure);
01973         }
01974         if(!rc) data.reset();
01975         return data;
01976     }
01977 };
01978 
01979 struct RxFailChannelSettings {
01980     Value<uint8_t> mode;
01981     Value<uint16_t> val;
01982 };
01983 
01984 // MSP_RXFAIL_CONFIG: 77
01985 struct RxFailConfigs : public Message {
01986     RxFailConfigs(FirmwareVariant v) : Message(v) {}
01987 
01988     virtual ID id() const override { return ID::MSP_RXFAIL_CONFIG; }
01989 
01990     std::vector<RxFailChannelSettings> channels;
01991 
01992     virtual bool decode(const ByteVector& data) override {
01993         bool rc = true;
01994         channels.clear();
01995         while(rc && data.unpacking_remaining()) {
01996             RxFailChannelSettings tmp;
01997             rc &= data.unpack(tmp.mode);
01998             rc &= data.unpack(tmp.val);
01999             channels.push_back(tmp);
02000         }
02001         return rc;
02002     }
02003 };
02004 
02005 // MSP_SET_RXFAIL_CONFIG: 78
02006 struct SetRxFailConfigs : public RxFailChannelSettings, public Message {
02007     SetRxFailConfigs(FirmwareVariant v) : Message(v) {}
02008 
02009     virtual ID id() const override { return ID::MSP_SET_RXFAIL_CONFIG; }
02010 
02011     Value<uint8_t> channel;
02012 
02013     virtual bool decode(const ByteVector& data) override {
02014         bool rc = true;
02015         rc &= data.unpack(channel);
02016         rc &= data.unpack(mode);
02017         rc &= data.unpack(val);
02018         return rc;
02019     }
02020 };
02021 
02022 // MSP_SDCARD_SUMMARY: 79
02023 struct SdcardSummary : public Message {
02024     SdcardSummary(FirmwareVariant v) : Message(v) {}
02025 
02026     virtual ID id() const override { return ID::MSP_SDCARD_SUMMARY; }
02027 
02028     Value<uint8_t> flags;
02029     Value<uint8_t> state;
02030     Value<uint8_t> last_error;
02031     Value<uint32_t> free_space_kb;
02032     Value<uint32_t> total_space_kb;
02033 
02034     virtual bool decode(const ByteVector& data) override {
02035         bool rc = true;
02036         rc &= data.unpack(flags);
02037         rc &= data.unpack(state);
02038         rc &= data.unpack(last_error);
02039         rc &= data.unpack(free_space_kb);
02040         rc &= data.unpack(total_space_kb);
02041         return rc;
02042     }
02043 };
02044 
02045 struct BlackboxConfigSettings {
02046     Value<uint8_t> device;
02047     Value<uint8_t> rate_num;
02048     Value<uint8_t> rate_denom;
02049     bool p_ratio_set;
02050     Value<uint16_t> p_ratio;
02051 };
02052 
02053 // MSP_BLACKBOX_CONFIG: 80
02054 struct BlackboxConfig : public BlackboxConfigSettings, public Message {
02055     BlackboxConfig(FirmwareVariant v) : Message(v) {}
02056 
02057     virtual ID id() const override { return ID::MSP_BLACKBOX_CONFIG; }
02058 
02059     Value<uint8_t> supported;
02060 
02061     virtual bool decode(const ByteVector& data) override {
02062         bool rc     = true;
02063         p_ratio_set = false;
02064         rc &= data.unpack(supported);
02065         rc &= data.unpack(device);
02066         rc &= data.unpack(rate_num);
02067         rc &= data.unpack(rate_denom);
02068         if(data.unpacking_remaining()) {
02069             p_ratio_set = true;
02070             rc &= data.unpack(p_ratio);
02071         }
02072         return rc;
02073     }
02074 };
02075 
02076 // MSP_SET_BLACKBOX_CONFIG: 81
02077 struct SetBlackboxConfig : public BlackboxConfigSettings, public Message {
02078     SetBlackboxConfig(FirmwareVariant v) : Message(v) {}
02079 
02080     virtual ID id() const override { return ID::MSP_SET_BLACKBOX_CONFIG; }
02081 
02082     virtual ByteVectorUptr encode() const override {
02083         ByteVectorUptr data = std::make_unique<ByteVector>();
02084         bool rc             = true;
02085         rc &= data->pack(device);
02086         rc &= data->pack(rate_num);
02087         rc &= data->pack(rate_denom);
02088         if(p_ratio_set) rc &= data->pack(p_ratio);
02089         if(!rc) data.reset();
02090         return data;
02091     }
02092 };
02093 
02094 struct TransponderConfigSettings {
02095     Value<uint8_t> provider;
02096     Value<uint8_t> data_length;
02097 };
02098 
02099 // MSP_TRANSPONDER_CONFIG: 82
02100 struct TransponderConfig : public Message {
02101     TransponderConfig(FirmwareVariant v) : Message(v) {}
02102 
02103     virtual ID id() const override { return ID::MSP_TRANSPONDER_CONFIG; }
02104 
02105     Value<uint8_t> transponder_count;
02106     std::vector<TransponderConfigSettings> transponder_data;
02107     Value<uint8_t> provider;
02108     ByteVector provider_data;
02109 
02110     virtual bool decode(const ByteVector& data) override {
02111         bool rc = true;
02112         rc &= data.unpack(transponder_count);
02113         if(!transponder_count()) return rc;
02114         for(uint8_t i = 0; i < transponder_count(); ++i) {
02115             TransponderConfigSettings tmp;
02116             rc &= data.unpack(tmp.provider);
02117             rc &= data.unpack(tmp.data_length);
02118             transponder_data.push_back(tmp);
02119         }
02120         rc &= data.unpack(provider);
02121         if(!provider()) return rc;
02122         uint8_t data_len = transponder_data[provider() - 1].data_length();
02123         provider_data    = ByteVector(data.unpacking_iterator(),
02124                                    data.unpacking_iterator() + data_len);
02125         rc &= data.consume(data_len);
02126         return rc;
02127     }
02128 };
02129 
02130 // MSP_SET_TRANSPONDER_CONFIG: 83
02131 struct SetTransponderConfig : public Message {
02132     SetTransponderConfig(FirmwareVariant v) : Message(v) {}
02133 
02134     virtual ID id() const override { return ID::MSP_SET_TRANSPONDER_CONFIG; }
02135 
02136     Value<uint8_t> provider;
02137     ByteVector provider_data;
02138 
02139     virtual ByteVectorUptr encode() const override {
02140         ByteVectorUptr data = std::make_unique<ByteVector>();
02141         bool rc             = true;
02142         rc &= data->pack(provider);
02143         rc &= data->pack(provider_data);
02144         if(!rc) data.reset();
02145         return data;
02146     }
02147 };
02148 
02149 // Differences between iNav and BF/CF
02150 // MSP_OSD_CONFIG: 84
02151 struct OsdConfig : public Message {
02152     OsdConfig(FirmwareVariant v) : Message(v) {}
02153 
02154     virtual ID id() const override { return ID::MSP_OSD_CONFIG; }
02155 
02156     Value<uint8_t> osd_flags;
02157     Value<uint8_t> video_system;
02158     Value<uint8_t> units;
02159     Value<uint8_t> rssi_alarm;
02160     Value<uint16_t> battery_cap_warn;
02161     Value<uint16_t> time_alarm;
02162     Value<uint16_t> alt_alarm;
02163     Value<uint16_t> dist_alarm;
02164     Value<uint16_t> neg_alt_alarm;
02165     std::array<uint16_t, OSD_ITEM_COUNT> item_pos;
02166 
02167     virtual bool decode(const ByteVector& data) override {
02168         bool rc = true;
02169         rc &= data.unpack(osd_flags);
02170         if(rc && osd_flags()) {
02171             rc &= data.unpack(video_system);
02172             rc &= data.unpack(units);
02173             rc &= data.unpack(rssi_alarm);
02174             rc &= data.unpack(battery_cap_warn);
02175             rc &= data.unpack(time_alarm);
02176             rc &= data.unpack(alt_alarm);
02177             rc &= data.unpack(dist_alarm);
02178             rc &= data.unpack(neg_alt_alarm);
02179             for(size_t i = 0; i < OSD_ITEM_COUNT; ++i) {
02180                 rc &= data.unpack(item_pos[i]);
02181             }
02182         }
02183         return rc;
02184     }
02185 };
02186 
02187 // MSP_SET_OSD_CONFIG: 85
02188 struct SetOsdConfig : public Message {
02189     SetOsdConfig(FirmwareVariant v) : Message(v) {}
02190 
02191     virtual ID id() const override { return ID::MSP_SET_OSD_CONFIG; }
02192 
02193     int8_t param_idx;
02194     Value<uint16_t> item_pos;
02195     Value<uint8_t> video_system;
02196     Value<uint8_t> units;
02197     Value<uint8_t> rssi_alarm;
02198     Value<uint16_t> battery_cap_warn;
02199     Value<uint16_t> time_alarm;
02200     Value<uint16_t> alt_alarm;
02201     Value<uint16_t> dist_alarm;
02202     Value<uint16_t> neg_alt_alarm;
02203 
02204     virtual ByteVectorUptr encode() const override {
02205         ByteVectorUptr data = std::make_unique<ByteVector>();
02206         bool rc             = true;
02207         rc &= data->pack(param_idx);
02208         if(param_idx == -1) {
02209             rc &= data->pack(video_system);
02210             rc &= data->pack(units);
02211             rc &= data->pack(rssi_alarm);
02212             rc &= data->pack(battery_cap_warn);
02213             rc &= data->pack(time_alarm);
02214             rc &= data->pack(alt_alarm);
02215             rc &= data->pack(dist_alarm);
02216             rc &= data->pack(neg_alt_alarm);
02217         }
02218         else {
02219             rc &= data->pack(item_pos);
02220         }
02221         if(!rc) data.reset();
02222         return data;
02223     }
02224 };
02225 
02226 // MSP_OSD_CHAR_READ: 86 No reference implementation
02227 
02228 // MSP_OSD_CHAR_WRITE: 87
02229 struct OsdCharWrite : public Message {
02230     OsdCharWrite(FirmwareVariant v) : Message(v) {}
02231 
02232     virtual ID id() const override { return ID::MSP_OSD_CHAR_WRITE; }
02233 
02234     Value<uint8_t> addr;
02235     std::array<uint8_t, 54> font_data;
02236 
02237     virtual ByteVectorUptr encode() const override {
02238         ByteVectorUptr data = std::make_unique<ByteVector>();
02239         bool rc             = true;
02240         rc &= data->pack(addr);
02241         for(const auto& c : font_data) {
02242             rc &= data->pack(c);
02243         }
02244         if(!rc) data.reset();
02245         return data;
02246     }
02247 };
02248 
02249 // MSP_VTX_CONFIG: 88
02250 struct VtxConfig : public Message {
02251     VtxConfig(FirmwareVariant v) : Message(v) {}
02252 
02253     virtual ID id() const override { return ID::MSP_VTX_CONFIG; }
02254 
02255     Value<uint8_t> device_type;
02256     Value<uint8_t> band;
02257     Value<uint8_t> channel;
02258     Value<uint8_t> power_idx;
02259     Value<uint8_t> pit_mode;
02260     bool freq_set;
02261     Value<uint16_t> frequency;
02262 
02263     virtual bool decode(const ByteVector& data) override {
02264         bool rc  = true;
02265         freq_set = false;
02266         rc &= data.unpack(device_type);
02267         if(rc && (device_type() != 0xFF)) {
02268             rc &= data.unpack(band);
02269             rc &= data.unpack(channel);
02270             rc &= data.unpack(power_idx);
02271             rc &= data.unpack(pit_mode);
02272             if(data.unpacking_remaining()) {
02273                 freq_set = true;
02274                 rc &= data.unpack(frequency);
02275             }
02276         }
02277         return rc;
02278     }
02279 };
02280 
02281 // MSP_SET_VTX_CONFIG: 89
02282 struct SetVtxConfig : public Message {
02283     SetVtxConfig(FirmwareVariant v) : Message(v) {}
02284 
02285     virtual ID id() const override { return ID::MSP_SET_VTX_CONFIG; }
02286 
02287     Value<uint16_t> frequency;
02288     Value<uint8_t> power;
02289     Value<uint8_t> pit_mode;
02290 
02291     bool set_freq(uint8_t band, uint8_t channel) {
02292         if(band & 0xF8 || channel & 0xF8) {
02293             return false;
02294         }
02295         frequency = uint16_t(band - 1) & uint16_t((channel - 1) << 3);
02296         return true;
02297     }
02298 
02299     virtual ByteVectorUptr encode() const override {
02300         ByteVectorUptr data = std::make_unique<ByteVector>();
02301         bool rc             = true;
02302         rc &= data->pack(frequency);
02303         rc &= data->pack(power);
02304         rc &= data->pack(pit_mode);
02305         if(!rc) data.reset();
02306         return data;
02307     }
02308 };
02309 
02310 // Differs between iNav and BF/CF
02311 struct AdvancedConfigSettings {
02312     Value<uint8_t> gyro_sync_denom;
02313     Value<uint8_t> pid_process_denom;
02314     Value<uint8_t> use_unsynced_pwm;
02315     Value<uint8_t> motor_pwm_protocol;
02316     Value<uint16_t> motor_pwm_rate;
02317     Value<uint16_t> servo_pwm_rate;  // digitalIdleOffsetValue in BF/CF
02318     Value<uint8_t> gyro_sync;
02319     bool pwm_inversion_set;
02320     Value<uint8_t> pwm_inversion;
02321 };
02322 
02323 // Betaflight Additional Commands
02324 // MSP_ADVANCED_CONFIG: 90
02325 struct AdvancedConfig : public AdvancedConfigSettings, public Message {
02326     AdvancedConfig(FirmwareVariant v) : Message(v) {}
02327 
02328     virtual ID id() const override { return ID::MSP_ADVANCED_CONFIG; }
02329 
02330     virtual bool decode(const ByteVector& data) override {
02331         bool rc           = true;
02332         pwm_inversion_set = false;
02333         rc &= data.unpack(gyro_sync_denom);
02334         rc &= data.unpack(pid_process_denom);
02335         rc &= data.unpack(use_unsynced_pwm);
02336         rc &= data.unpack(motor_pwm_protocol);
02337         rc &= data.unpack(motor_pwm_rate);
02338         rc &= data.unpack(servo_pwm_rate);
02339         rc &= data.unpack(gyro_sync);
02340         if(rc && data.unpacking_remaining()) {
02341             pwm_inversion_set = true;
02342             rc &= data.unpack(pwm_inversion);
02343         }
02344         return rc;
02345     }
02346 };
02347 
02348 // MSP_SET_ADVANCED_CONFIG: 91
02349 struct SetAdvancedConfig : public AdvancedConfigSettings, public Message {
02350     SetAdvancedConfig(FirmwareVariant v) : Message(v) {}
02351 
02352     virtual ID id() const override { return ID::MSP_SET_ADVANCED_CONFIG; }
02353 
02354     virtual ByteVectorUptr encode() const override {
02355         ByteVectorUptr data = std::make_unique<ByteVector>();
02356         bool rc             = true;
02357         rc &= data->pack(gyro_sync_denom);
02358         rc &= data->pack(pid_process_denom);
02359         rc &= data->pack(use_unsynced_pwm);
02360         rc &= data->pack(motor_pwm_protocol);
02361         rc &= data->pack(motor_pwm_rate);
02362         rc &= data->pack(servo_pwm_rate);
02363         rc &= data->pack(gyro_sync);
02364         if(pwm_inversion_set) rc &= data->pack(pwm_inversion);
02365         if(!rc) data.reset();
02366         return data;
02367     }
02368 };
02369 
02370 struct FilterConfigSettings {
02371     Value<uint8_t> gyro_soft_lpf_hz;
02372     Value<uint16_t> dterm_lpf_hz;
02373     Value<uint16_t> yaw_lpf_hz;
02374     Value<uint16_t> gyro_soft_notch_hz_1;
02375     Value<uint16_t> gyro_soft_notch_cutoff_1;
02376     Value<uint16_t> dterm_soft_notch_hz;
02377     Value<uint16_t> dterm_soft_notch_cutoff;
02378     Value<uint16_t> gyro_soft_notch_hz_2;
02379     Value<uint16_t> gyro_soft_notch_cutoff_2;
02380     bool dterm_filter_type_set;
02381     Value<uint8_t> dterm_filter_type;
02382 };
02383 
02384 // MSP_FILTER_CONFIG: 92
02385 struct FilterConfig : public FilterConfigSettings, public Message {
02386     FilterConfig(FirmwareVariant v) : Message(v) {}
02387 
02388     virtual ID id() const override { return ID::MSP_FILTER_CONFIG; }
02389 
02390     virtual bool decode(const ByteVector& data) override {
02391         bool rc               = true;
02392         dterm_filter_type_set = false;
02393         rc &= data.unpack(gyro_soft_lpf_hz);
02394         rc &= data.unpack(dterm_lpf_hz);
02395         rc &= data.unpack(yaw_lpf_hz);
02396         rc &= data.unpack(gyro_soft_notch_hz_1);
02397         rc &= data.unpack(gyro_soft_notch_cutoff_1);
02398         rc &= data.unpack(dterm_soft_notch_hz);
02399         rc &= data.unpack(dterm_soft_notch_cutoff);
02400         rc &= data.unpack(gyro_soft_notch_hz_2);
02401         rc &= data.unpack(gyro_soft_notch_cutoff_2);
02402         if(rc && data.unpacking_remaining()) {
02403             dterm_filter_type_set = true;
02404             rc &= data.unpack(dterm_filter_type);
02405         }
02406         return rc;
02407     }
02408 };
02409 
02410 // MSP_SET_FILTER_CONFIG: 93
02411 struct SetFilterConfig : public FilterConfigSettings, public Message {
02412     SetFilterConfig(FirmwareVariant v) : Message(v) {}
02413 
02414     virtual ID id() const override { return ID::MSP_SET_FILTER_CONFIG; }
02415 
02416     virtual ByteVectorUptr encode() const override {
02417         ByteVectorUptr data = std::make_unique<ByteVector>();
02418         bool rc             = true;
02419         rc &= data->pack(gyro_soft_lpf_hz);
02420         rc &= data->pack(dterm_lpf_hz);
02421         rc &= data->pack(yaw_lpf_hz);
02422         rc &= data->pack(gyro_soft_notch_hz_1);
02423         rc &= data->pack(gyro_soft_notch_cutoff_1);
02424         rc &= data->pack(dterm_soft_notch_hz);
02425         rc &= data->pack(dterm_soft_notch_cutoff);
02426         rc &= data->pack(gyro_soft_notch_hz_2);
02427         rc &= data->pack(gyro_soft_notch_cutoff_2);
02428         if(dterm_filter_type_set) rc &= data->pack(dterm_filter_type);
02429         if(!rc) data.reset();
02430         return data;
02431     }
02432 };
02433 
02434 struct PidAdvancedSettings {
02435     Value<uint16_t> rollPitchItermIgnoreRate;
02436     Value<uint16_t> yawItermIgnoreRate;
02437     Value<uint16_t> yaw_p_limit;
02438     Value<uint8_t> deltaMethod;
02439     Value<uint8_t> vbatPidCompensation;
02440     Value<uint8_t> setpointRelaxRatio;
02441     Value<float> dterm_setpoint_weight;  // TODO scaled value
02442     Value<uint16_t> pidSumLimit;
02443     Value<uint8_t> itermThrottleGain;
02444     Value<uint32_t>
02445         axisAccelerationLimitRollPitch;        // TODO scaled and clamped value
02446     Value<uint32_t> axisAccelerationLimitYaw;  // TODO scaled and clamped value
02447 };
02448 
02449 // Difference between iNav and BF/CF
02450 // MSP_PID_ADVANCED: 94
02451 struct PidAdvanced : public PidAdvancedSettings, public Message {
02452     PidAdvanced(FirmwareVariant v) : Message(v) {}
02453 
02454     virtual ID id() const override { return ID::MSP_PID_ADVANCED; }
02455 
02456     virtual bool decode(const ByteVector& data) override {
02457         bool rc = true;
02458         rc &= data.unpack(rollPitchItermIgnoreRate);
02459         rc &= data.unpack(yawItermIgnoreRate);
02460         rc &= data.unpack(yaw_p_limit);
02461         rc &= data.unpack(deltaMethod);
02462         rc &= data.unpack(vbatPidCompensation);
02463         rc &= data.unpack(setpointRelaxRatio);
02464         rc &= data.unpack<uint8_t>(dterm_setpoint_weight, 0.01);
02465         rc &= data.unpack(pidSumLimit);
02466         rc &= data.unpack(itermThrottleGain);
02467         Value<uint16_t> tmp16;
02468         rc &= data.unpack(tmp16);
02469         axisAccelerationLimitRollPitch = tmp16() * 10;
02470         rc &= data.unpack(tmp16);
02471         axisAccelerationLimitYaw = tmp16() * 10;
02472         return rc;
02473     }
02474 };
02475 
02476 // MSP_SET_PID_ADVANCED: 95
02477 struct SetPidAdvanced : public PidAdvancedSettings, public Message {
02478     SetPidAdvanced(FirmwareVariant v) : Message(v) {}
02479 
02480     virtual ID id() const override { return ID::MSP_SET_PID_ADVANCED; }
02481 
02482     virtual ByteVectorUptr encode() const override {
02483         ByteVectorUptr data = std::make_unique<ByteVector>();
02484         bool rc             = true;
02485         rc &= data->pack(rollPitchItermIgnoreRate);
02486         rc &= data->pack(yawItermIgnoreRate);
02487         rc &= data->pack(yaw_p_limit);
02488         rc &= data->pack(deltaMethod);
02489         rc &= data->pack(vbatPidCompensation);
02490         rc &= data->pack(setpointRelaxRatio);
02491         rc &= data->pack(uint8_t(dterm_setpoint_weight() * 100));
02492         rc &= data->pack(pidSumLimit);
02493         rc &= data->pack(itermThrottleGain);
02494         rc &= data->pack(axisAccelerationLimitRollPitch() / 10);
02495         rc &= data->pack(axisAccelerationLimitYaw() / 10);
02496         if(!rc) data.reset();
02497         return data;
02498     }
02499 };
02500 
02501 struct SensorConfigSettings {
02502     Value<uint8_t> acc_hardware;
02503     Value<uint8_t> baro_hardware;
02504     Value<uint8_t> mag_hardware;
02505     bool extended_contents;
02506     Value<uint8_t> pitot_hardware;
02507     Value<uint8_t> rangefinder_hardware;
02508     Value<uint8_t> opflow_hardware;
02509 };
02510 
02511 // MSP_SENSOR_CONFIG: 96
02512 struct SensorConfig : public SensorConfigSettings, public Message {
02513     SensorConfig(FirmwareVariant v) : Message(v) {}
02514 
02515     virtual ID id() const override { return ID::MSP_SENSOR_CONFIG; }
02516 
02517     virtual bool decode(const ByteVector& data) override {
02518         bool rc           = true;
02519         extended_contents = false;
02520         rc &= data.unpack(acc_hardware);
02521         rc &= data.unpack(baro_hardware);
02522         rc &= data.unpack(mag_hardware);
02523         if(data.unpacking_remaining()) {
02524             extended_contents = true;
02525             rc &= data.unpack(pitot_hardware);
02526             rc &= data.unpack(rangefinder_hardware);
02527             rc &= data.unpack(opflow_hardware);
02528         }
02529         return rc;
02530     }
02531 };
02532 
02533 // MSP_SET_SENSOR_CONFIG: 97
02534 struct SetSensorConfig : public SensorConfigSettings, public Message {
02535     SetSensorConfig(FirmwareVariant v) : Message(v) {}
02536 
02537     virtual ID id() const override { return ID::MSP_SET_SENSOR_CONFIG; }
02538 
02539     virtual ByteVectorUptr encode() const override {
02540         ByteVectorUptr data = std::make_unique<ByteVector>();
02541         bool rc             = true;
02542         rc &= data->pack(acc_hardware);
02543         rc &= data->pack(baro_hardware);
02544         rc &= data->pack(mag_hardware);
02545         if(!extended_contents) {
02546             rc &= data->pack(pitot_hardware);
02547             rc &= data->pack(rangefinder_hardware);
02548             rc &= data->pack(opflow_hardware);
02549         }
02550         if(!rc) data.reset();
02551         return data;
02552     }
02553 };
02554 
02555 // MSP_CAMERA_CONTROL: 98
02556 struct CameraControl : public Message {
02557     CameraControl(FirmwareVariant v) : Message(v) {}
02558 
02559     virtual ID id() const override { return ID::MSP_CAMERA_CONTROL; }
02560 
02561     Value<uint8_t> key;
02562 
02563     virtual ByteVectorUptr encode() const override {
02564         ByteVectorUptr data = std::make_unique<ByteVector>();
02565         if(!data->pack(key)) data.reset();
02566         return data;
02567     }
02568 };
02569 
02570 // MSP_SET_ARMING_DISABLED: 99
02571 struct SetArmingDisabled : public Message {
02572     SetArmingDisabled(FirmwareVariant v) : Message(v) {}
02573 
02574     virtual ID id() const override { return ID::MSP_SET_ARMING_DISABLED; }
02575 
02576     Value<uint8_t> command;
02577     Value<uint8_t> disableRunawayTakeoff;
02578 
02579     virtual ByteVectorUptr encode() const override {
02580         ByteVectorUptr data = std::make_unique<ByteVector>();
02581         bool rc             = true;
02582         rc &= data->pack(command);
02583         rc &= data->pack(disableRunawayTakeoff);
02584         if(!rc) data.reset();
02585         return data;
02586     }
02587 };
02588 
02591 
02592 // MSP_IDENT: 100
02593 struct Ident : public Message {
02594     Ident(FirmwareVariant v) : Message(v) {}
02595 
02596     virtual ID id() const override { return ID::MSP_IDENT; }
02597 
02598     Value<uint8_t> version;
02599     MultiType type;
02600     Value<uint8_t> msp_version;
02601     std::set<Capability> capabilities;
02602 
02603     virtual bool decode(const ByteVector& data) override {
02604         bool rc = true;
02605 
02606         rc &= data.unpack(version);
02607         rc &= data.unpack((uint8_t&)type);
02608         rc &= data.unpack(msp_version);
02609         uint32_t capability;
02610         rc &= data.unpack(capability);
02611         if(!rc) return false;
02612         capabilities.clear();
02613         if(capability & (1 << 0)) capabilities.insert(Capability::BIND);
02614         if(capability & (1 << 2)) capabilities.insert(Capability::DYNBAL);
02615         if(capability & (1 << 3)) capabilities.insert(Capability::FLAP);
02616         if(capability & (1 << 4)) capabilities.insert(Capability::NAVCAP);
02617         if(capability & (1 << 5)) capabilities.insert(Capability::EXTAUX);
02618 
02619         return true;
02620     }
02621 
02622     bool has(const Capability& cap) const { return capabilities.count(cap); }
02623 
02624     bool hasBind() const { return has(Capability::BIND); }
02625 
02626     bool hasDynBal() const { return has(Capability::DYNBAL); }
02627 
02628     bool hasFlap() const { return has(Capability::FLAP); }
02629 
02630     virtual std::ostream& print(std::ostream& s) const override {
02631         std::string s_type;
02632         switch(type) {
02633         case msp::msg::MultiType::TRI:
02634             s_type = "Tricopter";
02635             break;
02636         case msp::msg::MultiType::QUADP:
02637             s_type = "Quadrocopter Plus";
02638             break;
02639         case msp::msg::MultiType::QUADX:
02640             s_type = "Quadrocopter X";
02641             break;
02642         case msp::msg::MultiType::BI:
02643             s_type = "BI-copter";
02644             break;
02645         default:
02646             s_type = "UNDEFINED";
02647             break;
02648         }
02649 
02650         s << "#Ident:" << std::endl;
02651 
02652         s << " MultiWii Version: " << version << std::endl
02653           << " MSP Version: " << msp_version << std::endl
02654           << " Type: " << s_type << std::endl
02655           << " Capabilities:" << std::endl;
02656 
02657         s << "    Bind:   ";
02658         hasBind() ? s << "ON" : s << "OFF";
02659         s << std::endl;
02660 
02661         s << "    DynBal: ";
02662         hasDynBal() ? s << "ON" : s << "OFF";
02663         s << std::endl;
02664 
02665         s << "    Flap:   ";
02666         hasFlap() ? s << "ON" : s << "OFF";
02667         s << std::endl;
02668 
02669         return s;
02670     }
02671 };
02672 
02673 struct StatusBase : public Packable {
02674     Value<uint16_t> cycle_time;  // in us
02675     Value<uint16_t> i2c_errors;
02676     std::set<Sensor> sensors;
02677     std::set<size_t> box_mode_flags;
02678     Value<uint8_t> current_profile;
02679 
02680     bool unpack_from(const ByteVector& data) {
02681         bool rc = true;
02682         rc &= data.unpack(cycle_time);
02683         rc &= data.unpack(i2c_errors);
02684 
02685         // get sensors
02686         sensors.clear();
02687         uint16_t sensor = 0;
02688         rc &= data.unpack(sensor);
02689         if(sensor & (1 << 0)) sensors.insert(Sensor::Accelerometer);
02690         if(sensor & (1 << 1)) sensors.insert(Sensor::Barometer);
02691         if(sensor & (1 << 2)) sensors.insert(Sensor::Magnetometer);
02692         if(sensor & (1 << 3)) sensors.insert(Sensor::GPS);
02693         if(sensor & (1 << 4)) sensors.insert(Sensor::Sonar);
02694         if(sensor & (1 << 5)) sensors.insert(Sensor::OpticalFlow);
02695         if(sensor & (1 << 6)) sensors.insert(Sensor::Pitot);
02696         if(sensor & (1 << 15)) sensors.insert(Sensor::GeneralHealth);
02697 
02698         // check active boxes
02699         box_mode_flags.clear();
02700         uint32_t flag = 0;
02701         rc &= data.unpack(flag);
02702         for(size_t ibox(0); ibox < sizeof(flag) * CHAR_BIT; ibox++) {
02703             if(flag & (1 << ibox)) box_mode_flags.insert(ibox);
02704         }
02705 
02706         rc &= data.unpack(current_profile);
02707         return rc;
02708     }
02709 
02710     virtual bool pack_into(ByteVector& data) const {
02711         bool rc = true;
02712         rc &= data.pack(cycle_time);
02713         rc &= data.pack(i2c_errors);
02714 
02715         Value<uint16_t> sensor_pack;
02716         sensor_pack = 0;
02717         for(const auto& s : sensors) {
02718             switch(s) {
02719             case Sensor::Accelerometer:
02720                 sensor_pack() |= (1 << 0);
02721                 break;
02722             case Sensor::Barometer:
02723                 sensor_pack() |= (1 << 1);
02724                 break;
02725             case Sensor::Magnetometer:
02726                 sensor_pack() |= (1 << 2);
02727                 break;
02728             case Sensor::GPS:
02729                 sensor_pack() |= (1 << 3);
02730                 break;
02731             case Sensor::Sonar:
02732                 sensor_pack() |= (1 << 4);
02733                 break;
02734             case Sensor::OpticalFlow:
02735                 sensor_pack() |= (1 << 5);
02736                 break;
02737             case Sensor::Pitot:
02738                 sensor_pack() |= (1 << 6);
02739                 break;
02740             case Sensor::GeneralHealth:
02741                 sensor_pack() |= (1 << 15);
02742                 break;
02743             }
02744         }
02745         rc &= data.pack(sensor_pack);
02746 
02747         Value<uint32_t> box_pack;
02748         box_pack = 0;
02749         for(const auto& b : box_mode_flags) {
02750             box_pack() |= (1 << b);
02751         }
02752         rc &= data.pack(box_pack);
02753         return rc;
02754     }
02755 };
02756 
02757 // MSP_STATUS: 101
02758 struct Status : public StatusBase, public Message {
02759     Status(FirmwareVariant v) : Message(v) {}
02760 
02761     virtual ID id() const override { return ID::MSP_STATUS; }
02762 
02763     Value<uint16_t> avg_system_load_pct;
02764     Value<uint16_t> gyro_cycle_time;
02765 
02766     virtual bool decode(const ByteVector& data) override {
02767         bool rc = true;
02768         rc &= StatusBase::unpack_from(data);
02769 
02770         if(fw_variant != FirmwareVariant::INAV) {
02771             rc &= data.unpack(avg_system_load_pct);
02772             rc &= data.unpack(gyro_cycle_time);
02773         }
02774         return rc;
02775     }
02776 
02777     bool hasAccelerometer() const {
02778         return sensors.count(Sensor::Accelerometer);
02779     }
02780 
02781     bool hasBarometer() const { return sensors.count(Sensor::Barometer); }
02782 
02783     bool hasMagnetometer() const { return sensors.count(Sensor::Magnetometer); }
02784 
02785     bool hasGPS() const { return sensors.count(Sensor::GPS); }
02786 
02787     bool hasSonar() const { return sensors.count(Sensor::Sonar); }
02788 
02789     bool hasOpticalFlow() const { return sensors.count(Sensor::OpticalFlow); }
02790 
02791     bool hasPitot() const { return sensors.count(Sensor::Pitot); }
02792 
02793     bool isHealthy() const { return sensors.count(Sensor::GeneralHealth); }
02794 
02795     virtual std::ostream& print(std::ostream& s) const override {
02796         s << "#Status:" << std::endl;
02797         s << " Cycle time: " << cycle_time << " us" << std::endl;
02798         s << " I2C errors: " << i2c_errors << std::endl;
02799         s << " Sensors:" << std::endl;
02800 
02801         s << "    Accelerometer: ";
02802         hasAccelerometer() ? s << "ON" : s << "OFF";
02803         s << std::endl;
02804 
02805         s << "    Barometer: ";
02806         hasBarometer() ? s << "ON" : s << "OFF";
02807         s << std::endl;
02808 
02809         s << "    Magnetometer: ";
02810         hasMagnetometer() ? s << "ON" : s << "OFF";
02811         s << std::endl;
02812 
02813         s << "    GPS: ";
02814         hasGPS() ? s << "ON" : s << "OFF";
02815         s << std::endl;
02816 
02817         s << "    Sonar: ";
02818         hasSonar() ? s << "ON" : s << "OFF";
02819         s << std::endl;
02820 
02821         s << " Active Boxes (by ID):";
02822         for(const size_t box_id : box_mode_flags) {
02823             s << " " << box_id;
02824         }
02825         s << std::endl;
02826 
02827         return s;
02828     }
02829 };
02830 
02831 // MSP_RAW_IMU: 102
02832 struct RawImu : public Message {
02833     RawImu(FirmwareVariant v) : Message(v) {}
02834 
02835     virtual ID id() const override { return ID::MSP_RAW_IMU; }
02836 
02837     std::array<Value<int16_t>, 3> acc;
02838     std::array<Value<int16_t>, 3> gyro;
02839     std::array<Value<int16_t>, 3> mag;
02840 
02841     virtual bool decode(const ByteVector& data) override {
02842         bool rc = true;
02843         for(auto& a : acc) {
02844             rc &= data.unpack(a);
02845         }
02846         for(auto& g : gyro) {
02847             rc &= data.unpack(g);
02848         }
02849         for(auto& m : mag) {
02850             rc &= data.unpack(m);
02851         }
02852         return rc;
02853     }
02854 
02855     virtual std::ostream& print(std::ostream& s) const override {
02856         s << "#Imu:" << std::endl;
02857         s << " Linear acceleration: " << acc[0] << ", " << acc[1] << ", "
02858           << acc[2] << std::endl;
02859         s << " Angular velocity: " << gyro[0] << ", " << gyro[1] << ", "
02860           << gyro[2] << std::endl;
02861         s << " Magnetometer: " << mag[0] << ", " << mag[1] << ", " << mag[2]
02862           << std::endl;
02863         return s;
02864     }
02865 };
02866 
02867 // helper class to convert raw imu readigs into standard physic units
02868 // custom scaling factors have to be derived from the sensor documentation
02869 struct ImuSI {
02870     std::array<Value<float>, 3> acc;   // m/s^2
02871     std::array<Value<float>, 3> gyro;  // deg/s
02872     std::array<Value<float>, 3> mag;   // uT
02873 
02874     ImuSI(RawImu raw,
02875           const float acc_1g,     // sensor value at 1g
02876           const float gyro_unit,  // resolution in 1/(deg/s)
02877           const float magn_gain,  // scale magnetic value to uT (micro Tesla)
02878           const float si_unit_1g  // acceleration at 1g (in m/s^2))
02879     ) {
02880         for(int i = 0; i < 3; ++i) {
02881             acc[i] = raw.acc[i]() / acc_1g * si_unit_1g;
02882         }
02883         for(int i = 0; i < 3; ++i) {
02884             gyro[i] = raw.gyro[i]() * gyro_unit;
02885         }
02886         for(int i = 0; i < 3; ++i) {
02887             mag[i] = raw.mag[i]() * magn_gain;
02888         }
02889     }
02890 
02891     std::ostream& print(std::ostream& s) const {
02892         s << "#Imu:" << std::endl;
02893         s << " Linear acceleration: " << acc[0] << ", " << acc[1] << ", "
02894           << acc[2] << " m/s²" << std::endl;
02895         s << " Angular velocity: " << gyro[0] << ", " << gyro[1] << ", "
02896           << gyro[2] << " deg/s" << std::endl;
02897         s << " Magnetometer: " << mag[0] << ", " << mag[1] << ", " << mag[2]
02898           << " uT" << std::endl;
02899         return s;
02900     }
02901 };
02902 
02903 // MSP_SERVO: 103
02904 struct Servo : public Message {
02905     Servo(FirmwareVariant v) : Message(v) {}
02906 
02907     virtual ID id() const override { return ID::MSP_SERVO; }
02908 
02909     std::array<uint16_t, N_SERVO> servo;
02910 
02911     virtual bool decode(const ByteVector& data) override {
02912         bool rc = true;
02913         for(auto& s : servo) rc &= data.unpack(s);
02914         return rc;
02915     }
02916 
02917     virtual std::ostream& print(std::ostream& s) const override {
02918         s << "#Servo:" << std::endl;
02919         s << " " << servo[0] << " " << servo[1] << " " << servo[2] << " "
02920           << servo[3] << std::endl;
02921         s << " " << servo[4] << " " << servo[5] << " " << servo[6] << " "
02922           << servo[7] << std::endl;
02923         return s;
02924     }
02925 };
02926 
02927 // MSP_MOTOR: 104
02928 struct Motor : public Message {
02929     Motor(FirmwareVariant v) : Message(v) {}
02930 
02931     virtual ID id() const override { return ID::MSP_MOTOR; }
02932 
02933     std::array<uint16_t, N_MOTOR> motor;
02934 
02935     virtual bool decode(const ByteVector& data) override {
02936         bool rc = true;
02937         for(auto& m : motor) rc &= data.unpack(m);
02938         return rc;
02939     }
02940 
02941     virtual std::ostream& print(std::ostream& s) const override {
02942         s << "#Motor:" << std::endl;
02943         s << " " << motor[0] << " " << motor[1] << " " << motor[2] << " "
02944           << motor[3] << std::endl;
02945         s << " " << motor[4] << " " << motor[5] << " " << motor[6] << " "
02946           << motor[7] << std::endl;
02947         return s;
02948     }
02949 };
02950 
02951 // MSP_RC: 105
02952 struct Rc : public Message {
02953     Rc(FirmwareVariant v) : Message(v) {}
02954 
02955     virtual ID id() const override { return ID::MSP_RC; }
02956 
02957     std::vector<uint16_t> channels;
02958 
02959     virtual bool decode(const ByteVector& data) override {
02960         channels.clear();
02961         bool rc = true;
02962         while(rc) {
02963             uint16_t rc_data;
02964             rc &= data.unpack(rc_data);
02965             if(rc) channels.push_back(rc_data);
02966         }
02967         return !channels.empty();
02968     }
02969 
02970     virtual std::ostream& print(std::ostream& s) const override {
02971         s << "#Rc channels (" << channels.size() << ") :" << std::endl;
02972         for(const uint16_t c : channels) {
02973             s << c << " ";
02974         }
02975         s << " " << std::endl;
02976         return s;
02977     }
02978 };
02979 
02980 // MSP_RAW_GPS: 106
02981 struct RawGPS : public Message {
02982     RawGPS(FirmwareVariant v) : Message(v) {}
02983 
02984     virtual ID id() const override { return ID::MSP_RAW_GPS; }
02985 
02986     Value<uint8_t> fix;
02987     Value<uint8_t> numSat;
02988     Value<float> lat;
02989     Value<float> lon;
02990     Value<float> altitude;
02991     Value<float> ground_speed;
02992     Value<float> ground_course;
02993     bool hdop_set;
02994     Value<float> hdop;
02995 
02996     virtual bool decode(const ByteVector& data) override {
02997         bool rc  = true;
02998         hdop_set = false;
02999         rc &= data.unpack(fix);
03000         rc &= data.unpack(numSat);
03001         rc &= data.unpack<int32_t>(lat, 1.f / 1e-7);
03002         rc &= data.unpack<int32_t>(lon, 1.f / 1e-7);
03003         rc &= data.unpack<int16_t>(altitude, 1.f);
03004         rc &= data.unpack<uint16_t>(ground_speed, 100.f);
03005         rc &= data.unpack<uint16_t>(ground_course, 10.f);
03006         if(data.unpacking_remaining()) {
03007             hdop_set = true;
03008             rc &= data.unpack<uint16_t>(hdop, 100.f);
03009         }
03010         return rc;
03011     }
03012 
03013     virtual std::ostream& print(std::ostream& s) const override {
03014         s << "#RawGPS:" << std::endl;
03015         s << " Fix: " << fix << std::endl;
03016         s << " Num Sat: " << numSat << std::endl;
03017         s << " Location: " << lat << " " << lon << std::endl;
03018         s << " Altitude: " << altitude << " m" << std::endl;
03019         s << " Ground speed: " << ground_speed << " m/s" << std::endl;
03020         s << " Ground course: " << ground_course << " deg" << std::endl;
03021         if(hdop_set) s << " HDOP: " << hdop << std::endl;
03022         return s;
03023     }
03024 };
03025 
03026 // MSP_COMP_GPS: 107
03027 struct CompGPS : public Message {
03028     CompGPS(FirmwareVariant v) : Message(v) {}
03029 
03030     virtual ID id() const override { return ID::MSP_COMP_GPS; }
03031 
03032     Value<uint16_t> distanceToHome;   // meter
03033     Value<uint16_t> directionToHome;  // degree
03034     Value<uint8_t> update;
03035 
03036     virtual bool decode(const ByteVector& data) override {
03037         bool rc = true;
03038         rc &= data.unpack(distanceToHome);
03039         rc &= data.unpack(directionToHome);
03040         rc &= data.unpack(update);
03041         return rc;
03042     }
03043 
03044     virtual std::ostream& print(std::ostream& s) const override {
03045         s << "#CompGPS:" << std::endl;
03046         s << " Distance: " << distanceToHome << std::endl;
03047         s << " Direction: " << directionToHome << std::endl;
03048         s << " Update: " << update << std::endl;
03049 
03050         return s;
03051     }
03052 };
03053 
03054 // TODO validate units
03055 // MSP_ATTITUDE: 108
03056 struct Attitude : public Message {
03057     Attitude(FirmwareVariant v) : Message(v) {}
03058 
03059     virtual ID id() const override { return ID::MSP_ATTITUDE; }
03060 
03061     Value<int16_t> roll;   // degree
03062     Value<int16_t> pitch;  // degree
03063     Value<int16_t> yaw;    // degree
03064 
03065     virtual bool decode(const ByteVector& data) override {
03066         bool rc = true;
03067         rc &= data.unpack(roll);
03068         rc &= data.unpack(pitch);
03069         rc &= data.unpack(yaw);
03070         return rc;
03071     }
03072 
03073     virtual std::ostream& print(std::ostream& s) const override {
03074         s << "#Attitude:" << std::endl;
03075         s << " Roll : " << roll << " deg" << std::endl;
03076         s << " Pitch : " << pitch << " deg" << std::endl;
03077         s << " Heading: " << yaw << " deg" << std::endl;
03078         return s;
03079     }
03080 };
03081 
03082 // TODO validate units
03083 // MSP_ALTITUDE: 109
03084 struct Altitude : public Message {
03085     Altitude(FirmwareVariant v) : Message(v) {}
03086 
03087     virtual ID id() const override { return ID::MSP_ALTITUDE; }
03088 
03089     Value<float> altitude;  // m
03090     Value<float> vario;     // m/s
03091     bool baro_altitude_set;
03092     Value<float> baro_altitude;
03093 
03094     virtual bool decode(const ByteVector& data) override {
03095         bool rc = true;
03096         rc &= data.unpack<int32_t>(altitude, 100.f);
03097         rc &= data.unpack<int16_t>(vario, 100.f);
03098         if(data.unpacking_remaining()) {
03099             baro_altitude_set = true;
03100             rc &= data.unpack<int32_t>(baro_altitude, 100.f);
03101         }
03102         return rc;
03103     }
03104 
03105     virtual std::ostream& print(std::ostream& s) const override {
03106         s << "#Altitude:" << std::endl;
03107         s << " Altitude: " << altitude << " m, var: " << vario << " m/s"
03108           << std::endl;
03109         s << " Barometer: ";
03110         if(baro_altitude_set)
03111             s << baro_altitude;
03112         else
03113             s << "<unset>";
03114         s << std::endl;
03115         return s;
03116     }
03117 };
03118 
03119 // TODO check amperage units
03120 // MSP_ANALOG: 110
03121 struct Analog : public Message {
03122     Analog(FirmwareVariant v) : Message(v) {}
03123 
03124     virtual ID id() const override { return ID::MSP_ANALOG; }
03125 
03126     Value<float> vbat;           // Volt
03127     Value<float> powerMeterSum;  // Ah
03128     Value<uint16_t> rssi;   // Received Signal Strength Indication [0; 1023]
03129     Value<float> amperage;  // Ampere
03130 
03131     virtual bool decode(const ByteVector& data) override {
03132         bool rc = true;
03133         rc &= data.unpack<uint8_t>(vbat, 0.1);
03134         rc &= data.unpack<uint16_t>(powerMeterSum, 0.001);
03135         rc &= data.unpack(rssi);
03136         rc &= data.unpack<int8_t>(amperage, 0.1);
03137         return rc;
03138     }
03139 
03140     virtual std::ostream& print(std::ostream& s) const override {
03141         s << "#Analog:" << std::endl;
03142         s << " Battery Voltage: " << vbat << " V" << std::endl;
03143         s << " Current: " << amperage << " A" << std::endl;
03144         s << " Power consumption: " << powerMeterSum << " Ah" << std::endl;
03145         s << " RSSI: " << rssi << std::endl;
03146         return s;
03147     }
03148 };
03149 
03150 struct RcTuningSettings {
03151     // RPY sequence
03152     std::array<Value<uint8_t>, 3> rates;
03153     std::array<Value<uint8_t>, 3> rcRates;
03154     std::array<Value<uint8_t>, 3> rcExpo;
03155 
03156     Value<uint8_t> dynamic_throttle_pid;
03157     Value<uint8_t> throttle_mid;
03158     Value<uint8_t> throttle_expo;
03159     Value<uint16_t> tpa_breakpoint;
03160 
03161     std::ostream& print(std::ostream& s) const {
03162         s << "#Rc Tuning:" << std::endl;
03163         s << " Rc Rate: " << rcRates[0] << " " << rcRates[1] << " "
03164           << rcRates[2] << std::endl;
03165         s << " Rc Expo: " << rcExpo[0] << " " << rcExpo[1] << " " << rcExpo[2]
03166           << std::endl;
03167 
03168         s << " Dynamic Throttle PID: " << dynamic_throttle_pid << std::endl;
03169         s << " Throttle MID: " << throttle_mid << std::endl;
03170         s << " Throttle Expo: " << throttle_expo << std::endl;
03171         return s;
03172     }
03173 };
03174 
03175 // Differences between iNav and BF/CF
03176 // MSP_RC_TUNING: 111
03177 struct RcTuning : public RcTuningSettings, public Message {
03178     RcTuning(FirmwareVariant v) : Message(v) {}
03179 
03180     virtual ID id() const override { return ID::MSP_RC_TUNING; }
03181 
03182     virtual bool decode(const ByteVector& data) override {
03183         bool rc = true;
03184         rc &= data.unpack(rcRates[0]);
03185         rc &= data.unpack(rcExpo[0]);
03186         for(size_t i = 0; i < 3; ++i) {
03187             rc &= data.unpack(rates[0]);
03188         }
03189         rc &= data.unpack(dynamic_throttle_pid);
03190         rc &= data.unpack(throttle_mid);
03191         rc &= data.unpack(throttle_expo);
03192         rc &= data.unpack(tpa_breakpoint);
03193         rc &= data.unpack(rcExpo[2]);
03194         if(fw_variant == FirmwareVariant::INAV) return rc;
03195         rc &= data.unpack(rcRates[2]);
03196         rc &= data.unpack(rcRates[1]);
03197         rc &= data.unpack(rcExpo[1]);
03198         return rc;
03199     }
03200 };
03201 
03202 // PID struct for messages 112 and 202
03203 struct PidTerms : public Packable {
03204     uint8_t P;
03205     uint8_t I;
03206     uint8_t D;
03207 
03208     bool unpack_from(const ByteVector& data) {
03209         bool rc = true;
03210         rc &= data.unpack(P);
03211         rc &= data.unpack(I);
03212         rc &= data.unpack(D);
03213         return rc;
03214     }
03215 
03216     bool pack_into(ByteVector& data) const {
03217         bool rc = true;
03218         rc &= data.pack(P);
03219         rc &= data.pack(I);
03220         rc &= data.pack(D);
03221         return rc;
03222     }
03223 };
03224 
03225 struct PidSettings {
03226     std::array<Value<PidTerms>,
03227                static_cast<uint8_t>(PID_Element::PID_ITEM_COUNT)>
03228         entry;
03229 
03230     std::ostream& print(std::ostream& s) const {
03231         uint8_t PID_ROLL =
03232             static_cast<uint8_t>(msp::msg::PID_Element::PID_ROLL);
03233         uint8_t PID_PITCH =
03234             static_cast<uint8_t>(msp::msg::PID_Element::PID_PITCH);
03235         uint8_t PID_YAW = static_cast<uint8_t>(msp::msg::PID_Element::PID_YAW);
03236         uint8_t PID_POS_Z =
03237             static_cast<uint8_t>(msp::msg::PID_Element::PID_POS_Z);
03238         uint8_t PID_POS_XY =
03239             static_cast<uint8_t>(msp::msg::PID_Element::PID_POS_XY);
03240         uint8_t PID_VEL_XY =
03241             static_cast<uint8_t>(msp::msg::PID_Element::PID_VEL_XY);
03242         uint8_t PID_SURFACE =
03243             static_cast<uint8_t>(msp::msg::PID_Element::PID_SURFACE);
03244         uint8_t PID_LEVEL =
03245             static_cast<uint8_t>(msp::msg::PID_Element::PID_LEVEL);
03246         uint8_t PID_HEADING =
03247             static_cast<uint8_t>(msp::msg::PID_Element::PID_HEADING);
03248         uint8_t PID_VEL_Z =
03249             static_cast<uint8_t>(msp::msg::PID_Element::PID_VEL_Z);
03250 
03251         s << std::setprecision(3);
03252         s << "#PID:" << std::endl;
03253         s << " Name      P     | I     | D     |" << std::endl;
03254         s << " ----------------|-------|-------|" << std::endl;
03255         s << " Roll:      " << entry[PID_ROLL]().P << "\t| "
03256           << entry[PID_ROLL]().I << "\t| " << entry[PID_ROLL]().D << std::endl;
03257         s << " Pitch:     " << entry[PID_PITCH]().P << "\t| "
03258           << entry[PID_PITCH]().I << "\t| " << entry[PID_PITCH]().D
03259           << std::endl;
03260         s << " Yaw:       " << entry[PID_YAW]().P << "\t| "
03261           << entry[PID_YAW]().I << "\t| " << entry[PID_YAW]().D << std::endl;
03262         s << " Altitude:  " << entry[PID_POS_Z]().P << "\t| "
03263           << entry[PID_POS_Z]().I << "\t| " << entry[PID_POS_Z]().D
03264           << std::endl;
03265 
03266         s << " Position:  " << entry[PID_POS_XY]().P << "\t| "
03267           << entry[PID_POS_XY]().I << "\t| " << entry[PID_POS_XY]().D
03268           << std::endl;
03269         s << " PositionR: " << entry[PID_VEL_XY]().P << "\t| "
03270           << entry[PID_VEL_XY]().I << "\t| " << entry[PID_VEL_XY]().D
03271           << std::endl;
03272         s << " NavR:      " << entry[PID_SURFACE]().P << "\t| "
03273           << entry[PID_SURFACE]().I << "\t| " << entry[PID_SURFACE]().D
03274           << std::endl;
03275         s << " Level:     " << entry[PID_LEVEL]().P << "\t| "
03276           << entry[PID_LEVEL]().I << "\t| " << entry[PID_LEVEL]().D
03277           << std::endl;
03278         s << " Magn:      " << entry[PID_HEADING]().P << "\t| "
03279           << entry[PID_HEADING]().I << "\t| " << entry[PID_HEADING]().D
03280           << std::endl;
03281         s << " Vel:       " << entry[PID_VEL_Z]().P << "\t| "
03282           << entry[PID_VEL_Z]().I << "\t| " << entry[PID_VEL_Z]().D
03283           << std::endl;
03284 
03285         return s;
03286     }
03287 };
03288 
03289 // TODO: revisit
03290 // MSP_PID: 112
03291 struct Pid : public PidSettings, public Message {
03292     Pid(FirmwareVariant v) : Message(v) {}
03293 
03294     virtual ID id() const override { return ID::MSP_PID; }
03295 
03296     virtual bool decode(const ByteVector& data) override {
03297         bool rc = true;
03298         for(uint8_t i = 0;
03299             i < static_cast<uint8_t>(PID_Element::PID_ITEM_COUNT);
03300             ++i) {
03301             rc &= data.unpack(entry[i]);
03302         }
03303         return rc;
03304     }
03305 };
03306 
03307 // MSP_ACTIVEBOXES: 113
03308 struct ActiveBoxes : public Message {
03309     ActiveBoxes(FirmwareVariant v) : Message(v) {}
03310 
03311     virtual ID id() const override { return ID::MSP_ACTIVEBOXES; }
03312 
03313     // box activation pattern
03314     std::vector<std::array<std::set<SwitchPosition>, NAUX>> box_pattern;
03315 
03316     virtual bool decode(const ByteVector& data) override {
03317         box_pattern.clear();
03318         bool rc = true;
03319         while(rc && data.unpacking_remaining() > 1) {
03320             Value<uint16_t> box_conf;
03321             rc &= data.unpack(box_conf);
03322             std::array<std::set<SwitchPosition>, NAUX> aux_sp;
03323             for(size_t iaux(0); iaux < NAUX; iaux++) {
03324                 for(size_t ip(0); ip < 3; ip++) {
03325                     if(box_conf() & (1 << (iaux * 3 + ip)))
03326                         aux_sp[iaux].insert(SwitchPosition(ip));
03327                 }  // each position (L,M,H)
03328             }      // each aux switch
03329             box_pattern.push_back(aux_sp);
03330         }  // each box
03331         return rc;
03332     }
03333 
03334     virtual std::ostream& print(std::ostream& s) const override {
03335         s << "#Box:" << std::endl;
03336         for(size_t ibox(0); ibox < box_pattern.size(); ibox++) {
03337             s << ibox << " ";
03338             for(size_t iaux(0); iaux < box_pattern[ibox].size(); iaux++) {
03339                 s << "aux" << iaux + 1 << ": ";
03340                 if(box_pattern[ibox][iaux].count(msp::msg::SwitchPosition::LOW))
03341                     s << "L";
03342                 else
03343                     s << "_";
03344                 if(box_pattern[ibox][iaux].count(msp::msg::SwitchPosition::MID))
03345                     s << "M";
03346                 else
03347                     s << "_";
03348                 if(box_pattern[ibox][iaux].count(
03349                        msp::msg::SwitchPosition::HIGH))
03350                     s << "H";
03351                 else
03352                     s << "_";
03353                 s << ", ";
03354             }
03355             s << std::endl;
03356         }
03357 
03358         return s;
03359     }
03360 };
03361 
03362 struct MiscSettings {
03363     Value<uint16_t> mid_rc;
03364     Value<uint16_t> min_throttle;
03365     Value<uint16_t> max_throttle;
03366     Value<uint16_t> min_command;
03367     Value<uint16_t> failsafe_throttle;
03368     Value<uint8_t> gps_provider;
03369     Value<uint8_t> gps_baudrate;
03370     Value<uint8_t> gps_ubx_sbas;
03371     Value<uint8_t> multiwii_current_meter_output;
03372     Value<uint8_t> rssi_channel;
03373     Value<uint8_t> reserved;
03374     Value<float> mag_declination;  // degree
03375     Value<float> voltage_scale, cell_min, cell_max, cell_warning;
03376 
03377     std::ostream& print(std::ostream& s) const {
03378         s << "#Miscellaneous:" << std::endl;
03379         s << " Mid rc: " << mid_rc << std::endl;
03380         s << " Min Throttle: " << min_throttle << std::endl;
03381         s << " Max Throttle: " << max_throttle << std::endl;
03382         s << " Failsafe Throttle: " << failsafe_throttle << std::endl;
03383 
03384         s << " Magnetic Declination: " << mag_declination << " deg"
03385           << std::endl;
03386         s << " Battery Voltage Scale: " << voltage_scale << " V" << std::endl;
03387         s << " Battery Warning Level 1: " << cell_min << " V" << std::endl;
03388         s << " Battery Warning Level 2: " << cell_max << " V" << std::endl;
03389         s << " Battery Critical Level: " << cell_warning << " V" << std::endl;
03390 
03391         return s;
03392     }
03393 };
03394 
03395 // MSP_MISC: 114
03396 struct Misc : public MiscSettings, public Message {
03397     Misc(FirmwareVariant v) : Message(v) {}
03398 
03399     virtual ID id() const override { return ID::MSP_MISC; }
03400 
03401     virtual bool decode(const ByteVector& data) override {
03402         bool rc = true;
03403         rc &= data.unpack(mid_rc);
03404         rc &= data.unpack(min_throttle);
03405         rc &= data.unpack(max_throttle);
03406         rc &= data.unpack(min_command);
03407         rc &= data.unpack(failsafe_throttle);
03408         rc &= data.unpack(gps_provider);
03409         rc &= data.unpack(gps_baudrate);
03410         rc &= data.unpack(gps_ubx_sbas);
03411         rc &= data.unpack(multiwii_current_meter_output);
03412         rc &= data.unpack(rssi_channel);
03413         rc &= data.unpack(reserved);
03414 
03415         rc &= data.unpack<uint16_t>(mag_declination, 0.1);
03416         rc &= data.unpack<uint8_t>(voltage_scale, 0.1);
03417         rc &= data.unpack<uint8_t>(cell_min, 0.1);
03418         rc &= data.unpack<uint8_t>(cell_max, 0.1);
03419         rc &= data.unpack<uint8_t>(cell_warning, 0.1);
03420         return rc;
03421     }
03422 };
03423 
03424 // MSP_MOTOR_PINS: 115
03425 struct MotorPins : public Message {
03426     MotorPins(FirmwareVariant v) : Message(v) {}
03427 
03428     virtual ID id() const override { return ID::MSP_MOTOR_PINS; }
03429 
03430     Value<uint8_t> pwm_pin[N_MOTOR];
03431 
03432     virtual bool decode(const ByteVector& data) override {
03433         bool rc = true;
03434         for(auto& pin : pwm_pin) rc &= data.unpack(pin);
03435         return rc;
03436     }
03437 
03438     virtual std::ostream& print(std::ostream& s) const override {
03439         s << "#Motor pins:" << std::endl;
03440         for(size_t imotor(0); imotor < msp::msg::N_MOTOR; imotor++) {
03441             s << " Motor " << imotor << ": pin " << size_t(pwm_pin[imotor]())
03442               << std::endl;
03443         }
03444 
03445         return s;
03446     }
03447 };
03448 
03449 // MSP_BOXNAMES: 116
03450 struct BoxNames : public Message {
03451     BoxNames(FirmwareVariant v) : Message(v) {}
03452 
03453     virtual ID id() const override { return ID::MSP_BOXNAMES; }
03454 
03455     std::vector<std::string> box_names;
03456 
03457     virtual bool decode(const ByteVector& data) override {
03458         box_names.clear();
03459         bool rc = true;
03460         std::string str;
03461         rc &= data.unpack(str);
03462         std::stringstream ss(str);
03463         std::string bname;
03464         while(getline(ss, bname, ';')) {
03465             box_names.push_back(bname);
03466         }
03467         return rc;
03468     }
03469 
03470     virtual std::ostream& print(std::ostream& s) const override {
03471         s << "# Box names:" << std::endl;
03472         for(size_t ibox(0); ibox < box_names.size(); ibox++) {
03473             s << " " << ibox << ": " << box_names[ibox] << std::endl;
03474         }
03475         return s;
03476     }
03477 };
03478 
03479 // MSP_PIDNAMES: 117
03480 struct PidNames : public Message {
03481     PidNames(FirmwareVariant v) : Message(v) {}
03482 
03483     virtual ID id() const override { return ID::MSP_PIDNAMES; }
03484 
03485     std::vector<std::string> pid_names;
03486 
03487     virtual bool decode(const ByteVector& data) override {
03488         pid_names.clear();
03489         bool rc = true;
03490         std::string str;
03491         rc &= data.unpack(str);
03492         std::stringstream ss(str);
03493         std::string pname;
03494         while(getline(ss, pname, ';')) {
03495             pid_names.push_back(pname);
03496         }
03497         return rc;
03498     }
03499 
03500     virtual std::ostream& print(std::ostream& s) const override {
03501         s << "#PID names:" << std::endl;
03502         for(size_t ipid(0); ipid < pid_names.size(); ipid++) {
03503             s << " " << ipid << ": " << pid_names[ipid] << std::endl;
03504         }
03505         return s;
03506     }
03507 };
03508 
03509 // MSP_WP: 118
03510 struct WayPoint : public Message {
03511     WayPoint(FirmwareVariant v) : Message(v) {}
03512 
03513     virtual ID id() const override { return ID::MSP_WP; }
03514 
03515     Value<uint8_t> wp_no;
03516     Value<uint32_t> lat;
03517     Value<uint32_t> lon;
03518     Value<uint32_t> altHold;
03519     Value<uint16_t> heading;
03520     Value<uint16_t> staytime;
03521     Value<uint8_t> navflag;
03522 
03523     virtual bool decode(const ByteVector& data) override {
03524         bool rc = true;
03525         rc &= data.unpack(wp_no);
03526         rc &= data.unpack(lat);
03527         rc &= data.unpack(lon);
03528         rc &= data.unpack(altHold);
03529         rc &= data.unpack(heading);
03530         rc &= data.unpack(staytime);
03531         rc &= data.unpack(navflag);
03532         return rc;
03533     }
03534 };
03535 
03536 // MSP_BOXIDS: 119
03537 struct BoxIds : public Message {
03538     BoxIds(FirmwareVariant v) : Message(v) {}
03539 
03540     virtual ID id() const override { return ID::MSP_BOXIDS; }
03541 
03542     ByteVector box_ids;
03543 
03544     virtual bool decode(const ByteVector& data) override {
03545         box_ids.clear();
03546 
03547         for(uint8_t bi : data) box_ids.push_back(bi);
03548         ;
03549 
03550         return true;
03551     }
03552 
03553     virtual std::ostream& print(std::ostream& s) const override {
03554         s << "#Box IDs:" << std::endl;
03555         for(size_t ibox(0); ibox < box_ids.size(); ibox++) {
03556             s << " " << ibox << ": " << size_t(box_ids[ibox]) << std::endl;
03557         }
03558         return s;
03559     }
03560 };
03561 
03562 struct ServoConfRange {
03563     Value<uint16_t> min;
03564     Value<uint16_t> max;
03565     Value<uint16_t> middle;
03566     Value<uint8_t> rate;
03567 };
03568 
03569 // MSP_SERVO_CONF: 120
03570 struct ServoConf : public Message {
03571     ServoConf(FirmwareVariant v) : Message(v) {}
03572 
03573     virtual ID id() const override { return ID::MSP_SERVO_CONF; }
03574 
03575     ServoConfRange servo_conf[N_SERVO];
03576 
03577     virtual bool decode(const ByteVector& data) override {
03578         bool rc = true;
03579         for(size_t i(0); i < N_SERVO; i++) {
03580             rc &= data.unpack(servo_conf[i].min);
03581             rc &= data.unpack(servo_conf[i].max);
03582             rc &= data.unpack(servo_conf[i].middle);
03583             rc &= data.unpack(servo_conf[i].rate);
03584         }
03585         return rc;
03586     }
03587 };
03588 
03589 // MSP_NAV_STATUS: 121
03590 struct NavStatus : public Message {
03591     NavStatus(FirmwareVariant v) : Message(v) {}
03592 
03593     virtual ID id() const override { return ID::MSP_NAV_STATUS; }
03594 
03595     Value<uint8_t> GPS_mode;
03596     Value<uint8_t> NAV_state;
03597     Value<uint8_t> mission_action;
03598     Value<uint8_t> mission_number;
03599     Value<uint8_t> NAV_error;
03600     int16_t target_bearing;  // degrees
03601 
03602     virtual bool decode(const ByteVector& data) override {
03603         bool rc = true;
03604         rc &= data.unpack(GPS_mode);
03605         rc &= data.unpack(NAV_state);
03606         rc &= data.unpack(mission_action);
03607         rc &= data.unpack(mission_number);
03608         rc &= data.unpack(NAV_error);
03609         rc &= data.unpack(target_bearing);
03610         return rc;
03611     }
03612 };
03613 
03614 struct GpsConf {
03615     uint8_t filtering;
03616     uint8_t lead_filter;
03617     uint8_t dont_reset_home_at_arm;
03618     uint8_t nav_controls_heading;
03619 
03620     uint8_t nav_tail_first;
03621     uint8_t nav_rth_takeoff_heading;
03622     uint8_t slow_nav;
03623     uint8_t wait_for_rth_alt;
03624 
03625     uint8_t ignore_throttle;
03626     uint8_t takeover_baro;
03627 
03628     uint16_t wp_radius;         // in cm
03629     uint16_t safe_wp_distance;  // in meter
03630     uint16_t nav_max_altitude;  // in meter
03631     uint16_t nav_speed_max;     // in cm/s
03632     uint16_t nav_speed_min;     // in cm/s
03633 
03634     uint8_t crosstrack_gain;  // * 100 (0-2.56)
03635     uint16_t nav_bank_max;    // degree * 100; (3000 default)
03636     uint16_t rth_altitude;    // in meter
03637     uint8_t land_speed;       // between 50 and 255 (100 approx = 50cm/sec)
03638     uint16_t fence;           // fence control in meters
03639 
03640     uint8_t max_wp_number;
03641 
03642     uint8_t checksum;
03643 };
03644 
03645 // MSP_NAV_CONFIG: 122
03646 struct NavConfig : public Message, public GpsConf {
03647     NavConfig(FirmwareVariant v) : Message(v) {}
03648 
03649     virtual ID id() const override { return ID::MSP_NAV_CONFIG; }
03650 
03651     virtual bool decode(const ByteVector& data) override {
03652         bool rc = true;
03653         rc &= data.unpack(filtering);
03654         rc &= data.unpack(lead_filter);
03655         rc &= data.unpack(dont_reset_home_at_arm);
03656         rc &= data.unpack(nav_controls_heading);
03657 
03658         rc &= data.unpack(nav_tail_first);
03659         rc &= data.unpack(nav_rth_takeoff_heading);
03660         rc &= data.unpack(slow_nav);
03661         rc &= data.unpack(wait_for_rth_alt);
03662 
03663         rc &= data.unpack(ignore_throttle);
03664         rc &= data.unpack(takeover_baro);
03665 
03666         rc &= data.unpack(wp_radius);
03667         rc &= data.unpack(safe_wp_distance);
03668         rc &= data.unpack(nav_max_altitude);
03669         rc &= data.unpack(nav_speed_max);
03670         rc &= data.unpack(nav_speed_min);
03671 
03672         rc &= data.unpack(crosstrack_gain);
03673         rc &= data.unpack(nav_bank_max);
03674         rc &= data.unpack(rth_altitude);
03675         rc &= data.unpack(land_speed);
03676         rc &= data.unpack(fence);
03677 
03678         rc &= data.unpack(max_wp_number);
03679         rc &= data.unpack(checksum);
03680 
03681         return rc;
03682     }
03683 };
03684 
03685 struct Motor3dConfig : public Message {
03686     Motor3dConfig(FirmwareVariant v) : Message(v) {}
03687 
03688     virtual ID id() const override { return ID::MSP_MOTOR_3D_CONFIG; }
03689 
03690     Value<uint16_t> deadband3d_low;
03691     Value<uint16_t> deadband3d_high;
03692     Value<uint16_t> neutral_3d;
03693 
03694     virtual bool decode(const ByteVector& data) override {
03695         bool rc = true;
03696         rc &= data.unpack(deadband3d_low);
03697         rc &= data.unpack(deadband3d_high);
03698         rc &= data.unpack(neutral_3d);
03699         return rc;
03700     }
03701 };
03702 
03703 struct RcDeadbandSettings {
03704     Value<uint8_t> deadband;
03705     Value<uint8_t> yaw_deadband;
03706     Value<uint8_t> alt_hold_deadband;
03707     Value<uint16_t> deadband3d_throttle;
03708 };
03709 
03710 struct RcDeadband : public RcDeadbandSettings, public Message {
03711     RcDeadband(FirmwareVariant v) : Message(v) {}
03712 
03713     virtual ID id() const override { return ID::MSP_RC_DEADBAND; }
03714 
03715     virtual bool decode(const ByteVector& data) override {
03716         bool rc = true;
03717         rc &= data.unpack(deadband);
03718         rc &= data.unpack(yaw_deadband);
03719         rc &= data.unpack(alt_hold_deadband);
03720         rc &= data.unpack(deadband3d_throttle);
03721         return rc;
03722     }
03723 };
03724 
03725 struct SensorAlignmentSettings {
03726     Value<uint8_t> gyro_align;
03727     Value<uint8_t> acc_align;
03728     Value<uint8_t> mag_align;
03729 };
03730 
03731 struct SensorAlignment : public SensorAlignmentSettings, public Message {
03732     SensorAlignment(FirmwareVariant v) : Message(v) {}
03733 
03734     virtual ID id() const override { return ID::MSP_SENSOR_ALIGNMENT; }
03735 
03736     virtual bool decode(const ByteVector& data) override {
03737         bool rc = true;
03738         rc &= data.unpack(gyro_align);
03739         rc &= data.unpack(acc_align);
03740         rc &= data.unpack(mag_align);
03741         return rc;
03742     }
03743 };
03744 
03745 struct LedStripModecolor : public Message {
03746     LedStripModecolor(FirmwareVariant v) : Message(v) {}
03747 
03748     virtual ID id() const override { return ID::MSP_LED_STRIP_MODECOLOR; }
03749 
03750     std::array<std::array<uint8_t, LED_DIRECTION_COUNT>, LED_MODE_COUNT>
03751         mode_colors;
03752     std::array<uint8_t, LED_SPECIAL_COLOR_COUNT> special_colors;
03753     Value<uint8_t> led_aux_channel;
03754     Value<uint8_t> reserved;
03755     Value<uint8_t> led_strip_aux_channel;
03756 
03757     virtual bool decode(const ByteVector& data) override {
03758         bool rc = true;
03759         for(auto& mode : mode_colors) {
03760             for(auto& color : mode) {
03761                 rc &= data.unpack(color);
03762             }
03763         }
03764         for(auto& special : special_colors) {
03765             rc &= data.unpack(special);
03766         }
03767 
03768         rc &= data.unpack(led_aux_channel);
03769         rc &= data.unpack(reserved);
03770         rc &= data.unpack(led_strip_aux_channel);
03771         return rc;
03772     }
03773 };
03774 
03775 struct VoltageMeter {
03776     Value<uint8_t> id;
03777     Value<uint8_t> val;
03778 };
03779 
03780 struct VoltageMeters : public Message {
03781     VoltageMeters(FirmwareVariant v) : Message(v) {}
03782 
03783     virtual ID id() const override { return ID::MSP_VOLTAGE_METERS; }
03784 
03785     std::vector<VoltageMeter> meters;
03786 
03787     virtual bool decode(const ByteVector& data) override {
03788         bool rc = true;
03789         for(auto& meter : meters) {
03790             rc &= data.unpack(meter.id);
03791             rc &= data.unpack(meter.val);
03792         }
03793         return rc;
03794     }
03795 };
03796 
03797 struct CurrentMeter {
03798     Value<uint8_t> id;
03799     Value<uint16_t> mAh_drawn;
03800     Value<uint16_t> mA;
03801 };
03802 
03803 struct CurrentMeters : public Message {
03804     CurrentMeters(FirmwareVariant v) : Message(v) {}
03805 
03806     virtual ID id() const override { return ID::MSP_CURRENT_METERS; }
03807 
03808     std::vector<CurrentMeter> meters;
03809 
03810     virtual bool decode(const ByteVector& data) override {
03811         bool rc = true;
03812         for(auto& meter : meters) {
03813             rc &= data.unpack(meter.id);
03814             rc &= data.unpack(meter.mAh_drawn);
03815             rc &= data.unpack(meter.mA);
03816         }
03817         return rc;
03818     }
03819 };
03820 
03821 struct BatteryState : public Message {
03822     BatteryState(FirmwareVariant v) : Message(v) {}
03823 
03824     virtual ID id() const override { return ID::MSP_BATTERY_STATE; }
03825 
03826     Value<uint8_t> cell_count;
03827     Value<uint16_t> capacity_mAh;
03828     Value<uint8_t> voltage;
03829     Value<uint16_t> mAh_drawn;
03830     Value<uint16_t> current;
03831     Value<uint8_t> state;
03832 
03833     virtual bool decode(const ByteVector& data) override {
03834         bool rc = true;
03835         rc &= data.unpack(cell_count);
03836         rc &= data.unpack(capacity_mAh);
03837         rc &= data.unpack(voltage);
03838         rc &= data.unpack(mAh_drawn);
03839         rc &= data.unpack(current);
03840         rc &= data.unpack(state);
03841         return rc;
03842     }
03843 };
03844 
03845 struct MotorConfigSettings {
03846     Value<uint16_t> min_throttle;
03847     Value<uint16_t> max_throttle;
03848     Value<uint16_t> min_command;
03849 };
03850 
03851 struct MotorConfig : public MotorConfigSettings, public Message {
03852     MotorConfig(FirmwareVariant v) : Message(v) {}
03853 
03854     virtual ID id() const override { return ID::MSP_MOTOR_CONFIG; }
03855 
03856     virtual bool decode(const ByteVector& data) override {
03857         bool rc = true;
03858         rc &= data.unpack(min_throttle);
03859         rc &= data.unpack(max_throttle);
03860         rc &= data.unpack(min_command);
03861         return rc;
03862     }
03863 };
03864 
03865 struct GpsConfigSettings {
03866     Value<uint8_t> provider;
03867     Value<uint8_t> sbas_mode;
03868     Value<uint8_t> auto_config;
03869     Value<uint8_t> auto_baud;
03870 };
03871 
03872 struct GpsConfig : public GpsConfigSettings, public Message {
03873     GpsConfig(FirmwareVariant v) : Message(v) {}
03874 
03875     virtual ID id() const override { return ID::MSP_GPS_CONFIG; }
03876 
03877     virtual bool decode(const ByteVector& data) override {
03878         bool rc = true;
03879         rc &= data.unpack(provider);
03880         rc &= data.unpack(sbas_mode);
03881         rc &= data.unpack(auto_config);
03882         rc &= data.unpack(auto_baud);
03883         return rc;
03884     }
03885 };
03886 
03887 struct CompassConfig : public Message {
03888     CompassConfig(FirmwareVariant v) : Message(v) {}
03889 
03890     virtual ID id() const override { return ID::MSP_COMPASS_CONFIG; }
03891 
03892     Value<uint16_t> mag_declination;
03893 
03894     virtual bool decode(const ByteVector& data) override {
03895         return data.unpack(mag_declination);
03896     }
03897 };
03898 
03899 struct EscData {
03900     Value<uint8_t> temperature;
03901     Value<uint16_t> rpm;
03902 };
03903 
03904 struct EscSensorData : public Message {
03905     EscSensorData(FirmwareVariant v) : Message(v) {}
03906 
03907     virtual ID id() const override { return ID::MSP_ESC_SENSOR_DATA; }
03908 
03909     Value<uint8_t> motor_count;
03910     std::vector<EscData> esc_data;
03911 
03912     virtual bool decode(const ByteVector& data) override {
03913         if(data.empty()) {
03914             motor_count = 0;
03915             return true;
03916         }
03917         bool rc = true;
03918         rc &= data.unpack(motor_count);
03919         for(int i = 0; i < motor_count(); ++i) {
03920             EscData esc;
03921             rc &= data.unpack(esc.temperature);
03922             rc &= data.unpack(esc.rpm);
03923             esc_data.push_back(esc);
03924         }
03925         return rc;
03926     }
03927 };
03928 
03929 struct StatusEx : public StatusBase, public Message {
03930     StatusEx(FirmwareVariant v) : Message(v) {}
03931 
03932     virtual ID id() const override { return ID::MSP_STATUS_EX; }
03933 
03934     // bf/cf fields
03935     Value<uint8_t> max_profiles;
03936     Value<uint8_t> control_rate_profile;
03937     // iNav fields
03938     Value<uint16_t> avg_system_load_pct;
03939     Value<uint16_t> arming_flags;
03940     Value<uint8_t> acc_calibration_axis_flags;
03941 
03942     virtual bool decode(const ByteVector& data) override {
03943         bool rc = true;
03944         rc &= StatusBase::unpack_from(data);
03945         if(fw_variant == FirmwareVariant::INAV) {
03946             rc &= data.unpack(avg_system_load_pct);
03947             rc &= data.unpack(arming_flags);
03948             rc &= data.unpack(acc_calibration_axis_flags);
03949         }
03950         else {
03951             rc &= data.unpack(max_profiles);
03952             rc &= data.unpack(control_rate_profile);
03953         }
03954         return rc;
03955     }
03956 };
03957 
03958 struct SensorStatus : public Message {
03959     SensorStatus(FirmwareVariant v) : Message(v) {}
03960 
03961     virtual ID id() const override { return ID::MSP_SENSOR_STATUS; }
03962 
03963     Value<uint8_t> hardware_healthy;
03964     Value<uint8_t> hw_gyro_status;
03965     Value<uint8_t> hw_acc_status;
03966     Value<uint8_t> hw_compass_status;
03967     Value<uint8_t> hw_baro_status;
03968     Value<uint8_t> hw_gps_status;
03969     Value<uint8_t> hw_rangefinder_status;
03970     Value<uint8_t> hw_pitometer_status;
03971     Value<uint8_t> hw_optical_flow_status;
03972 
03973     virtual bool decode(const ByteVector& data) override {
03974         bool rc = true;
03975         rc &= data.unpack(hardware_healthy);
03976         rc &= data.unpack(hw_gyro_status);
03977         rc &= data.unpack(hw_acc_status);
03978         rc &= data.unpack(hw_compass_status);
03979         rc &= data.unpack(hw_baro_status);
03980         rc &= data.unpack(hw_gps_status);
03981         rc &= data.unpack(hw_rangefinder_status);
03982         rc &= data.unpack(hw_pitometer_status);
03983         rc &= data.unpack(hw_optical_flow_status);
03984         return rc;
03985     }
03986 };
03987 
03988 // MSP_UID                         = 160,
03989 struct Uid : public Message {
03990     Uid(FirmwareVariant v) : Message(v) {}
03991 
03992     virtual ID id() const override { return ID::MSP_UID; }
03993 
03994     Value<uint32_t> u_id_0;
03995     Value<uint32_t> u_id_1;
03996     Value<uint32_t> u_id_2;
03997 
03998     virtual bool decode(const ByteVector& data) override {
03999         bool rc = true;
04000         rc &= data.unpack(u_id_0);
04001         rc &= data.unpack(u_id_1);
04002         rc &= data.unpack(u_id_2);
04003         return rc;
04004     }
04005 };
04006 
04007 struct GpsSvInfoSettings {
04008     uint8_t channel;
04009     uint8_t sv_id;
04010     uint8_t quality;
04011     uint8_t cno;
04012 };
04013 
04014 // MSP_GPSSVINFO                   = 164,
04015 struct GpsSvInfo : public Message {
04016     GpsSvInfo(FirmwareVariant v) : Message(v) {}
04017 
04018     virtual ID id() const override { return ID::MSP_GPSSVINFO; }
04019 
04020     Value<uint8_t> hdop;
04021 
04022     Value<uint8_t> channel_count;
04023     std::vector<GpsSvInfoSettings> sv_info;
04024 
04025     virtual bool decode(const ByteVector& data) override {
04026         bool rc = true;
04027         if(fw_variant == FirmwareVariant::INAV) {
04028             rc &= data.consume(4);
04029             rc &= data.unpack(hdop);
04030         }
04031         else {
04032             rc &= data.unpack(channel_count);
04033             for(uint8_t i = 0; i < channel_count(); ++i) {
04034                 GpsSvInfoSettings tmp;
04035                 rc &= data.unpack(tmp.channel);
04036                 rc &= data.unpack(tmp.sv_id);
04037                 rc &= data.unpack(tmp.quality);
04038                 rc &= data.unpack(tmp.cno);
04039             }
04040         }
04041         return rc;
04042     }
04043 };
04044 
04045 // MSP_GPSSTATISTICS               = 166,
04046 struct GpsStatistics : public Message {
04047     GpsStatistics(FirmwareVariant v) : Message(v) {}
04048 
04049     virtual ID id() const override { return ID::MSP_GPSSTATISTICS; }
04050 
04051     Value<uint16_t> last_msg_dt;
04052     Value<uint32_t> errors;
04053     Value<uint32_t> timeouts;
04054     Value<uint32_t> packet_count;
04055     Value<uint16_t> hdop;
04056     Value<uint16_t> eph;
04057     Value<uint16_t> epv;
04058 
04059     virtual bool decode(const ByteVector& data) override {
04060         bool rc = true;
04061         rc &= data.unpack(last_msg_dt);
04062         rc &= data.unpack(errors);
04063         rc &= data.unpack(timeouts);
04064         rc &= data.unpack(packet_count);
04065         rc &= data.unpack(hdop);
04066         rc &= data.unpack(eph);
04067         rc &= data.unpack(epv);
04068         return rc;
04069     }
04070 };
04071 
04072 // no actual implementations
04073 // MSP_OSD_VIDEO_CONFIG            = 180,
04074 struct OsdVideoConfig : public Message {
04075     OsdVideoConfig(FirmwareVariant v) : Message(v) {}
04076 
04077     virtual ID id() const override { return ID::MSP_OSD_VIDEO_CONFIG; }
04078 
04079     virtual bool decode(const ByteVector& /*data*/) override { return false; }
04080 };
04081 
04082 // MSP_SET_OSD_VIDEO_CONFIG        = 181,
04083 struct SetOsdVideoConfig : public Message {
04084     SetOsdVideoConfig(FirmwareVariant v) : Message(v) {}
04085 
04086     virtual ID id() const override { return ID::MSP_SET_OSD_VIDEO_CONFIG; }
04087 };
04088 
04089 // MSP_DISPLAYPORT                 = 182,
04090 struct Displayport : public Message {
04091     Displayport(FirmwareVariant v) : Message(v) {}
04092 
04093     virtual ID id() const override { return ID::MSP_DISPLAYPORT; }
04094 
04095     Value<uint8_t> sub_cmd;
04096     Value<uint8_t> row;
04097     Value<uint8_t> col;
04098     Value<std::string> str;
04099 
04100     virtual ByteVectorUptr encode() const override {
04101         ByteVectorUptr data = std::make_unique<ByteVector>();
04102         bool rc             = true;
04103         rc &= data->pack(sub_cmd);
04104         if(sub_cmd() == 3) {
04105             rc &= data->pack(row);
04106             rc &= data->pack(col);
04107             rc &= data->pack(uint8_t(0));
04108             rc &= data->pack(uint8_t(str().size()));
04109             rc &= data->pack(str);
04110         }
04111         if(!rc) data.reset();
04112         return data;
04113     }
04114 };
04115 
04116 // Not available in iNav (183-185)
04117 // MSP_COPY_PROFILE                = 183,
04118 struct CopyProfile : public Message {
04119     CopyProfile(FirmwareVariant v) : Message(v) {}
04120 
04121     virtual ID id() const override { return ID::MSP_COPY_PROFILE; }
04122 
04123     Value<uint8_t> profile_type;
04124     Value<uint8_t> dest_profile_idx;
04125     Value<uint8_t> src_profile_idx;
04126 
04127     virtual ByteVectorUptr encode() const override {
04128         ByteVectorUptr data = std::make_unique<ByteVector>();
04129         bool rc             = true;
04130         rc &= data->pack(profile_type);
04131         rc &= data->pack(dest_profile_idx);
04132         rc &= data->pack(src_profile_idx);
04133         if(!rc) data.reset();
04134         return data;
04135     }
04136 };
04137 
04138 struct BeeperConfigSettings {
04139     Value<uint32_t> beeper_off_mask;
04140     Value<uint8_t> beacon_tone;
04141 };
04142 
04143 // MSP_BEEPER_CONFIG               = 184,
04144 struct BeeperConfig : public BeeperConfigSettings, public Message {
04145     BeeperConfig(FirmwareVariant v) : Message(v) {}
04146 
04147     virtual ID id() const override { return ID::MSP_BEEPER_CONFIG; }
04148 
04149     virtual bool decode(const ByteVector& data) override {
04150         bool rc = true;
04151         rc &= data.unpack(beeper_off_mask);
04152         rc &= data.unpack(beacon_tone);
04153         return rc;
04154     }
04155 };
04156 
04157 // MSP_SET_BEEPER_CONFIG           = 185,
04158 struct SetBeeperConfig : public BeeperConfigSettings, public Message {
04159     SetBeeperConfig(FirmwareVariant v) : Message(v) {}
04160 
04161     virtual ID id() const override { return ID::MSP_SET_BEEPER_CONFIG; }
04162 
04163     virtual ByteVectorUptr encode() const override {
04164         ByteVectorUptr data = std::make_unique<ByteVector>();
04165         bool rc             = true;
04166         rc &= data->pack(beeper_off_mask);
04167         if(beacon_tone.set()) {
04168             rc &= data->pack(beacon_tone);
04169         }
04170         if(!rc) data.reset();
04171         return data;
04172     }
04173 };
04174 
04175 // MSP_SET_TX_INFO                 = 186, // in message           Used to send
04176 // runtime information from TX lua scripts to the firmware
04177 struct SetTxInfo : public Message {
04178     SetTxInfo(FirmwareVariant v) : Message(v) {}
04179 
04180     virtual ID id() const override { return ID::MSP_SET_TX_INFO; }
04181 
04182     Value<uint8_t> rssi;
04183 
04184     virtual ByteVectorUptr encode() const override {
04185         ByteVectorUptr data = std::make_unique<ByteVector>();
04186         if(!data->pack(rssi)) data.reset();
04187         return data;
04188     }
04189 };
04190 
04191 // MSP_TX_INFO                     = 187, // out message          Used by TX lua
04192 // scripts to read information from the firmware
04193 struct TxInfo : public Message {
04194     TxInfo(FirmwareVariant v) : Message(v) {}
04195 
04196     virtual ID id() const override { return ID::MSP_TX_INFO; }
04197 
04198     Value<uint8_t> rssi_source;
04199     Value<uint8_t> rtc_date_time_status;
04200 
04201     virtual bool decode(const ByteVector& data) override {
04202         bool rc = true;
04203         rc &= data.unpack(rssi_source);
04204         rc &= data.unpack(rtc_date_time_status);
04205         return rc;
04206     }
04207 };
04208 
04211 
04212 // MSP_SET_RAW_RC: 200
04213 // This message is accepted but ignored on betaflight 3.0.1 onwards
04214 // if "USE_RX_MSP" is not defined for the target. In this case, you can manually
04215 // add "#define USE_RX_MSP" to your 'target.h'.
04216 struct SetRawRc : public Message {
04217     SetRawRc(FirmwareVariant v) : Message(v) {}
04218 
04219     virtual ID id() const override { return ID::MSP_SET_RAW_RC; }
04220 
04221     std::vector<uint16_t> channels;
04222 
04223     virtual ByteVectorUptr encode() const override {
04224         ByteVectorUptr data = std::make_unique<ByteVector>();
04225         bool rc             = true;
04226         for(const uint16_t& c : channels) {
04227             rc &= data->pack(c);
04228         }
04229         if(!rc) data.reset();
04230         return data;
04231     }
04232 };
04233 
04234 // MSP_SET_RAW_GPS: 201
04235 struct SetRawGPS : public Message {
04236     SetRawGPS(FirmwareVariant v) : Message(v) {}
04237 
04238     virtual ID id() const override { return ID::MSP_SET_RAW_GPS; }
04239 
04240     Value<uint8_t> fix;
04241     Value<uint8_t> numSat;
04242     Value<uint32_t> lat;
04243     Value<uint32_t> lon;
04244     Value<uint16_t> altitude;
04245     Value<uint16_t> speed;
04246 
04247     virtual ByteVectorUptr encode() const override {
04248         ByteVectorUptr data = std::make_unique<ByteVector>();
04249         bool rc             = true;
04250         rc &= data->pack(fix);
04251         rc &= data->pack(numSat);
04252         rc &= data->pack(lat);
04253         rc &= data->pack(lon);
04254         rc &= data->pack(altitude);
04255         rc &= data->pack(speed);
04256         assert(data->size() == 14);
04257         if(!rc) data.reset();
04258         return data;
04259     }
04260 };
04261 
04262 // MSP_SET_PID: 202,
04263 struct SetPid : public PidSettings, public Message {
04264     SetPid(FirmwareVariant v) : Message(v) {}
04265 
04266     virtual ID id() const override { return ID::MSP_SET_PID; }
04267 
04268     virtual ByteVectorUptr encode() const override {
04269         ByteVectorUptr data = std::make_unique<ByteVector>();
04270         bool rc             = true;
04271         for(uint8_t i = 0;
04272             i < static_cast<uint8_t>(PID_Element::PID_ITEM_COUNT);
04273             ++i) {
04274             rc &= data->pack(entry[i]);
04275         }
04276         if(!rc) data.reset();
04277         return data;
04278     }
04279 };
04280 
04281 // Depricated - no examples
04282 // MSP_SET_BOX: 203,
04283 struct SetBox : public Message {
04284     SetBox(FirmwareVariant v) : Message(v) {}
04285 
04286     virtual ID id() const override { return ID::MSP_SET_BOX; }
04287 };
04288 
04289 // Differences between iNav and BF/CF - this is BF/CF variant
04290 // MSP_SET_RC_TUNING: 204
04291 struct SetRcTuning : public RcTuningSettings, public Message {
04292     SetRcTuning(FirmwareVariant v) : Message(v) {}
04293 
04294     virtual ID id() const override { return ID::MSP_SET_RC_TUNING; }
04295 
04296     virtual ByteVectorUptr encode() const override {
04297         ByteVectorUptr data = std::make_unique<ByteVector>();
04298         bool rc             = true;
04299         rc &= data->pack(rcRates[0]);
04300         rc &= data->pack(rcExpo[0]);
04301         for(const auto& r : rates) {
04302             rc &= data->pack(r);
04303         }
04304         rc &= data->pack(dynamic_throttle_pid);
04305         rc &= data->pack(throttle_mid);
04306         rc &= data->pack(throttle_expo);
04307         rc &= data->pack(tpa_breakpoint);
04308         // this field is optional in all firmwares
04309 
04310         if(!rcExpo[2].set()) goto packing_finished;
04311         rc &= data->pack(rcExpo[2]);
04312         // INAV quits her
04313 
04314         if(fw_variant == FirmwareVariant::INAV) goto packing_finished;
04315         // these fields are optional in BF/CF
04316 
04317         if(!rcRates[2].set()) goto packing_finished;
04318         rc &= data->pack(rcRates[2]);
04319 
04320         if(!rcRates[1].set()) goto packing_finished;
04321         rc &= data->pack(rcRates[1]);
04322 
04323         if(!rcExpo[1].set()) goto packing_finished;
04324         rc &= data->pack(rcExpo[1]);
04325 
04326     packing_finished:
04327         if(!rc) data.reset();
04328         return data;
04329     }
04330 };
04331 
04332 // MSP_ACC_CALIBRATION: 205
04333 struct AccCalibration : public Message {
04334     AccCalibration(FirmwareVariant v) : Message(v) {}
04335 
04336     virtual ID id() const override { return ID::MSP_ACC_CALIBRATION; }
04337 };
04338 
04339 // MSP_MAG_CALIBRATION: 206
04340 struct MagCalibration : public Message {
04341     MagCalibration(FirmwareVariant v) : Message(v) {}
04342 
04343     virtual ID id() const override { return ID::MSP_MAG_CALIBRATION; }
04344 };
04345 
04346 // MSP_SET_MISC: 207
04347 struct SetMisc : public MiscSettings, public Message {
04348     SetMisc(FirmwareVariant v) : Message(v) {}
04349 
04350     virtual ID id() const override { return ID::MSP_SET_MISC; }
04351 
04352     virtual ByteVectorUptr encode() const override {
04353         ByteVectorUptr data = std::make_unique<ByteVector>();
04354         bool rc             = true;
04355         rc &= data->pack(mid_rc);
04356         rc &= data->pack(min_throttle);
04357         rc &= data->pack(max_throttle);
04358         rc &= data->pack(failsafe_throttle);
04359         rc &= data->pack(gps_provider);
04360         rc &= data->pack(gps_baudrate);
04361         rc &= data->pack(gps_ubx_sbas);
04362         rc &= data->pack(multiwii_current_meter_output);
04363         rc &= data->pack(rssi_channel);
04364         rc &= data->pack(reserved);
04365         rc &= data->pack<uint16_t>(mag_declination, 10.f);
04366         rc &= data->pack<uint8_t>(voltage_scale, 10.f);
04367         rc &= data->pack<uint8_t>(cell_min, 10.f);
04368         rc &= data->pack<uint8_t>(cell_max, 10.f);
04369         rc &= data->pack<uint8_t>(cell_warning, 10.f);
04370         if(!rc) data.reset();
04371         return data;
04372     }
04373 };
04374 
04375 // MSP_RESET_CONF: 208
04376 struct ResetConfig : public Message {
04377     ResetConfig(FirmwareVariant v) : Message(v) {}
04378 
04379     virtual ID id() const override { return ID::MSP_RESET_CONF; }
04380 };
04381 
04382 // MSP_SET_WP: 209
04383 struct SetWp : public Message {
04384     SetWp(FirmwareVariant v) : Message(v) {}
04385 
04386     virtual ID id() const override { return ID::MSP_SET_WP; }
04387 
04388     Value<uint8_t> wp_no;
04389     Value<uint32_t> lat;
04390     Value<uint32_t> lon;
04391     Value<uint32_t> alt;
04392 
04393     Value<uint16_t> p1;
04394     Value<uint16_t> p2;
04395     Value<uint16_t> p3;
04396     Value<uint8_t> nav_flag;
04397 
04398     virtual ByteVectorUptr encode() const override {
04399         ByteVectorUptr data = std::make_unique<ByteVector>();
04400         bool rc             = true;
04401         rc &= data->pack(wp_no);
04402         rc &= data->pack(lat);
04403         rc &= data->pack(lon);
04404         rc &= data->pack(alt);
04405         rc &= data->pack(p1);
04406         rc &= data->pack(p2);
04407         if(fw_variant == FirmwareVariant::INAV) {
04408             rc &= data->pack(p3);
04409         }
04410         rc &= data->pack(nav_flag);
04411         return data;
04412     }
04413 };
04414 
04415 // MSP_SELECT_SETTING: 210
04416 struct SelectSetting : public Message {
04417     SelectSetting(FirmwareVariant v) : Message(v) {}
04418 
04419     virtual ID id() const override { return ID::MSP_SELECT_SETTING; }
04420 
04421     uint8_t current_setting;
04422 
04423     virtual ByteVectorUptr encode() const override {
04424         ByteVectorUptr data = std::make_unique<ByteVector>();
04425         if(!data->pack(current_setting)) data.reset();
04426         return data;
04427     }
04428 };
04429 
04430 // MSP_SET_HEADING: 211
04431 struct SetHeading : public Message {
04432     SetHeading(FirmwareVariant v) : Message(v) {}
04433 
04434     virtual ID id() const override { return ID::MSP_SET_HEADING; }
04435 
04436     int16_t heading;
04437 
04438     virtual ByteVectorUptr encode() const override {
04439         ByteVectorUptr data = std::make_unique<ByteVector>();
04440         if(!data->pack(heading)) data.reset();
04441         assert(data->size() == 2);
04442         return data;
04443     }
04444 };
04445 
04446 // MSP_SET_SERVO_CONF: 212
04447 struct SetServoConf : public Message {
04448     SetServoConf(FirmwareVariant v) : Message(v) {}
04449 
04450     virtual ID id() const override { return ID::MSP_SET_SERVO_CONF; }
04451 
04452     Value<uint8_t> servo_idx;
04453     Value<uint16_t> min;
04454     Value<uint16_t> max;
04455     Value<uint16_t> middle;
04456     Value<uint8_t> rate;
04457 
04458     Value<uint8_t> forward_from_channel;
04459     Value<uint32_t> reversed_sources;
04460 
04461     virtual ByteVectorUptr encode() const override {
04462         ByteVectorUptr data = std::make_unique<ByteVector>();
04463         bool rc             = true;
04464         rc &= data->pack(servo_idx);
04465         rc &= data->pack(min);
04466         rc &= data->pack(max);
04467         rc &= data->pack(middle);
04468         rc &= data->pack(rate);
04469         if(fw_variant == FirmwareVariant::INAV) {
04470             uint8_t tmp = 0;
04471             rc &= data->pack(tmp);
04472             rc &= data->pack(tmp);
04473         }
04474         rc &= data->pack(forward_from_channel);
04475         rc &= data->pack(reversed_sources);
04476         if(!rc) data.reset();
04477         return data;
04478     }
04479 };
04480 
04481 // MSP_SET_MOTOR: 214
04482 struct SetMotor : public Message {
04483     SetMotor(FirmwareVariant v) : Message(v) {}
04484 
04485     virtual ID id() const override { return ID::MSP_SET_MOTOR; }
04486 
04487     std::array<uint16_t, N_MOTOR> motor;
04488 
04489     virtual ByteVectorUptr encode() const override {
04490         ByteVectorUptr data = std::make_unique<ByteVector>();
04491         bool rc             = true;
04492         for(size_t i(0); i < N_MOTOR; i++) rc &= data->pack(motor[i]);
04493         assert(data->size() == N_MOTOR * 2);
04494         if(!rc) data.reset();
04495         return data;
04496     }
04497 };
04498 
04499 // MSP_SET_NAV_CONFIG              = 215
04500 struct SetNavConfig : public Message {
04501     SetNavConfig(FirmwareVariant v) : Message(v) {}
04502 
04503     virtual ID id() const override { return ID::MSP_SET_NAV_CONFIG; }
04504 };
04505 
04506 // MSP_SET_MOTOR_3D_CONF           = 217
04507 struct SetMotor3dConf : public Message {
04508     SetMotor3dConf(FirmwareVariant v) : Message(v) {}
04509 
04510     virtual ID id() const override { return ID::MSP_SET_MOTOR_3D_CONF; }
04511 
04512     Value<uint16_t> deadband3d_low;
04513     Value<uint16_t> deadband3d_high;
04514     Value<uint16_t> neutral_3d;
04515 
04516     virtual ByteVectorUptr encode() const override {
04517         ByteVectorUptr data = std::make_unique<ByteVector>();
04518         bool rc             = true;
04519         rc &= data->pack(deadband3d_low);
04520         rc &= data->pack(deadband3d_high);
04521         rc &= data->pack(neutral_3d);
04522         if(!rc) data.reset();
04523         return data;
04524     }
04525 };
04526 
04527 // MSP_SET_RC_DEADBAND             = 218
04528 struct SetRcDeadband : public RcDeadbandSettings, public Message {
04529     SetRcDeadband(FirmwareVariant v) : Message(v) {}
04530 
04531     virtual ID id() const override { return ID::MSP_SET_RC_DEADBAND; }
04532 
04533     virtual ByteVectorUptr encode() const override {
04534         ByteVectorUptr data = std::make_unique<ByteVector>();
04535         bool rc             = true;
04536         rc &= data->pack(deadband);
04537         rc &= data->pack(yaw_deadband);
04538         rc &= data->pack(alt_hold_deadband);
04539         rc &= data->pack(deadband3d_throttle);
04540         if(!rc) data.reset();
04541         return data;
04542     }
04543 };
04544 
04545 // MSP_SET_RESET_CURR_PID          = 219
04546 struct SetResetCurrPid : public Message {
04547     SetResetCurrPid(FirmwareVariant v) : Message(v) {}
04548 
04549     virtual ID id() const override { return ID::MSP_SET_RESET_CURR_PID; }
04550 };
04551 
04552 // MSP_SET_SENSOR_ALIGNMENT        = 220
04553 struct SetSensorAlignment : public SensorAlignmentSettings, public Message {
04554     SetSensorAlignment(FirmwareVariant v) : Message(v) {}
04555 
04556     virtual ID id() const override { return ID::MSP_SET_SENSOR_ALIGNMENT; }
04557 
04558     virtual ByteVectorUptr encode() const override {
04559         ByteVectorUptr data = std::make_unique<ByteVector>();
04560         bool rc             = true;
04561         rc &= data->pack(gyro_align);
04562         rc &= data->pack(acc_align);
04563         rc &= data->pack(mag_align);
04564         if(!rc) data.reset();
04565         return data;
04566     }
04567 };
04568 
04569 // MSP_SET_LED_STRIP_MODECOLOR     = 221
04570 struct SetLedStripModecolor : public SensorAlignmentSettings, public Message {
04571     SetLedStripModecolor(FirmwareVariant v) : Message(v) {}
04572 
04573     virtual ID id() const override { return ID::MSP_SET_LED_STRIP_MODECOLOR; }
04574 
04575     Value<uint8_t> mode_idx;
04576     Value<uint8_t> fun_idx;
04577     Value<uint8_t> color;
04578 
04579     virtual ByteVectorUptr encode() const override {
04580         ByteVectorUptr data = std::make_unique<ByteVector>();
04581         bool rc             = true;
04582         rc &= data->pack(mode_idx);
04583         rc &= data->pack(fun_idx);
04584         rc &= data->pack(color);
04585         if(!rc) data.reset();
04586         return data;
04587     }
04588 };
04589 
04590 // Not available in iNav (222-224)
04591 // MSP_SET_MOTOR_CONFIG            = 222    //out message         Motor
04592 // configuration (min/max throttle, etc)
04593 struct SetMotorConfig : public MotorConfigSettings, public Message {
04594     SetMotorConfig(FirmwareVariant v) : Message(v) {}
04595 
04596     virtual ID id() const override { return ID::MSP_SET_MOTOR_CONFIG; }
04597 
04598     virtual ByteVectorUptr encode() const override {
04599         ByteVectorUptr data = std::make_unique<ByteVector>();
04600         bool rc             = true;
04601         rc &= data->pack(min_throttle);
04602         rc &= data->pack(max_throttle);
04603         rc &= data->pack(min_command);
04604         if(!rc) data.reset();
04605         return data;
04606     }
04607 };
04608 
04609 // MSP_SET_GPS_CONFIG              = 223    //out message         GPS
04610 // configuration
04611 struct SetGpsConfig : public GpsConfigSettings, public Message {
04612     SetGpsConfig(FirmwareVariant v) : Message(v) {}
04613 
04614     virtual ID id() const override { return ID::MSP_SET_GPS_CONFIG; }
04615 
04616     virtual ByteVectorUptr encode() const override {
04617         ByteVectorUptr data = std::make_unique<ByteVector>();
04618         bool rc             = true;
04619         rc &= data->pack(provider);
04620         rc &= data->pack(sbas_mode);
04621         rc &= data->pack(auto_config);
04622         rc &= data->pack(auto_baud);
04623         if(!rc) data.reset();
04624         return data;
04625     }
04626 };
04627 
04628 // MSP_SET_COMPASS_CONFIG          = 224    //out message         Compass
04629 // configuration
04630 struct SetCompassConfig : public Message {
04631     SetCompassConfig(FirmwareVariant v) : Message(v) {}
04632 
04633     virtual ID id() const override { return ID::MSP_SET_GPS_CONFIG; }
04634 
04635     Value<float> mag_declination;
04636 
04637     virtual ByteVectorUptr encode() const override {
04638         ByteVectorUptr data = std::make_unique<ByteVector>();
04639         if(!data->pack<uint16_t>(mag_declination, 10)) data.reset();
04640         return data;
04641     }
04642 };
04643 
04644 struct AccTrimSettings {
04645     Value<uint16_t> pitch;
04646     Value<uint16_t> roll;
04647 };
04648 
04649 // MSP_SET_ACC_TRIM                = 239    //in message          set acc angle
04650 // trim values
04651 struct SetAccTrim : public AccTrimSettings, public Message {
04652     SetAccTrim(FirmwareVariant v) : Message(v) {}
04653 
04654     virtual ID id() const override { return ID::MSP_SET_ACC_TRIM; }
04655 
04656     virtual ByteVectorUptr encode() const override {
04657         ByteVectorUptr data = std::make_unique<ByteVector>();
04658         bool rc             = true;
04659         rc &= data->pack(pitch);
04660         rc &= data->pack(roll);
04661         if(!rc) data.reset();
04662         return data;
04663     }
04664 };
04665 
04666 // MSP_ACC_TRIM                    = 240    //out message         get acc angle
04667 // trim values
04668 struct AccTrim : public AccTrimSettings, public Message {
04669     AccTrim(FirmwareVariant v) : Message(v) {}
04670 
04671     virtual ID id() const override { return ID::MSP_ACC_TRIM; }
04672 
04673     virtual bool decode(const ByteVector& data) override {
04674         bool rc = true;
04675         rc &= data.unpack(pitch);
04676         rc &= data.unpack(roll);
04677         return rc;
04678     }
04679 };
04680 
04681 struct ServoMixRule : public Packable {
04682     uint8_t target_channel;
04683     uint8_t input_source;
04684     uint8_t rate;
04685     uint8_t speed;
04686     uint8_t min;
04687     uint8_t max;
04688     uint8_t box;
04689 
04690     bool unpack_from(const ByteVector& data) {
04691         bool rc = true;
04692         rc &= data.unpack(target_channel);
04693         rc &= data.unpack(input_source);
04694         rc &= data.unpack(rate);
04695         rc &= data.unpack(speed);
04696         rc &= data.unpack(min);
04697         rc &= data.unpack(max);
04698         rc &= data.unpack(box);
04699         return rc;
04700     }
04701 
04702     bool pack_into(ByteVector& data) const {
04703         bool rc = true;
04704         rc &= data.pack(target_channel);
04705         rc &= data.pack(input_source);
04706         rc &= data.pack(rate);
04707         rc &= data.pack(speed);
04708         rc &= data.pack(min);
04709         rc &= data.pack(max);
04710         rc &= data.pack(box);
04711         return rc;
04712     }
04713 };
04714 
04715 // MSP_SERVO_MIX_RULES             = 241    //out message         Returns servo
04716 // mixer configuration
04717 struct ServoMixRules : public Message {
04718     ServoMixRules(FirmwareVariant v) : Message(v) {}
04719 
04720     virtual ID id() const override { return ID::MSP_SERVO_MIX_RULES; }
04721 
04722     std::vector<Value<ServoMixRule>> rules;
04723 
04724     virtual bool decode(const ByteVector& data) override {
04725         bool rc = true;
04726         while(data.unpacking_remaining()) {
04727             Value<ServoMixRule> rule;
04728             rc &= data.unpack(rule);
04729             if(rc)
04730                 rules.push_back(rule);
04731             else
04732                 break;
04733         }
04734         return rc;
04735     }
04736 };
04737 
04738 // MSP_SET_SERVO_MIX_RULE          = 242    //in message          Sets servo
04739 // mixer configuration
04740 struct SetServoMixRule : public Message {
04741     SetServoMixRule(FirmwareVariant v) : Message(v) {}
04742 
04743     virtual ID id() const override { return ID::MSP_SERVO_MIX_RULES; }
04744 
04745     Value<ServoMixRule> rule;
04746 
04747     virtual ByteVectorUptr encode() const override {
04748         ByteVectorUptr data = std::make_unique<ByteVector>();
04749         if(!data->pack(rule)) data.reset();
04750         return data;
04751     }
04752 };
04753 
04754 // not used in CF, BF, iNav
04755 // MSP_PASSTHROUGH_SERIAL          = 244
04756 struct PassthroughSerial : public Message {
04757     PassthroughSerial(FirmwareVariant v) : Message(v) {}
04758 
04759     virtual ID id() const override { return ID::MSP_PASSTHROUGH_SERIAL; }
04760 };
04761 
04762 // MSP_SET_4WAY_IF                 = 245    //in message          Sets 4way
04763 // interface
04764 struct Set4WayIF : public Message {
04765     Set4WayIF(FirmwareVariant v) : Message(v) {}
04766 
04767     virtual ID id() const override { return ID::MSP_SET_4WAY_IF; }
04768 
04769     Value<uint8_t> esc_mode;
04770     Value<uint8_t> esc_port_index;
04771 
04772     Value<uint8_t> esc_count;
04773 
04774     virtual ByteVectorUptr encode() const override {
04775         ByteVectorUptr data = std::make_unique<ByteVector>();
04776         bool rc             = true;
04777         if(esc_mode.set()) {
04778             rc &= data->pack(esc_mode);
04779             rc &= data->pack(esc_port_index);
04780         }
04781         if(!rc) data.reset();
04782         return data;
04783     }
04784 
04785     virtual bool decode(const ByteVector& data) override {
04786         return data.unpack(esc_count);
04787     }
04788 };
04789 
04790 struct RtcVals {
04791     Value<uint32_t> secs;
04792     Value<uint16_t> millis;
04793 };
04794 
04795 // MSP_SET_RTC                     = 246    //in message          Sets the RTC
04796 // clock
04797 struct SetRtc : public RtcVals, public Message {
04798     SetRtc(FirmwareVariant v) : Message(v) {}
04799 
04800     virtual ID id() const override { return ID::MSP_SET_RTC; }
04801 
04802     virtual ByteVectorUptr encode() const override {
04803         ByteVectorUptr data = std::make_unique<ByteVector>();
04804         bool rc             = true;
04805         rc &= data->pack(secs);
04806         rc &= data->pack(millis);
04807         if(!rc) data.reset();
04808         return data;
04809     }
04810 };
04811 
04812 // MSP_RTC                         = 247    //out message         Gets the RTC
04813 // clock
04814 struct Rtc : public RtcVals, public Message {
04815     Rtc(FirmwareVariant v) : Message(v) {}
04816 
04817     virtual ID id() const override { return ID::MSP_RTC; }
04818 
04819     virtual bool decode(const ByteVector& data) override {
04820         bool rc = true;
04821         rc &= data.unpack(secs);
04822         rc &= data.unpack(millis);
04823         return rc;
04824     }
04825 };
04826 
04827 // MSP_EEPROM_WRITE: 250
04828 struct WriteEEPROM : public Message {
04829     WriteEEPROM(FirmwareVariant v) : Message(v) {}
04830 
04831     virtual ID id() const override { return ID::MSP_EEPROM_WRITE; }
04832 };
04833 
04834 // MSP_RESERVE_1: 251,    //reserved for system usage
04835 struct Reserve1 : public Message {
04836     Reserve1(FirmwareVariant v) : Message(v) {}
04837 
04838     virtual ID id() const override { return ID::MSP_RESERVE_1; }
04839 };
04840 
04841 // MSP_RESERVE_2: 252,    //reserved for system usage
04842 struct Reserve2 : public Message {
04843     Reserve2(FirmwareVariant v) : Message(v) {}
04844 
04845     virtual ID id() const override { return ID::MSP_RESERVE_2; }
04846 };
04847 
04848 // MSP_DEBUGMSG: 253
04849 struct DebugMessage : public Message {
04850     DebugMessage(FirmwareVariant v) : Message(v) {}
04851 
04852     virtual ID id() const override { return ID::MSP_DEBUGMSG; }
04853 
04854     Value<std::string> debug_msg;
04855 
04856     virtual bool decode(const ByteVector& data) override {
04857         return data.unpack(debug_msg);
04858     }
04859 };
04860 
04861 // MSP_DEBUG: 254
04862 struct Debug : public Message {
04863     Debug(FirmwareVariant v) : Message(v) {}
04864 
04865     virtual ID id() const override { return ID::MSP_DEBUG; }
04866 
04867     Value<uint16_t> debug1;
04868     Value<uint16_t> debug2;
04869     Value<uint16_t> debug3;
04870     Value<uint16_t> debug4;
04871 
04872     virtual bool decode(const ByteVector& data) override {
04873         bool rc = true;
04874         rc &= data.unpack(debug1);
04875         rc &= data.unpack(debug2);
04876         rc &= data.unpack(debug3);
04877         rc &= data.unpack(debug4);
04878         return rc;
04879     }
04880 };
04881 
04882 // MSP_V2_FRAME: 255
04883 struct V2Frame : public Message {
04884     V2Frame(FirmwareVariant v) : Message(v) {}
04885 
04886     virtual ID id() const override { return ID::MSP_V2_FRAME; }
04887 };
04888 
04889 // MSP2_COMMON_TZ                  = 0x1001,  //out message   Gets the TZ offset
04890 // for the local time (returns: minutes(i16))
04891 struct CommonTz : public Message {
04892     CommonTz(FirmwareVariant v) : Message(v) {}
04893 
04894     virtual ID id() const override { return ID::MSP2_COMMON_TZ; }
04895 
04896     Value<uint16_t> tz_offset;
04897 
04898     virtual bool decode(const ByteVector& data) override {
04899         return data.unpack(tz_offset);
04900     }
04901 };
04902 
04903 // MSP2_COMMON_SET_TZ              = 0x1002,  //in message    Sets the TZ offset
04904 // for the local time (args: minutes(i16))
04905 struct CommonSetTz : public Message {
04906     CommonSetTz(FirmwareVariant v) : Message(v) {}
04907 
04908     virtual ID id() const override { return ID::MSP2_COMMON_SET_TZ; }
04909 
04910     Value<uint16_t> tz_offset;
04911 
04912     virtual ByteVectorUptr encode() const override {
04913         ByteVectorUptr data = std::make_unique<ByteVector>();
04914         if(!data->pack(tz_offset)) data.reset();
04915         return data;
04916     }
04917 };
04918 
04919 enum class DATA_TYPE : uint8_t {
04920     UNSET,
04921     UINT8,
04922     INT8,
04923     UINT16,
04924     INT16,
04925     UINT32,
04926     FLOAT,
04927     STRING
04928 };
04929 
04930 // MSP2_COMMON_SETTING             = 0x1003,  //in/out message   Returns the
04931 // value for a setting
04932 struct CommonSetting : public Message {
04933     CommonSetting(FirmwareVariant v) : Message(v) {}
04934 
04935     virtual ID id() const override { return ID::MSP2_COMMON_SETTING; }
04936 
04937     Value<std::string> setting_name;
04938     Value<uint8_t> uint8_val;
04939     Value<int8_t> int8_val;
04940     Value<uint16_t> uint16_val;
04941     Value<int16_t> int16_val;
04942     Value<uint32_t> uint32_val;
04943     Value<float> float_val;
04944     Value<std::string> string_val;
04945 
04946     DATA_TYPE expected_data_type;
04947 
04948     virtual ByteVectorUptr encode() const override {
04949         ByteVectorUptr data = std::make_unique<ByteVector>();
04950         bool rc             = true;
04951         rc &= data->pack(setting_name);
04952         if(!rc) data.reset();
04953         return data;
04954     }
04955 
04956     // TODO
04957     virtual bool decode(const ByteVector& data) override {
04958         std::cout << "decoding " << data;
04959         switch(expected_data_type) {
04960         case DATA_TYPE::UINT8:
04961             return data.unpack(uint8_val);
04962         case DATA_TYPE::INT8:
04963             return data.unpack(int8_val);
04964         case DATA_TYPE::UINT16:
04965             return data.unpack(uint16_val);
04966         case DATA_TYPE::INT16:
04967             return data.unpack(int16_val);
04968         case DATA_TYPE::UINT32:
04969             return data.unpack(uint32_val);
04970         case DATA_TYPE::FLOAT:
04971             return data.unpack(float_val);
04972         case DATA_TYPE::STRING:
04973             return data.unpack(string_val);
04974         default:
04975             return false;
04976         }
04977     }
04978 
04979     virtual std::ostream& print(std::ostream& s) const override {
04980         s << "#Setting:" << std::endl;
04981         s << " " << setting_name << ": ";
04982 
04983         switch(expected_data_type) {
04984         case DATA_TYPE::UINT8:
04985             s << uint8_val;
04986             break;
04987         case DATA_TYPE::INT8:
04988             s << int8_val;
04989             break;
04990         case DATA_TYPE::UINT16:
04991             s << uint16_val;
04992             break;
04993         case DATA_TYPE::INT16:
04994             s << int16_val;
04995             break;
04996         case DATA_TYPE::UINT32:
04997             s << uint32_val;
04998             break;
04999         case DATA_TYPE::FLOAT:
05000             s << float_val;
05001             break;
05002         case DATA_TYPE::STRING:
05003             s << string_val;
05004             break;
05005         default:
05006             s << "<invalid>";
05007         }
05008 
05009         s << std::endl;
05010 
05011         return s;
05012     }
05013 };
05014 
05015 // MSP2_COMMON_SET_SETTING         = 0x1004,  //in message    Sets the value for
05016 // a setting
05017 struct CommonSetSetting : public Message {
05018     CommonSetSetting(FirmwareVariant v) : Message(v) {}
05019 
05020     virtual ID id() const override { return ID::MSP2_COMMON_SET_SETTING; }
05021 
05022     Value<std::string> setting_name;
05023     Value<uint8_t> uint8_val;
05024     Value<int8_t> int8_val;
05025     Value<uint16_t> uint16_val;
05026     Value<int16_t> int16_val;
05027     Value<uint32_t> uint32_val;
05028     Value<float> float_val;
05029     Value<std::string> string_val;
05030 
05031     DATA_TYPE expected_data_type;
05032 
05033     virtual ByteVectorUptr encode() const override {
05034         ByteVectorUptr data = std::make_unique<ByteVector>();
05035         bool rc             = true;
05036         rc &= data->pack(setting_name);
05037         if(uint8_val.set())
05038             rc &= data->pack(uint8_val);
05039         else if(int8_val.set())
05040             rc &= data->pack(int8_val);
05041         else if(uint16_val.set())
05042             rc &= data->pack(uint16_val);
05043         else if(int16_val.set())
05044             rc &= data->pack(int16_val);
05045         else if(uint32_val.set())
05046             rc &= data->pack(uint32_val);
05047         else if(float_val.set())
05048             rc &= data->pack(float_val);
05049         else if(string_val.set())
05050             rc &= data->pack(string_val);
05051         if(!rc) data.reset();
05052         return data;
05053     }
05054 };
05055 
05056 struct MotorMixer : public Packable {
05057     Value<float> throttle;
05058     Value<float> roll;
05059     Value<float> pitch;
05060     Value<float> yaw;
05061 
05062     bool unpack_from(const ByteVector& data) {
05063         bool rc = true;
05064         rc &= data.unpack<uint16_t>(throttle, 1000.0);
05065         rc &= data.unpack<uint16_t>(roll, 1000.0, 1.0);
05066         rc &= data.unpack<uint16_t>(pitch, 1000.0, 1.0);
05067         rc &= data.unpack<uint16_t>(yaw, 1000.0, 1.0);
05068         return rc;
05069     }
05070 
05071     bool pack_into(ByteVector& data) const {
05072         bool rc = true;
05073         rc &= data.pack<uint16_t>(throttle, 1000.0, 1.0);
05074         rc &= data.pack<uint16_t>(roll, 1000.0, 1.0);
05075         rc &= data.pack<uint16_t>(pitch, 1000.0, 1.0);
05076         rc &= data.pack<uint16_t>(yaw, 1000.0, 1.0);
05077         return rc;
05078     }
05079 };
05080 
05081 // MSP2_COMMON_MOTOR_MIXER         = 0x1005,
05082 struct CommonMotorMixer : public Message {
05083     CommonMotorMixer(FirmwareVariant v) : Message(v) {}
05084 
05085     virtual ID id() const override { return ID::MSP2_COMMON_MOTOR_MIXER; }
05086 
05087     std::vector<MotorMixer> mixer;
05088 
05089     virtual bool decode(const ByteVector& data) override {
05090         bool rc = true;
05091         while(data.unpacking_remaining()) {
05092             MotorMixer m;
05093             rc &= data.unpack(m);
05094             mixer.push_back(m);
05095         }
05096         return rc;
05097     }
05098 };
05099 
05100 // MSP2_COMMON_SET_MOTOR_MIXER     = 0x1006,
05101 struct CommonSetMotorMixer : public Message {
05102     CommonSetMotorMixer(FirmwareVariant v) : Message(v) {}
05103 
05104     virtual ID id() const override { return ID::MSP2_COMMON_SET_MOTOR_MIXER; }
05105 
05106     Value<uint8_t> index;
05107     MotorMixer mixer;
05108 
05109     virtual ByteVectorUptr encode() const override {
05110         ByteVectorUptr data = std::make_unique<ByteVector>();
05111         bool rc             = true;
05112         rc &= data->pack(index);
05113         rc &= data->pack(mixer);
05114         if(!rc) data.reset();
05115         return data;
05116     }
05117 };
05118 
05119 // MSP2_INAV_STATUS                = 0x2000,
05120 struct InavStatus : public StatusBase, public Message {
05121     InavStatus(FirmwareVariant v) : Message(v) {}
05122 
05123     virtual ID id() const override { return ID::MSP2_INAV_STATUS; }
05124 
05125     Value<uint16_t> avg_system_load_pct;
05126     Value<uint8_t> config_profile;
05127     Value<uint32_t> arming_flags;
05128 
05129     virtual bool decode(const ByteVector& data) override {
05130         bool rc = true;
05131         rc &= data.unpack(cycle_time);
05132         rc &= data.unpack(i2c_errors);
05133 
05134         // get sensors
05135         sensors.clear();
05136         uint16_t sensor = 0;
05137         rc &= data.unpack(sensor);
05138         if(sensor & (1 << 0)) sensors.insert(Sensor::Accelerometer);
05139         if(sensor & (1 << 1)) sensors.insert(Sensor::Barometer);
05140         if(sensor & (1 << 2)) sensors.insert(Sensor::Magnetometer);
05141         if(sensor & (1 << 3)) sensors.insert(Sensor::GPS);
05142         if(sensor & (1 << 4)) sensors.insert(Sensor::Sonar);
05143         if(sensor & (1 << 5)) sensors.insert(Sensor::OpticalFlow);
05144         if(sensor & (1 << 6)) sensors.insert(Sensor::Pitot);
05145         if(sensor & (1 << 15)) sensors.insert(Sensor::GeneralHealth);
05146 
05147         rc &= data.unpack(avg_system_load_pct);
05148         rc &= data.unpack(config_profile);
05149 
05150         rc &= data.unpack(arming_flags);
05151 
05152         // check active boxes
05153         box_mode_flags.clear();
05154         uint32_t flag = 0;
05155         rc &= data.unpack(flag);
05156         for(size_t ibox(0); ibox < sizeof(flag) * CHAR_BIT; ibox++) {
05157             if(flag & (1 << ibox)) box_mode_flags.insert(ibox);
05158         }
05159 
05160         return rc;
05161     }
05162 
05163     bool hasAccelerometer() const {
05164         return sensors.count(Sensor::Accelerometer);
05165     }
05166 
05167     bool hasBarometer() const { return sensors.count(Sensor::Barometer); }
05168 
05169     bool hasMagnetometer() const { return sensors.count(Sensor::Magnetometer); }
05170 
05171     bool hasGPS() const { return sensors.count(Sensor::GPS); }
05172 
05173     bool hasSonar() const { return sensors.count(Sensor::Sonar); }
05174 
05175     bool hasOpticalFlow() const { return sensors.count(Sensor::OpticalFlow); }
05176 
05177     bool hasPitot() const { return sensors.count(Sensor::Pitot); }
05178 
05179     bool isHealthy() const { return sensors.count(Sensor::GeneralHealth); }
05180 
05181     virtual std::ostream& print(std::ostream& s) const override {
05182         s << "#Status:" << std::endl;
05183         s << " Cycle time: " << cycle_time << " us" << std::endl;
05184         s << " Average system load: " << avg_system_load_pct << "%"
05185           << std::endl;
05186         s << " Arming flags: " << armingFlagToString(arming_flags())
05187           << std::endl;
05188         s << " I2C errors: " << i2c_errors << std::endl;
05189         s << " Sensors:" << std::endl;
05190 
05191         s << "    Accelerometer: ";
05192         hasAccelerometer() ? s << "ON" : s << "OFF";
05193         s << std::endl;
05194 
05195         s << "    Barometer: ";
05196         hasBarometer() ? s << "ON" : s << "OFF";
05197         s << std::endl;
05198 
05199         s << "    Magnetometer: ";
05200         hasMagnetometer() ? s << "ON" : s << "OFF";
05201         s << std::endl;
05202 
05203         s << "    GPS: ";
05204         hasGPS() ? s << "ON" : s << "OFF";
05205         s << std::endl;
05206 
05207         s << "    Sonar: ";
05208         hasSonar() ? s << "ON" : s << "OFF";
05209         s << std::endl;
05210 
05211         s << " Active Boxes (by ID):";
05212         for(const size_t box_id : box_mode_flags) {
05213             s << " " << box_id;
05214         }
05215         s << std::endl;
05216 
05217         return s;
05218     }
05219 };
05220 
05221 // MSP2_INAV_OPTICAL_FLOW          = 0x2001,
05222 struct InavOpticalFlow : public Message {
05223     InavOpticalFlow(FirmwareVariant v) : Message(v) {}
05224 
05225     virtual ID id() const override { return ID::MSP2_INAV_OPTICAL_FLOW; }
05226 
05227     Value<uint8_t> raw_quality;
05228     Value<uint16_t> flow_rate_x;
05229     Value<uint16_t> flow_rate_y;
05230     Value<uint16_t> body_rate_x;
05231     Value<uint16_t> body_rate_y;
05232 
05233     virtual bool decode(const ByteVector& data) override {
05234         bool rc = true;
05235         rc &= data.unpack(raw_quality);
05236         rc &= data.unpack(flow_rate_x);
05237         rc &= data.unpack(flow_rate_y);
05238         rc &= data.unpack(body_rate_x);
05239         rc &= data.unpack(body_rate_y);
05240         return rc;
05241     }
05242 };
05243 
05244 // MSP2_INAV_ANALOG                = 0x2002,
05245 struct InavAnalog : public Message {
05246     InavAnalog(FirmwareVariant v) : Message(v) {}
05247 
05248     virtual ID id() const override { return ID::MSP2_INAV_ANALOG; }
05249 
05250     Value<uint8_t> battery_voltage;
05251     Value<uint16_t> mAh_drawn;
05252     Value<uint16_t> rssi;
05253     Value<uint16_t> amperage;
05254 
05255     virtual bool decode(const ByteVector& data) override {
05256         bool rc = true;
05257         rc &= data.unpack(battery_voltage);
05258         rc &= data.unpack(mAh_drawn);
05259         rc &= data.unpack(rssi);
05260         rc &= data.unpack(amperage);
05261         return rc;
05262     }
05263 };
05264 
05265 struct InavMiscSettings {
05266     Value<uint16_t> mid_rc;
05267     Value<uint16_t> min_throttle;
05268     Value<uint16_t> max_throttle;
05269     Value<uint16_t> min_command;
05270     Value<uint16_t> failsafe_throttle;
05271     Value<uint8_t> gps_provider;
05272     Value<uint8_t> gps_baudrate;
05273     Value<uint8_t> gps_ubx_sbas;
05274     Value<uint8_t> rssi_channel;
05275     Value<uint16_t> mag_declination;
05276     Value<uint16_t> voltage_scale;
05277     Value<uint16_t> cell_min;
05278     Value<uint16_t> cell_max;
05279     Value<uint16_t> cell_warning;
05280     Value<uint32_t> capacity;
05281     Value<uint32_t> capacity_warning;
05282     Value<uint32_t> capacity_critical;
05283     Value<uint8_t> capacity_units;
05284 };
05285 
05286 // MSP2_INAV_MISC                  = 0x2003,
05287 struct InavMisc : public InavMiscSettings, public Message {
05288     InavMisc(FirmwareVariant v) : Message(v) {}
05289 
05290     virtual ID id() const override { return ID::MSP2_INAV_MISC; }
05291 
05292     virtual bool decode(const ByteVector& data) override {
05293         bool rc = true;
05294         rc &= data.unpack(mid_rc);
05295         rc &= data.unpack(min_throttle);
05296         rc &= data.unpack(max_throttle);
05297         rc &= data.unpack(min_command);
05298         rc &= data.unpack(failsafe_throttle);
05299         rc &= data.unpack(gps_provider);
05300         rc &= data.unpack(gps_baudrate);
05301         rc &= data.unpack(gps_ubx_sbas);
05302         rc &= data.unpack(rssi_channel);
05303         rc &= data.unpack(mag_declination);
05304         rc &= data.unpack(voltage_scale);
05305         rc &= data.unpack(cell_min);
05306         rc &= data.unpack(cell_max);
05307         rc &= data.unpack(cell_warning);
05308         rc &= data.unpack(capacity);
05309         rc &= data.unpack(capacity_warning);
05310         rc &= data.unpack(capacity_critical);
05311         rc &= data.unpack(capacity_units);
05312         return rc;
05313     }
05314 };
05315 
05316 // MSP2_INAV_SET_MISC              = 0x2004,
05317 struct InavSetMisc : public InavMiscSettings, public Message {
05318     InavSetMisc(FirmwareVariant v) : Message(v) {}
05319 
05320     virtual ID id() const override { return ID::MSP2_INAV_SET_MISC; }
05321 
05322     virtual ByteVectorUptr encode() const override {
05323         ByteVectorUptr data = std::make_unique<ByteVector>();
05324         bool rc             = true;
05325         rc &= data->pack(mid_rc);
05326         rc &= data->pack(min_throttle);
05327         rc &= data->pack(mid_rc);
05328         rc &= data->pack(max_throttle);
05329         rc &= data->pack(min_command);
05330         rc &= data->pack(failsafe_throttle);
05331         rc &= data->pack(gps_provider);
05332         rc &= data->pack(gps_baudrate);
05333         rc &= data->pack(gps_ubx_sbas);
05334         rc &= data->pack(rssi_channel);
05335         rc &= data->pack(mag_declination);
05336         rc &= data->pack(voltage_scale);
05337         rc &= data->pack(cell_min);
05338         rc &= data->pack(cell_max);
05339         rc &= data->pack(cell_warning);
05340         rc &= data->pack(capacity);
05341         rc &= data->pack(capacity_warning);
05342         rc &= data->pack(capacity_critical);
05343         rc &= data->pack(capacity_units);
05344         if(!rc) data.reset();
05345         return data;
05346     }
05347 };
05348 
05349 struct InavBatteryConfigSettings {
05350     Value<uint16_t> voltage_scale;
05351     Value<uint16_t> cell_min;
05352     Value<uint16_t> cell_max;
05353     Value<uint16_t> cell_warning;
05354     Value<uint16_t> current_offset;
05355     Value<uint16_t> current_scale;
05356     Value<uint32_t> capacity;
05357     Value<uint32_t> capacity_warning;
05358     Value<uint32_t> capacity_critical;
05359     Value<uint8_t> capacity_units;
05360 };
05361 
05362 // MSP2_INAV_BATTERY_CONFIG        = 0x2005,
05363 struct InavBatteryConfig : public InavBatteryConfigSettings, public Message {
05364     InavBatteryConfig(FirmwareVariant v) : Message(v) {}
05365 
05366     virtual ID id() const override { return ID::MSP2_INAV_BATTERY_CONFIG; }
05367 
05368     virtual bool decode(const ByteVector& data) override {
05369         bool rc = true;
05370         rc &= data.unpack(voltage_scale);
05371         rc &= data.unpack(cell_min);
05372         rc &= data.unpack(cell_max);
05373         rc &= data.unpack(cell_warning);
05374         rc &= data.unpack(current_offset);
05375         rc &= data.unpack(current_scale);
05376         rc &= data.unpack(capacity);
05377         rc &= data.unpack(capacity_warning);
05378         rc &= data.unpack(capacity_critical);
05379         rc &= data.unpack(capacity_units);
05380         return rc;
05381     }
05382 };
05383 
05384 // MSP2_INAV_SET_BATTERY_CONFIG    = 0x2006,
05385 struct InavSetBatteryConfig : public InavBatteryConfigSettings, public Message {
05386     InavSetBatteryConfig(FirmwareVariant v) : Message(v) {}
05387 
05388     virtual ID id() const override { return ID::MSP2_INAV_SET_BATTERY_CONFIG; }
05389 
05390     virtual ByteVectorUptr encode() const override {
05391         ByteVectorUptr data = std::make_unique<ByteVector>();
05392         bool rc             = true;
05393         rc &= data->pack(voltage_scale);
05394         rc &= data->pack(cell_min);
05395         rc &= data->pack(cell_max);
05396         rc &= data->pack(cell_warning);
05397         rc &= data->pack(current_offset);
05398         rc &= data->pack(current_scale);
05399         rc &= data->pack(capacity);
05400         rc &= data->pack(capacity_warning);
05401         rc &= data->pack(capacity_critical);
05402         rc &= data->pack(capacity_units);
05403         if(!rc) data.reset();
05404         return data;
05405     }
05406 };
05407 
05408 struct InavRateProfileSettings {
05409     Value<uint8_t> throttle_rc_mid;
05410     Value<uint8_t> throttle_rc_expo;
05411     Value<uint8_t> throttle_dyn_pid;
05412     Value<uint16_t> throttle_pa_breakpoint;
05413 
05414     Value<uint8_t> stabilized_rc_expo;
05415     Value<uint8_t> stabilized_rc_yaw_expo;
05416     Value<uint8_t> stabilized_rate_r;
05417     Value<uint8_t> stabilized_rate_p;
05418     Value<uint8_t> stabilized_rate_y;
05419 
05420     Value<uint8_t> manual_rc_expo;
05421     Value<uint8_t> manual_rc_yaw_expo;
05422     Value<uint8_t> manual_rate_r;
05423     Value<uint8_t> manual_rate_p;
05424     Value<uint8_t> manual_rate_y;
05425 };
05426 
05427 // MSP2_INAV_RATE_PROFILE          = 0x2007,
05428 struct InavRateProfile : public InavRateProfileSettings, public Message {
05429     InavRateProfile(FirmwareVariant v) : Message(v) {}
05430 
05431     virtual ID id() const override { return ID::MSP2_INAV_RATE_PROFILE; }
05432 
05433     virtual bool decode(const ByteVector& data) override {
05434         bool rc = true;
05435         rc &= data.unpack(throttle_rc_mid);
05436         rc &= data.unpack(throttle_rc_expo);
05437         rc &= data.unpack(throttle_dyn_pid);
05438         rc &= data.unpack(throttle_pa_breakpoint);
05439 
05440         rc &= data.unpack(stabilized_rc_expo);
05441         rc &= data.unpack(stabilized_rc_yaw_expo);
05442         rc &= data.unpack(stabilized_rate_r);
05443         rc &= data.unpack(stabilized_rate_p);
05444         rc &= data.unpack(stabilized_rate_y);
05445 
05446         rc &= data.unpack(manual_rc_expo);
05447         rc &= data.unpack(manual_rc_yaw_expo);
05448         rc &= data.unpack(manual_rate_r);
05449         rc &= data.unpack(manual_rate_p);
05450         rc &= data.unpack(manual_rate_y);
05451         return rc;
05452     }
05453 };
05454 
05455 // MSP2_INAV_SET_RATE_PROFILE      = 0x2008,
05456 struct InavSetRateProfile : public InavRateProfileSettings, public Message {
05457     InavSetRateProfile(FirmwareVariant v) : Message(v) {}
05458 
05459     virtual ID id() const override { return ID::MSP2_INAV_SET_RATE_PROFILE; }
05460 
05461     virtual ByteVectorUptr encode() const override {
05462         ByteVectorUptr data = std::make_unique<ByteVector>();
05463         bool rc             = true;
05464         rc &= data->pack(throttle_rc_mid);
05465         rc &= data->pack(throttle_rc_expo);
05466         rc &= data->pack(throttle_dyn_pid);
05467         rc &= data->pack(throttle_pa_breakpoint);
05468 
05469         rc &= data->pack(stabilized_rc_expo);
05470         rc &= data->pack(stabilized_rc_yaw_expo);
05471         rc &= data->pack(stabilized_rate_r);
05472         rc &= data->pack(stabilized_rate_p);
05473         rc &= data->pack(stabilized_rate_y);
05474 
05475         rc &= data->pack(manual_rc_expo);
05476         rc &= data->pack(manual_rc_yaw_expo);
05477         rc &= data->pack(manual_rate_r);
05478         rc &= data->pack(manual_rate_p);
05479         rc &= data->pack(manual_rate_y);
05480         if(!rc) data.reset();
05481         return data;
05482     }
05483 };
05484 
05485 // MSP2_INAV_AIR_SPEED             = 0x2009
05486 struct InavAirSpeed : public InavMiscSettings, public Message {
05487     InavAirSpeed(FirmwareVariant v) : Message(v) {}
05488 
05489     virtual ID id() const override { return ID::MSP2_INAV_RATE_PROFILE; }
05490 
05491     Value<uint32_t> speed;
05492 
05493     virtual bool decode(const ByteVector& data) override {
05494         return data.unpack(speed);
05495     }
05496 };
05497 
05498 }  // namespace msg
05499 }  // namespace msp
05500 
05501 inline std::ostream& operator<<(std::ostream& s, const msp::msg::ImuSI& val) {
05502     return val.print(s);
05503 }
05504 
05505 #endif  // MSP_MSG_HPP


msp
Author(s): Christian Rauch
autogenerated on Thu Jun 20 2019 19:40:38