msp_msg.hpp
Go to the documentation of this file.
1 // MSP message definitions
2 // http://www.multiwii.com/wiki/index.php?title=Multiwii_Serial_Protocol
3 
4 #ifndef MSP_MSG_HPP
5 #define MSP_MSG_HPP
6 
7 #include <array>
8 #include <cassert>
9 #include <climits>
10 #include <iomanip>
11 #include <set>
12 #include <sstream>
13 #include <string>
14 #include <vector>
15 #include "Message.hpp"
16 
17 /*================================================================
18  * actual messages have id and the relevant encode decode methods
19  * the logic for encoding and decoding must be within a message-derived class
20  * non message-derived structs must have pack/unpack subroutines
21  *
22  */
23 
24 // undefine macros defined by GNU C std library
25 #undef major
26 #undef minor
27 
28 namespace msp {
29 
30 enum class ID : uint16_t {
31  MSP_API_VERSION = 1,
32  MSP_FC_VARIANT = 2,
33  MSP_FC_VERSION = 3,
34  MSP_BOARD_INFO = 4,
35  MSP_BUILD_INFO = 5,
36  MSP_INAV_PID = 6,
37  MSP_SET_INAV_PID = 7,
38  MSP_NAME = 10, // out message
39  MSP_SET_NAME = 11, // in message
40  MSP_NAV_POSHOLD = 12, // only in iNav
41  MSP_SET_NAV_POSHOLD = 13, // only in iNav
46  MSP_WP_MISSION_LOAD = 18, // Load mission from NVRAM
47  MSP_WP_MISSION_SAVE = 19, // Save mission to NVRAM
48  MSP_WP_GETINFO = 20,
51  MSP_FW_CONFIG = 23,
52  MSP_SET_FW_CONFIG = 24,
53  MSP_BATTERY_CONFIG = 32, // not avaialable in iNav
54  MSP_SET_BATTERY_CONFIG = 33, // not avaialable in iNav
55  MSP_MODE_RANGES = 34,
56  MSP_SET_MODE_RANGE = 35,
57  MSP_FEATURE = 36,
58  MSP_SET_FEATURE = 37,
63  MSP_MIXER = 42,
64  MSP_SET_MIXER = 43,
65  MSP_RX_CONFIG = 44,
66  MSP_SET_RX_CONFIG = 45,
67  MSP_LED_COLORS = 46,
68  MSP_SET_LED_COLORS = 47,
71  MSP_RSSI_CONFIG = 50,
79  MSP_SONAR_ALTITUDE = 58,
80  MSP_PID_CONTROLLER = 59,
82  MSP_ARMING_CONFIG = 61,
84  MSP_RX_MAP = 64,
85  MSP_SET_RX_MAP = 65,
86  MSP_BF_CONFIG = 66, // depricated, out message
87  MSP_SET_BF_CONFIG = 67, // depricated, in message
88  MSP_REBOOT = 68,
89  MSP_BF_BUILD_INFO = 69, // depricated, iNav
91  MSP_DATAFLASH_READ = 71,
93  MSP_LOOP_TIME = 73, // depricated, iNav
94  MSP_SET_LOOP_TIME = 74, // depricated, iNav
97  MSP_RXFAIL_CONFIG = 77, // depricated, iNav
98  MSP_SET_RXFAIL_CONFIG = 78, // depricated, iNav
99  MSP_SDCARD_SUMMARY = 79,
100  MSP_BLACKBOX_CONFIG = 80,
104  MSP_OSD_CONFIG = 84, // out message, betaflight
105  MSP_SET_OSD_CONFIG = 85, // in message, betaflight
106  MSP_OSD_CHAR_READ = 86, // out message, betaflight
107  MSP_OSD_CHAR_WRITE = 87,
108  MSP_VTX_CONFIG = 88,
109  MSP_SET_VTX_CONFIG = 89,
110  MSP_ADVANCED_CONFIG = 90,
112  MSP_FILTER_CONFIG = 92,
114  MSP_PID_ADVANCED = 94,
116  MSP_SENSOR_CONFIG = 96,
118  MSP_CAMERA_CONTROL = 98, // MSP_SPECIAL_PARAMETERS
119  MSP_SET_ARMING_DISABLED = 99, // MSP_SET_SPECIAL_PARAMETERS
120  MSP_IDENT = 100, // depricated
121  MSP_STATUS = 101,
122  MSP_RAW_IMU = 102,
123  MSP_SERVO = 103,
124  MSP_MOTOR = 104,
125  MSP_RC = 105,
126  MSP_RAW_GPS = 106,
127  MSP_COMP_GPS = 107,
128  MSP_ATTITUDE = 108,
129  MSP_ALTITUDE = 109,
130  MSP_ANALOG = 110,
131  MSP_RC_TUNING = 111,
132  MSP_PID = 112,
133  MSP_ACTIVEBOXES = 113, // depricated, iNav
134  MSP_MISC = 114, // depricated, iNav
135  MSP_MOTOR_PINS = 115, // depricated, iNav
136  MSP_BOXNAMES = 116,
137  MSP_PIDNAMES = 117,
138  MSP_WP = 118,
139  MSP_BOXIDS = 119,
140  MSP_SERVO_CONF = 120,
141  MSP_NAV_STATUS = 121,
142  MSP_NAV_CONFIG = 122,
143  MSP_MOTOR_3D_CONFIG = 124,
144  MSP_RC_DEADBAND = 125,
145  MSP_SENSOR_ALIGNMENT = 126,
147  MSP_VOLTAGE_METERS = 128, // not present in iNav
148  MSP_CURRENT_METERS = 129, // not present in iNav
149  MSP_BATTERY_STATE = 130, // not present in iNav
150  MSP_MOTOR_CONFIG = 131, // out message
151  MSP_GPS_CONFIG = 132, // out message
152  MSP_COMPASS_CONFIG = 133, // out message
153  MSP_ESC_SENSOR_DATA = 134, // out message
154  MSP_STATUS_EX = 150,
155  MSP_SENSOR_STATUS = 151, // only iNav
156  MSP_UID = 160,
157  MSP_GPSSVINFO = 164,
158  MSP_GPSSTATISTICS = 166,
159  MSP_OSD_VIDEO_CONFIG = 180,
161  MSP_DISPLAYPORT = 182,
162  MSP_COPY_PROFILE = 183, // not in iNav
163  MSP_BEEPER_CONFIG = 184, // not in iNav
164  MSP_SET_BEEPER_CONFIG = 185, // not in iNav
165  MSP_SET_TX_INFO = 186, // in message
166  MSP_TX_INFO = 187, // out message
167  MSP_SET_RAW_RC = 200,
168  MSP_SET_RAW_GPS = 201,
169  MSP_SET_PID = 202,
170  MSP_SET_BOX = 203, // depricated
171  MSP_SET_RC_TUNING = 204,
172  MSP_ACC_CALIBRATION = 205,
173  MSP_MAG_CALIBRATION = 206,
174  MSP_SET_MISC = 207, // depricated
175  MSP_RESET_CONF = 208,
176  MSP_SET_WP = 209,
177  MSP_SELECT_SETTING = 210,
178  MSP_SET_HEADING = 211,
179  MSP_SET_SERVO_CONF = 212,
180  MSP_SET_MOTOR = 214,
181  MSP_SET_NAV_CONFIG = 215,
182  MSP_SET_MOTOR_3D_CONF = 217,
183  MSP_SET_RC_DEADBAND = 218,
187  MSP_SET_MOTOR_CONFIG = 222, // out message
188  MSP_SET_GPS_CONFIG = 223, // out message
189  MSP_SET_COMPASS_CONFIG = 224, // out message
190  MSP_SET_ACC_TRIM = 239, // in message
191  MSP_ACC_TRIM = 240, // out message
192  MSP_SERVO_MIX_RULES = 241, // out message
193  MSP_SET_SERVO_MIX_RULE = 242, // in message
194  MSP_PASSTHROUGH_SERIAL = 244, // not used in CF, BF, iNav
195  MSP_SET_4WAY_IF = 245, // in message
196  MSP_SET_RTC = 246, // in message
197  MSP_RTC = 247, // out message
198  MSP_EEPROM_WRITE = 250, // in message
199  MSP_RESERVE_1 = 251, // reserved for system usage
200  MSP_RESERVE_2 = 252, // reserved for system usage
201  MSP_DEBUGMSG = 253, // out message
202  MSP_DEBUG = 254, // out message
203  MSP_V2_FRAME = 255, // MSPv2 over MSPv1
204 
205  MSP2_COMMON_TZ = 0x1001, // out message, TZ offset
206  MSP2_COMMON_SET_TZ = 0x1002, // in message, sets the TZ offset
207  MSP2_COMMON_SETTING = 0x1003, // in/out message, returns setting
208  MSP2_COMMON_SET_SETTING = 0x1004, // in message, sets a setting value
209  MSP2_COMMON_MOTOR_MIXER = 0x1005,
211  MSP2_INAV_STATUS = 0x2000,
212  MSP2_INAV_OPTICAL_FLOW = 0x2001,
213  MSP2_INAV_ANALOG = 0x2002,
214  MSP2_INAV_MISC = 0x2003,
215  MSP2_INAV_SET_MISC = 0x2004,
216  MSP2_INAV_BATTERY_CONFIG = 0x2005,
218  MSP2_INAV_RATE_PROFILE = 0x2007,
220  MSP2_INAV_AIR_SPEED = 0x2009
221 };
222 
223 enum class ArmingFlags : uint32_t {
224  ARMED = (1 << 2),
225  WAS_EVER_ARMED = (1 << 3),
226 
228 
229  ARMING_DISABLED_NOT_LEVEL = (1 << 8),
235  ARMING_DISABLED_ARM_SWITCH = (1 << 14),
237  ARMING_DISABLED_BOXFAILSAFE = (1 << 16),
238  ARMING_DISABLED_BOXKILLSWITCH = (1 << 17),
239  ARMING_DISABLED_RC_LINK = (1 << 18),
240  ARMING_DISABLED_THROTTLE = (1 << 19),
241  ARMING_DISABLED_CLI = (1 << 20),
242  ARMING_DISABLED_CMS_MENU = (1 << 21),
243  ARMING_DISABLED_OSD_MENU = (1 << 22),
245  ARMING_DISABLED_SERVO_AUTOTRIM = (1 << 24),
246  ARMING_DISABLED_OOM = (1 << 25),
248 
262 };
263 
264 inline std::string armingFlagToString(uint32_t flag) {
265  std::string val;
266  if(flag & (1 << 2)) val += "ARMED ";
267  if(flag & (1 << 3)) val += "WAS_EVER_ARMED ";
268  if(flag & (1 << 7)) val += "ARMING_DISABLED_FAILSAFE_SYSTEM ";
269  if(flag & (1 << 8)) val += "ARMING_DISABLED_NOT_LEVEL ";
270  if(flag & (1 << 9)) val += "ARMING_DISABLED_SENSORS_CALIBRATING ";
271  if(flag & (1 << 10)) val += "ARMING_DISABLED_SYSTEM_OVERLOADED ";
272  if(flag & (1 << 11)) val += "ARMING_DISABLED_NAVIGATION_UNSAFE ";
273  if(flag & (1 << 12)) val += "ARMING_DISABLED_COMPASS_NOT_CALIBRATED ";
274  if(flag & (1 << 13)) val += "ARMING_DISABLED_ACCELEROMETER_NOT_CALIBRATED ";
275  if(flag & (1 << 14)) val += "ARMING_DISABLED_ARM_SWITCH ";
276  if(flag & (1 << 15)) val += "ARMING_DISABLED_HARDWARE_FAILURE ";
277  if(flag & (1 << 16)) val += "ARMING_DISABLED_BOXFAILSAFE ";
278  if(flag & (1 << 17)) val += "ARMING_DISABLED_BOXKILLSWITCH ";
279  if(flag & (1 << 18)) val += "ARMING_DISABLED_RC_LINK ";
280  if(flag & (1 << 19)) val += "ARMING_DISABLED_THROTTLE ";
281  if(flag & (1 << 20)) val += "ARMING_DISABLED_CLI ";
282  if(flag & (1 << 21)) val += "ARMING_DISABLED_CMS_MENU ";
283  if(flag & (1 << 22)) val += "ARMING_DISABLED_OSD_MENU ";
284  if(flag & (1 << 23)) val += "ARMING_DISABLED_ROLLPITCH_NOT_CENTERED ";
285  if(flag & (1 << 24)) val += "ARMING_DISABLED_SERVO_AUTOTRIM ";
286  if(flag & (1 << 25)) val += "ARMING_DISABLED_OOM ";
287  if(flag & (1 << 26)) val += "ARMING_DISABLED_INVALID_SETTING ";
288  return val;
289 }
290 
291 namespace msg {
292 
293 const static size_t N_SERVO = 8;
294 const static size_t N_MOTOR = 8;
295 
296 const static size_t BOARD_IDENTIFIER_LENGTH = 4;
297 
298 const static size_t BUILD_DATE_LENGTH = 11;
299 const static size_t BUILD_TIME_LENGTH = 8;
300 const static size_t GIT_SHORT_REVISION_LENGTH = 7;
301 
302 const static size_t MAX_NAME_LENGTH = 16;
303 const static size_t MAX_MODE_ACTIVATION_CONDITION_COUNT = 20;
304 
305 const static size_t LED_CONFIGURABLE_COLOR_COUNT = 16;
306 const static size_t LED_MAX_STRIP_LENGTH = 32;
307 
308 const static size_t MAX_ADJUSTMENT_RANGE_COUNT = 12;
309 const static size_t MAX_SIMULTANEOUS_ADJUSTMENT_COUNT = 6;
310 
311 const static size_t OSD_ITEM_COUNT = 41; // manual count from iNav io/osd.h
312 
313 const static size_t MAX_MAPPABLE_RX_INPUTS = 4; // unique to REVO?
314 
315 const static size_t LED_MODE_COUNT = 6;
316 const static size_t LED_DIRECTION_COUNT = 6;
317 const static size_t LED_SPECIAL_COLOR_COUNT = 11;
318 
319 enum class MultiType : uint8_t {
320  TRI = 1,
321  QUADP, // 2
322  QUADX, // 3
323  BI, // 4
324  GIMBAL, // 5
325  Y6, // 6
326  HEX6, // 7
327  FLYING_WING, // 8
328  Y4, // 9
329  HEX6X, // 10
330  OCTOX8, // 11
331  OCTOFLATP, // 12
332  OCTOFLATX, // 13
333  AIRPLANE, // 14
334  HELI_120_CCPM, // 15
335  HELI_90_DEG, // 16
336  VTAIL4, // 17
337  HEX6H, // 18
338  DUALCOPTER = 20,
339  SINGLECOPTER, // 21
340 };
341 
342 enum class Capability { BIND, DYNBAL, FLAP, NAVCAP, EXTAUX };
343 
344 enum class Sensor {
346  Barometer,
347  Magnetometer,
348  GPS,
349  Sonar,
350  OpticalFlow,
351  Pitot,
353 };
354 
355 const static size_t NAUX = 4;
356 
357 enum class SwitchPosition : size_t {
358  LOW = 0,
359  MID = 1,
360  HIGH = 2,
361 };
362 
363 static const std::vector<std::string> FEATURES = {"RX_PPM",
364  "VBAT",
365  "INFLIGHT_ACC_CAL",
366  "RX_SERIAL",
367  "MOTOR_STOP",
368  "SERVO_TILT",
369  "SOFTSERIAL",
370  "GPS",
371  "FAILSAFE",
372  "SONAR",
373  "TELEMETRY",
374  "AMPERAGE_METER",
375  "3D",
376  "RX_PARALLEL_PWM",
377  "RX_MSP",
378  "RSSI_ADC",
379  "LED_STRIP",
380  "DISPLAY",
381  "ONESHOT125",
382  "BLACKBOX",
383  "CHANNEL_FORWARDING",
384  "TRANSPONDER",
385  "OSD"};
386 
387 enum class PID_Element : uint8_t {
388  PID_ROLL = 0,
389  PID_PITCH,
390  PID_YAW,
391  PID_POS_Z,
392  PID_POS_XY,
393  PID_VEL_XY,
394  PID_SURFACE,
395  PID_LEVEL,
396  PID_HEADING,
397  PID_VEL_Z,
399 };
400 
403 
404 // MSP_API_VERSION: 1
405 struct ApiVersion : public Message {
407 
408  virtual ID id() const override { return ID::MSP_API_VERSION; }
409 
413 
414  virtual bool decode(const ByteVector& data) override {
415  bool rc = true;
416  rc &= data.unpack(protocol);
417  rc &= data.unpack(major);
418  rc &= data.unpack(minor);
419  return rc;
420  }
421 
422  virtual std::ostream& print(std::ostream& s) const override {
423  s << "#Api Version:" << std::endl;
424  s << " API: " << major << "." << minor << std::endl;
425  s << " Protocol: " << protocol << std::endl;
426  return s;
427  }
428 };
429 
430 // MSP_FC_VARIANT: 2
431 struct FcVariant : public Message {
433 
434  virtual ID id() const override { return ID::MSP_FC_VARIANT; }
435 
437 
438  virtual bool decode(const ByteVector& data) override {
439  return data.unpack(identifier, data.size());
440  }
441 
442  virtual std::ostream& print(std::ostream& s) const override {
443  s << "#FC variant:" << std::endl;
444  s << " Identifier: " << identifier << std::endl;
445  return s;
446  }
447 };
448 
449 // MSP_FC_VERSION: 3
450 struct FcVersion : public Message {
452 
453  virtual ID id() const override { return ID::MSP_FC_VERSION; }
454 
458 
459  virtual bool decode(const ByteVector& data) override {
460  bool rc = true;
461  rc &= data.unpack(major);
462  rc &= data.unpack(minor);
463  rc &= data.unpack(patch_level);
464  return rc;
465  }
466 
467  virtual std::ostream& print(std::ostream& s) const override {
468  s << "#FC version:" << std::endl;
469  s << " Version: " << major << "." << minor << "." << patch_level
470  << std::endl;
471  return s;
472  }
473 };
474 
475 // MSP_BOARD_INFO: 4
476 struct BoardInfo : public Message {
478 
479  virtual ID id() const override { return ID::MSP_BOARD_INFO; }
480 
486 
487  virtual bool decode(const ByteVector& data) override {
488  bool rc = true;
489  rc &= data.unpack(identifier, BOARD_IDENTIFIER_LENGTH);
490  rc &= data.unpack(version);
491  rc &= data.unpack(osd_support);
492  rc &= data.unpack(comms_capabilites);
493  uint8_t name_len = 0;
494  rc &= data.unpack(name_len);
495  rc &= data.unpack(name, name_len);
496  return rc;
497  }
498 
499  virtual std::ostream& print(std::ostream& s) const override {
500  s << "#Board Info:" << std::endl;
501  s << " Identifier: " << identifier << std::endl;
502  s << " Version: " << version << std::endl;
503  s << " OSD support: " << osd_support << std::endl;
504  s << " Comms bitmask: " << comms_capabilites << std::endl;
505  s << " Board Name: " << name << std::endl;
506  return s;
507  }
508 };
509 
510 // MSP_BUILD_INFO: 5
511 struct BuildInfo : public Message {
513 
514  virtual ID id() const override { return ID::MSP_BUILD_INFO; }
515 
519 
520  virtual bool decode(const ByteVector& data) override {
521  bool rc = true;
522  rc &= data.unpack(buildDate, BUILD_DATE_LENGTH);
523  rc &= data.unpack(buildTime, BUILD_TIME_LENGTH);
524  rc &= data.unpack(shortGitRevision, GIT_SHORT_REVISION_LENGTH);
525  return rc;
526  }
527 
528  virtual std::ostream& print(std::ostream& s) const override {
529  s << "#Build Info:" << std::endl;
530  s << " Date: " << buildDate << std::endl;
531  s << " Time: " << buildTime << std::endl;
532  s << " Git revision: " << shortGitRevision << std::endl;
533  return s;
534  }
535 };
536 
546 };
547 
548 // MSP_INAV_PID: 6
549 struct InavPid : public InavPidSettings, public Message {
551 
552  virtual ID id() const override { return ID::MSP_INAV_PID; }
553 
554  virtual bool decode(const ByteVector& data) override {
555  bool rc = true;
556  rc &= data.unpack(async_mode);
557  rc &= data.unpack(acc_task_frequency);
558  rc &= data.unpack(attitude_task_frequency);
559  rc &= data.unpack(heading_hold_rate_limit);
560  rc &= data.unpack(heading_hold_error_lpf_freq);
561  rc &= data.unpack(yaw_jump_prevention_limit);
562  rc &= data.unpack(gyro_lpf);
563  rc &= data.unpack(acc_soft_lpf_hz);
564  // read the reserved bytes
565  rc &= data.consume(4);
566  return rc;
567  }
568 };
569 
570 // MSP_SET_INAV_PID: 7
571 struct SetInavPid : public InavPidSettings, public Message {
573 
574  virtual ID id() const override { return ID::MSP_SET_INAV_PID; }
575 
576  virtual ByteVectorUptr encode() const override {
577  ByteVectorUptr data = std::make_unique<ByteVector>();
578  bool rc = true;
579  rc &= data->pack(async_mode);
580  rc &= data->pack(acc_task_frequency);
581  rc &= data->pack(attitude_task_frequency);
582  rc &= data->pack(heading_hold_rate_limit);
583  rc &= data->pack(heading_hold_error_lpf_freq);
584  rc &= data->pack(yaw_jump_prevention_limit);
585  rc &= data->pack(gyro_lpf);
586  rc &= data->pack(acc_soft_lpf_hz);
587  // write the reserved bytes
588  rc &= data->pack(uint32_t(0));
589  if(!rc) data.reset();
590  return data;
591  }
592 };
593 
594 // MSP_NAME: 10
595 struct BoardName : public Message {
597 
598  virtual ID id() const override { return ID::MSP_NAME; }
599 
601 
602  virtual bool decode(const ByteVector& data) override {
603  return data.unpack(name);
604  }
605 };
606 
607 // MSP_SET_NAME: 11
608 struct SetBoardName : public Message {
610 
611  virtual ID id() const override { return ID::MSP_SET_NAME; }
612 
614 
615  virtual ByteVectorUptr encode() const override {
616  ByteVectorUptr data = std::make_unique<ByteVector>();
617  if(!data->pack(name, MAX_NAME_LENGTH)) data.reset();
618  return data;
619  }
620 };
621 
631 };
632 
633 // MSP_NAV_POSHOLD: 12
634 struct NavPosHold : public NavPosHoldSettings, public Message {
636 
637  virtual ID id() const override { return ID::MSP_NAV_POSHOLD; }
638 
639  virtual bool decode(const ByteVector& data) override {
640  bool rc = true;
641  rc &= data.unpack(user_control_mode);
642  rc &= data.unpack(max_auto_speed);
643  rc &= data.unpack(max_auto_climb_rate);
644  rc &= data.unpack(max_manual_speed);
645  rc &= data.unpack(max_manual_climb_rate);
646  rc &= data.unpack(max_bank_angle);
647  rc &= data.unpack(use_thr_mid_for_althold);
648  rc &= data.unpack(hover_throttle);
649  return rc;
650  }
651 };
652 
653 // MSP_SET_NAV_POSHOLD: 13
654 struct SetNavPosHold : public NavPosHoldSettings, public Message {
656 
657  virtual ID id() const override { return ID::MSP_SET_NAV_POSHOLD; }
658 
659  virtual ByteVectorUptr encode() const override {
660  ByteVectorUptr data = std::make_unique<ByteVector>();
661  bool rc = true;
662  rc &= data->pack(user_control_mode);
663  rc &= data->pack(max_auto_speed);
664  rc &= data->pack(max_auto_climb_rate);
665  rc &= data->pack(max_manual_speed);
666  rc &= data->pack(max_manual_climb_rate);
667  rc &= data->pack(max_bank_angle);
668  rc &= data->pack(use_thr_mid_for_althold);
669  rc &= data->pack(hover_throttle);
670  if(!rc) data.reset();
671  return data;
672  }
673 };
674 
682 };
683 
684 // MSP_CALIBRATION_DATA: 14
687 
688  virtual ID id() const override { return ID::MSP_CALIBRATION_DATA; }
689 
691 
692  virtual bool decode(const ByteVector& data) override {
693  bool rc = true;
694  rc &= data.unpack(axis_calibration_flags);
695  rc &= data.unpack(acc_zero_x);
696  rc &= data.unpack(acc_zero_y);
697  rc &= data.unpack(acc_zero_z);
698  rc &= data.unpack(acc_gain_x);
699  rc &= data.unpack(acc_gain_y);
700  rc &= data.unpack(acc_gain_z);
701  return rc;
702  }
703 };
704 
705 // MSP_SET_CALIBRATION_DATA: 15
708 
709  virtual ID id() const override { return ID::MSP_SET_CALIBRATION_DATA; }
710 
711  virtual ByteVectorUptr encode() const override {
712  ByteVectorUptr data = std::make_unique<ByteVector>();
713  bool rc = true;
714  rc &= data->pack(acc_zero_x);
715  rc &= data->pack(acc_zero_y);
716  rc &= data->pack(acc_zero_z);
717  rc &= data->pack(acc_gain_x);
718  rc &= data->pack(acc_gain_y);
719  rc &= data->pack(acc_gain_z);
720  if(!rc) data.reset();
721  return data;
722  }
723 };
724 
733 };
734 
735 // MSP_POSITION_ESTIMATION_CONFIG: 16
737  public Message {
739 
740  virtual ID id() const override {
742  }
743 
744  virtual bool decode(const ByteVector& data) override {
745  bool rc = true;
746  rc &= data.unpack<uint16_t>(w_z_baro_p, 100);
747  rc &= data.unpack<uint16_t>(w_z_gps_p, 100);
748  rc &= data.unpack<uint16_t>(w_z_gps_v, 100);
749  rc &= data.unpack<uint16_t>(w_xy_gps_p, 100);
750  rc &= data.unpack<uint16_t>(w_xy_gps_v, 100);
751  rc &= data.unpack(gps_min_sats);
752  rc &= data.unpack(use_gps_vel_NED);
753  return rc;
754  }
755 };
756 
757 // MSP_SET_POSITION_ESTIMATION_CONFIG: 17
759  public Message {
761 
762  virtual ID id() const override {
764  }
765 
766  virtual ByteVectorUptr encode() const override {
767  ByteVectorUptr data = std::make_unique<ByteVector>();
768  bool rc = true;
769  rc &= data->pack<uint16_t>(w_z_baro_p, 100);
770  rc &= data->pack<uint16_t>(w_z_gps_p, 100);
771  rc &= data->pack<uint16_t>(w_z_gps_v, 100);
772  rc &= data->pack<uint16_t>(w_xy_gps_p, 100);
773  rc &= data->pack<uint16_t>(w_xy_gps_v, 100);
774  rc &= data->pack(gps_min_sats);
775  rc &= data->pack(use_gps_vel_NED);
776  if(!rc) data.reset();
777  return data;
778  }
779 };
780 
781 // MSP_WP_MISSION_LOAD: 18
782 struct WpMissionLoad : public Message {
784 
785  virtual ID id() const override { return ID::MSP_WP_MISSION_LOAD; }
786 
787  virtual ByteVectorUptr encode() const override {
788  ByteVectorUptr data = std::make_unique<ByteVector>();
789  if(!data->pack(uint8_t(0))) data.reset();
790  return data;
791  }
792 };
793 
794 // MSP_WP_MISSION_SAVE: 19
795 struct WpMissionSave : public Message {
797 
798  virtual ID id() const override { return ID::MSP_WP_MISSION_SAVE; }
799 
800  virtual ByteVectorUptr encode() const override {
801  ByteVectorUptr data = std::make_unique<ByteVector>();
802  if(!data->pack(uint8_t(0))) data.reset();
803  return data;
804  }
805 };
806 
807 // MSP_WP_GETINFO: 20
808 struct WpGetInfo : public Message {
810 
811  virtual ID id() const override { return ID::MSP_WP_GETINFO; }
812 
817 
818  virtual bool decode(const ByteVector& data) override {
819  bool rc = true;
820  rc &= data.unpack(wp_capabilites);
821  rc &= data.unpack(max_waypoints);
822  rc &= data.unpack(wp_list_valid);
823  rc &= data.unpack(wp_count);
824  return rc;
825  }
826 };
827 
841 };
842 
843 // MSP_RTH_AND_LAND_CONFIG: 21
846 
847  virtual ID id() const override { return ID::MSP_RTH_AND_LAND_CONFIG; }
848 
849  virtual bool decode(const ByteVector& data) override {
850  bool rc = true;
851  rc &= data.unpack(min_rth_distance);
852  rc &= data.unpack(rth_climb_first);
853  rc &= data.unpack(rth_climb_ignore_emerg);
854  rc &= data.unpack(rth_tail_first);
855  rc &= data.unpack(rth_allow_landing);
856  rc &= data.unpack(rth_alt_control_mode);
857  rc &= data.unpack(rth_abort_threshold);
858  rc &= data.unpack(rth_altitude);
859  rc &= data.unpack(land_descent_rate);
860  rc &= data.unpack(land_slowdown_minalt);
861  rc &= data.unpack(land_slowdown_maxalt);
862  rc &= data.unpack(emerg_descent_rate);
863  return rc;
864  }
865 };
866 
867 // MSP_SET_RTH_AND_LAND_CONFIG: 22
870 
871  virtual ID id() const override { return ID::MSP_SET_RTH_AND_LAND_CONFIG; }
872 
873  virtual ByteVectorUptr encode() const override {
874  ByteVectorUptr data = std::make_unique<ByteVector>();
875  bool rc = true;
876  rc &= data->pack(min_rth_distance);
877  rc &= data->pack(rth_climb_first);
878  rc &= data->pack(rth_climb_ignore_emerg);
879  rc &= data->pack(rth_tail_first);
880  rc &= data->pack(rth_allow_landing);
881  rc &= data->pack(rth_alt_control_mode);
882  rc &= data->pack(rth_abort_threshold);
883  rc &= data->pack(rth_altitude);
884  rc &= data->pack(land_descent_rate);
885  rc &= data->pack(land_slowdown_minalt);
886  rc &= data->pack(land_slowdown_maxalt);
887  rc &= data->pack(emerg_descent_rate);
888  if(!rc) data.reset();
889  return data;
890  }
891 };
892 
902 };
903 
904 // MSP_FW_CONFIG: 23
905 struct FwConfig : public FwConfigSettings, public Message {
907 
908  virtual ID id() const override { return ID::MSP_FW_CONFIG; }
909 
910  virtual bool decode(const ByteVector& data) override {
911  bool rc = true;
912  rc &= data.unpack(cruise_throttle);
913  rc &= data.unpack(min_throttle);
914  rc &= data.unpack(max_throttle);
915  rc &= data.unpack(max_bank_angle);
916  rc &= data.unpack(max_climb_angle);
917  rc &= data.unpack(max_dive_angle);
918  rc &= data.unpack(pitch_to_throttle);
919  rc &= data.unpack(loiter_radius);
920  return rc;
921  }
922 };
923 
924 // MSP_SET_FW_CONFIG: 24
925 struct SetFwConfig : public FwConfigSettings, public Message {
927 
928  virtual ID id() const override { return ID::MSP_SET_FW_CONFIG; }
929 
930  virtual ByteVectorUptr encode() const override {
931  ByteVectorUptr data = std::make_unique<ByteVector>();
932  bool rc = true;
933  rc &= data->pack(cruise_throttle);
934  rc &= data->pack(min_throttle);
935  rc &= data->pack(max_throttle);
936  rc &= data->pack(max_bank_angle);
937  rc &= data->pack(max_climb_angle);
938  rc &= data->pack(max_dive_angle);
939  rc &= data->pack(pitch_to_throttle);
940  rc &= data->pack(loiter_radius);
941  if(!rc) data.reset();
942  return data;
943  }
944 };
945 
953 };
954 
955 // MSP_BATTERY_CONFIG: 32
956 struct BatteryConfig : public BatteryConfigSettings, public Message {
958 
959  virtual ID id() const override { return ID::MSP_BATTERY_CONFIG; }
960 
961  virtual bool decode(const ByteVector& data) override {
962  bool rc = true;
963  rc &= data.unpack(vbatmincellvoltage);
964  rc &= data.unpack(vbatmaxcellvoltage);
965  rc &= data.unpack(vbatwarningcellvoltage);
966  rc &= data.unpack(batteryCapacity);
967  rc &= data.unpack(voltageMeterSource);
968  rc &= data.unpack(currentMeterSource);
969  return rc;
970  }
971 };
972 
973 // MSP_SET_BATTERY_CONFIG: 33
976 
977  virtual ID id() const override { return ID::MSP_SET_BATTERY_CONFIG; }
978 
979  virtual ByteVectorUptr encode() const override {
980  ByteVectorUptr data = std::make_unique<ByteVector>();
981  bool rc = true;
982  rc &= data->pack(vbatmincellvoltage);
983  rc &= data->pack(vbatmaxcellvoltage);
984  rc &= data->pack(vbatwarningcellvoltage);
985  rc &= data->pack(batteryCapacity);
986  rc &= data->pack(voltageMeterSource);
987  rc &= data->pack(currentMeterSource);
988  if(!rc) data.reset();
989  return data;
990  }
991 };
992 
998 };
999 
1000 // MSP_MODE_RANGES: 34
1001 struct ModeRanges : public Message {
1003 
1004  virtual ID id() const override { return ID::MSP_MODE_RANGES; }
1005 
1006  std::array<box_description, MAX_MODE_ACTIVATION_CONDITION_COUNT> boxes;
1007 
1008  virtual bool decode(const ByteVector& data) override {
1009  bool rc = true;
1010  for(size_t i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) {
1011  rc &= data.unpack(boxes[i].id);
1012  rc &= data.unpack(boxes[i].aux_channel_index);
1013  rc &= data.unpack(boxes[i].startStep);
1014  rc &= data.unpack(boxes[i].endStep);
1015  }
1016  return rc;
1017  }
1018 };
1019 
1020 // MSP_SET_MODE_RANGE: 35
1021 struct SetModeRange : public Message {
1023 
1024  virtual ID id() const override { return ID::MSP_SET_MODE_RANGE; }
1025 
1028 
1029  virtual ByteVectorUptr encode() const override {
1030  ByteVectorUptr data = std::make_unique<ByteVector>();
1031  bool rc = true;
1032  rc &= data->pack(mode_activation_condition_idx);
1033  rc &= data->pack(box.id);
1034  rc &= data->pack(box.aux_channel_index);
1035  rc &= data->pack(box.startStep);
1036  rc &= data->pack(box.endStep);
1037  if(!rc) data.reset();
1038  return data;
1039  }
1040 };
1041 
1042 // MSP_FEATURE: 36
1043 struct Feature : public Message {
1045 
1046  virtual ID id() const override { return ID::MSP_FEATURE; }
1047 
1048  std::set<std::string> features;
1049 
1050  virtual bool decode(const ByteVector& data) override {
1051  uint32_t mask;
1052  bool rc = data.unpack(mask);
1053  if(!rc) return rc;
1054  features.clear();
1055  for(size_t ifeat(0); ifeat < FEATURES.size(); ifeat++) {
1056  if(mask & (1 << ifeat)) features.insert(FEATURES[ifeat]);
1057  }
1058  return rc;
1059  }
1060 
1061  virtual std::ostream& print(std::ostream& s) const override {
1062  s << "#Features:" << std::endl;
1063  for(const std::string& f : features) {
1064  s << f << std::endl;
1065  }
1066  return s;
1067  }
1068 };
1069 
1070 // MSP_SET_FEATURE: 37
1071 struct SetFeature : public Message {
1073 
1074  virtual ID id() const override { return ID::MSP_SET_FEATURE; }
1075 
1076  std::set<std::string> features;
1077 
1078  virtual ByteVectorUptr encode() const override {
1079  ByteVectorUptr data = std::make_unique<ByteVector>();
1080  uint32_t mask = 0;
1081  for(size_t ifeat(0); ifeat < FEATURES.size(); ifeat++) {
1082  if(features.count(FEATURES[ifeat])) mask |= 1 << ifeat;
1083  }
1084  if(!data->pack(mask)) data.reset();
1085  return data;
1086  }
1087 };
1088 
1089 // iNav uses decidegrees, BF/CF use degrees
1094 };
1095 
1096 // MSP_BOARD_ALIGNMENT: 38
1099 
1100  virtual ID id() const override { return ID::MSP_BOARD_ALIGNMENT; }
1101 
1102  virtual bool decode(const ByteVector& data) override {
1103  bool rc = true;
1104  rc &= data.unpack(roll);
1105  rc &= data.unpack(pitch);
1106  rc &= data.unpack(yaw);
1107  return rc;
1108  }
1109 };
1110 
1111 // MSP_SET_BOARD_ALIGNMENT: 39
1114 
1115  virtual ID id() const override { return ID::MSP_BOARD_ALIGNMENT; }
1116 
1117  virtual ByteVectorUptr encode() const override {
1118  ByteVectorUptr data = std::make_unique<ByteVector>();
1119  bool rc = true;
1120  rc &= data->pack(roll);
1121  rc &= data->pack(pitch);
1122  rc &= data->pack(yaw);
1123  if(!rc) data.reset();
1124  return data;
1125  }
1126 };
1127 
1133 };
1134 
1135 // MSP_CURRENT_METER_CONFIG: 40 (differs from Cleanflight/BetaFlight)
1138 
1139  virtual ID id() const override { return ID::MSP_CURRENT_METER_CONFIG; }
1140 
1141  virtual bool decode(const ByteVector& data) override {
1142  bool rc = true;
1143  rc &= data.unpack(currnet_scale);
1144  rc &= data.unpack(current_offset);
1145  rc &= data.unpack(current_type);
1146  rc &= data.unpack(capacity);
1147  return rc;
1148  }
1149 };
1150 
1151 // MSP_SET_CURRENT_METER_CONFIG: 41 (differs from Cleanflight/BetaFlight)
1153  public Message {
1155 
1156  virtual ID id() const override { return ID::MSP_SET_CURRENT_METER_CONFIG; }
1157 
1158  virtual ByteVectorUptr encode() const override {
1159  ByteVectorUptr data = std::make_unique<ByteVector>();
1160  bool rc = true;
1161  rc &= data->pack(currnet_scale);
1162  rc &= data->pack(current_offset);
1163  rc &= data->pack(current_type);
1164  rc &= data->pack(capacity);
1165  if(!rc) data.reset();
1166  return data;
1167  }
1168 };
1169 
1170 // MSP_MIXER: 42
1171 struct Mixer : public Message {
1173 
1174  virtual ID id() const override { return ID::MSP_MIXER; }
1175 
1177 
1178  virtual bool decode(const ByteVector& data) override {
1179  return data.unpack(mode);
1180  }
1181 };
1182 
1183 // MSP_SET_MIXER: 43
1184 struct SetMixer : public Message {
1186 
1187  virtual ID id() const override { return ID::MSP_SET_MIXER; }
1188 
1190 
1191  virtual ByteVectorUptr encode() const override {
1192  ByteVectorUptr data = std::make_unique<ByteVector>();
1193  if(!data->pack(mode)) data.reset();
1194  return data;
1195  }
1196 };
1197 
1200  // group1
1206  // group 2
1209  // group 3
1213  // group 4
1217  // group 5
1219  // group 6 - iNav only
1221 
1222  std::ostream& rxConfigPrint(std::ostream& s) const {
1223  s << "#RX configuration:" << std::endl;
1224  s << " serialrx_provider: " << serialrx_provider << std::endl;
1225  s << " maxcheck: " << maxcheck << std::endl;
1226  s << " midrc: " << midrc << std::endl;
1227  s << " mincheck: " << mincheck << std::endl;
1228  s << " spektrum_sat_bind: " << spektrum_sat_bind << std::endl;
1229  s << " rx_min_usec: " << rx_min_usec << std::endl;
1230  s << " rx_max_usec: " << rx_max_usec << std::endl;
1231  s << " rcInterpolation: " << rcInterpolation << std::endl;
1232  s << " rcInterpolationInterval: " << rcInterpolationInterval
1233  << std::endl;
1234  s << " airModeActivateThreshold: " << airModeActivateThreshold
1235  << std::endl;
1236  s << " rx_spi_protocol: " << rx_spi_protocol << std::endl;
1237  s << " rx_spi_id: " << rx_spi_id << std::endl;
1238  s << " rx_spi_rf_channel_count: " << rx_spi_rf_channel_count
1239  << std::endl;
1240  s << " fpvCamAngleDegrees: " << fpvCamAngleDegrees << std::endl;
1241  s << " receiverType: " << receiverType << std::endl;
1242  return s;
1243  }
1244 };
1245 
1246 // MSP_RX_CONFIG: 44
1247 struct RxConfig : public RxConfigSettings, public Message {
1249 
1250  virtual ID id() const override { return ID::MSP_RX_CONFIG; }
1251 
1252  virtual bool decode(const ByteVector& data) override {
1253  bool rc = true;
1254  valid_data_groups = 1;
1255  rc &= data.unpack(serialrx_provider);
1256  rc &= data.unpack(maxcheck);
1257  rc &= data.unpack(midrc);
1258  rc &= data.unpack(mincheck);
1259  rc &= data.unpack(spektrum_sat_bind);
1260  if(data.unpacking_remaining() == 0) return rc;
1261 
1262  valid_data_groups += 1;
1263  rc &= data.unpack(rx_min_usec);
1264  rc &= data.unpack(rx_max_usec);
1265  if(data.unpacking_remaining() == 0) return rc;
1266 
1267  valid_data_groups += 1;
1268  rc &= data.unpack(rcInterpolation);
1269  rc &= data.unpack(rcInterpolationInterval);
1270  rc &= data.unpack(airModeActivateThreshold);
1271  if(data.unpacking_remaining() == 0) return rc;
1272 
1273  valid_data_groups += 1;
1274  rc &= data.unpack(rx_spi_protocol);
1275  rc &= data.unpack(rx_spi_id);
1276  rc &= data.unpack(rx_spi_rf_channel_count);
1277  if(data.unpacking_remaining() == 0) return rc;
1278 
1279  valid_data_groups += 1;
1280  rc &= data.unpack(fpvCamAngleDegrees);
1281  if(data.unpacking_remaining() == 0) return rc;
1282 
1283  valid_data_groups += 1;
1284  rc &= data.unpack(receiverType);
1285  return rc;
1286  }
1287 
1288  virtual std::ostream& print(std::ostream& s) const override {
1289  return rxConfigPrint(s);
1290  }
1291 };
1292 
1293 // MSP_SET_RX_CONFIG: 45
1294 struct SetRxConfig : public RxConfigSettings, public Message {
1296 
1297  virtual ID id() const override { return ID::MSP_SET_RX_CONFIG; }
1298 
1299  virtual ByteVectorUptr encode() const override {
1300  ByteVectorUptr data = std::make_unique<ByteVector>();
1301  bool rc = true;
1302  rc &= data->pack(serialrx_provider);
1303  rc &= data->pack(maxcheck);
1304  rc &= data->pack(midrc);
1305  rc &= data->pack(mincheck);
1306  rc &= data->pack(spektrum_sat_bind);
1307  if(valid_data_groups == 1) goto packing_finished;
1308  rc &= data->pack(rx_min_usec);
1309  rc &= data->pack(rx_max_usec);
1310  if(valid_data_groups == 2) goto packing_finished;
1311  rc &= data->pack(rcInterpolation);
1312  rc &= data->pack(rcInterpolationInterval);
1313  rc &= data->pack(airModeActivateThreshold);
1314  if(valid_data_groups == 3) goto packing_finished;
1315  rc &= data->pack(rx_spi_protocol);
1316  rc &= data->pack(rx_spi_id);
1317  rc &= data->pack(rx_spi_rf_channel_count);
1318  if(valid_data_groups == 4) goto packing_finished;
1319  rc &= data->pack(fpvCamAngleDegrees);
1320  if(valid_data_groups == 5) goto packing_finished;
1321  rc &= data->pack(receiverType);
1322  packing_finished:
1323  if(!rc) data.reset();
1324  return data;
1325  }
1326 
1327  virtual std::ostream& print(std::ostream& s) const override {
1328  return rxConfigPrint(s);
1329  }
1330 };
1331 
1332 struct HsvColor : public Packable {
1336 
1337  bool unpack_from(const ByteVector& data) {
1338  bool rc = true;
1339  rc &= data.unpack(h);
1340  rc &= data.unpack(s);
1341  rc &= data.unpack(v);
1342  return rc;
1343  }
1344 
1345  bool pack_into(ByteVector& data) const {
1346  bool rc = true;
1347  rc &= data.pack(h);
1348  rc &= data.pack(s);
1349  rc &= data.pack(v);
1350  return rc;
1351  }
1352 };
1353 
1354 // MSP_LED_COLORS: 46
1355 struct LedColors : public Message {
1357 
1358  virtual ID id() const override { return ID::MSP_LED_COLORS; }
1359 
1360  std::array<HsvColor, LED_CONFIGURABLE_COLOR_COUNT> colors;
1361 
1362  virtual bool decode(const ByteVector& data) override {
1363  bool rc = true;
1364  for(auto& c : colors) {
1365  rc &= data.unpack(c);
1366  }
1367  return rc;
1368  }
1369 };
1370 
1371 // MSP_SET_LED_COLORS: 47
1372 struct SetLedColors : public Message {
1374 
1375  virtual ID id() const override { return ID::MSP_SET_LED_COLORS; }
1376 
1377  std::array<HsvColor, LED_CONFIGURABLE_COLOR_COUNT> colors;
1378 
1379  virtual ByteVectorUptr encode() const override {
1380  ByteVectorUptr data = std::make_unique<ByteVector>();
1381  bool rc = true;
1382  for(size_t i = 0; i < LED_CONFIGURABLE_COLOR_COUNT; ++i) {
1383  rc &= data->pack(colors[i].h);
1384  rc &= data->pack(colors[i].s);
1385  rc &= data->pack(colors[i].v);
1386  }
1387  if(!rc) data.reset();
1388  return data;
1389  }
1390 };
1391 
1392 // MSP_LED_STRIP_CONFIG: 48
1393 struct LedStripConfigs : public Message {
1395 
1396  virtual ID id() const override { return ID::MSP_LED_STRIP_CONFIG; }
1397 
1398  std::array<uint32_t, LED_MAX_STRIP_LENGTH> configs;
1399 
1400  virtual bool decode(const ByteVector& data) override {
1401  bool rc = true;
1402  for(size_t i = 0; i < LED_MAX_STRIP_LENGTH; ++i) {
1403  rc &= data.unpack(configs[i]);
1404  }
1405  return rc;
1406  }
1407 };
1408 
1409 // MSP_SET_LED_STRIP_CONFIG: 49
1410 struct SetLedStripConfig : public Message {
1412 
1413  virtual ID id() const override { return ID::MSP_SET_LED_STRIP_CONFIG; }
1414 
1417 
1418  virtual ByteVectorUptr encode() const override {
1419  ByteVectorUptr data = std::make_unique<ByteVector>();
1420  bool rc = true;
1421  rc &= data->pack(cfg_index);
1422  rc &= data->pack(config);
1423  if(!rc) data.reset();
1424  return data;
1425  }
1426 };
1427 
1428 // MSP_RSSI_CONFIG: 50
1429 struct RssiConfig : public Message {
1431 
1432  virtual ID id() const override { return ID::MSP_RSSI_CONFIG; }
1433 
1435 
1436  virtual bool decode(const ByteVector& data) override {
1437  return data.unpack(rssi_channel);
1438  }
1439 };
1440 
1441 // MSP_SET_RSSI_CONFIG: 51
1442 struct SetRssiConfig : public Message {
1444 
1445  virtual ID id() const override { return ID::MSP_SET_RSSI_CONFIG; }
1446 
1448 
1449  virtual ByteVectorUptr encode() const override {
1450  ByteVectorUptr data = std::make_unique<ByteVector>();
1451  if(!data->pack(rssi_channel)) data.reset();
1452  return data;
1453  }
1454 };
1455 
1463 };
1464 
1465 // MSP_ADJUSTMENT_RANGES: 52
1466 struct AdjustmentRanges : public Message {
1468 
1469  virtual ID id() const override { return ID::MSP_ADJUSTMENT_RANGES; }
1470 
1471  std::array<adjustmentRange, MAX_ADJUSTMENT_RANGE_COUNT> ranges;
1472 
1473  virtual bool decode(const ByteVector& data) override {
1474  bool rc = true;
1475  for(size_t i = 0; i < MAX_ADJUSTMENT_RANGE_COUNT; ++i) {
1476  rc &= data.unpack(ranges[i].adjustmentIndex);
1477  rc &= data.unpack(ranges[i].auxChannelIndex);
1478  rc &= data.unpack(ranges[i].range_startStep);
1479  rc &= data.unpack(ranges[i].range_endStep);
1480  rc &= data.unpack(ranges[i].adjustmentFunction);
1481  rc &= data.unpack(ranges[i].auxSwitchChannelIndex);
1482  }
1483  return rc;
1484  }
1485 };
1486 
1487 // MSP_SET_ADJUSTMENT_RANGE: 53
1488 struct SetAdjustmentRange : public Message {
1490 
1491  virtual ID id() const override { return ID::MSP_SET_ADJUSTMENT_RANGE; }
1492 
1495 
1496  virtual ByteVectorUptr encode() const override {
1497  ByteVectorUptr data = std::make_unique<ByteVector>();
1498  bool rc = true;
1499  rc &= data->pack(range_index);
1500  rc &= data->pack(range.adjustmentIndex);
1501  rc &= data->pack(range.auxChannelIndex);
1502  rc &= data->pack(range.range_startStep);
1503  rc &= data->pack(range.range_endStep);
1504  rc &= data->pack(range.adjustmentFunction);
1505  rc &= data->pack(range.auxSwitchChannelIndex);
1506  if(!rc) data.reset();
1507  return data;
1508  }
1509 };
1510 
1518 };
1519 
1520 // MSP_CF_SERIAL_CONFIG: 54
1521 struct CfSerialConfig : public Message {
1523 
1524  virtual ID id() const override { return ID::MSP_CF_SERIAL_CONFIG; }
1525 
1526  std::vector<CfSerialConfigSettings> configs;
1527 
1528  virtual bool decode(const ByteVector& data) override {
1529  bool rc = true;
1530  do {
1532  rc &= data.unpack(tmp.identifier);
1533  rc &= data.unpack(tmp.functionMask);
1534  rc &= data.unpack(tmp.mspBaudrateIndx);
1535  rc &= data.unpack(tmp.gpsBaudrateIndx);
1536  rc &= data.unpack(tmp.telemetryBaudrateIndx);
1537  rc &= data.unpack(tmp.peripheralBaudrateIndx);
1538  if(rc) configs.push_back(tmp);
1539  } while(rc);
1540  return configs.size();
1541  }
1542 };
1543 
1544 // MSP_SET_CF_SERIAL_CONFIG: 55
1545 struct SetCfSerialConfig : public Message {
1547 
1548  virtual ID id() const override { return ID::MSP_SET_CF_SERIAL_CONFIG; }
1549 
1550  std::vector<CfSerialConfigSettings> configs;
1551 
1552  virtual ByteVectorUptr encode() const override {
1553  ByteVectorUptr data = std::make_unique<ByteVector>();
1554  bool rc = true;
1555  for(const auto& config : configs) {
1556  rc &= data->pack(config.identifier);
1557  rc &= data->pack(config.functionMask);
1558  rc &= data->pack(config.mspBaudrateIndx);
1559  rc &= data->pack(config.gpsBaudrateIndx);
1560  rc &= data->pack(config.telemetryBaudrateIndx);
1561  rc &= data->pack(config.peripheralBaudrateIndx);
1562  }
1563  if(!rc) data.reset();
1564  return data;
1565  }
1566 };
1567 
1573 };
1574 
1575 // MSP_VOLTAGE_METER_CONFIG: 56 (differs from Cleanflight/BetaFlight)
1578 
1579  virtual ID id() const override { return ID::MSP_VOLTAGE_METER_CONFIG; }
1580 
1581  virtual bool decode(const ByteVector& data) override {
1582  bool rc = true;
1583  rc &= data.unpack(scale_dV);
1584  rc &= data.unpack(cell_min_dV);
1585  rc &= data.unpack(cell_max_dV);
1586  rc &= data.unpack(cell_warning_dV);
1587  return rc;
1588  }
1589 };
1590 
1591 // MSP_SET_VOLTAGE_METER_CONFIG: 57 (differs from Cleanflight/BetaFlight)
1593  public Message {
1595 
1596  virtual ID id() const override { return ID::MSP_SET_VOLTAGE_METER_CONFIG; }
1597 
1598  virtual ByteVectorUptr encode() const override {
1599  ByteVectorUptr data = std::make_unique<ByteVector>();
1600  bool rc = true;
1601  rc &= data->pack(scale_dV);
1602  rc &= data->pack(cell_min_dV);
1603  rc &= data->pack(cell_max_dV);
1604  rc &= data->pack(cell_warning_dV);
1605  if(!rc) data.reset();
1606  return data;
1607  }
1608 };
1609 
1610 // MSP_SONAR_ALTITUDE: 58
1611 struct SonarAltitude : public Message {
1613 
1614  virtual ID id() const override { return ID::MSP_SONAR_ALTITUDE; }
1615 
1617 
1618  virtual bool decode(const ByteVector& data) override {
1619  return data.unpack(altitude_cm);
1620  }
1621 };
1622 
1623 // MSP_PID_CONTROLLER: 59
1624 struct PidController : public Message {
1626 
1627  virtual ID id() const override { return ID::MSP_PID_CONTROLLER; }
1628 
1630 
1631  virtual bool decode(const ByteVector& data) override {
1632  return data.unpack(controller_id);
1633  }
1634 };
1635 
1636 // MSP_SET_PID_CONTROLLER: 60
1637 struct SetPidController : public Message {
1639 
1640  virtual ID id() const override { return ID::MSP_SET_PID_CONTROLLER; }
1641 };
1642 
1648 };
1649 
1650 // MSP_ARMING_CONFIG: 61
1651 struct ArmingConfig : public ArmingConfigSettings, public Message {
1653 
1654  virtual ID id() const override { return ID::MSP_ARMING_CONFIG; }
1655 
1656  virtual bool decode(const ByteVector& data) override {
1657  bool rc = true;
1658  rc &= data.unpack(auto_disarm_delay);
1659  rc &= data.unpack(disarm_kill_switch);
1660  if(data.unpack(imu_small_angle)) imu_small_angle_valid = true;
1661  return rc;
1662  }
1663 };
1664 
1665 // MSP_SET_ARMING_CONFIG: 62
1668 
1669  virtual ID id() const override { return ID::MSP_SET_ARMING_CONFIG; }
1670 
1671  virtual ByteVectorUptr encode() const override {
1672  ByteVectorUptr data = std::make_unique<ByteVector>();
1673  bool rc = true;
1674  rc &= data->pack(auto_disarm_delay);
1675  rc &= data->pack(disarm_kill_switch);
1676  if(imu_small_angle_valid) rc &= data->pack(imu_small_angle);
1677  if(!rc) data.reset();
1678  return data;
1679  }
1680 };
1681 
1683  std::array<uint8_t, MAX_MAPPABLE_RX_INPUTS> map;
1684 
1685  std::ostream& printRxMapSettings(std::ostream& s) const {
1686  s << "#Channel mapping:" << std::endl;
1687  for(size_t i(0); i < map.size(); i++) {
1688  s << " " << i << ": " << size_t(map[i]) << std::endl;
1689  }
1690  return s;
1691  }
1692 };
1693 
1694 // MSP_RX_MAP: 64
1695 struct RxMap : public RxMapSettings, public Message {
1697 
1698  virtual ID id() const override { return ID::MSP_RX_MAP; }
1699 
1700  virtual bool decode(const ByteVector& data) override {
1701  if(data.size() < MAX_MAPPABLE_RX_INPUTS) return false;
1702  bool rc = true;
1703  for(size_t i = 0; i < MAX_MAPPABLE_RX_INPUTS; ++i) {
1704  rc &= data.unpack(map[i]);
1705  }
1706  return rc;
1707  }
1708 
1709  virtual std::ostream& print(std::ostream& s) const override {
1710  return printRxMapSettings(s);
1711  }
1712 };
1713 
1714 // MSP_SET_RX_MAP: 65
1715 struct SetRxMap : public RxMapSettings, public Message {
1717 
1718  virtual ID id() const override { return ID::MSP_SET_RX_MAP; }
1719 
1720  virtual ByteVectorUptr encode() const override {
1721  ByteVectorUptr data = std::make_unique<ByteVector>();
1722  bool rc = true;
1723  for(const auto& channel : map) {
1724  rc &= data->pack(channel);
1725  }
1726  if(!rc) data.reset();
1727  return data;
1728  }
1729 
1730  virtual std::ostream& print(std::ostream& s) const override {
1731  return printRxMapSettings(s);
1732  }
1733 };
1734 
1735 // iNav uses decidegrees, BF/CF use degrees
1745 };
1746 
1747 // MSP_BF_CONFIG: 66, //out message baseflight-specific settings that aren't
1748 // covered elsewhere
1749 struct BfConfig : public BfConfigSettings, public Message {
1751 
1752  virtual ID id() const override { return ID::MSP_BF_CONFIG; }
1753 
1754  virtual bool decode(const ByteVector& data) override {
1755  bool rc = true;
1756  rc &= data.unpack(mixer_mode);
1757  rc &= data.unpack(feature_mask);
1758  rc &= data.unpack(serialrx_provider);
1759  rc &= data.unpack(roll);
1760  rc &= data.unpack(pitch);
1761  rc &= data.unpack(yaw);
1762  rc &= data.unpack(current_meter_scale);
1763  rc &= data.unpack(current_meter_offset);
1764  return rc;
1765  }
1766 };
1767 
1768 // MSP_SET_BF_CONFIG: 67, //in message baseflight-specific settings save
1769 struct SetBfConfig : public BfConfigSettings, public Message {
1771 
1772  virtual ID id() const override { return ID::MSP_SET_BF_CONFIG; }
1773 
1774  virtual ByteVectorUptr encode() const override {
1775  ByteVectorUptr data = std::make_unique<ByteVector>();
1776  bool rc = true;
1777  rc &= data->pack(mixer_mode);
1778  rc &= data->pack(feature_mask);
1779  rc &= data->pack(serialrx_provider);
1780  rc &= data->pack(roll);
1781  rc &= data->pack(pitch);
1782  rc &= data->pack(yaw);
1783  rc &= data->pack(current_meter_scale);
1784  rc &= data->pack(current_meter_offset);
1785  if(!rc) data.reset();
1786  return data;
1787  }
1788 };
1789 
1790 // MSP_REBOOT: 68
1791 struct Reboot : public Message {
1793 
1794  virtual ID id() const override { return ID::MSP_REBOOT; }
1795 };
1796 
1797 // MSP_BF_BUILD_INFO: 69
1798 struct BfBuildInfo : public Message {
1800 
1801  virtual ID id() const override { return ID::MSP_BF_BUILD_INFO; }
1802 
1806 
1807  virtual bool decode(const ByteVector& data) override {
1808  bool rc = true;
1809  rc &= data.unpack(build_date, 11);
1810  rc &= data.unpack(reserved1);
1811  rc &= data.unpack(reserved2);
1812  return rc;
1813  }
1814 };
1815 
1816 // MSP_DATAFLASH_SUMMARY: 70
1817 struct DataflashSummary : public Message {
1819 
1820  virtual ID id() const override { return ID::MSP_DATAFLASH_SUMMARY; }
1821 
1826 
1827  virtual bool decode(const ByteVector& data) override {
1828  bool rc = true;
1829  rc &= data.unpack(flash_is_ready);
1830  rc &= data.unpack(sectors);
1831  rc &= data.unpack(total_size);
1832  rc &= data.unpack(offset);
1833  return rc;
1834  }
1835 };
1836 
1837 // message format differs between iNav and BF/CF
1838 // MSP_DATAFLASH_READ: 71
1839 struct DataflashRead : public Message {
1841 
1842  virtual ID id() const override { return ID::MSP_DATAFLASH_READ; }
1843 
1848 
1849  virtual ByteVectorUptr encode() const override {
1850  ByteVectorUptr data = std::make_unique<ByteVector>();
1851  bool rc = true;
1852  rc &= data->pack(read_address);
1853  rc &= data->pack(read_size);
1854  rc &= data->pack(allow_compression);
1855  if(!rc) data.reset();
1856  return data;
1857  }
1858 
1859  virtual bool decode(const ByteVector& data) override {
1860  bool rc = true;
1861  rc &= data.unpack(read_address);
1862  flash_data = ByteVector(data.unpacking_iterator(), data.end());
1863  rc &= data.consume(flash_data.size());
1864  return rc;
1865  }
1866 };
1867 
1868 // MSP_DATAFLASH_ERASE: 72
1869 struct DataflashErase : public Message {
1871 
1872  virtual ID id() const override { return ID::MSP_DATAFLASH_ERASE; }
1873 
1874  virtual bool decode(const ByteVector& /*data*/) override { return true; }
1875 };
1876 
1877 // MSP_LOOP_TIME: 73
1878 struct LoopTime : public Message {
1880 
1881  virtual ID id() const override { return ID::MSP_LOOP_TIME; }
1882 
1884 
1885  virtual bool decode(const ByteVector& data) override {
1886  return data.unpack(loop_time);
1887  }
1888 };
1889 
1890 // MSP_SET_LOOP_TIME:74
1891 struct SetLoopTime : public Message {
1893 
1894  virtual ID id() const override { return ID::MSP_SET_LOOP_TIME; }
1895 
1897 
1898  virtual ByteVectorUptr encode() const override {
1899  ByteVectorUptr data = std::make_unique<ByteVector>();
1900  if(!data->pack(loop_time)) data.reset();
1901  return data;
1902  }
1903 };
1904 
1920 };
1921 
1922 // MSP_FAILSAFE_CONFIG: 75
1923 struct FailsafeConfig : public FailsafeSettings, public Message {
1925 
1926  virtual ID id() const override { return ID::MSP_FAILSAFE_CONFIG; }
1927 
1928  virtual bool decode(const ByteVector& data) override {
1929  bool rc = true;
1930  extended_contents = false;
1931  rc &= data.unpack(delay);
1932  rc &= data.unpack(off_delay);
1933  rc &= data.unpack(throttle);
1934  rc &= data.unpack(kill_switch);
1935  rc &= data.unpack(throttle_low_delay);
1936  rc &= data.unpack(procedure);
1937  if(data.unpacking_remaining() == 0) return rc;
1938  extended_contents = true;
1939  rc &= data.unpack(recovery_delay);
1940  rc &= data.unpack(fw_roll_angle);
1941  rc &= data.unpack(fw_pitch_angle);
1942  rc &= data.unpack(fw_yaw_rate);
1943  rc &= data.unpack(stick_motion_threshold);
1944  rc &= data.unpack(min_distance);
1945  rc &= data.unpack(min_distance_procedure);
1946  return rc;
1947  }
1948 };
1949 
1950 // MSP_SET_FAILSAFE_CONFIG: 76
1951 struct SetFailsafeConfig : public FailsafeSettings, public Message {
1953 
1954  virtual ID id() const override { return ID::MSP_SET_FAILSAFE_CONFIG; }
1955 
1956  virtual ByteVectorUptr encode() const override {
1957  ByteVectorUptr data = std::make_unique<ByteVector>();
1958  bool rc = true;
1959  rc &= data->pack(delay);
1960  rc &= data->pack(off_delay);
1961  rc &= data->pack(throttle);
1962  rc &= data->pack(kill_switch);
1963  rc &= data->pack(throttle_low_delay);
1964  rc &= data->pack(procedure);
1965  if(extended_contents) {
1966  rc &= data->pack(recovery_delay);
1967  rc &= data->pack(fw_roll_angle);
1968  rc &= data->pack(fw_pitch_angle);
1969  rc &= data->pack(fw_yaw_rate);
1970  rc &= data->pack(stick_motion_threshold);
1971  rc &= data->pack(min_distance);
1972  rc &= data->pack(min_distance_procedure);
1973  }
1974  if(!rc) data.reset();
1975  return data;
1976  }
1977 };
1978 
1982 };
1983 
1984 // MSP_RXFAIL_CONFIG: 77
1985 struct RxFailConfigs : public Message {
1987 
1988  virtual ID id() const override { return ID::MSP_RXFAIL_CONFIG; }
1989 
1990  std::vector<RxFailChannelSettings> channels;
1991 
1992  virtual bool decode(const ByteVector& data) override {
1993  bool rc = true;
1994  channels.clear();
1995  while(rc && data.unpacking_remaining()) {
1997  rc &= data.unpack(tmp.mode);
1998  rc &= data.unpack(tmp.val);
1999  channels.push_back(tmp);
2000  }
2001  return rc;
2002  }
2003 };
2004 
2005 // MSP_SET_RXFAIL_CONFIG: 78
2008 
2009  virtual ID id() const override { return ID::MSP_SET_RXFAIL_CONFIG; }
2010 
2012 
2013  virtual bool decode(const ByteVector& data) override {
2014  bool rc = true;
2015  rc &= data.unpack(channel);
2016  rc &= data.unpack(mode);
2017  rc &= data.unpack(val);
2018  return rc;
2019  }
2020 };
2021 
2022 // MSP_SDCARD_SUMMARY: 79
2023 struct SdcardSummary : public Message {
2025 
2026  virtual ID id() const override { return ID::MSP_SDCARD_SUMMARY; }
2027 
2033 
2034  virtual bool decode(const ByteVector& data) override {
2035  bool rc = true;
2036  rc &= data.unpack(flags);
2037  rc &= data.unpack(state);
2038  rc &= data.unpack(last_error);
2039  rc &= data.unpack(free_space_kb);
2040  rc &= data.unpack(total_space_kb);
2041  return rc;
2042  }
2043 };
2044 
2051 };
2052 
2053 // MSP_BLACKBOX_CONFIG: 80
2056 
2057  virtual ID id() const override { return ID::MSP_BLACKBOX_CONFIG; }
2058 
2060 
2061  virtual bool decode(const ByteVector& data) override {
2062  bool rc = true;
2063  p_ratio_set = false;
2064  rc &= data.unpack(supported);
2065  rc &= data.unpack(device);
2066  rc &= data.unpack(rate_num);
2067  rc &= data.unpack(rate_denom);
2068  if(data.unpacking_remaining()) {
2069  p_ratio_set = true;
2070  rc &= data.unpack(p_ratio);
2071  }
2072  return rc;
2073  }
2074 };
2075 
2076 // MSP_SET_BLACKBOX_CONFIG: 81
2079 
2080  virtual ID id() const override { return ID::MSP_SET_BLACKBOX_CONFIG; }
2081 
2082  virtual ByteVectorUptr encode() const override {
2083  ByteVectorUptr data = std::make_unique<ByteVector>();
2084  bool rc = true;
2085  rc &= data->pack(device);
2086  rc &= data->pack(rate_num);
2087  rc &= data->pack(rate_denom);
2088  if(p_ratio_set) rc &= data->pack(p_ratio);
2089  if(!rc) data.reset();
2090  return data;
2091  }
2092 };
2093 
2097 };
2098 
2099 // MSP_TRANSPONDER_CONFIG: 82
2100 struct TransponderConfig : public Message {
2102 
2103  virtual ID id() const override { return ID::MSP_TRANSPONDER_CONFIG; }
2104 
2106  std::vector<TransponderConfigSettings> transponder_data;
2109 
2110  virtual bool decode(const ByteVector& data) override {
2111  bool rc = true;
2112  rc &= data.unpack(transponder_count);
2113  if(!transponder_count()) return rc;
2114  for(uint8_t i = 0; i < transponder_count(); ++i) {
2116  rc &= data.unpack(tmp.provider);
2117  rc &= data.unpack(tmp.data_length);
2118  transponder_data.push_back(tmp);
2119  }
2120  rc &= data.unpack(provider);
2121  if(!provider()) return rc;
2122  uint8_t data_len = transponder_data[provider() - 1].data_length();
2123  provider_data = ByteVector(data.unpacking_iterator(),
2124  data.unpacking_iterator() + data_len);
2125  rc &= data.consume(data_len);
2126  return rc;
2127  }
2128 };
2129 
2130 // MSP_SET_TRANSPONDER_CONFIG: 83
2133 
2134  virtual ID id() const override { return ID::MSP_SET_TRANSPONDER_CONFIG; }
2135 
2138 
2139  virtual ByteVectorUptr encode() const override {
2140  ByteVectorUptr data = std::make_unique<ByteVector>();
2141  bool rc = true;
2142  rc &= data->pack(provider);
2143  rc &= data->pack(provider_data);
2144  if(!rc) data.reset();
2145  return data;
2146  }
2147 };
2148 
2149 // Differences between iNav and BF/CF
2150 // MSP_OSD_CONFIG: 84
2151 struct OsdConfig : public Message {
2153 
2154  virtual ID id() const override { return ID::MSP_OSD_CONFIG; }
2155 
2165  std::array<uint16_t, OSD_ITEM_COUNT> item_pos;
2166 
2167  virtual bool decode(const ByteVector& data) override {
2168  bool rc = true;
2169  rc &= data.unpack(osd_flags);
2170  if(rc && osd_flags()) {
2171  rc &= data.unpack(video_system);
2172  rc &= data.unpack(units);
2173  rc &= data.unpack(rssi_alarm);
2174  rc &= data.unpack(battery_cap_warn);
2175  rc &= data.unpack(time_alarm);
2176  rc &= data.unpack(alt_alarm);
2177  rc &= data.unpack(dist_alarm);
2178  rc &= data.unpack(neg_alt_alarm);
2179  for(size_t i = 0; i < OSD_ITEM_COUNT; ++i) {
2180  rc &= data.unpack(item_pos[i]);
2181  }
2182  }
2183  return rc;
2184  }
2185 };
2186 
2187 // MSP_SET_OSD_CONFIG: 85
2188 struct SetOsdConfig : public Message {
2190 
2191  virtual ID id() const override { return ID::MSP_SET_OSD_CONFIG; }
2192 
2193  int8_t param_idx;
2203 
2204  virtual ByteVectorUptr encode() const override {
2205  ByteVectorUptr data = std::make_unique<ByteVector>();
2206  bool rc = true;
2207  rc &= data->pack(param_idx);
2208  if(param_idx == -1) {
2209  rc &= data->pack(video_system);
2210  rc &= data->pack(units);
2211  rc &= data->pack(rssi_alarm);
2212  rc &= data->pack(battery_cap_warn);
2213  rc &= data->pack(time_alarm);
2214  rc &= data->pack(alt_alarm);
2215  rc &= data->pack(dist_alarm);
2216  rc &= data->pack(neg_alt_alarm);
2217  }
2218  else {
2219  rc &= data->pack(item_pos);
2220  }
2221  if(!rc) data.reset();
2222  return data;
2223  }
2224 };
2225 
2226 // MSP_OSD_CHAR_READ: 86 No reference implementation
2227 
2228 // MSP_OSD_CHAR_WRITE: 87
2229 struct OsdCharWrite : public Message {
2231 
2232  virtual ID id() const override { return ID::MSP_OSD_CHAR_WRITE; }
2233 
2235  std::array<uint8_t, 54> font_data;
2236 
2237  virtual ByteVectorUptr encode() const override {
2238  ByteVectorUptr data = std::make_unique<ByteVector>();
2239  bool rc = true;
2240  rc &= data->pack(addr);
2241  for(const auto& c : font_data) {
2242  rc &= data->pack(c);
2243  }
2244  if(!rc) data.reset();
2245  return data;
2246  }
2247 };
2248 
2249 // MSP_VTX_CONFIG: 88
2250 struct VtxConfig : public Message {
2252 
2253  virtual ID id() const override { return ID::MSP_VTX_CONFIG; }
2254 
2260  bool freq_set;
2262 
2263  virtual bool decode(const ByteVector& data) override {
2264  bool rc = true;
2265  freq_set = false;
2266  rc &= data.unpack(device_type);
2267  if(rc && (device_type() != 0xFF)) {
2268  rc &= data.unpack(band);
2269  rc &= data.unpack(channel);
2270  rc &= data.unpack(power_idx);
2271  rc &= data.unpack(pit_mode);
2272  if(data.unpacking_remaining()) {
2273  freq_set = true;
2274  rc &= data.unpack(frequency);
2275  }
2276  }
2277  return rc;
2278  }
2279 };
2280 
2281 // MSP_SET_VTX_CONFIG: 89
2282 struct SetVtxConfig : public Message {
2284 
2285  virtual ID id() const override { return ID::MSP_SET_VTX_CONFIG; }
2286 
2290 
2291  bool set_freq(uint8_t band, uint8_t channel) {
2292  if(band & 0xF8 || channel & 0xF8) {
2293  return false;
2294  }
2295  frequency = uint16_t(band - 1) & uint16_t((channel - 1) << 3);
2296  return true;
2297  }
2298 
2299  virtual ByteVectorUptr encode() const override {
2300  ByteVectorUptr data = std::make_unique<ByteVector>();
2301  bool rc = true;
2302  rc &= data->pack(frequency);
2303  rc &= data->pack(power);
2304  rc &= data->pack(pit_mode);
2305  if(!rc) data.reset();
2306  return data;
2307  }
2308 };
2309 
2310 // Differs between iNav and BF/CF
2317  Value<uint16_t> servo_pwm_rate; // digitalIdleOffsetValue in BF/CF
2321 };
2322 
2323 // Betaflight Additional Commands
2324 // MSP_ADVANCED_CONFIG: 90
2327 
2328  virtual ID id() const override { return ID::MSP_ADVANCED_CONFIG; }
2329 
2330  virtual bool decode(const ByteVector& data) override {
2331  bool rc = true;
2332  pwm_inversion_set = false;
2333  rc &= data.unpack(gyro_sync_denom);
2334  rc &= data.unpack(pid_process_denom);
2335  rc &= data.unpack(use_unsynced_pwm);
2336  rc &= data.unpack(motor_pwm_protocol);
2337  rc &= data.unpack(motor_pwm_rate);
2338  rc &= data.unpack(servo_pwm_rate);
2339  rc &= data.unpack(gyro_sync);
2340  if(rc && data.unpacking_remaining()) {
2341  pwm_inversion_set = true;
2342  rc &= data.unpack(pwm_inversion);
2343  }
2344  return rc;
2345  }
2346 };
2347 
2348 // MSP_SET_ADVANCED_CONFIG: 91
2351 
2352  virtual ID id() const override { return ID::MSP_SET_ADVANCED_CONFIG; }
2353 
2354  virtual ByteVectorUptr encode() const override {
2355  ByteVectorUptr data = std::make_unique<ByteVector>();
2356  bool rc = true;
2357  rc &= data->pack(gyro_sync_denom);
2358  rc &= data->pack(pid_process_denom);
2359  rc &= data->pack(use_unsynced_pwm);
2360  rc &= data->pack(motor_pwm_protocol);
2361  rc &= data->pack(motor_pwm_rate);
2362  rc &= data->pack(servo_pwm_rate);
2363  rc &= data->pack(gyro_sync);
2364  if(pwm_inversion_set) rc &= data->pack(pwm_inversion);
2365  if(!rc) data.reset();
2366  return data;
2367  }
2368 };
2369 
2382 };
2383 
2384 // MSP_FILTER_CONFIG: 92
2385 struct FilterConfig : public FilterConfigSettings, public Message {
2387 
2388  virtual ID id() const override { return ID::MSP_FILTER_CONFIG; }
2389 
2390  virtual bool decode(const ByteVector& data) override {
2391  bool rc = true;
2392  dterm_filter_type_set = false;
2393  rc &= data.unpack(gyro_soft_lpf_hz);
2394  rc &= data.unpack(dterm_lpf_hz);
2395  rc &= data.unpack(yaw_lpf_hz);
2396  rc &= data.unpack(gyro_soft_notch_hz_1);
2397  rc &= data.unpack(gyro_soft_notch_cutoff_1);
2398  rc &= data.unpack(dterm_soft_notch_hz);
2399  rc &= data.unpack(dterm_soft_notch_cutoff);
2400  rc &= data.unpack(gyro_soft_notch_hz_2);
2401  rc &= data.unpack(gyro_soft_notch_cutoff_2);
2402  if(rc && data.unpacking_remaining()) {
2403  dterm_filter_type_set = true;
2404  rc &= data.unpack(dterm_filter_type);
2405  }
2406  return rc;
2407  }
2408 };
2409 
2410 // MSP_SET_FILTER_CONFIG: 93
2413 
2414  virtual ID id() const override { return ID::MSP_SET_FILTER_CONFIG; }
2415 
2416  virtual ByteVectorUptr encode() const override {
2417  ByteVectorUptr data = std::make_unique<ByteVector>();
2418  bool rc = true;
2419  rc &= data->pack(gyro_soft_lpf_hz);
2420  rc &= data->pack(dterm_lpf_hz);
2421  rc &= data->pack(yaw_lpf_hz);
2422  rc &= data->pack(gyro_soft_notch_hz_1);
2423  rc &= data->pack(gyro_soft_notch_cutoff_1);
2424  rc &= data->pack(dterm_soft_notch_hz);
2425  rc &= data->pack(dterm_soft_notch_cutoff);
2426  rc &= data->pack(gyro_soft_notch_hz_2);
2427  rc &= data->pack(gyro_soft_notch_cutoff_2);
2428  if(dterm_filter_type_set) rc &= data->pack(dterm_filter_type);
2429  if(!rc) data.reset();
2430  return data;
2431  }
2432 };
2433 
2445  axisAccelerationLimitRollPitch; // TODO scaled and clamped value
2446  Value<uint32_t> axisAccelerationLimitYaw; // TODO scaled and clamped value
2447 };
2448 
2449 // Difference between iNav and BF/CF
2450 // MSP_PID_ADVANCED: 94
2451 struct PidAdvanced : public PidAdvancedSettings, public Message {
2453 
2454  virtual ID id() const override { return ID::MSP_PID_ADVANCED; }
2455 
2456  virtual bool decode(const ByteVector& data) override {
2457  bool rc = true;
2458  rc &= data.unpack(rollPitchItermIgnoreRate);
2459  rc &= data.unpack(yawItermIgnoreRate);
2460  rc &= data.unpack(yaw_p_limit);
2461  rc &= data.unpack(deltaMethod);
2462  rc &= data.unpack(vbatPidCompensation);
2463  rc &= data.unpack(setpointRelaxRatio);
2464  rc &= data.unpack<uint8_t>(dterm_setpoint_weight, 100);
2465  rc &= data.unpack(pidSumLimit);
2466  rc &= data.unpack(itermThrottleGain);
2467  rc &= data.unpack<uint16_t>(axisAccelerationLimitRollPitch, 0.1);
2468  rc &= data.unpack<uint16_t>(axisAccelerationLimitYaw, 0.1);
2469  return rc;
2470  }
2471 };
2472 
2473 // MSP_SET_PID_ADVANCED: 95
2474 struct SetPidAdvanced : public PidAdvancedSettings, public Message {
2476 
2477  virtual ID id() const override { return ID::MSP_SET_PID_ADVANCED; }
2478 
2479  virtual ByteVectorUptr encode() const override {
2480  ByteVectorUptr data = std::make_unique<ByteVector>();
2481  bool rc = true;
2482  rc &= data->pack(rollPitchItermIgnoreRate);
2483  rc &= data->pack(yawItermIgnoreRate);
2484  rc &= data->pack(yaw_p_limit);
2485  rc &= data->pack(deltaMethod);
2486  rc &= data->pack(vbatPidCompensation);
2487  rc &= data->pack(setpointRelaxRatio);
2488  rc &= data->pack<uint8_t>(dterm_setpoint_weight, 100);
2489  rc &= data->pack(pidSumLimit);
2490  rc &= data->pack(itermThrottleGain);
2491  rc &= data->pack<uint16_t>(axisAccelerationLimitRollPitch, 0.1);
2492  rc &= data->pack<uint16_t>(axisAccelerationLimitYaw, 0.1);
2493  if(!rc) data.reset();
2494  return data;
2495  }
2496 };
2497 
2506 };
2507 
2508 // MSP_SENSOR_CONFIG: 96
2509 struct SensorConfig : public SensorConfigSettings, public Message {
2511 
2512  virtual ID id() const override { return ID::MSP_SENSOR_CONFIG; }
2513 
2514  virtual bool decode(const ByteVector& data) override {
2515  bool rc = true;
2516  extended_contents = false;
2517  rc &= data.unpack(acc_hardware);
2518  rc &= data.unpack(baro_hardware);
2519  rc &= data.unpack(mag_hardware);
2520  if(data.unpacking_remaining()) {
2521  extended_contents = true;
2522  rc &= data.unpack(pitot_hardware);
2523  rc &= data.unpack(rangefinder_hardware);
2524  rc &= data.unpack(opflow_hardware);
2525  }
2526  return rc;
2527  }
2528 };
2529 
2530 // MSP_SET_SENSOR_CONFIG: 97
2533 
2534  virtual ID id() const override { return ID::MSP_SET_SENSOR_CONFIG; }
2535 
2536  virtual ByteVectorUptr encode() const override {
2537  ByteVectorUptr data = std::make_unique<ByteVector>();
2538  bool rc = true;
2539  rc &= data->pack(acc_hardware);
2540  rc &= data->pack(baro_hardware);
2541  rc &= data->pack(mag_hardware);
2542  if(!extended_contents) {
2543  rc &= data->pack(pitot_hardware);
2544  rc &= data->pack(rangefinder_hardware);
2545  rc &= data->pack(opflow_hardware);
2546  }
2547  if(!rc) data.reset();
2548  return data;
2549  }
2550 };
2551 
2552 // MSP_CAMERA_CONTROL: 98
2553 struct CameraControl : public Message {
2555 
2556  virtual ID id() const override { return ID::MSP_CAMERA_CONTROL; }
2557 
2559 
2560  virtual ByteVectorUptr encode() const override {
2561  ByteVectorUptr data = std::make_unique<ByteVector>();
2562  if(!data->pack(key)) data.reset();
2563  return data;
2564  }
2565 };
2566 
2567 // MSP_SET_ARMING_DISABLED: 99
2568 struct SetArmingDisabled : public Message {
2570 
2571  virtual ID id() const override { return ID::MSP_SET_ARMING_DISABLED; }
2572 
2575 
2576  virtual ByteVectorUptr encode() const override {
2577  ByteVectorUptr data = std::make_unique<ByteVector>();
2578  bool rc = true;
2579  rc &= data->pack(command);
2580  rc &= data->pack(disableRunawayTakeoff);
2581  if(!rc) data.reset();
2582  return data;
2583  }
2584 };
2585 
2588 
2589 // MSP_IDENT: 100
2590 struct Ident : public Message {
2592 
2593  virtual ID id() const override { return ID::MSP_IDENT; }
2594 
2598  std::set<Capability> capabilities;
2599 
2600  virtual bool decode(const ByteVector& data) override {
2601  bool rc = true;
2602 
2603  rc &= data.unpack(version);
2604  rc &= data.unpack((uint8_t&)type);
2605  rc &= data.unpack(msp_version);
2606  uint32_t capability;
2607  rc &= data.unpack(capability);
2608  if(!rc) return false;
2609  capabilities.clear();
2610  if(capability & (1 << 0)) capabilities.insert(Capability::BIND);
2611  if(capability & (1 << 2)) capabilities.insert(Capability::DYNBAL);
2612  if(capability & (1 << 3)) capabilities.insert(Capability::FLAP);
2613  if(capability & (1 << 4)) capabilities.insert(Capability::NAVCAP);
2614  if(capability & (1 << 5)) capabilities.insert(Capability::EXTAUX);
2615 
2616  return true;
2617  }
2618 
2619  bool has(const Capability& cap) const { return capabilities.count(cap); }
2620 
2621  bool hasBind() const { return has(Capability::BIND); }
2622 
2623  bool hasDynBal() const { return has(Capability::DYNBAL); }
2624 
2625  bool hasFlap() const { return has(Capability::FLAP); }
2626 
2627  virtual std::ostream& print(std::ostream& s) const override {
2628  std::string s_type;
2629  switch(type) {
2631  s_type = "Tricopter";
2632  break;
2634  s_type = "Quadrocopter Plus";
2635  break;
2637  s_type = "Quadrocopter X";
2638  break;
2640  s_type = "BI-copter";
2641  break;
2642  default:
2643  s_type = "UNDEFINED";
2644  break;
2645  }
2646 
2647  s << "#Ident:" << std::endl;
2648 
2649  s << " MultiWii Version: " << version << std::endl
2650  << " MSP Version: " << msp_version << std::endl
2651  << " Type: " << s_type << std::endl
2652  << " Capabilities:" << std::endl;
2653 
2654  s << " Bind: ";
2655  hasBind() ? s << "ON" : s << "OFF";
2656  s << std::endl;
2657 
2658  s << " DynBal: ";
2659  hasDynBal() ? s << "ON" : s << "OFF";
2660  s << std::endl;
2661 
2662  s << " Flap: ";
2663  hasFlap() ? s << "ON" : s << "OFF";
2664  s << std::endl;
2665 
2666  return s;
2667  }
2668 };
2669 
2670 struct StatusBase : public Packable {
2673  std::set<Sensor> sensors;
2674  std::set<size_t> box_mode_flags;
2676 
2677  bool unpack_from(const ByteVector& data) {
2678  bool rc = true;
2679  rc &= data.unpack(cycle_time);
2680  rc &= data.unpack(i2c_errors);
2681 
2682  // get sensors
2683  sensors.clear();
2684  uint16_t sensor = 0;
2685  rc &= data.unpack(sensor);
2686  if(sensor & (1 << 0)) sensors.insert(Sensor::Accelerometer);
2687  if(sensor & (1 << 1)) sensors.insert(Sensor::Barometer);
2688  if(sensor & (1 << 2)) sensors.insert(Sensor::Magnetometer);
2689  if(sensor & (1 << 3)) sensors.insert(Sensor::GPS);
2690  if(sensor & (1 << 4)) sensors.insert(Sensor::Sonar);
2691  if(sensor & (1 << 5)) sensors.insert(Sensor::OpticalFlow);
2692  if(sensor & (1 << 6)) sensors.insert(Sensor::Pitot);
2693  if(sensor & (1 << 15)) sensors.insert(Sensor::GeneralHealth);
2694 
2695  // check active boxes
2696  box_mode_flags.clear();
2697  uint32_t flag = 0;
2698  rc &= data.unpack(flag);
2699  for(size_t ibox(0); ibox < sizeof(flag) * CHAR_BIT; ibox++) {
2700  if(flag & (1 << ibox)) box_mode_flags.insert(ibox);
2701  }
2702 
2703  rc &= data.unpack(current_profile);
2704  return rc;
2705  }
2706 
2707  virtual bool pack_into(ByteVector& data) const {
2708  bool rc = true;
2709  rc &= data.pack(cycle_time);
2710  rc &= data.pack(i2c_errors);
2711 
2712  Value<uint16_t> sensor_pack;
2713  sensor_pack = 0;
2714  for(const auto& s : sensors) {
2715  switch(s) {
2716  case Sensor::Accelerometer:
2717  sensor_pack() |= (1 << 0);
2718  break;
2719  case Sensor::Barometer:
2720  sensor_pack() |= (1 << 1);
2721  break;
2722  case Sensor::Magnetometer:
2723  sensor_pack() |= (1 << 2);
2724  break;
2725  case Sensor::GPS:
2726  sensor_pack() |= (1 << 3);
2727  break;
2728  case Sensor::Sonar:
2729  sensor_pack() |= (1 << 4);
2730  break;
2731  case Sensor::OpticalFlow:
2732  sensor_pack() |= (1 << 5);
2733  break;
2734  case Sensor::Pitot:
2735  sensor_pack() |= (1 << 6);
2736  break;
2737  case Sensor::GeneralHealth:
2738  sensor_pack() |= (1 << 15);
2739  break;
2740  }
2741  }
2742  rc &= data.pack(sensor_pack);
2743 
2744  Value<uint32_t> box_pack;
2745  box_pack = 0;
2746  for(const auto& b : box_mode_flags) {
2747  box_pack() |= (1 << b);
2748  }
2749  rc &= data.pack(box_pack);
2750  return rc;
2751  }
2752 };
2753 
2754 // MSP_STATUS: 101
2755 struct Status : public StatusBase, public Message {
2757 
2758  virtual ID id() const override { return ID::MSP_STATUS; }
2759 
2762 
2763  virtual bool decode(const ByteVector& data) override {
2764  bool rc = true;
2765  rc &= StatusBase::unpack_from(data);
2766 
2767  if(fw_variant != FirmwareVariant::INAV) {
2768  rc &= data.unpack(avg_system_load_pct);
2769  rc &= data.unpack(gyro_cycle_time);
2770  }
2771  return rc;
2772  }
2773 
2774  bool hasAccelerometer() const {
2775  return sensors.count(Sensor::Accelerometer);
2776  }
2777 
2778  bool hasBarometer() const { return sensors.count(Sensor::Barometer); }
2779 
2780  bool hasMagnetometer() const { return sensors.count(Sensor::Magnetometer); }
2781 
2782  bool hasGPS() const { return sensors.count(Sensor::GPS); }
2783 
2784  bool hasSonar() const { return sensors.count(Sensor::Sonar); }
2785 
2786  bool hasOpticalFlow() const { return sensors.count(Sensor::OpticalFlow); }
2787 
2788  bool hasPitot() const { return sensors.count(Sensor::Pitot); }
2789 
2790  bool isHealthy() const { return sensors.count(Sensor::GeneralHealth); }
2791 
2792  virtual std::ostream& print(std::ostream& s) const override {
2793  s << "#Status:" << std::endl;
2794  s << " Cycle time: " << cycle_time << " us" << std::endl;
2795  s << " I2C errors: " << i2c_errors << std::endl;
2796  s << " Sensors:" << std::endl;
2797 
2798  s << " Accelerometer: ";
2799  hasAccelerometer() ? s << "ON" : s << "OFF";
2800  s << std::endl;
2801 
2802  s << " Barometer: ";
2803  hasBarometer() ? s << "ON" : s << "OFF";
2804  s << std::endl;
2805 
2806  s << " Magnetometer: ";
2807  hasMagnetometer() ? s << "ON" : s << "OFF";
2808  s << std::endl;
2809 
2810  s << " GPS: ";
2811  hasGPS() ? s << "ON" : s << "OFF";
2812  s << std::endl;
2813 
2814  s << " Sonar: ";
2815  hasSonar() ? s << "ON" : s << "OFF";
2816  s << std::endl;
2817 
2818  s << " Active Boxes (by ID):";
2819  for(const size_t box_id : box_mode_flags) {
2820  s << " " << box_id;
2821  }
2822  s << std::endl;
2823 
2824  return s;
2825  }
2826 };
2827 
2828 // MSP_RAW_IMU: 102
2829 struct RawImu : public Message {
2831 
2832  virtual ID id() const override { return ID::MSP_RAW_IMU; }
2833 
2834  std::array<Value<int16_t>, 3> acc;
2835  std::array<Value<int16_t>, 3> gyro;
2836  std::array<Value<int16_t>, 3> mag;
2837 
2838  virtual bool decode(const ByteVector& data) override {
2839  bool rc = true;
2840  for(auto& a : acc) {
2841  rc &= data.unpack(a);
2842  }
2843  for(auto& g : gyro) {
2844  rc &= data.unpack(g);
2845  }
2846  for(auto& m : mag) {
2847  rc &= data.unpack(m);
2848  }
2849  return rc;
2850  }
2851 
2852  virtual std::ostream& print(std::ostream& s) const override {
2853  s << "#Imu:" << std::endl;
2854  s << " Linear acceleration: " << acc[0] << ", " << acc[1] << ", "
2855  << acc[2] << std::endl;
2856  s << " Angular velocity: " << gyro[0] << ", " << gyro[1] << ", "
2857  << gyro[2] << std::endl;
2858  s << " Magnetometer: " << mag[0] << ", " << mag[1] << ", " << mag[2]
2859  << std::endl;
2860  return s;
2861  }
2862 };
2863 
2864 // helper class to convert raw imu readigs into standard physic units
2865 // custom scaling factors have to be derived from the sensor documentation
2866 struct ImuSI {
2867  std::array<Value<float>, 3> acc; // m/s^2
2868  std::array<Value<float>, 3> gyro; // deg/s
2869  std::array<Value<float>, 3> mag; // uT
2870 
2872  const float acc_1g, // sensor value at 1g
2873  const float gyro_unit, // resolution in 1/(deg/s)
2874  const float magn_gain, // scale magnetic value to uT (micro Tesla)
2875  const float si_unit_1g // acceleration at 1g (in m/s^2))
2876  ) {
2877  for(int i = 0; i < 3; ++i) {
2878  acc[i] = raw.acc[i]() / acc_1g * si_unit_1g;
2879  }
2880  for(int i = 0; i < 3; ++i) {
2881  gyro[i] = raw.gyro[i]() * gyro_unit;
2882  }
2883  for(int i = 0; i < 3; ++i) {
2884  mag[i] = raw.mag[i]() * magn_gain;
2885  }
2886  }
2887 
2888  std::ostream& print(std::ostream& s) const {
2889  s << "#Imu:" << std::endl;
2890  s << " Linear acceleration: " << acc[0] << ", " << acc[1] << ", "
2891  << acc[2] << " m/s²" << std::endl;
2892  s << " Angular velocity: " << gyro[0] << ", " << gyro[1] << ", "
2893  << gyro[2] << " deg/s" << std::endl;
2894  s << " Magnetometer: " << mag[0] << ", " << mag[1] << ", " << mag[2]
2895  << " uT" << std::endl;
2896  return s;
2897  }
2898 };
2899 
2900 // MSP_SERVO: 103
2901 struct Servo : public Message {
2903 
2904  virtual ID id() const override { return ID::MSP_SERVO; }
2905 
2906  std::array<uint16_t, N_SERVO> servo; // [1000, 2000]
2907 
2908  virtual bool decode(const ByteVector& data) override {
2909  bool rc = true;
2910  for(auto& s : servo) rc &= data.unpack(s);
2911  return rc;
2912  }
2913 
2914  virtual std::ostream& print(std::ostream& s) const override {
2915  s << "#Servo:" << std::endl;
2916  s << " " << servo[0] << " " << servo[1] << " " << servo[2] << " "
2917  << servo[3] << std::endl;
2918  s << " " << servo[4] << " " << servo[5] << " " << servo[6] << " "
2919  << servo[7] << std::endl;
2920  return s;
2921  }
2922 };
2923 
2924 // MSP_MOTOR: 104
2925 struct Motor : public Message {
2927 
2928  virtual ID id() const override { return ID::MSP_MOTOR; }
2929 
2930  std::array<uint16_t, N_MOTOR> motor; // [1000, 2000]
2931 
2932  virtual bool decode(const ByteVector& data) override {
2933  bool rc = true;
2934  for(auto& m : motor) rc &= data.unpack(m);
2935  return rc;
2936  }
2937 
2938  virtual std::ostream& print(std::ostream& s) const override {
2939  s << "#Motor:" << std::endl;
2940  s << " " << motor[0] << " " << motor[1] << " " << motor[2] << " "
2941  << motor[3] << std::endl;
2942  s << " " << motor[4] << " " << motor[5] << " " << motor[6] << " "
2943  << motor[7] << std::endl;
2944  return s;
2945  }
2946 };
2947 
2948 // MSP_RC: 105
2949 struct Rc : public Message {
2951 
2952  virtual ID id() const override { return ID::MSP_RC; }
2953 
2954  std::vector<uint16_t> channels; // [1000, 2000]
2955 
2956  virtual bool decode(const ByteVector& data) override {
2957  channels.clear();
2958  bool rc = true;
2959  while(rc) {
2960  uint16_t rc_data;
2961  rc &= data.unpack(rc_data);
2962  if(rc) channels.push_back(rc_data);
2963  }
2964  return !channels.empty();
2965  }
2966 
2967  virtual std::ostream& print(std::ostream& s) const override {
2968  s << "#Rc channels (" << channels.size() << ") :" << std::endl;
2969  for(const uint16_t c : channels) {
2970  s << c << " ";
2971  }
2972  s << " " << std::endl;
2973  return s;
2974  }
2975 };
2976 
2977 // MSP_RAW_GPS: 106
2978 struct RawGPS : public Message {
2980 
2981  virtual ID id() const override { return ID::MSP_RAW_GPS; }
2982 
2990  bool hdop_set;
2992 
2993  virtual bool decode(const ByteVector& data) override {
2994  bool rc = true;
2995  hdop_set = false;
2996  rc &= data.unpack(fix);
2997  rc &= data.unpack(numSat);
2998  rc &= data.unpack<int32_t>(lat, 1e7);
2999  rc &= data.unpack<int32_t>(lon, 1e7);
3000  rc &= data.unpack<int16_t>(altitude);
3001  rc &= data.unpack<uint16_t>(ground_speed, 100);
3002  rc &= data.unpack<uint16_t>(ground_course, 10);
3003  if(data.unpacking_remaining()) {
3004  hdop_set = true;
3005  rc &= data.unpack<uint16_t>(hdop, 100);
3006  }
3007  return rc;
3008  }
3009 
3010  virtual std::ostream& print(std::ostream& s) const override {
3011  s << "#RawGPS:" << std::endl;
3012  s << " Fix: " << fix << std::endl;
3013  s << " Num Sat: " << numSat << std::endl;
3014  s << " Location: " << lat << " " << lon << std::endl;
3015  s << " Altitude: " << altitude << " m" << std::endl;
3016  s << " Ground speed: " << ground_speed << " m/s" << std::endl;
3017  s << " Ground course: " << ground_course << " deg" << std::endl;
3018  if(hdop_set) s << " HDOP: " << hdop << std::endl;
3019  return s;
3020  }
3021 };
3022 
3023 // MSP_COMP_GPS: 107
3024 struct CompGPS : public Message {
3026 
3027  virtual ID id() const override { return ID::MSP_COMP_GPS; }
3028 
3030  Value<uint16_t> directionToHome; // [-180, +180] degree
3032 
3033  virtual bool decode(const ByteVector& data) override {
3034  bool rc = true;
3035  rc &= data.unpack(distanceToHome);
3036  rc &= data.unpack(directionToHome);
3037  rc &= data.unpack(update);
3038  return rc;
3039  }
3040 
3041  virtual std::ostream& print(std::ostream& s) const override {
3042  s << "#CompGPS:" << std::endl;
3043  s << " Distance: " << distanceToHome << std::endl;
3044  s << " Direction: " << directionToHome << std::endl;
3045  s << " Update: " << update << std::endl;
3046 
3047  return s;
3048  }
3049 };
3050 
3051 // MSP_ATTITUDE: 108
3052 struct Attitude : public Message {
3054 
3055  virtual ID id() const override { return ID::MSP_ATTITUDE; }
3056 
3057  Value<float> roll; // [-180, +180] degree
3058  Value<float> pitch; // [-90, +90] degree
3059  Value<int16_t> yaw; // [-180, +180] degree
3060 
3061  virtual bool decode(const ByteVector& data) override {
3062  bool rc = true;
3063  rc &= data.unpack<int16_t>(roll, 10);
3064  rc &= data.unpack<int16_t>(pitch, 10);
3065  rc &= data.unpack(yaw);
3066  return rc;
3067  }
3068 
3069  virtual std::ostream& print(std::ostream& s) const override {
3070  s << "#Attitude:" << std::endl;
3071  s << " Roll : " << roll << " deg" << std::endl;
3072  s << " Pitch : " << pitch << " deg" << std::endl;
3073  s << " Heading: " << yaw << " deg" << std::endl;
3074  return s;
3075  }
3076 };
3077 
3078 // TODO validate units
3079 // MSP_ALTITUDE: 109
3080 struct Altitude : public Message {
3082 
3083  virtual ID id() const override { return ID::MSP_ALTITUDE; }
3084 
3089 
3090  virtual bool decode(const ByteVector& data) override {
3091  bool rc = true;
3092  rc &= data.unpack<int32_t>(altitude, 100);
3093  rc &= data.unpack<int16_t>(vario, 100);
3094  if(data.unpacking_remaining()) {
3095  baro_altitude_set = true;
3096  rc &= data.unpack<int32_t>(baro_altitude, 100);
3097  }
3098  return rc;
3099  }
3100 
3101  virtual std::ostream& print(std::ostream& s) const override {
3102  s << "#Altitude:" << std::endl;
3103  s << " Altitude: " << altitude << " m, var: " << vario << " m/s"
3104  << std::endl;
3105  s << " Barometer: ";
3106  if(baro_altitude_set)
3107  s << baro_altitude;
3108  else
3109  s << "<unset>";
3110  s << std::endl;
3111  return s;
3112  }
3113 };
3114 
3115 // MSP_ANALOG: 110
3116 struct Analog : public Message {
3118 
3119  virtual ID id() const override { return ID::MSP_ANALOG; }
3120 
3123  Value<uint16_t> rssi; // Received Signal Strength Indication [0, 1023]
3125 
3126  virtual bool decode(const ByteVector& data) override {
3127  bool rc = true;
3128  rc &= data.unpack<uint8_t>(vbat, 10);
3129  rc &= data.unpack<uint16_t>(powerMeterSum, 1000);
3130  rc &= data.unpack(rssi);
3131  rc &= data.unpack<int8_t>(amperage, 100);
3132  return rc;
3133  }
3134 
3135  virtual std::ostream& print(std::ostream& s) const override {
3136  s << "#Analog:" << std::endl;
3137  s << " Battery Voltage: " << vbat << " V" << std::endl;
3138  s << " Current: " << amperage << " A" << std::endl;
3139  s << " Power consumption: " << powerMeterSum << " Ah" << std::endl;
3140  s << " RSSI: " << rssi << std::endl;
3141  return s;
3142  }
3143 };
3144 
3146  // RPY sequence
3147  std::array<Value<uint8_t>, 3> rates;
3148  std::array<Value<uint8_t>, 3> rcRates;
3149  std::array<Value<uint8_t>, 3> rcExpo;
3150 
3155 
3156  std::ostream& print(std::ostream& s) const {
3157  s << "#Rc Tuning:" << std::endl;
3158  s << " Rc Rate: " << rcRates[0] << " " << rcRates[1] << " "
3159  << rcRates[2] << std::endl;
3160  s << " Rc Expo: " << rcExpo[0] << " " << rcExpo[1] << " " << rcExpo[2]
3161  << std::endl;
3162 
3163  s << " Dynamic Throttle PID: " << dynamic_throttle_pid << std::endl;
3164  s << " Throttle MID: " << throttle_mid << std::endl;
3165  s << " Throttle Expo: " << throttle_expo << std::endl;
3166  return s;
3167  }
3168 };
3169 
3170 // Differences between iNav and BF/CF
3171 // MSP_RC_TUNING: 111
3172 struct RcTuning : public RcTuningSettings, public Message {
3174 
3175  virtual ID id() const override { return ID::MSP_RC_TUNING; }
3176 
3177  virtual bool decode(const ByteVector& data) override {
3178  bool rc = true;
3179  rc &= data.unpack(rcRates[0]);
3180  rc &= data.unpack(rcExpo[0]);
3181  for(size_t i = 0; i < 3; ++i) {
3182  rc &= data.unpack(rates[0]);
3183  }
3184  rc &= data.unpack(dynamic_throttle_pid);
3185  rc &= data.unpack(throttle_mid);
3186  rc &= data.unpack(throttle_expo);
3187  rc &= data.unpack(tpa_breakpoint);
3188  rc &= data.unpack(rcExpo[2]);
3189  if(fw_variant == FirmwareVariant::INAV) return rc;
3190  rc &= data.unpack(rcRates[2]);
3191  rc &= data.unpack(rcRates[1]);
3192  rc &= data.unpack(rcExpo[1]);
3193  return rc;
3194  }
3195 };
3196 
3197 // PID struct for messages 112 and 202
3198 struct PidTerms : public Packable {
3199  uint8_t P;
3200  uint8_t I;
3201  uint8_t D;
3202 
3203  bool unpack_from(const ByteVector& data) {
3204  bool rc = true;
3205  rc &= data.unpack(P);
3206  rc &= data.unpack(I);
3207  rc &= data.unpack(D);
3208  return rc;
3209  }
3210 
3211  bool pack_into(ByteVector& data) const {
3212  bool rc = true;
3213  rc &= data.pack(P);
3214  rc &= data.pack(I);
3215  rc &= data.pack(D);
3216  return rc;
3217  }
3218 };
3219 
3220 struct PidSettings {
3221  std::array<Value<PidTerms>,
3222  static_cast<uint8_t>(PID_Element::PID_ITEM_COUNT)>
3223  entry;
3224 
3225  std::ostream& print(std::ostream& s) const {
3226  uint8_t PID_ROLL =
3227  static_cast<uint8_t>(msp::msg::PID_Element::PID_ROLL);
3228  uint8_t PID_PITCH =
3229  static_cast<uint8_t>(msp::msg::PID_Element::PID_PITCH);
3230  uint8_t PID_YAW = static_cast<uint8_t>(msp::msg::PID_Element::PID_YAW);
3231  uint8_t PID_POS_Z =
3232  static_cast<uint8_t>(msp::msg::PID_Element::PID_POS_Z);
3233  uint8_t PID_POS_XY =
3234  static_cast<uint8_t>(msp::msg::PID_Element::PID_POS_XY);
3235  uint8_t PID_VEL_XY =
3236  static_cast<uint8_t>(msp::msg::PID_Element::PID_VEL_XY);
3237  uint8_t PID_SURFACE =
3238  static_cast<uint8_t>(msp::msg::PID_Element::PID_SURFACE);
3239  uint8_t PID_LEVEL =
3240  static_cast<uint8_t>(msp::msg::PID_Element::PID_LEVEL);
3241  uint8_t PID_HEADING =
3242  static_cast<uint8_t>(msp::msg::PID_Element::PID_HEADING);
3243  uint8_t PID_VEL_Z =
3244  static_cast<uint8_t>(msp::msg::PID_Element::PID_VEL_Z);
3245 
3246  s << std::setprecision(3);
3247  s << "#PID:" << std::endl;
3248  s << " Name P | I | D |" << std::endl;
3249  s << " ----------------|-------|-------|" << std::endl;
3250  s << " Roll: " << entry[PID_ROLL]().P << "\t| "
3251  << entry[PID_ROLL]().I << "\t| " << entry[PID_ROLL]().D << std::endl;
3252  s << " Pitch: " << entry[PID_PITCH]().P << "\t| "
3253  << entry[PID_PITCH]().I << "\t| " << entry[PID_PITCH]().D
3254  << std::endl;
3255  s << " Yaw: " << entry[PID_YAW]().P << "\t| "
3256  << entry[PID_YAW]().I << "\t| " << entry[PID_YAW]().D << std::endl;
3257  s << " Altitude: " << entry[PID_POS_Z]().P << "\t| "
3258  << entry[PID_POS_Z]().I << "\t| " << entry[PID_POS_Z]().D
3259  << std::endl;
3260 
3261  s << " Position: " << entry[PID_POS_XY]().P << "\t| "
3262  << entry[PID_POS_XY]().I << "\t| " << entry[PID_POS_XY]().D
3263  << std::endl;
3264  s << " PositionR: " << entry[PID_VEL_XY]().P << "\t| "
3265  << entry[PID_VEL_XY]().I << "\t| " << entry[PID_VEL_XY]().D
3266  << std::endl;
3267  s << " NavR: " << entry[PID_SURFACE]().P << "\t| "
3268  << entry[PID_SURFACE]().I << "\t| " << entry[PID_SURFACE]().D
3269  << std::endl;
3270  s << " Level: " << entry[PID_LEVEL]().P << "\t| "
3271  << entry[PID_LEVEL]().I << "\t| " << entry[PID_LEVEL]().D
3272  << std::endl;
3273  s << " Magn: " << entry[PID_HEADING]().P << "\t| "
3274  << entry[PID_HEADING]().I << "\t| " << entry[PID_HEADING]().D
3275  << std::endl;
3276  s << " Vel: " << entry[PID_VEL_Z]().P << "\t| "
3277  << entry[PID_VEL_Z]().I << "\t| " << entry[PID_VEL_Z]().D
3278  << std::endl;
3279 
3280  return s;
3281  }
3282 };
3283 
3284 // TODO: revisit
3285 // MSP_PID: 112
3286 struct Pid : public PidSettings, public Message {
3288 
3289  virtual ID id() const override { return ID::MSP_PID; }
3290 
3291  virtual bool decode(const ByteVector& data) override {
3292  bool rc = true;
3293  for(uint8_t i = 0;
3294  i < static_cast<uint8_t>(PID_Element::PID_ITEM_COUNT);
3295  ++i) {
3296  rc &= data.unpack(entry[i]);
3297  }
3298  return rc;
3299  }
3300 };
3301 
3302 // MSP_ACTIVEBOXES: 113
3303 struct ActiveBoxes : public Message {
3305 
3306  virtual ID id() const override { return ID::MSP_ACTIVEBOXES; }
3307 
3308  // box activation pattern
3309  std::vector<std::array<std::set<SwitchPosition>, NAUX>> box_pattern;
3310 
3311  virtual bool decode(const ByteVector& data) override {
3312  box_pattern.clear();
3313  bool rc = true;
3314  while(rc && data.unpacking_remaining() > 1) {
3315  Value<uint16_t> box_conf;
3316  rc &= data.unpack(box_conf);
3317  std::array<std::set<SwitchPosition>, NAUX> aux_sp;
3318  for(size_t iaux(0); iaux < NAUX; iaux++) {
3319  for(size_t ip(0); ip < 3; ip++) {
3320  if(box_conf() & (1 << (iaux * 3 + ip)))
3321  aux_sp[iaux].insert(SwitchPosition(ip));
3322  } // each position (L,M,H)
3323  } // each aux switch
3324  box_pattern.push_back(aux_sp);
3325  } // each box
3326  return rc;
3327  }
3328 
3329  virtual std::ostream& print(std::ostream& s) const override {
3330  s << "#Box:" << std::endl;
3331  for(size_t ibox(0); ibox < box_pattern.size(); ibox++) {
3332  s << ibox << " ";
3333  for(size_t iaux(0); iaux < box_pattern[ibox].size(); iaux++) {
3334  s << "aux" << iaux + 1 << ": ";
3335  if(box_pattern[ibox][iaux].count(msp::msg::SwitchPosition::LOW))
3336  s << "L";
3337  else
3338  s << "_";
3339  if(box_pattern[ibox][iaux].count(msp::msg::SwitchPosition::MID))
3340  s << "M";
3341  else
3342  s << "_";
3343  if(box_pattern[ibox][iaux].count(
3345  s << "H";
3346  else
3347  s << "_";
3348  s << ", ";
3349  }
3350  s << std::endl;
3351  }
3352 
3353  return s;
3354  }
3355 };
3356 
3361  Value<uint16_t> min_command; // [1000, 2000]
3370  Value<float> voltage_scale, cell_min, cell_max, cell_warning;
3371 
3372  std::ostream& print(std::ostream& s) const {
3373  s << "#Miscellaneous:" << std::endl;
3374  s << " Mid rc: " << mid_rc << std::endl;
3375  s << " Min Throttle: " << min_throttle << std::endl;
3376  s << " Max Throttle: " << max_throttle << std::endl;
3377  s << " Failsafe Throttle: " << failsafe_throttle << std::endl;
3378 
3379  s << " Magnetic Declination: " << mag_declination << " deg"
3380  << std::endl;
3381  s << " Battery Voltage Scale: " << voltage_scale << " V" << std::endl;
3382  s << " Battery Warning Level 1: " << cell_min << " V" << std::endl;
3383  s << " Battery Warning Level 2: " << cell_max << " V" << std::endl;
3384  s << " Battery Critical Level: " << cell_warning << " V" << std::endl;
3385 
3386  return s;
3387  }
3388 };
3389 
3390 // MSP_MISC: 114
3391 struct Misc : public MiscSettings, public Message {
3393 
3394  virtual ID id() const override { return ID::MSP_MISC; }
3395 
3396  virtual bool decode(const ByteVector& data) override {
3397  bool rc = true;
3398  rc &= data.unpack(mid_rc);
3399  rc &= data.unpack(min_throttle);
3400  rc &= data.unpack(max_throttle);
3401  rc &= data.unpack(min_command);
3402  rc &= data.unpack(failsafe_throttle);
3403  rc &= data.unpack(gps_provider);
3404  rc &= data.unpack(gps_baudrate);
3405  rc &= data.unpack(gps_ubx_sbas);
3406  rc &= data.unpack(multiwii_current_meter_output);
3407  rc &= data.unpack(rssi_channel);
3408  rc &= data.unpack(reserved);
3409 
3410  rc &= data.unpack<uint16_t>(mag_declination, 10);
3411  rc &= data.unpack<uint8_t>(voltage_scale, 10);
3412  rc &= data.unpack<uint8_t>(cell_min, 10);
3413  rc &= data.unpack<uint8_t>(cell_max, 10);
3414  rc &= data.unpack<uint8_t>(cell_warning, 10);
3415  return rc;
3416  }
3417 };
3418 
3419 // MSP_MOTOR_PINS: 115
3420 struct MotorPins : public Message {
3422 
3423  virtual ID id() const override { return ID::MSP_MOTOR_PINS; }
3424 
3426 
3427  virtual bool decode(const ByteVector& data) override {
3428  bool rc = true;
3429  for(auto& pin : pwm_pin) rc &= data.unpack(pin);
3430  return rc;
3431  }
3432 
3433  virtual std::ostream& print(std::ostream& s) const override {
3434  s << "#Motor pins:" << std::endl;
3435  for(size_t imotor(0); imotor < msp::msg::N_MOTOR; imotor++) {
3436  s << " Motor " << imotor << ": pin " << size_t(pwm_pin[imotor]())
3437  << std::endl;
3438  }
3439 
3440  return s;
3441  }
3442 };
3443 
3444 // MSP_BOXNAMES: 116
3445 struct BoxNames : public Message {
3447 
3448  virtual ID id() const override { return ID::MSP_BOXNAMES; }
3449 
3450  std::vector<std::string> box_names;
3451 
3452  virtual bool decode(const ByteVector& data) override {
3453  box_names.clear();
3454  bool rc = true;
3455  std::string str;
3456  rc &= data.unpack(str);
3457  std::stringstream ss(str);
3458  std::string bname;
3459  while(getline(ss, bname, ';')) {
3460  box_names.push_back(bname);
3461  }
3462  return rc;
3463  }
3464 
3465  virtual std::ostream& print(std::ostream& s) const override {
3466  s << "# Box names:" << std::endl;
3467  for(size_t ibox(0); ibox < box_names.size(); ibox++) {
3468  s << " " << ibox << ": " << box_names[ibox] << std::endl;
3469  }
3470  return s;
3471  }
3472 };
3473 
3474 // MSP_PIDNAMES: 117
3475 struct PidNames : public Message {
3477 
3478  virtual ID id() const override { return ID::MSP_PIDNAMES; }
3479 
3480  std::vector<std::string> pid_names;
3481 
3482  virtual bool decode(const ByteVector& data) override {
3483  pid_names.clear();
3484  bool rc = true;
3485  std::string str;
3486  rc &= data.unpack(str);
3487  std::stringstream ss(str);
3488  std::string pname;
3489  while(getline(ss, pname, ';')) {
3490  pid_names.push_back(pname);
3491  }
3492  return rc;
3493  }
3494 
3495  virtual std::ostream& print(std::ostream& s) const override {
3496  s << "#PID names:" << std::endl;
3497  for(size_t ipid(0); ipid < pid_names.size(); ipid++) {
3498  s << " " << ipid << ": " << pid_names[ipid] << std::endl;
3499  }
3500  return s;
3501  }
3502 };
3503 
3504 // MSP_WP: 118
3505 struct WayPoint : public Message {
3507 
3508  virtual ID id() const override { return ID::MSP_WP; }
3509 
3517 
3518  virtual bool decode(const ByteVector& data) override {
3519  bool rc = true;
3520  rc &= data.unpack(wp_no);
3521  rc &= data.unpack(lat);
3522  rc &= data.unpack(lon);
3523  rc &= data.unpack(altHold);
3524  rc &= data.unpack(heading);
3525  rc &= data.unpack(staytime);
3526  rc &= data.unpack(navflag);
3527  return rc;
3528  }
3529 };
3530 
3531 // MSP_BOXIDS: 119
3532 struct BoxIds : public Message {
3534 
3535  virtual ID id() const override { return ID::MSP_BOXIDS; }
3536 
3538 
3539  virtual bool decode(const ByteVector& data) override {
3540  box_ids.clear();
3541 
3542  for(uint8_t bi : data) box_ids.push_back(bi);
3543  ;
3544 
3545  return true;
3546  }
3547 
3548  virtual std::ostream& print(std::ostream& s) const override {
3549  s << "#Box IDs:" << std::endl;
3550  for(size_t ibox(0); ibox < box_ids.size(); ibox++) {
3551  s << " " << ibox << ": " << size_t(box_ids[ibox]) << std::endl;
3552  }
3553  return s;
3554  }
3555 };
3556 
3558  Value<uint16_t> min; // [1000, 2000]
3559  Value<uint16_t> max; // [1000, 2000]
3560  Value<uint16_t> middle; // [1000, 2000]
3561  Value<uint8_t> rate; // [0, 100]
3562 };
3563 
3564 // MSP_SERVO_CONF: 120
3565 struct ServoConf : public Message {
3567 
3568  virtual ID id() const override { return ID::MSP_SERVO_CONF; }
3569 
3571 
3572  virtual bool decode(const ByteVector& data) override {
3573  bool rc = true;
3574  for(size_t i(0); i < N_SERVO; i++) {
3575  rc &= data.unpack(servo_conf[i].min);
3576  rc &= data.unpack(servo_conf[i].max);
3577  rc &= data.unpack(servo_conf[i].middle);
3578  rc &= data.unpack(servo_conf[i].rate);
3579  }
3580  return rc;
3581  }
3582 };
3583 
3584 // MSP_NAV_STATUS: 121
3585 struct NavStatus : public Message {
3587 
3588  virtual ID id() const override { return ID::MSP_NAV_STATUS; }
3589 
3595  int16_t target_bearing; // degrees
3596 
3597  virtual bool decode(const ByteVector& data) override {
3598  bool rc = true;
3599  rc &= data.unpack(GPS_mode);
3600  rc &= data.unpack(NAV_state);
3601  rc &= data.unpack(mission_action);
3602  rc &= data.unpack(mission_number);
3603  rc &= data.unpack(NAV_error);
3604  rc &= data.unpack(target_bearing);
3605  return rc;
3606  }
3607 };
3608 
3609 struct GpsConf {
3610  uint8_t filtering;
3611  uint8_t lead_filter;
3614 
3617  uint8_t slow_nav;
3619 
3621  uint8_t takeover_baro;
3622 
3623  uint16_t wp_radius; // in cm
3624  uint16_t safe_wp_distance; // in meter
3625  uint16_t nav_max_altitude; // in meter
3626  uint16_t nav_speed_max; // in cm/s
3627  uint16_t nav_speed_min; // in cm/s
3628 
3629  uint8_t crosstrack_gain; // * 100 (0-2.56)
3630  uint16_t nav_bank_max; // degree * 100; (3000 default)
3631  uint16_t rth_altitude; // in meter
3632  uint8_t land_speed; // between 50 and 255 (100 approx = 50cm/sec)
3633  uint16_t fence; // fence control in meters
3634 
3635  uint8_t max_wp_number;
3636 
3637  uint8_t checksum;
3638 };
3639 
3640 // MSP_NAV_CONFIG: 122
3641 struct NavConfig : public Message, public GpsConf {
3643 
3644  virtual ID id() const override { return ID::MSP_NAV_CONFIG; }
3645 
3646  virtual bool decode(const ByteVector& data) override {
3647  bool rc = true;
3648  rc &= data.unpack(filtering);
3649  rc &= data.unpack(lead_filter);
3650  rc &= data.unpack(dont_reset_home_at_arm);
3651  rc &= data.unpack(nav_controls_heading);
3652 
3653  rc &= data.unpack(nav_tail_first);
3654  rc &= data.unpack(nav_rth_takeoff_heading);
3655  rc &= data.unpack(slow_nav);
3656  rc &= data.unpack(wait_for_rth_alt);
3657 
3658  rc &= data.unpack(ignore_throttle);
3659  rc &= data.unpack(takeover_baro);
3660 
3661  rc &= data.unpack(wp_radius);
3662  rc &= data.unpack(safe_wp_distance);
3663  rc &= data.unpack(nav_max_altitude);
3664  rc &= data.unpack(nav_speed_max);
3665  rc &= data.unpack(nav_speed_min);
3666 
3667  rc &= data.unpack(crosstrack_gain);
3668  rc &= data.unpack(nav_bank_max);
3669  rc &= data.unpack(rth_altitude);
3670  rc &= data.unpack(land_speed);
3671  rc &= data.unpack(fence);
3672 
3673  rc &= data.unpack(max_wp_number);
3674  rc &= data.unpack(checksum);
3675 
3676  return rc;
3677  }
3678 };
3679 
3680 struct Motor3dConfig : public Message {
3682 
3683  virtual ID id() const override { return ID::MSP_MOTOR_3D_CONFIG; }
3684 
3688 
3689  virtual bool decode(const ByteVector& data) override {
3690  bool rc = true;
3691  rc &= data.unpack(deadband3d_low);
3692  rc &= data.unpack(deadband3d_high);
3693  rc &= data.unpack(neutral_3d);
3694  return rc;
3695  }
3696 };
3697 
3703 };
3704 
3705 struct RcDeadband : public RcDeadbandSettings, public Message {
3707 
3708  virtual ID id() const override { return ID::MSP_RC_DEADBAND; }
3709 
3710  virtual bool decode(const ByteVector& data) override {
3711  bool rc = true;
3712  rc &= data.unpack(deadband);
3713  rc &= data.unpack(yaw_deadband);
3714  rc &= data.unpack(alt_hold_deadband);
3715  rc &= data.unpack(deadband3d_throttle);
3716  return rc;
3717  }
3718 };
3719 
3724 };
3725 
3728 
3729  virtual ID id() const override { return ID::MSP_SENSOR_ALIGNMENT; }
3730 
3731  virtual bool decode(const ByteVector& data) override {
3732  bool rc = true;
3733  rc &= data.unpack(gyro_align);
3734  rc &= data.unpack(acc_align);
3735  rc &= data.unpack(mag_align);
3736  return rc;
3737  }
3738 };
3739 
3740 struct LedStripModecolor : public Message {
3742 
3743  virtual ID id() const override { return ID::MSP_LED_STRIP_MODECOLOR; }
3744 
3745  std::array<std::array<uint8_t, LED_DIRECTION_COUNT>, LED_MODE_COUNT>
3747  std::array<uint8_t, LED_SPECIAL_COLOR_COUNT> special_colors;
3751 
3752  virtual bool decode(const ByteVector& data) override {
3753  bool rc = true;
3754  for(auto& mode : mode_colors) {
3755  for(auto& color : mode) {
3756  rc &= data.unpack(color);
3757  }
3758  }
3759  for(auto& special : special_colors) {
3760  rc &= data.unpack(special);
3761  }
3762 
3763  rc &= data.unpack(led_aux_channel);
3764  rc &= data.unpack(reserved);
3765  rc &= data.unpack(led_strip_aux_channel);
3766  return rc;
3767  }
3768 };
3769 
3773 };
3774 
3775 struct VoltageMeters : public Message {
3777 
3778  virtual ID id() const override { return ID::MSP_VOLTAGE_METERS; }
3779 
3780  std::vector<VoltageMeter> meters;
3781 
3782  virtual bool decode(const ByteVector& data) override {
3783  const size_t nmeter = data.size() / 2;
3784  meters.resize(nmeter);
3785  bool rc = true;
3786  for(size_t i = 0; i < nmeter; i++) {
3787  rc &= data.unpack(meters[i].id);
3788  rc &= data.unpack<uint8_t>(meters[i].voltage, 10);
3789  }
3790  return rc;
3791  }
3792 
3793  virtual std::ostream& print(std::ostream& s) const override {
3794  s << "#Voltages (" << meters.size() << "):" << std::endl;
3795  for(const VoltageMeter& meter : meters) {
3796  s << meter.id << ": " << meter.voltage << "V" << std::endl;
3797  }
3798  return s;
3799  }
3800 };
3801 
3806 };
3807 
3808 struct CurrentMeters : public Message {
3810 
3811  virtual ID id() const override { return ID::MSP_CURRENT_METERS; }
3812 
3813  std::vector<CurrentMeter> meters;
3814 
3815  virtual bool decode(const ByteVector& data) override {
3816  const size_t nmeter = data.size() / 5;
3817  meters.resize(nmeter);
3818  bool rc = true;
3819  for(size_t i = 0; i < nmeter; i++) {
3820  rc &= data.unpack(meters[i].id);
3821  rc &= data.unpack(meters[i].mAh_drawn);
3822  rc &= data.unpack<uint16_t>(meters[i].amperage, 1000);
3823  }
3824  return rc;
3825  }
3826 
3827  virtual std::ostream& print(std::ostream& s) const override {
3828  s << "#Current (" << meters.size() << "):" << std::endl;
3829  for(const CurrentMeter& meter : meters) {
3830  s << meter.id << ": " << meter.mAh_drawn << "mAh ("
3831  << meter.amperage << "A)" << std::endl;
3832  }
3833  return s;
3834  }
3835 };
3836 
3837 struct BatteryState : public Message {
3838  enum class state_t : uint8_t { OK, WARNING, CRITICAL, NOT_PRESENT, INIT };
3839 
3841 
3842  virtual ID id() const override { return ID::MSP_BATTERY_STATE; }
3843 
3850 
3851  virtual bool decode(const ByteVector& data) override {
3852  bool rc = true;
3853  rc &= data.unpack(cell_count);
3854  rc &= data.unpack(capacity_mAh);
3855  rc &= data.unpack<uint8_t>(voltage, 10);
3856  rc &= data.unpack(mAh_drawn);
3857  rc &= data.unpack<uint16_t>(amperage, 100);
3858  uint8_t state_tmp;
3859  rc &= data.unpack(state_tmp);
3860  state = state_t(state_tmp);
3861  return rc;
3862  }
3863 
3864  virtual std::ostream& print(std::ostream& s) const override {
3865  s << "#Battery:" << std::endl
3866  << " Cells: " << cell_count << "S" << std::endl
3867  << " Capacity: " << capacity_mAh << "mAh" << std::endl
3868  << " Voltage: " << voltage << "V" << std::endl
3869  << " Current drawn: " << mAh_drawn << "mAh" << std::endl
3870  << " Current: " << amperage << "A" << std::endl;
3871  s << " State: ";
3872  switch(state) {
3873  case state_t::OK:
3874  s << "OK";
3875  break;
3876  case state_t::WARNING:
3877  s << "WARNING";
3878  break;
3879  case state_t::CRITICAL:
3880  s << "CRITICAL";
3881  break;
3882  case state_t::NOT_PRESENT:
3883  s << "NOT_PRESENT";
3884  break;
3885  case state_t::INIT:
3886  s << "INIT";
3887  break;
3888  default:
3889  s << "UNKNOWN";
3890  }
3891  s << std::endl;
3892  return s;
3893  }
3894 };
3895 
3900 };
3901 
3902 struct MotorConfig : public MotorConfigSettings, public Message {
3904 
3905  virtual ID id() const override { return ID::MSP_MOTOR_CONFIG; }
3906 
3907  virtual bool decode(const ByteVector& data) override {
3908  bool rc = true;
3909  rc &= data.unpack(min_throttle);
3910  rc &= data.unpack(max_throttle);
3911  rc &= data.unpack(min_command);
3912  return rc;
3913  }
3914 };
3915 
3921 };
3922 
3923 struct GpsConfig : public GpsConfigSettings, public Message {
3925 
3926  virtual ID id() const override { return ID::MSP_GPS_CONFIG; }
3927 
3928  virtual bool decode(const ByteVector& data) override {
3929  bool rc = true;
3930  rc &= data.unpack(provider);
3931  rc &= data.unpack(sbas_mode);
3932  rc &= data.unpack(auto_config);
3933  rc &= data.unpack(auto_baud);
3934  return rc;
3935  }
3936 };
3937 
3938 struct CompassConfig : public Message {
3940 
3941  virtual ID id() const override { return ID::MSP_COMPASS_CONFIG; }
3942 
3944 
3945  virtual bool decode(const ByteVector& data) override {
3946  return data.unpack(mag_declination);
3947  }
3948 };
3949 
3950 struct EscData {
3953 };
3954 
3955 struct EscSensorData : public Message {
3957 
3958  virtual ID id() const override { return ID::MSP_ESC_SENSOR_DATA; }
3959 
3961  std::vector<EscData> esc_data;
3962 
3963  virtual bool decode(const ByteVector& data) override {
3964  if(data.empty()) {
3965  motor_count = 0;
3966  return true;
3967  }
3968  bool rc = true;
3969  rc &= data.unpack(motor_count);
3970  for(int i = 0; i < motor_count(); ++i) {
3971  EscData esc;
3972  rc &= data.unpack(esc.temperature);
3973  rc &= data.unpack(esc.rpm);
3974  esc_data.push_back(esc);
3975  }
3976  return rc;
3977  }
3978 };
3979 
3980 struct StatusEx : public StatusBase, public Message {
3982 
3983  virtual ID id() const override { return ID::MSP_STATUS_EX; }
3984 
3985  // bf/cf fields
3988  // iNav fields
3992 
3993  virtual bool decode(const ByteVector& data) override {
3994  bool rc = true;
3995  rc &= StatusBase::unpack_from(data);
3996  if(fw_variant == FirmwareVariant::INAV) {
3997  rc &= data.unpack(avg_system_load_pct);
3998  rc &= data.unpack(arming_flags);
3999  rc &= data.unpack(acc_calibration_axis_flags);
4000  }
4001  else {
4002  rc &= data.unpack(max_profiles);
4003  rc &= data.unpack(control_rate_profile);
4004  }
4005  return rc;
4006  }
4007 };
4008 
4009 struct SensorStatus : public Message {
4011 
4012  virtual ID id() const override { return ID::MSP_SENSOR_STATUS; }
4013 
4023 
4024  virtual bool decode(const ByteVector& data) override {
4025  bool rc = true;
4026  rc &= data.unpack(hardware_healthy);
4027  rc &= data.unpack(hw_gyro_status);
4028  rc &= data.unpack(hw_acc_status);
4029  rc &= data.unpack(hw_compass_status);
4030  rc &= data.unpack(hw_baro_status);
4031  rc &= data.unpack(hw_gps_status);
4032  rc &= data.unpack(hw_rangefinder_status);
4033  rc &= data.unpack(hw_pitometer_status);
4034  rc &= data.unpack(hw_optical_flow_status);
4035  return rc;
4036  }
4037 };
4038 
4039 // MSP_UID = 160,
4040 struct Uid : public Message {
4042 
4043  virtual ID id() const override { return ID::MSP_UID; }
4044 
4048 
4049  virtual bool decode(const ByteVector& data) override {
4050  bool rc = true;
4051  rc &= data.unpack(u_id_0);
4052  rc &= data.unpack(u_id_1);
4053  rc &= data.unpack(u_id_2);
4054  return rc;
4055  }
4056 };
4057 
4059  uint8_t channel;
4060  uint8_t sv_id;
4061  uint8_t quality;
4062  uint8_t cno;
4063 };
4064 
4065 // MSP_GPSSVINFO = 164,
4066 struct GpsSvInfo : public Message {
4068 
4069  virtual ID id() const override { return ID::MSP_GPSSVINFO; }
4070 
4072 
4074  std::vector<GpsSvInfoSettings> sv_info;
4075 
4076  virtual bool decode(const ByteVector& data) override {
4077  bool rc = true;
4078  if(fw_variant == FirmwareVariant::INAV) {
4079  rc &= data.consume(4);
4080  rc &= data.unpack(hdop);
4081  }
4082  else {
4083  rc &= data.unpack(channel_count);
4084  for(uint8_t i = 0; i < channel_count(); ++i) {
4085  GpsSvInfoSettings tmp;
4086  rc &= data.unpack(tmp.channel);
4087  rc &= data.unpack(tmp.sv_id);
4088  rc &= data.unpack(tmp.quality);
4089  rc &= data.unpack(tmp.cno);
4090  }
4091  }
4092  return rc;
4093  }
4094 };
4095 
4096 // MSP_GPSSTATISTICS = 166,
4097 struct GpsStatistics : public Message {
4099 
4100  virtual ID id() const override { return ID::MSP_GPSSTATISTICS; }
4101 
4109 
4110  virtual bool decode(const ByteVector& data) override {
4111  bool rc = true;
4112  rc &= data.unpack(last_msg_dt);
4113  rc &= data.unpack(errors);
4114  rc &= data.unpack(timeouts);
4115  rc &= data.unpack(packet_count);
4116  rc &= data.unpack(hdop);
4117  rc &= data.unpack(eph);
4118  rc &= data.unpack(epv);
4119  return rc;
4120  }
4121 };
4122 
4123 // no actual implementations
4124 // MSP_OSD_VIDEO_CONFIG = 180,
4125 struct OsdVideoConfig : public Message {
4127 
4128  virtual ID id() const override { return ID::MSP_OSD_VIDEO_CONFIG; }
4129 
4130  virtual bool decode(const ByteVector& /*data*/) override { return false; }
4131 };
4132 
4133 // MSP_SET_OSD_VIDEO_CONFIG = 181,
4134 struct SetOsdVideoConfig : public Message {
4136 
4137  virtual ID id() const override { return ID::MSP_SET_OSD_VIDEO_CONFIG; }
4138 };
4139 
4140 // MSP_DISPLAYPORT = 182,
4141 struct Displayport : public Message {
4143 
4144  virtual ID id() const override { return ID::MSP_DISPLAYPORT; }
4145 
4150 
4151  virtual ByteVectorUptr encode() const override {
4152  ByteVectorUptr data = std::make_unique<ByteVector>();
4153  bool rc = true;
4154  rc &= data->pack(sub_cmd);
4155  if(sub_cmd() == 3) {
4156  rc &= data->pack(row);
4157  rc &= data->pack(col);
4158  rc &= data->pack(uint8_t(0));
4159  rc &= data->pack(uint8_t(str().size()));
4160  rc &= data->pack(str);
4161  }
4162  if(!rc) data.reset();
4163  return data;
4164  }
4165 };
4166 
4167 // Not available in iNav (183-185)
4168 // MSP_COPY_PROFILE = 183,
4169 struct CopyProfile : public Message {
4171 
4172  virtual ID id() const override { return ID::MSP_COPY_PROFILE; }
4173 
4177 
4178  virtual ByteVectorUptr encode() const override {
4179  ByteVectorUptr data = std::make_unique<ByteVector>();
4180  bool rc = true;
4181  rc &= data->pack(profile_type);
4182  rc &= data->pack(dest_profile_idx);
4183  rc &= data->pack(src_profile_idx);
4184  if(!rc) data.reset();
4185  return data;
4186  }
4187 };
4188 
4192 };
4193 
4194 // MSP_BEEPER_CONFIG = 184,
4195 struct BeeperConfig : public BeeperConfigSettings, public Message {
4197 
4198  virtual ID id() const override { return ID::MSP_BEEPER_CONFIG; }
4199 
4200  virtual bool decode(const ByteVector& data) override {
4201  bool rc = true;
4202  rc &= data.unpack(beeper_off_mask);
4203  rc &= data.unpack(beacon_tone);
4204  return rc;
4205  }
4206 };
4207 
4208 // MSP_SET_BEEPER_CONFIG = 185,
4211 
4212  virtual ID id() const override { return ID::MSP_SET_BEEPER_CONFIG; }
4213 
4214  virtual ByteVectorUptr encode() const override {
4215  ByteVectorUptr data = std::make_unique<ByteVector>();
4216  bool rc = true;
4217  rc &= data->pack(beeper_off_mask);
4218  if(beacon_tone.set()) {
4219  rc &= data->pack(beacon_tone);
4220  }
4221  if(!rc) data.reset();
4222  return data;
4223  }
4224 };
4225 
4226 // MSP_SET_TX_INFO = 186, // in message Used to send
4227 // runtime information from TX lua scripts to the firmware
4228 struct SetTxInfo : public Message {
4230 
4231  virtual ID id() const override { return ID::MSP_SET_TX_INFO; }
4232 
4234 
4235  virtual ByteVectorUptr encode() const override {
4236  ByteVectorUptr data = std::make_unique<ByteVector>();
4237  if(!data->pack(rssi)) data.reset();
4238  return data;
4239  }
4240 };
4241 
4242 // MSP_TX_INFO = 187, // out message Used by TX lua
4243 // scripts to read information from the firmware
4244 struct TxInfo : public Message {
4246 
4247  virtual ID id() const override { return ID::MSP_TX_INFO; }
4248 
4251 
4252  virtual bool decode(const ByteVector& data) override {
4253  bool rc = true;
4254  rc &= data.unpack(rssi_source);
4255  rc &= data.unpack(rtc_date_time_status);
4256  return rc;
4257  }
4258 };
4259 
4262 
4263 // MSP_SET_RAW_RC: 200
4264 // This message is accepted but ignored on betaflight 3.0.1 onwards
4265 // if "USE_RX_MSP" is not defined for the target. In this case, you can manually
4266 // add "#define USE_RX_MSP" to your 'target.h'.
4267 struct SetRawRc : public Message {
4269 
4270  virtual ID id() const override { return ID::MSP_SET_RAW_RC; }
4271 
4272  std::vector<uint16_t> channels; // [1000, 2000]
4273 
4274  virtual ByteVectorUptr encode() const override {
4275  ByteVectorUptr data = std::make_unique<ByteVector>();
4276  bool rc = true;
4277  for(const uint16_t& c : channels) {
4278  rc &= data->pack(c);
4279  }
4280  if(!rc) data.reset();
4281  return data;
4282  }
4283 };
4284 
4285 // MSP_SET_RAW_GPS: 201
4286 struct SetRawGPS : public Message {
4288 
4289  virtual ID id() const override { return ID::MSP_SET_RAW_GPS; }
4290 
4293  Value<float> lat; // degree
4294  Value<float> lon; // degree
4297 
4298  virtual ByteVectorUptr encode() const override {
4299  ByteVectorUptr data = std::make_unique<ByteVector>();
4300  bool rc = true;
4301  rc &= data->pack(fix);
4302  rc &= data->pack(numSat);
4303  rc &= data->pack<int32_t>(lat, 1e7);
4304  rc &= data->pack<int32_t>(lon, 1e7);
4305  rc &= data->pack(altitude);
4306  rc &= data->pack<uint16_t>(speed, 100);
4307  assert(data->size() == 14);
4308  if(!rc) data.reset();
4309  return data;
4310  }
4311 };
4312 
4313 // MSP_SET_PID: 202,
4314 struct SetPid : public PidSettings, public Message {
4316 
4317  virtual ID id() const override { return ID::MSP_SET_PID; }
4318 
4319  virtual ByteVectorUptr encode() const override {
4320  ByteVectorUptr data = std::make_unique<ByteVector>();
4321  bool rc = true;
4322  for(uint8_t i = 0;
4323  i < static_cast<uint8_t>(PID_Element::PID_ITEM_COUNT);
4324  ++i) {
4325  rc &= data->pack(entry[i]);
4326  }
4327  if(!rc) data.reset();
4328  return data;
4329  }
4330 };
4331 
4332 // Depricated - no examples
4333 // MSP_SET_BOX: 203,
4334 struct SetBox : public Message {
4336 
4337  virtual ID id() const override { return ID::MSP_SET_BOX; }
4338 };
4339 
4340 // Differences between iNav and BF/CF - this is BF/CF variant
4341 // MSP_SET_RC_TUNING: 204
4342 struct SetRcTuning : public RcTuningSettings, public Message {
4344 
4345  virtual ID id() const override { return ID::MSP_SET_RC_TUNING; }
4346 
4347  virtual ByteVectorUptr encode() const override {
4348  ByteVectorUptr data = std::make_unique<ByteVector>();
4349  bool rc = true;
4350  rc &= data->pack(rcRates[0]);
4351  rc &= data->pack(rcExpo[0]);
4352  for(const auto& r : rates) {
4353  rc &= data->pack(r);
4354  }
4355  rc &= data->pack(dynamic_throttle_pid);
4356  rc &= data->pack(throttle_mid);
4357  rc &= data->pack(throttle_expo);
4358  rc &= data->pack(tpa_breakpoint);
4359  // this field is optional in all firmwares
4360 
4361  if(!rcExpo[2].set()) goto packing_finished;
4362  rc &= data->pack(rcExpo[2]);
4363  // INAV quits her
4364 
4365  if(fw_variant == FirmwareVariant::INAV) goto packing_finished;
4366  // these fields are optional in BF/CF
4367 
4368  if(!rcRates[2].set()) goto packing_finished;
4369  rc &= data->pack(rcRates[2]);
4370 
4371  if(!rcRates[1].set()) goto packing_finished;
4372  rc &= data->pack(rcRates[1]);
4373 
4374  if(!rcExpo[1].set()) goto packing_finished;
4375  rc &= data->pack(rcExpo[1]);
4376 
4377  packing_finished:
4378  if(!rc) data.reset();
4379  return data;
4380  }
4381 };
4382 
4383 // MSP_ACC_CALIBRATION: 205
4384 struct AccCalibration : public Message {
4386 
4387  virtual ID id() const override { return ID::MSP_ACC_CALIBRATION; }
4388 };
4389 
4390 // MSP_MAG_CALIBRATION: 206
4391 struct MagCalibration : public Message {
4393 
4394  virtual ID id() const override { return ID::MSP_MAG_CALIBRATION; }
4395 };
4396 
4397 // MSP_SET_MISC: 207
4398 struct SetMisc : public MiscSettings, public Message {
4400 
4401  virtual ID id() const override { return ID::MSP_SET_MISC; }
4402 
4403  virtual ByteVectorUptr encode() const override {
4404  ByteVectorUptr data = std::make_unique<ByteVector>();
4405  bool rc = true;
4406  rc &= data->pack(mid_rc);
4407  rc &= data->pack(min_throttle);
4408  rc &= data->pack(max_throttle);
4409  rc &= data->pack(failsafe_throttle);
4410  rc &= data->pack(gps_provider);
4411  rc &= data->pack(gps_baudrate);
4412  rc &= data->pack(gps_ubx_sbas);
4413  rc &= data->pack(multiwii_current_meter_output);
4414  rc &= data->pack(rssi_channel);
4415  rc &= data->pack(reserved);
4416  rc &= data->pack<uint16_t>(mag_declination, 10);
4417  rc &= data->pack<uint8_t>(voltage_scale, 10);
4418  rc &= data->pack<uint8_t>(cell_min, 10);
4419  rc &= data->pack<uint8_t>(cell_max, 10);
4420  rc &= data->pack<uint8_t>(cell_warning, 10);
4421  if(!rc) data.reset();
4422  return data;
4423  }
4424 };
4425 
4426 // MSP_RESET_CONF: 208
4427 struct ResetConfig : public Message {
4429 
4430  virtual ID id() const override { return ID::MSP_RESET_CONF; }
4431 };
4432 
4433 // MSP_SET_WP: 209
4434 struct SetWp : public Message {
4436 
4437  virtual ID id() const override { return ID::MSP_SET_WP; }
4438 
4444 
4449 
4450  virtual ByteVectorUptr encode() const override {
4451  ByteVectorUptr data = std::make_unique<ByteVector>();
4452  bool rc = true;
4453  rc &= data->pack(wp_no);
4454  if(fw_variant == FirmwareVariant::INAV) {
4455  rc &= data->pack(action);
4456  }
4457  rc &= data->pack(lat);
4458  rc &= data->pack(lon);
4459  rc &= data->pack(alt);
4460  rc &= data->pack(p1);
4461  rc &= data->pack(p2);
4462  if(fw_variant == FirmwareVariant::INAV) {
4463  rc &= data->pack(p3);
4464  }
4465  rc &= data->pack(nav_flag);
4466  return data;
4467  }
4468 };
4469 
4470 // MSP_SELECT_SETTING: 210
4471 struct SelectSetting : public Message {
4473 
4474  virtual ID id() const override { return ID::MSP_SELECT_SETTING; }
4475 
4477 
4478  virtual ByteVectorUptr encode() const override {
4479  ByteVectorUptr data = std::make_unique<ByteVector>();
4480  if(!data->pack(current_setting)) data.reset();
4481  return data;
4482  }
4483 };
4484 
4485 // MSP_SET_HEADING: 211
4486 struct SetHeading : public Message {
4488 
4489  virtual ID id() const override { return ID::MSP_SET_HEADING; }
4490 
4491  int16_t heading;
4492 
4493  virtual ByteVectorUptr encode() const override {
4494  ByteVectorUptr data = std::make_unique<ByteVector>();
4495  if(!data->pack(heading)) data.reset();
4496  assert(data->size() == 2);
4497  return data;
4498  }
4499 };
4500 
4501 // TODO: check number of servos
4502 // MSP_SET_SERVO_CONF: 212
4503 struct SetServoConf : public Message {
4505 
4506  virtual ID id() const override { return ID::MSP_SET_SERVO_CONF; }
4507 
4513 
4516 
4517  virtual ByteVectorUptr encode() const override {
4518  ByteVectorUptr data = std::make_unique<ByteVector>();
4519  bool rc = true;
4520  rc &= data->pack(servo_idx);
4521  rc &= data->pack(min);
4522  rc &= data->pack(max);
4523  rc &= data->pack(middle);
4524  rc &= data->pack(rate);
4525  if(fw_variant == FirmwareVariant::INAV) {
4526  uint8_t tmp = 0;
4527  rc &= data->pack(tmp);
4528  rc &= data->pack(tmp);
4529  }
4530  rc &= data->pack(forward_from_channel);
4531  rc &= data->pack(reversed_sources);
4532  if(!rc) data.reset();
4533  return data;
4534  }
4535 };
4536 
4537 // MSP_SET_MOTOR: 214
4538 struct SetMotor : public Message {
4540 
4541  virtual ID id() const override { return ID::MSP_SET_MOTOR; }
4542 
4543  std::array<uint16_t, N_MOTOR> motor;
4544 
4545  virtual ByteVectorUptr encode() const override {
4546  ByteVectorUptr data = std::make_unique<ByteVector>();
4547  bool rc = true;
4548  for(size_t i(0); i < N_MOTOR; i++) rc &= data->pack(motor[i]);
4549  assert(data->size() == N_MOTOR * 2);
4550  if(!rc) data.reset();
4551  return data;
4552  }
4553 };
4554 
4555 // MSP_SET_NAV_CONFIG = 215
4556 struct SetNavConfig : public Message {
4558 
4559  virtual ID id() const override { return ID::MSP_SET_NAV_CONFIG; }
4560 };
4561 
4562 // MSP_SET_MOTOR_3D_CONF = 217
4563 struct SetMotor3dConf : public Message {
4565 
4566  virtual ID id() const override { return ID::MSP_SET_MOTOR_3D_CONF; }
4567 
4571 
4572  virtual ByteVectorUptr encode() const override {
4573  ByteVectorUptr data = std::make_unique<ByteVector>();
4574  bool rc = true;
4575  rc &= data->pack(deadband3d_low);
4576  rc &= data->pack(deadband3d_high);
4577  rc &= data->pack(neutral_3d);
4578  if(!rc) data.reset();
4579  return data;
4580  }
4581 };
4582 
4583 // MSP_SET_RC_DEADBAND = 218
4584 struct SetRcDeadband : public RcDeadbandSettings, public Message {
4586 
4587  virtual ID id() const override { return ID::MSP_SET_RC_DEADBAND; }
4588 
4589  virtual ByteVectorUptr encode() const override {
4590  ByteVectorUptr data = std::make_unique<ByteVector>();
4591  bool rc = true;
4592  rc &= data->pack(deadband);
4593  rc &= data->pack(yaw_deadband);
4594  rc &= data->pack(alt_hold_deadband);
4595  rc &= data->pack(deadband3d_throttle);
4596  if(!rc) data.reset();
4597  return data;
4598  }
4599 };
4600 
4601 // MSP_SET_RESET_CURR_PID = 219
4602 struct SetResetCurrPid : public Message {
4604 
4605  virtual ID id() const override { return ID::MSP_SET_RESET_CURR_PID; }
4606 };
4607 
4608 // MSP_SET_SENSOR_ALIGNMENT = 220
4611 
4612  virtual ID id() const override { return ID::MSP_SET_SENSOR_ALIGNMENT; }
4613 
4614  virtual ByteVectorUptr encode() const override {
4615  ByteVectorUptr data = std::make_unique<ByteVector>();
4616  bool rc = true;
4617  rc &= data->pack(gyro_align);
4618  rc &= data->pack(acc_align);
4619  rc &= data->pack(mag_align);
4620  if(!rc) data.reset();
4621  return data;
4622  }
4623 };
4624 
4625 // MSP_SET_LED_STRIP_MODECOLOR = 221
4628 
4629  virtual ID id() const override { return ID::MSP_SET_LED_STRIP_MODECOLOR; }
4630 
4634 
4635  virtual ByteVectorUptr encode() const override {
4636  ByteVectorUptr data = std::make_unique<ByteVector>();
4637  bool rc = true;
4638  rc &= data->pack(mode_idx);
4639  rc &= data->pack(fun_idx);
4640  rc &= data->pack(color);
4641  if(!rc) data.reset();
4642  return data;
4643  }
4644 };
4645 
4646 // Not available in iNav (222-224)
4647 // MSP_SET_MOTOR_CONFIG = 222 //out message Motor
4648 // configuration (min/max throttle, etc)
4649 struct SetMotorConfig : public MotorConfigSettings, public Message {
4651 
4652  virtual ID id() const override { return ID::MSP_SET_MOTOR_CONFIG; }
4653 
4654  virtual ByteVectorUptr encode() const override {
4655  ByteVectorUptr data = std::make_unique<ByteVector>();
4656  bool rc = true;
4657  rc &= data->pack(min_throttle);
4658  rc &= data->pack(max_throttle);
4659  rc &= data->pack(min_command);
4660  if(!rc) data.reset();
4661  return data;
4662  }
4663 };
4664 
4665 // MSP_SET_GPS_CONFIG = 223 //out message GPS
4666 // configuration
4667 struct SetGpsConfig : public GpsConfigSettings, public Message {
4669 
4670  virtual ID id() const override { return ID::MSP_SET_GPS_CONFIG; }
4671 
4672  virtual ByteVectorUptr encode() const override {
4673  ByteVectorUptr data = std::make_unique<ByteVector>();
4674  bool rc = true;
4675  rc &= data->pack(provider);
4676  rc &= data->pack(sbas_mode);
4677  rc &= data->pack(auto_config);
4678  rc &= data->pack(auto_baud);
4679  if(!rc) data.reset();
4680  return data;
4681  }
4682 };
4683 
4684 // MSP_SET_COMPASS_CONFIG = 224 //out message Compass
4685 // configuration
4686 struct SetCompassConfig : public Message {
4688 
4689  virtual ID id() const override { return ID::MSP_SET_GPS_CONFIG; }
4690 
4692 
4693  virtual ByteVectorUptr encode() const override {
4694  ByteVectorUptr data = std::make_unique<ByteVector>();
4695  if(!data->pack<uint16_t>(mag_declination, 10)) data.reset();
4696  return data;
4697  }
4698 };
4699 
4703 };
4704 
4705 // MSP_SET_ACC_TRIM = 239 //in message set acc angle
4706 // trim values
4707 struct SetAccTrim : public AccTrimSettings, public Message {
4709 
4710  virtual ID id() const override { return ID::MSP_SET_ACC_TRIM; }
4711 
4712  virtual ByteVectorUptr encode() const override {
4713  ByteVectorUptr data = std::make_unique<ByteVector>();
4714  bool rc = true;
4715  rc &= data->pack(pitch);
4716  rc &= data->pack(roll);
4717  if(!rc) data.reset();
4718  return data;
4719  }
4720 };
4721 
4722 // MSP_ACC_TRIM = 240 //out message get acc angle
4723 // trim values
4724 struct AccTrim : public AccTrimSettings, public Message {
4726 
4727  virtual ID id() const override { return ID::MSP_ACC_TRIM; }
4728 
4729  virtual bool decode(const ByteVector& data) override {
4730  bool rc = true;
4731  rc &= data.unpack(pitch);
4732  rc &= data.unpack(roll);
4733  return rc;
4734  }
4735 };
4736 
4737 struct ServoMixRule : public Packable {
4739  uint8_t input_source;
4740  uint8_t rate;
4741  uint8_t speed;
4742  uint8_t min;
4743  uint8_t max;
4744  uint8_t box;
4745 
4746  bool unpack_from(const ByteVector& data) {
4747  bool rc = true;
4748  rc &= data.unpack(target_channel);
4749  rc &= data.unpack(input_source);
4750  rc &= data.unpack(rate);
4751  rc &= data.unpack(speed);
4752  rc &= data.unpack(min);
4753  rc &= data.unpack(max);
4754  rc &= data.unpack(box);
4755  return rc;
4756  }
4757 
4758  bool pack_into(ByteVector& data) const {
4759  bool rc = true;
4760  rc &= data.pack(target_channel);
4761  rc &= data.pack(input_source);
4762  rc &= data.pack(rate);
4763  rc &= data.pack(speed);
4764  rc &= data.pack(min);
4765  rc &= data.pack(max);
4766  rc &= data.pack(box);
4767  return rc;
4768  }
4769 };
4770 
4771 // MSP_SERVO_MIX_RULES = 241 //out message Returns servo
4772 // mixer configuration
4773 struct ServoMixRules : public Message {
4775 
4776  virtual ID id() const override { return ID::MSP_SERVO_MIX_RULES; }
4777 
4778  std::vector<Value<ServoMixRule>> rules;
4779 
4780  virtual bool decode(const ByteVector& data) override {
4781  bool rc = true;
4782  while(data.unpacking_remaining()) {
4783  Value<ServoMixRule> rule;
4784  rc &= data.unpack(rule);
4785  if(rc)
4786  rules.push_back(rule);
4787  else
4788  break;
4789  }
4790  return rc;
4791  }
4792 };
4793 
4794 // MSP_SET_SERVO_MIX_RULE = 242 //in message Sets servo
4795 // mixer configuration
4796 struct SetServoMixRule : public Message {
4798 
4799  virtual ID id() const override { return ID::MSP_SERVO_MIX_RULES; }
4800 
4802 
4803  virtual ByteVectorUptr encode() const override {
4804  ByteVectorUptr data = std::make_unique<ByteVector>();
4805  if(!data->pack(rule)) data.reset();
4806  return data;
4807  }
4808 };
4809 
4810 // not used in CF, BF, iNav
4811 // MSP_PASSTHROUGH_SERIAL = 244
4812 struct PassthroughSerial : public Message {
4814 
4815  virtual ID id() const override { return ID::MSP_PASSTHROUGH_SERIAL; }
4816 };
4817 
4818 // MSP_SET_4WAY_IF = 245 //in message Sets 4way
4819 // interface
4820 struct Set4WayIF : public Message {
4822 
4823  virtual ID id() const override { return ID::MSP_SET_4WAY_IF; }
4824 
4827 
4829 
4830  virtual ByteVectorUptr encode() const override {
4831  ByteVectorUptr data = std::make_unique<ByteVector>();
4832  bool rc = true;
4833  if(esc_mode.set()) {
4834  rc &= data->pack(esc_mode);
4835  rc &= data->pack(esc_port_index);
4836  }
4837  if(!rc) data.reset();
4838  return data;
4839  }
4840 
4841  virtual bool decode(const ByteVector& data) override {
4842  return data.unpack(esc_count);
4843  }
4844 };
4845 
4846 struct RtcVals {
4849 };
4850 
4851 // MSP_SET_RTC = 246 //in message Sets the RTC
4852 // clock
4853 struct SetRtc : public RtcVals, public Message {
4855 
4856  virtual ID id() const override { return ID::MSP_SET_RTC; }
4857 
4858  virtual ByteVectorUptr encode() const override {
4859  ByteVectorUptr data = std::make_unique<ByteVector>();
4860  bool rc = true;
4861  rc &= data->pack(secs);
4862  rc &= data->pack(millis);
4863  if(!rc) data.reset();
4864  return data;
4865  }
4866 };
4867 
4868 // MSP_RTC = 247 //out message Gets the RTC
4869 // clock
4870 struct Rtc : public RtcVals, public Message {
4872 
4873  virtual ID id() const override { return ID::MSP_RTC; }
4874 
4875  virtual bool decode(const ByteVector& data) override {
4876  bool rc = true;
4877  rc &= data.unpack(secs);
4878  rc &= data.unpack(millis);
4879  return rc;
4880  }
4881 };
4882 
4883 // MSP_EEPROM_WRITE: 250
4884 struct WriteEEPROM : public Message {
4886 
4887  virtual ID id() const override { return ID::MSP_EEPROM_WRITE; }
4888 };
4889 
4890 // MSP_RESERVE_1: 251, //reserved for system usage
4891 struct Reserve1 : public Message {
4893 
4894  virtual ID id() const override { return ID::MSP_RESERVE_1; }
4895 };
4896 
4897 // MSP_RESERVE_2: 252, //reserved for system usage
4898 struct Reserve2 : public Message {
4900 
4901  virtual ID id() const override { return ID::MSP_RESERVE_2; }
4902 };
4903 
4904 // MSP_DEBUGMSG: 253
4905 struct DebugMessage : public Message {
4907 
4908  virtual ID id() const override { return ID::MSP_DEBUGMSG; }
4909 
4911 
4912  virtual bool decode(const ByteVector& data) override {
4913  return data.unpack(debug_msg);
4914  }
4915 };
4916 
4917 // MSP_DEBUG: 254
4918 struct Debug : public Message {
4920 
4921  virtual ID id() const override { return ID::MSP_DEBUG; }
4922 
4927 
4928  virtual bool decode(const ByteVector& data) override {
4929  bool rc = true;
4930  rc &= data.unpack(debug1);
4931  rc &= data.unpack(debug2);
4932  rc &= data.unpack(debug3);
4933  rc &= data.unpack(debug4);
4934  return rc;
4935  }
4936 };
4937 
4938 // MSP_V2_FRAME: 255
4939 struct V2Frame : public Message {
4941 
4942  virtual ID id() const override { return ID::MSP_V2_FRAME; }
4943 };
4944 
4945 // MSP2_COMMON_TZ = 0x1001, //out message Gets the TZ offset
4946 // for the local time (returns: minutes(i16))
4947 struct CommonTz : public Message {
4949 
4950  virtual ID id() const override { return ID::MSP2_COMMON_TZ; }
4951 
4953 
4954  virtual bool decode(const ByteVector& data) override {
4955  return data.unpack(tz_offset);
4956  }
4957 };
4958 
4959 // MSP2_COMMON_SET_TZ = 0x1002, //in message Sets the TZ offset
4960 // for the local time (args: minutes(i16))
4961 struct CommonSetTz : public Message {
4963 
4964  virtual ID id() const override { return ID::MSP2_COMMON_SET_TZ; }
4965 
4967 
4968  virtual ByteVectorUptr encode() const override {
4969  ByteVectorUptr data = std::make_unique<ByteVector>();
4970  if(!data->pack(tz_offset)) data.reset();
4971  return data;
4972  }
4973 };
4974 
4975 enum class DATA_TYPE : uint8_t {
4976  UNSET,
4977  UINT8,
4978  INT8,
4979  UINT16,
4980  INT16,
4981  UINT32,
4982  FLOAT,
4983  STRING
4984 };
4985 
4986 // MSP2_COMMON_SETTING = 0x1003, //in/out message Returns the
4987 // value for a setting
4988 struct CommonSetting : public Message {
4990 
4991  virtual ID id() const override { return ID::MSP2_COMMON_SETTING; }
4992 
5001 
5003 
5004  virtual ByteVectorUptr encode() const override {
5005  ByteVectorUptr data = std::make_unique<ByteVector>();
5006  bool rc = true;
5007  rc &= data->pack(setting_name);
5008  if(!rc) data.reset();
5009  return data;
5010  }
5011 
5012  virtual bool decode(const ByteVector& data) override {
5013  switch(expected_data_type) {
5014  case DATA_TYPE::UINT8:
5015  return data.unpack(uint8_val);
5016  case DATA_TYPE::INT8:
5017  return data.unpack(int8_val);
5018  case DATA_TYPE::UINT16:
5019  return data.unpack(uint16_val);
5020  case DATA_TYPE::INT16:
5021  return data.unpack(int16_val);
5022  case DATA_TYPE::UINT32:
5023  return data.unpack(uint32_val);
5024  case DATA_TYPE::FLOAT:
5025  return data.unpack(float_val);
5026  case DATA_TYPE::STRING:
5027  return data.unpack(string_val);
5028  default:
5029  return false;
5030  }
5031  }
5032 
5033  virtual std::ostream& print(std::ostream& s) const override {
5034  s << "#Setting:" << std::endl;
5035  s << " " << setting_name << ": ";
5036 
5037  switch(expected_data_type) {
5038  case DATA_TYPE::UINT8:
5039  s << uint8_val;
5040  break;
5041  case DATA_TYPE::INT8:
5042  s << int8_val;
5043  break;
5044  case DATA_TYPE::UINT16:
5045  s << uint16_val;
5046  break;
5047  case DATA_TYPE::INT16:
5048  s << int16_val;
5049  break;
5050  case DATA_TYPE::UINT32:
5051  s << uint32_val;
5052  break;
5053  case DATA_TYPE::FLOAT:
5054  s << float_val;
5055  break;
5056  case DATA_TYPE::STRING:
5057  s << string_val;
5058  break;
5059  default:
5060  s << "<invalid>";
5061  }
5062 
5063  s << std::endl;
5064 
5065  return s;
5066  }
5067 };
5068 
5069 // MSP2_COMMON_SET_SETTING = 0x1004, //in message Sets the value for
5070 // a setting
5071 struct CommonSetSetting : public Message {
5073 
5074  virtual ID id() const override { return ID::MSP2_COMMON_SET_SETTING; }
5075 
5084 
5086 
5087  virtual ByteVectorUptr encode() const override {
5088  ByteVectorUptr data = std::make_unique<ByteVector>();
5089  bool rc = true;
5090  rc &= data->pack(setting_name);
5091  if(uint8_val.set())
5092  rc &= data->pack(uint8_val);
5093  else if(int8_val.set())
5094  rc &= data->pack(int8_val);
5095  else if(uint16_val.set())
5096  rc &= data->pack(uint16_val);
5097  else if(int16_val.set())
5098  rc &= data->pack(int16_val);
5099  else if(uint32_val.set())
5100  rc &= data->pack(uint32_val);
5101  else if(float_val.set())
5102  rc &= data->pack(float_val);
5103  else if(string_val.set())
5104  rc &= data->pack(string_val);
5105  if(!rc) data.reset();
5106  return data;
5107  }
5108 };
5109 
5110 struct MotorMixer : public Packable {
5115 
5116  bool unpack_from(const ByteVector& data) {
5117  bool rc = true;
5118  rc &= data.unpack<uint16_t>(throttle, 1000);
5119  rc &= data.unpack<uint16_t>(roll, 1000, 1);
5120  rc &= data.unpack<uint16_t>(pitch, 1000, 1);
5121  rc &= data.unpack<uint16_t>(yaw, 1000, 1);
5122  return rc;
5123  }
5124 
5125  bool pack_into(ByteVector& data) const {
5126  bool rc = true;
5127  rc &= data.pack<uint16_t>(throttle, 1000, 1);
5128  rc &= data.pack<uint16_t>(roll, 1000, 1);
5129  rc &= data.pack<uint16_t>(pitch, 1000, 1);
5130  rc &= data.pack<uint16_t>(yaw, 1000, 1);
5131  return rc;
5132  }
5133 };
5134 
5135 // MSP2_COMMON_MOTOR_MIXER = 0x1005,
5136 struct CommonMotorMixer : public Message {
5138 
5139  virtual ID id() const override { return ID::MSP2_COMMON_MOTOR_MIXER; }
5140 
5141  std::vector<MotorMixer> mixer;
5142 
5143  virtual bool decode(const ByteVector& data) override {
5144  bool rc = true;
5145  while(data.unpacking_remaining()) {
5146  MotorMixer m;
5147  rc &= data.unpack(m);
5148  mixer.push_back(m);
5149  }
5150  return rc;
5151  }
5152 };
5153 
5154 // MSP2_COMMON_SET_MOTOR_MIXER = 0x1006,
5155 struct CommonSetMotorMixer : public Message {
5157 
5158  virtual ID id() const override { return ID::MSP2_COMMON_SET_MOTOR_MIXER; }
5159 
5162 
5163  virtual ByteVectorUptr encode() const override {
5164  ByteVectorUptr data = std::make_unique<ByteVector>();
5165  bool rc = true;
5166  rc &= data->pack(index);
5167  rc &= data->pack(mixer);
5168  if(!rc) data.reset();
5169  return data;
5170  }
5171 };
5172 
5173 // MSP2_INAV_STATUS = 0x2000,
5174 struct InavStatus : public StatusBase, public Message {
5176 
5177  virtual ID id() const override { return ID::MSP2_INAV_STATUS; }
5178 
5182 
5183  virtual bool decode(const ByteVector& data) override {
5184  bool rc = true;
5185  rc &= data.unpack(cycle_time);
5186  rc &= data.unpack(i2c_errors);
5187 
5188  // get sensors
5189  sensors.clear();
5190  uint16_t sensor = 0;
5191  rc &= data.unpack(sensor);
5192  if(sensor & (1 << 0)) sensors.insert(Sensor::Accelerometer);
5193  if(sensor & (1 << 1)) sensors.insert(Sensor::Barometer);
5194  if(sensor & (1 << 2)) sensors.insert(Sensor::Magnetometer);
5195  if(sensor & (1 << 3)) sensors.insert(Sensor::GPS);
5196  if(sensor & (1 << 4)) sensors.insert(Sensor::Sonar);
5197  if(sensor & (1 << 5)) sensors.insert(Sensor::OpticalFlow);
5198  if(sensor & (1 << 6)) sensors.insert(Sensor::Pitot);
5199  if(sensor & (1 << 15)) sensors.insert(Sensor::GeneralHealth);
5200 
5201  rc &= data.unpack(avg_system_load_pct);
5202  rc &= data.unpack(config_profile);
5203 
5204  rc &= data.unpack(arming_flags);
5205 
5206  // check active boxes
5207  box_mode_flags.clear();
5208  uint32_t flag = 0;
5209  rc &= data.unpack(flag);
5210  for(size_t ibox(0); ibox < sizeof(flag) * CHAR_BIT; ibox++) {
5211  if(flag & (1 << ibox)) box_mode_flags.insert(ibox);
5212  }
5213 
5214  return rc;
5215  }
5216 
5217  bool hasAccelerometer() const {
5218  return sensors.count(Sensor::Accelerometer);
5219  }
5220 
5221  bool hasBarometer() const { return sensors.count(Sensor::Barometer); }
5222 
5223  bool hasMagnetometer() const { return sensors.count(Sensor::Magnetometer); }
5224 
5225  bool hasGPS() const { return sensors.count(Sensor::GPS); }
5226 
5227  bool hasSonar() const { return sensors.count(Sensor::Sonar); }
5228 
5229  bool hasOpticalFlow() const { return sensors.count(Sensor::OpticalFlow); }
5230 
5231  bool hasPitot() const { return sensors.count(Sensor::Pitot); }
5232 
5233  bool isHealthy() const { return sensors.count(Sensor::GeneralHealth); }
5234 
5235  virtual std::ostream& print(std::ostream& s) const override {
5236  s << "#Status:" << std::endl;
5237  s << " Cycle time: " << cycle_time << " us" << std::endl;
5238  s << " Average system load: " << avg_system_load_pct << "%"
5239  << std::endl;
5240  s << " Arming flags: " << armingFlagToString(arming_flags())
5241  << std::endl;
5242  s << " I2C errors: " << i2c_errors << std::endl;
5243  s << " Sensors:" << std::endl;
5244 
5245  s << " Accelerometer: ";
5246  hasAccelerometer() ? s << "ON" : s << "OFF";
5247  s << std::endl;
5248 
5249  s << " Barometer: ";
5250  hasBarometer() ? s << "ON" : s << "OFF";
5251  s << std::endl;
5252 
5253  s << " Magnetometer: ";
5254  hasMagnetometer() ? s << "ON" : s << "OFF";
5255  s << std::endl;
5256 
5257  s << " GPS: ";
5258  hasGPS() ? s << "ON" : s << "OFF";
5259  s << std::endl;
5260 
5261  s << " Sonar: ";
5262  hasSonar() ? s << "ON" : s << "OFF";
5263  s << std::endl;
5264 
5265  s << " Active Boxes (by ID):";
5266  for(const size_t box_id : box_mode_flags) {
5267  s << " " << box_id;
5268  }
5269  s << std::endl;
5270 
5271  return s;
5272  }
5273 };
5274 
5275 // MSP2_INAV_OPTICAL_FLOW = 0x2001,
5276 struct InavOpticalFlow : public Message {
5278 
5279  virtual ID id() const override { return ID::MSP2_INAV_OPTICAL_FLOW; }
5280 
5286 
5287  virtual bool decode(const ByteVector& data) override {
5288  bool rc = true;
5289  rc &= data.unpack(raw_quality);
5290  rc &= data.unpack(flow_rate_x);
5291  rc &= data.unpack(flow_rate_y);
5292  rc &= data.unpack(body_rate_x);
5293  rc &= data.unpack(body_rate_y);
5294  return rc;
5295  }
5296 };
5297 
5298 // MSP2_INAV_ANALOG = 0x2002,
5299 struct InavAnalog : public Message {
5301 
5302  virtual ID id() const override { return ID::MSP2_INAV_ANALOG; }
5303 
5308 
5309  virtual bool decode(const ByteVector& data) override {
5310  bool rc = true;
5311  rc &= data.unpack(battery_voltage);
5312  rc &= data.unpack(mAh_drawn);
5313  rc &= data.unpack(rssi);
5314  rc &= data.unpack(amperage);
5315  return rc;
5316  }
5317 };
5318 
5338 };
5339 
5340 // MSP2_INAV_MISC = 0x2003,
5341 struct InavMisc : public InavMiscSettings, public Message {
5343 
5344  virtual ID id() const override { return ID::MSP2_INAV_MISC; }
5345 
5346  virtual bool decode(const ByteVector& data) override {
5347  bool rc = true;
5348  rc &= data.unpack(mid_rc);
5349  rc &= data.unpack(min_throttle);
5350  rc &= data.unpack(max_throttle);
5351  rc &= data.unpack(min_command);
5352  rc &= data.unpack(failsafe_throttle);
5353  rc &= data.unpack(gps_provider);
5354  rc &= data.unpack(gps_baudrate);
5355  rc &= data.unpack(gps_ubx_sbas);
5356  rc &= data.unpack(rssi_channel);
5357  rc &= data.unpack(mag_declination);
5358  rc &= data.unpack(voltage_scale);
5359  rc &= data.unpack(cell_min);
5360  rc &= data.unpack(cell_max);
5361  rc &= data.unpack(cell_warning);
5362  rc &= data.unpack(capacity);
5363  rc &= data.unpack(capacity_warning);
5364  rc &= data.unpack(capacity_critical);
5365  rc &= data.unpack(capacity_units);
5366  return rc;
5367  }
5368 };
5369 
5370 // MSP2_INAV_SET_MISC = 0x2004,
5371 struct InavSetMisc : public InavMiscSettings, public Message {
5373 
5374  virtual ID id() const override { return ID::MSP2_INAV_SET_MISC; }
5375 
5376  virtual ByteVectorUptr encode() const override {
5377  ByteVectorUptr data = std::make_unique<ByteVector>();
5378  bool rc = true;
5379  rc &= data->pack(mid_rc);
5380  rc &= data->pack(min_throttle);
5381  rc &= data->pack(mid_rc);
5382  rc &= data->pack(max_throttle);
5383  rc &= data->pack(min_command);
5384  rc &= data->pack(failsafe_throttle);
5385  rc &= data->pack(gps_provider);
5386  rc &= data->pack(gps_baudrate);
5387  rc &= data->pack(gps_ubx_sbas);
5388  rc &= data->pack(rssi_channel);
5389  rc &= data->pack(mag_declination);
5390  rc &= data->pack(voltage_scale);
5391  rc &= data->pack(cell_min);
5392  rc &= data->pack(cell_max);
5393  rc &= data->pack(cell_warning);
5394  rc &= data->pack(capacity);
5395  rc &= data->pack(capacity_warning);
5396  rc &= data->pack(capacity_critical);
5397  rc &= data->pack(capacity_units);
5398  if(!rc) data.reset();
5399  return data;
5400  }
5401 };
5402 
5414 };
5415 
5416 // MSP2_INAV_BATTERY_CONFIG = 0x2005,
5419 
5420  virtual ID id() const override { return ID::MSP2_INAV_BATTERY_CONFIG; }
5421 
5422  virtual bool decode(const ByteVector& data) override {
5423  bool rc = true;
5424  rc &= data.unpack(voltage_scale);
5425  rc &= data.unpack(cell_min);
5426  rc &= data.unpack(cell_max);
5427  rc &= data.unpack(cell_warning);
5428  rc &= data.unpack(current_offset);
5429  rc &= data.unpack(current_scale);
5430  rc &= data.unpack(capacity);
5431  rc &= data.unpack(capacity_warning);
5432  rc &= data.unpack(capacity_critical);
5433  rc &= data.unpack(capacity_units);
5434  return rc;
5435  }
5436 };
5437 
5438 // MSP2_INAV_SET_BATTERY_CONFIG = 0x2006,
5441 
5442  virtual ID id() const override { return ID::MSP2_INAV_SET_BATTERY_CONFIG; }
5443 
5444  virtual ByteVectorUptr encode() const override {
5445  ByteVectorUptr data = std::make_unique<ByteVector>();
5446  bool rc = true;
5447  rc &= data->pack(voltage_scale);
5448  rc &= data->pack(cell_min);
5449  rc &= data->pack(cell_max);
5450  rc &= data->pack(cell_warning);
5451  rc &= data->pack(current_offset);
5452  rc &= data->pack(current_scale);
5453  rc &= data->pack(capacity);
5454  rc &= data->pack(capacity_warning);
5455  rc &= data->pack(capacity_critical);
5456  rc &= data->pack(capacity_units);
5457  if(!rc) data.reset();
5458  return data;
5459  }
5460 };
5461 
5467 
5473 
5479 };
5480 
5481 // MSP2_INAV_RATE_PROFILE = 0x2007,
5484 
5485  virtual ID id() const override { return ID::MSP2_INAV_RATE_PROFILE; }
5486 
5487  virtual bool decode(const ByteVector& data) override {
5488  bool rc = true;
5489  rc &= data.unpack(throttle_rc_mid);
5490  rc &= data.unpack(throttle_rc_expo);
5491  rc &= data.unpack(throttle_dyn_pid);
5492  rc &= data.unpack(throttle_pa_breakpoint);
5493 
5494  rc &= data.unpack(stabilized_rc_expo);
5495  rc &= data.unpack(stabilized_rc_yaw_expo);
5496  rc &= data.unpack(stabilized_rate_r);
5497  rc &= data.unpack(stabilized_rate_p);
5498  rc &= data.unpack(stabilized_rate_y);
5499 
5500  rc &= data.unpack(manual_rc_expo);
5501  rc &= data.unpack(manual_rc_yaw_expo);
5502  rc &= data.unpack(manual_rate_r);
5503  rc &= data.unpack(manual_rate_p);
5504  rc &= data.unpack(manual_rate_y);
5505  return rc;
5506  }
5507 };
5508 
5509 // MSP2_INAV_SET_RATE_PROFILE = 0x2008,
5512 
5513  virtual ID id() const override { return ID::MSP2_INAV_SET_RATE_PROFILE; }
5514 
5515  virtual ByteVectorUptr encode() const override {
5516  ByteVectorUptr data = std::make_unique<ByteVector>();
5517  bool rc = true;
5518  rc &= data->pack(throttle_rc_mid);
5519  rc &= data->pack(throttle_rc_expo);
5520  rc &= data->pack(throttle_dyn_pid);
5521  rc &= data->pack(throttle_pa_breakpoint);
5522 
5523  rc &= data->pack(stabilized_rc_expo);
5524  rc &= data->pack(stabilized_rc_yaw_expo);
5525  rc &= data->pack(stabilized_rate_r);
5526  rc &= data->pack(stabilized_rate_p);
5527  rc &= data->pack(stabilized_rate_y);
5528 
5529  rc &= data->pack(manual_rc_expo);
5530  rc &= data->pack(manual_rc_yaw_expo);
5531  rc &= data->pack(manual_rate_r);
5532  rc &= data->pack(manual_rate_p);
5533  rc &= data->pack(manual_rate_y);
5534  if(!rc) data.reset();
5535  return data;
5536  }
5537 };
5538 
5539 // MSP2_INAV_AIR_SPEED = 0x2009
5540 struct InavAirSpeed : public InavMiscSettings, public Message {
5542 
5543  virtual ID id() const override { return ID::MSP2_INAV_RATE_PROFILE; }
5544 
5546 
5547  virtual bool decode(const ByteVector& data) override {
5548  return data.unpack(speed);
5549  }
5550 };
5551 
5552 } // namespace msg
5553 } // namespace msp
5554 
5555 inline std::ostream& operator<<(std::ostream& s, const msp::msg::ImuSI& val) {
5556  return val.print(s);
5557 }
5558 
5559 #endif // MSP_MSG_HPP
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:1158
Value< uint8_t > vbatwarningcellvoltage
Definition: msp_msg.hpp:949
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:2232
Definition of a pure virtual class used to indicate that a child class can pack itself into a ByteVec...
Definition: ByteVector.hpp:458
Cleanflight.
Definition: msp_msg.hpp:405
Value< uint16_t > max
Definition: msp_msg.hpp:3559
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:4572
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:4654
Value< std::string > debug_msg
Definition: msp_msg.hpp:4910
Value< uint8_t > units
Definition: msp_msg.hpp:2196
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:2838
Value< uint8_t > throttle_expo
Definition: msp_msg.hpp:3153
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:1598
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4908
Uid(FirmwareVariant v)
Definition: msp_msg.hpp:4041
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:2904
Value< float > pitch
Definition: msp_msg.hpp:5113
Value< uint8_t > rssi_alarm
Definition: msp_msg.hpp:2197
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4172
BoardInfo(FirmwareVariant v)
Definition: msp_msg.hpp:477
SetWp(FirmwareVariant v)
Definition: msp_msg.hpp:4435
Value< uint8_t > pit_mode
Definition: msp_msg.hpp:2259
Value< uint16_t > tpa_breakpoint
Definition: msp_msg.hpp:3154
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:453
Value< uint16_t > neutral_3d
Definition: msp_msg.hpp:3687
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4776
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:5287
uint16_t nav_speed_min
Definition: msp_msg.hpp:3627
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:1827
Value< uint8_t > deadband
Definition: msp_msg.hpp:3699
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:5183
Value< uint8_t > hdop
Definition: msp_msg.hpp:4071
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:3842
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:4672
virtual std::ostream & print(std::ostream &s) const override
Definition: msp_msg.hpp:1061
Altitude(FirmwareVariant v)
Definition: msp_msg.hpp:3081
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:1187
Value< uint8_t > rth_alt_control_mode
Definition: msp_msg.hpp:834
TransponderConfig(FirmwareVariant v)
Definition: msp_msg.hpp:2101
Value< uint8_t > off_delay
Definition: msp_msg.hpp:1908
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:1654
Value< uint16_t > tz_offset
Definition: msp_msg.hpp:4966
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:5487
Value< uint16_t > mag_declination
Definition: msp_msg.hpp:5329
Value< uint8_t > row
Definition: msp_msg.hpp:4147
NavConfig(FirmwareVariant v)
Definition: msp_msg.hpp:3642
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:5374
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:1029
Value< uint8_t > servo_idx
Definition: msp_msg.hpp:4508
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:3427
Value< uint8_t > config_profile
Definition: msp_msg.hpp:5180
Value< uint16_t > neg_alt_alarm
Definition: msp_msg.hpp:2164
SetSensorConfig(FirmwareVariant v)
Definition: msp_msg.hpp:2532
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4799
Value< uint16_t > min_throttle
Definition: msp_msg.hpp:5321
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:871
Value< uint8_t > serialrx_provider
Definition: msp_msg.hpp:1201
SetBfConfig(FirmwareVariant v)
Definition: msp_msg.hpp:1770
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:849
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:798
Value< uint8_t > multiwii_current_meter_output
Definition: msp_msg.hpp:3366
Value< uint16_t > yaw_lpf_hz
Definition: msp_msg.hpp:2373
Value< uint8_t > raw_quality
Definition: msp_msg.hpp:5281
Value< uint16_t > neg_alt_alarm
Definition: msp_msg.hpp:2202
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:3394
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:4635
SetRcTuning(FirmwareVariant v)
Definition: msp_msg.hpp:4343
Value< uint16_t > roll
Definition: msp_msg.hpp:1740
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:3177
Value< uint8_t > max_waypoints
Definition: msp_msg.hpp:814
MultiType type
Definition: msp_msg.hpp:2596
Value< float > altitude
Definition: msp_msg.hpp:3085
bool unpack(T &val) const
Extracts little endian integers from the ByteVector. Consumes a number of bytes matching sizeof(T)...
Definition: ByteVector.hpp:224
SetCalibrationData(FirmwareVariant v)
Definition: msp_msg.hpp:707
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:3539
Value< uint16_t > avg_system_load_pct
Definition: msp_msg.hpp:5179
Value< uint8_t > gps_provider
Definition: msp_msg.hpp:3363
Value< float > lat
Definition: msp_msg.hpp:4293
std::array< Value< float >, 3 > gyro
Definition: msp_msg.hpp:2868
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:2512
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:2354
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:3306
Value< uint32_t > arming_flags
Definition: msp_msg.hpp:5181
Value< float > hdop
Definition: msp_msg.hpp:2991
Value< uint8_t > flags
Definition: msp_msg.hpp:2028
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4043
WpGetInfo(FirmwareVariant v)
Definition: msp_msg.hpp:809
Value< uint16_t > min
Definition: msp_msg.hpp:3558
Value< uint8_t > use_thr_mid_for_althold
Definition: msp_msg.hpp:629
Value< uint8_t > gps_ubx_sbas
Definition: msp_msg.hpp:3365
Value< uint8_t > addr
Definition: msp_msg.hpp:2234
bool hasMagnetometer() const
Definition: msp_msg.hpp:2780
static const size_t LED_SPECIAL_COLOR_COUNT
Definition: msp_msg.hpp:317
Value< uint8_t > state
Definition: msp_msg.hpp:2029
static const size_t OSD_ITEM_COUNT
Definition: msp_msg.hpp:311
virtual std::ostream & print(std::ostream &s) const override
Definition: msp_msg.hpp:3827
Value< float > voltage
Definition: msp_msg.hpp:3772
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:1552
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:818
Value< uint16_t > eph
Definition: msp_msg.hpp:4107
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:3958
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:3090
Motor3dConfig(FirmwareVariant v)
Definition: msp_msg.hpp:3681
Value< uint32_t > capacity_critical
Definition: msp_msg.hpp:5412
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:2253
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:1627
bool unpack_from(const ByteVector &data)
Definition: msp_msg.hpp:3203
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:1614
Value< uint16_t > rollPitchItermIgnoreRate
Definition: msp_msg.hpp:2435
SetFilterConfig(FirmwareVariant v)
Definition: msp_msg.hpp:2412
std::vector< std::string > pid_names
Definition: msp_msg.hpp:3480
static const size_t LED_CONFIGURABLE_COLOR_COUNT
Definition: msp_msg.hpp:305
Value< uint8_t > wp_no
Definition: msp_msg.hpp:3510
virtual bool decode(const ByteVector &) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:1874
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:1156
virtual std::ostream & print(std::ostream &s) const override
Definition: msp_msg.hpp:1288
Value< uint16_t > neutral_3d
Definition: msp_msg.hpp:4570
SetAdvancedConfig(FirmwareVariant v)
Definition: msp_msg.hpp:2350
Value< std::string > identifier
Definition: msp_msg.hpp:436
Value< uint16_t > max_manual_climb_rate
Definition: msp_msg.hpp:627
Value< float > altitude
Definition: msp_msg.hpp:2987
Value< uint8_t > auto_baud
Definition: msp_msg.hpp:3920
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:2952
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:3743
bool hasBind() const
Definition: msp_msg.hpp:2621
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:1718
Value< uint16_t > read_size
Definition: msp_msg.hpp:1845
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:4450
Ident(FirmwareVariant v)
Definition: msp_msg.hpp:2591
Value< uint8_t > range_index
Definition: msp_msg.hpp:1493
Value< uint8_t > imu_small_angle
Definition: msp_msg.hpp:1647
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:3928
Value< uint8_t > sbas_mode
Definition: msp_msg.hpp:3918
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:5376
std::array< uint16_t, N_SERVO > servo
Definition: msp_msg.hpp:2906
SetFailsafeConfig(FirmwareVariant v)
Definition: msp_msg.hpp:1952
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:930
SetTransponderConfig(FirmwareVariant v)
Definition: msp_msg.hpp:2132
Value< uint8_t > deltaMethod
Definition: msp_msg.hpp:2438
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:4954
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:847
StatusEx(FirmwareVariant v)
Definition: msp_msg.hpp:3981
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:1024
Value< uint8_t > peripheralBaudrateIndx
Definition: msp_msg.hpp:1517
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4387
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:3027
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:2477
virtual bool pack_into(ByteVector &data) const
Definition: msp_msg.hpp:2707
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4670
static const size_t N_MOTOR
Definition: msp_msg.hpp:294
Value< uint16_t > frequency
Definition: msp_msg.hpp:2287
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4612
Value< float > yaw
Definition: msp_msg.hpp:5114
Rc(FirmwareVariant v)
Definition: msp_msg.hpp:2950
Value< uint8_t > heading_hold_error_lpf_freq
Definition: msp_msg.hpp:542
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:1496
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:4298
SetCfSerialConfig(FirmwareVariant v)
Definition: msp_msg.hpp:1546
Value< uint8_t > acc_soft_lpf_hz
Definition: msp_msg.hpp:545
std::array< uint16_t, N_MOTOR > motor
Definition: msp_msg.hpp:4543
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:1074
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:615
Value< uint16_t > batteryCapacity
Definition: msp_msg.hpp:950
Value< uint8_t > hw_optical_flow_status
Definition: msp_msg.hpp:4022
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:5513
SetBeeperConfig(FirmwareVariant v)
Definition: msp_msg.hpp:4210
Misc(FirmwareVariant v)
Definition: msp_msg.hpp:3392
std::set< Capability > capabilities
Definition: msp_msg.hpp:2598
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:1671
Value< uint8_t > stabilized_rc_yaw_expo
Definition: msp_msg.hpp:5469
Value< uint8_t > provider
Definition: msp_msg.hpp:2107
Value< uint32_t > capacity_warning
Definition: msp_msg.hpp:5335
std::ostream & print(std::ostream &s) const
Definition: msp_msg.hpp:3372
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:3289
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:479
bool hasSonar() const
Definition: msp_msg.hpp:5227
Value< uint32_t > lon
Definition: msp_msg.hpp:3512
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:2057
Value< uint16_t > loop_time
Definition: msp_msg.hpp:1883
std::vector< MotorMixer > mixer
Definition: msp_msg.hpp:5141
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4100
Value< uint8_t > osd_support
Definition: msp_msg.hpp:483
Value< uint16_t > min_command
Definition: msp_msg.hpp:3899
Reserve2(FirmwareVariant v)
Definition: msp_msg.hpp:4899
InavMisc(FirmwareVariant v)
Definition: msp_msg.hpp:5342
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:1872
Value< float > vario
Definition: msp_msg.hpp:3086
Value< uint8_t > action
Definition: msp_msg.hpp:4440
virtual bool decode(const ByteVector &) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:4130
VoltageMeters(FirmwareVariant v)
Definition: msp_msg.hpp:3776
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:598
DataflashRead(FirmwareVariant v)
Definition: msp_msg.hpp:1840
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:5139
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:5004
Value< uint8_t > gps_provider
Definition: msp_msg.hpp:5325
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:5279
Value< uint8_t > max_bank_angle
Definition: msp_msg.hpp:628
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:4493
Value< uint8_t > acc_calibration_axis_flags
Definition: msp_msg.hpp:3991
Value< float > throttle
Definition: msp_msg.hpp:5111
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4856
TxInfo(FirmwareVariant v)
Definition: msp_msg.hpp:4245
SetRawGPS(FirmwareVariant v)
Definition: msp_msg.hpp:4287
Value< std::string > name
Definition: msp_msg.hpp:600
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:1807
InavBatteryConfig(FirmwareVariant v)
Definition: msp_msg.hpp:5418
Value< uint8_t > spektrum_sat_bind
Definition: msp_msg.hpp:1205
Value< uint32_t > capacity
Definition: msp_msg.hpp:5334
Value< uint16_t > alt_alarm
Definition: msp_msg.hpp:2162
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:1004
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:711
Value< uint8_t > stabilized_rate_p
Definition: msp_msg.hpp:5471
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:2536
SetAdjustmentRange(FirmwareVariant v)
Definition: msp_msg.hpp:1489
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:1100
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4921
Value< uint32_t > axisAccelerationLimitRollPitch
Definition: msp_msg.hpp:2445
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:1174
std::vector< uint16_t > channels
Definition: msp_msg.hpp:2954
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:2593
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:3568
CommonSetTz(FirmwareVariant v)
Definition: msp_msg.hpp:4962
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:4830
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:2560
MotorConfig(FirmwareVariant v)
Definition: msp_msg.hpp:3903
Value< uint8_t > auxChannelIndex
Definition: msp_msg.hpp:1458
CompGPS(FirmwareVariant v)
Definition: msp_msg.hpp:3025
std::set< Sensor > sensors
Definition: msp_msg.hpp:2673
Value< uint8_t > hw_acc_status
Definition: msp_msg.hpp:4016
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:928
Value< uint16_t > yaw_jump_prevention_limit
Definition: msp_msg.hpp:543
int16_t target_bearing
Definition: msp_msg.hpp:3595
Value< uint8_t > src_profile_idx
Definition: msp_msg.hpp:4176
Value< uint16_t > body_rate_x
Definition: msp_msg.hpp:5284
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:1885
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:3055
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:1379
Value< uint32_t > config
Definition: msp_msg.hpp:1416
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4727
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:2328
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:408
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:1859
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:1449
Motor(FirmwareVariant v)
Definition: msp_msg.hpp:2926
Value< uint16_t > staytime
Definition: msp_msg.hpp:3515
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:3452
Value< uint8_t > mixer_mode
Definition: msp_msg.hpp:1737
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:4235
Value< uint8_t > gps_baudrate
Definition: msp_msg.hpp:3364
Value< uint8_t > id
Definition: msp_msg.hpp:994
OsdConfig(FirmwareVariant v)
Definition: msp_msg.hpp:2152
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4950
Value< uint16_t > item_pos
Definition: msp_msg.hpp:2194
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:2414
Value< uint16_t > voltage_scale
Definition: msp_msg.hpp:5330
bool unpack_from(const ByteVector &data)
Definition: msp_msg.hpp:2677
Value< uint8_t > delay
Definition: msp_msg.hpp:1907
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:3061
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:3778
Value< uint8_t > endStep
Definition: msp_msg.hpp:997
BuildInfo(FirmwareVariant v)
Definition: msp_msg.hpp:512
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:766
Value< float > ground_course
Definition: msp_msg.hpp:2989
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:1631
Value< uint32_t > speed
Definition: msp_msg.hpp:5545
Value< uint8_t > reserved
Definition: msp_msg.hpp:3368
InavPid(FirmwareVariant v)
Definition: msp_msg.hpp:550
Mixer(FirmwareVariant v)
Definition: msp_msg.hpp:1172
Rtc(FirmwareVariant v)
Definition: msp_msg.hpp:4871
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:1988
Value< uint8_t > max_climb_angle
Definition: msp_msg.hpp:898
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:2082
Value< uint8_t > gyro_soft_lpf_hz
Definition: msp_msg.hpp:2371
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:1772
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:1548
Value< uint8_t > throttle_mid
Definition: msp_msg.hpp:3152
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:2285
Value< uint16_t > dterm_soft_notch_hz
Definition: msp_msg.hpp:2376
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:3033
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:1445
std::set< std::string > features
Definition: msp_msg.hpp:1048
Value< uint16_t > time_alarm
Definition: msp_msg.hpp:2161
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:3396
Value< uint16_t > mAh_drawn
Definition: msp_msg.hpp:5305
Value< uint8_t > disarm_kill_switch
Definition: msp_msg.hpp:1645
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:3588
Value< uint16_t > middle
Definition: msp_msg.hpp:4511
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:1115
Value< uint8_t > battery_voltage
Definition: msp_msg.hpp:5304
Value< uint16_t > deadband3d_high
Definition: msp_msg.hpp:3686
Value< uint16_t > heading
Definition: msp_msg.hpp:3514
Value< float > voltage
Definition: msp_msg.hpp:3846
Value< uint8_t > video_system
Definition: msp_msg.hpp:2157
Value< uint16_t > min_command
Definition: msp_msg.hpp:3361
Value< float > amperage
Definition: msp_msg.hpp:3805
SetRcDeadband(FirmwareVariant v)
Definition: msp_msg.hpp:4585
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:4347
bool hasSonar() const
Definition: msp_msg.hpp:2784
Value< uint8_t > protocol
Definition: msp_msg.hpp:410
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:438
Value< uint8_t > s
Definition: msp_msg.hpp:1334
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:1894
SetMixer(FirmwareVariant v)
Definition: msp_msg.hpp:1185
Value< uint8_t > mode_activation_condition_idx
Definition: msp_msg.hpp:1026
std::vector< CfSerialConfigSettings > configs
Definition: msp_msg.hpp:1526
Value< float > pitch
Definition: msp_msg.hpp:3058
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:4803
AccCalibration(FirmwareVariant v)
Definition: msp_msg.hpp:4385
Value< uint16_t > loop_time
Definition: msp_msg.hpp:1896
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4942
bool hasOpticalFlow() const
Definition: msp_msg.hpp:2786
Value< uint16_t > cruise_throttle
Definition: msp_msg.hpp:894
Value< uint8_t > device_type
Definition: msp_msg.hpp:2255
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:1752
Value< std::string > setting_name
Definition: msp_msg.hpp:5076
CommonSetMotorMixer(FirmwareVariant v)
Definition: msp_msg.hpp:5156
Value< uint8_t > hw_baro_status
Definition: msp_msg.hpp:4018
Value< uint16_t > hover_throttle
Definition: msp_msg.hpp:630
Value< uint8_t > esc_mode
Definition: msp_msg.hpp:4825
Value< uint8_t > setpointRelaxRatio
Definition: msp_msg.hpp:2440
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:2061
Value< uint16_t > min_throttle
Definition: msp_msg.hpp:895
DATA_TYPE expected_data_type
Definition: msp_msg.hpp:5002
bool hasPitot() const
Definition: msp_msg.hpp:5231
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:5420
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:977
NavStatus(FirmwareVariant v)
Definition: msp_msg.hpp:3586
Value< uint8_t > throttle_dyn_pid
Definition: msp_msg.hpp:5465
Value< uint8_t > rtc_date_time_status
Definition: msp_msg.hpp:4250
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:762
Value< uint16_t > arming_flags
Definition: msp_msg.hpp:3990
Value< uint8_t > col
Definition: msp_msg.hpp:4148
bool set_freq(uint8_t band, uint8_t channel)
Definition: msp_msg.hpp:2291
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:1898
ActiveBoxes(FirmwareVariant v)
Definition: msp_msg.hpp:3304
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:873
Value< std::string > setting_name
Definition: msp_msg.hpp:4993
Value< uint8_t > procedure
Definition: msp_msg.hpp:1912
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:2534
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:2154
SetLedColors(FirmwareVariant v)
Definition: msp_msg.hpp:1373
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:5012
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:1992
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:1849
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4012
Value< uint16_t > millis
Definition: msp_msg.hpp:4848
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:3983
Value< uint8_t > recovery_delay
Definition: msp_msg.hpp:1913
Value< uint16_t > motor_pwm_rate
Definition: msp_msg.hpp:2316
SetModeRange(FirmwareVariant v)
Definition: msp_msg.hpp:1022
Value< uint8_t > id
Definition: msp_msg.hpp:3803
SwitchPosition
Definition: msp_msg.hpp:357
Value< uint16_t > gyro_soft_notch_hz_1
Definition: msp_msg.hpp:2374
Value< uint8_t > max_bank_angle
Definition: msp_msg.hpp:897
Value< std::string > str
Definition: msp_msg.hpp:4149
Value< int16_t > int16_val
Definition: msp_msg.hpp:5080
bool isHealthy() const
Definition: msp_msg.hpp:5233
Value< uint8_t > units
Definition: msp_msg.hpp:2158
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:2832
Value< uint16_t > mincheck
Definition: msp_msg.hpp:1204
SonarAltitude(FirmwareVariant v)
Definition: msp_msg.hpp:1612
Value< uint8_t > kill_switch
Definition: msp_msg.hpp:1910
uint8_t land_speed
Definition: msp_msg.hpp:3632
Value< uint8_t > last_error
Definition: msp_msg.hpp:2030
Value< uint8_t > use_unsynced_pwm
Definition: msp_msg.hpp:2314
virtual std::ostream & print(std::ostream &s) const override
Definition: msp_msg.hpp:442
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:3731
Value< uint16_t > cycle_time
Definition: msp_msg.hpp:2671
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:800
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:1432
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:1640
std::vector< Value< ServoMixRule > > rules
Definition: msp_msg.hpp:4778
Value< uint16_t > max_auto_speed
Definition: msp_msg.hpp:624
Value< uint8_t > pitch_to_throttle
Definition: msp_msg.hpp:900
Value< uint8_t > comms_capabilites
Definition: msp_msg.hpp:484
ID
Definition: msp_msg.hpp:30
bool unpack_from(const ByteVector &data)
Definition: msp_msg.hpp:5116
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:1436
ServoConf(FirmwareVariant v)
Definition: msp_msg.hpp:3566
Value< uint8_t > osd_flags
Definition: msp_msg.hpp:2156
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:4912
std::array< Value< int16_t >, 3 > mag
Definition: msp_msg.hpp:2836
AdvancedConfig(FirmwareVariant v)
Definition: msp_msg.hpp:2326
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:910
NavPosHold(FirmwareVariant v)
Definition: msp_msg.hpp:635
bool hasAccelerometer() const
Definition: msp_msg.hpp:2774
Value< float > speed
Definition: msp_msg.hpp:4296
SetPositionEstimationConfig(FirmwareVariant v)
Definition: msp_msg.hpp:760
Value< uint16_t > fw_roll_angle
Definition: msp_msg.hpp:1914
uint8_t takeover_baro
Definition: msp_msg.hpp:3621
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:1413
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4587
Value< uint8_t > rth_climb_ignore_emerg
Definition: msp_msg.hpp:831
Value< uint32_t > beeper_off_mask
Definition: msp_msg.hpp:4190
static const size_t LED_MAX_STRIP_LENGTH
Definition: msp_msg.hpp:306
Value< uint16_t > debug3
Definition: msp_msg.hpp:4925
Value< float > baro_altitude
Definition: msp_msg.hpp:3088
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:514
Value< std::string > shortGitRevision
Definition: msp_msg.hpp:518
Value< uint8_t > min_distance_procedure
Definition: msp_msg.hpp:1919
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:3815
Value< uint8_t > channel
Definition: msp_msg.hpp:2011
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:4478
std::array< uint8_t, LED_SPECIAL_COLOR_COUNT > special_colors
Definition: msp_msg.hpp:3747
PidNames(FirmwareVariant v)
Definition: msp_msg.hpp:3476
bool pack(const T &val)
Packs integer types into the ByteVector. Ensures little endian packing.
Definition: ByteVector.hpp:51
RcTuning(FirmwareVariant v)
Definition: msp_msg.hpp:3173
Value< uint8_t > pid_process_denom
Definition: msp_msg.hpp:2313
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:1581
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:2134
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:2758
bool hasDynBal() const
Definition: msp_msg.hpp:2623
Value< uint8_t > rx_spi_protocol
Definition: msp_msg.hpp:1214
virtual std::ostream & print(std::ostream &s) const override
Definition: msp_msg.hpp:3548
Value< uint8_t > rangefinder_hardware
Definition: msp_msg.hpp:2504
Value< std::string > string_val
Definition: msp_msg.hpp:5000
Value< uint16_t > p1
Definition: msp_msg.hpp:4445
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:2352
RxMap(FirmwareVariant v)
Definition: msp_msg.hpp:1696
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:2167
Value< uint32_t > altHold
Definition: msp_msg.hpp:3513
LedStripConfigs(FirmwareVariant v)
Definition: msp_msg.hpp:1394
ArmingFlags
Definition: msp_msg.hpp:223
std::vector< CfSerialConfigSettings > configs
Definition: msp_msg.hpp:1550
bool pack_into(ByteVector &data) const
Definition: msp_msg.hpp:5125
Value< uint16_t > pitch
Definition: msp_msg.hpp:4701
Value< uint8_t > mission_action
Definition: msp_msg.hpp:3592
SetInavPid(FirmwareVariant v)
Definition: msp_msg.hpp:572
Value< uint16_t > functionMask
Definition: msp_msg.hpp:1513
Value< uint16_t > airModeActivateThreshold
Definition: msp_msg.hpp:1212
Value< uint8_t > rx_spi_rf_channel_count
Definition: msp_msg.hpp:1216
Value< float > ground_speed
Definition: msp_msg.hpp:2988
Value< uint8_t > serialrx_provider
Definition: msp_msg.hpp:1739
virtual std::ostream & print(std::ostream &s) const override
Definition: msp_msg.hpp:1709
Value< uint32_t > capacity_critical
Definition: msp_msg.hpp:5336
CurrentMeters(FirmwareVariant v)
Definition: msp_msg.hpp:3809
bool has(const Capability &cap) const
Definition: msp_msg.hpp:2619
InavAirSpeed(FirmwareVariant v)
Definition: msp_msg.hpp:5541
MotorPins(FirmwareVariant v)
Definition: msp_msg.hpp:3421
Value< uint16_t > i2c_errors
Definition: msp_msg.hpp:2672
uint8_t wait_for_rth_alt
Definition: msp_msg.hpp:3618
SensorStatus(FirmwareVariant v)
Definition: msp_msg.hpp:4010
Value< float > powerMeterSum
Definition: msp_msg.hpp:3122
Value< uint16_t > acc_gain_z
Definition: msp_msg.hpp:681
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:1596
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:5485
Value< float > voltage_scale
Definition: msp_msg.hpp:3370
Value< uint8_t > rcInterpolation
Definition: msp_msg.hpp:1210
Value< uint16_t > acc_gain_x
Definition: msp_msg.hpp:679
BlackboxConfig(FirmwareVariant v)
Definition: msp_msg.hpp:2055
OsdCharWrite(FirmwareVariant v)
Definition: msp_msg.hpp:2230
RawImu(FirmwareVariant v)
Definition: msp_msg.hpp:2830
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:5309
std::vector< uint16_t > channels
Definition: msp_msg.hpp:4272
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:4252
virtual std::ostream & print(std::ostream &s) const override
Definition: msp_msg.hpp:2792
std::ostream & print(std::ostream &s) const
Definition: msp_msg.hpp:3225
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:5177
Value< uint32_t > uint32_val
Definition: msp_msg.hpp:4998
BatteryState(FirmwareVariant v)
Definition: msp_msg.hpp:3840
Value< uint8_t > reserved
Definition: msp_msg.hpp:3749
InavSetMisc(FirmwareVariant v)
Definition: msp_msg.hpp:5372
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4689
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:2454
uint16_t nav_bank_max
Definition: msp_msg.hpp:3630
std::array< uint16_t, OSD_ITEM_COUNT > item_pos
Definition: msp_msg.hpp:2165
Value< uint16_t > frequency
Definition: msp_msg.hpp:2261
SetBox(FirmwareVariant v)
Definition: msp_msg.hpp:4335
Value< uint32_t > free_space_kb
Definition: msp_msg.hpp:2031
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:3689
Value< uint32_t > u_id_1
Definition: msp_msg.hpp:4046
RthAndLandConfig(FirmwareVariant v)
Definition: msp_msg.hpp:845
SetPidAdvanced(FirmwareVariant v)
Definition: msp_msg.hpp:2475
Value< uint8_t > power
Definition: msp_msg.hpp:2288
Value< uint16_t > max_auto_climb_rate
Definition: msp_msg.hpp:625
FirmwareVariant
Enum of firmware variants.
Value< uint8_t > hw_gyro_status
Definition: msp_msg.hpp:4015
PidAdvanced(FirmwareVariant v)
Definition: msp_msg.hpp:2452
Value< uint8_t > hw_gps_status
Definition: msp_msg.hpp:4019
bool consume(std::size_t count) const
Manually consumes data, thus skipping the values.
Definition: ByteVector.hpp:436
CompassConfig(FirmwareVariant v)
Definition: msp_msg.hpp:3939
Attitude(FirmwareVariant v)
Definition: msp_msg.hpp:3053
Value< uint16_t > mAh_drawn
Definition: msp_msg.hpp:3847
Value< uint16_t > deadband3d_low
Definition: msp_msg.hpp:4568
Value< uint16_t > directionToHome
Definition: msp_msg.hpp:3030
SetCompassConfig(FirmwareVariant v)
Definition: msp_msg.hpp:4687
InavSetRateProfile(FirmwareVariant v)
Definition: msp_msg.hpp:5511
Value< uint16_t > attitude_task_frequency
Definition: msp_msg.hpp:540
DataflashSummary(FirmwareVariant v)
Definition: msp_msg.hpp:1818
SetBoardAlignment(FirmwareVariant v)
Definition: msp_msg.hpp:1113
Value< uint16_t > debug1
Definition: msp_msg.hpp:4923
Value< uint16_t > uint16_val
Definition: msp_msg.hpp:4996
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:3811
SetMotor3dConf(FirmwareVariant v)
Definition: msp_msg.hpp:4564
SetPid(FirmwareVariant v)
Definition: msp_msg.hpp:4315
Value< uint16_t > altitude
Definition: msp_msg.hpp:4295
Displayport(FirmwareVariant v)
Definition: msp_msg.hpp:4142
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:2191
Value< int16_t > int16_val
Definition: msp_msg.hpp:4997
Value< uint16_t > gyro_soft_notch_cutoff_2
Definition: msp_msg.hpp:2379
CommonMotorMixer(FirmwareVariant v)
Definition: msp_msg.hpp:5137
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:3963
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:2013
std::array< HsvColor, LED_CONFIGURABLE_COLOR_COUNT > colors
Definition: msp_msg.hpp:1360
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:4151
bool hasMagnetometer() const
Definition: msp_msg.hpp:5223
Value< uint16_t > alt_alarm
Definition: msp_msg.hpp:2200
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:3083
bool hasGPS() const
Definition: msp_msg.hpp:2782
Value< std::string > buildDate
Definition: msp_msg.hpp:516
CameraControl(FirmwareVariant v)
Definition: msp_msg.hpp:2554
Value< uint16_t > p3
Definition: msp_msg.hpp:4447
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4823
Value< uint8_t > baro_hardware
Definition: msp_msg.hpp:2500
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:5346
SetFwConfig(FirmwareVariant v)
Definition: msp_msg.hpp:926
ImuSI(RawImu raw, const float acc_1g, const float gyro_unit, const float magn_gain, const float si_unit_1g)
Definition: msp_msg.hpp:2871
Servo(FirmwareVariant v)
Definition: msp_msg.hpp:2902
Value< uint16_t > min_command
Definition: msp_msg.hpp:5323
Value< uint8_t > power_idx
Definition: msp_msg.hpp:2258
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:3478
Value< uint16_t > current_meter_scale
Definition: msp_msg.hpp:1743
Value< std::string > buildTime
Definition: msp_msg.hpp:517
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:574
bool hasBarometer() const
Definition: msp_msg.hpp:2778
virtual std::ostream & print(std::ostream &s) const override
Definition: msp_msg.hpp:3010
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4887
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:2763
CommonSetting(FirmwareVariant v)
Definition: msp_msg.hpp:4989
uint8_t lead_filter
Definition: msp_msg.hpp:3611
Value< uint32_t > read_address
Definition: msp_msg.hpp:1844
Value< uint32_t > sectors
Definition: msp_msg.hpp:1823
Value< uint16_t > deadband3d_throttle
Definition: msp_msg.hpp:3702
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:2993
Value< uint16_t > mid_rc
Definition: msp_msg.hpp:5320
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:3423
Value< uint16_t > yawItermIgnoreRate
Definition: msp_msg.hpp:2436
SetFeature(FirmwareVariant v)
Definition: msp_msg.hpp:1072
static const size_t N_SERVO
Definition: msp_msg.hpp:293
Value< uint8_t > rcInterpolationInterval
Definition: msp_msg.hpp:1211
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:961
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:4841
Value< uint16_t > middle
Definition: msp_msg.hpp:3560
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:1046
Value< uint32_t > secs
Definition: msp_msg.hpp:4847
Value< uint16_t > version
Definition: msp_msg.hpp:482
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:959
Value< uint16_t > acc_gain_y
Definition: msp_msg.hpp:680
Value< uint16_t > rpm
Definition: msp_msg.hpp:3952
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:2956
Value< uint32_t > lat
Definition: msp_msg.hpp:3511
Value< uint8_t > receiverType
Definition: msp_msg.hpp:1220
std::ostream & print(std::ostream &s) const
Definition: msp_msg.hpp:2888
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4289
std::array< Value< float >, 3 > mag
Definition: msp_msg.hpp:2869
Value< uint8_t > dterm_filter_type
Definition: msp_msg.hpp:2381
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:2034
GpsStatistics(FirmwareVariant v)
Definition: msp_msg.hpp:4098
Value< uint8_t > minor
Definition: msp_msg.hpp:412
std::unique_ptr< ByteVector > ByteVectorUptr
Definition: ByteVector.hpp:465
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:3535
BoxIds(FirmwareVariant v)
Definition: msp_msg.hpp:3533
SetLedStripConfig(FirmwareVariant v)
Definition: msp_msg.hpp:1411
CommonSetSetting(FirmwareVariant v)
Definition: msp_msg.hpp:5072
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:2263
bool hasGPS() const
Definition: msp_msg.hpp:5225
Value< uint16_t > gyro_soft_notch_hz_2
Definition: msp_msg.hpp:2378
Value< uint16_t > max_throttle
Definition: msp_msg.hpp:3360
GpsConfig(FirmwareVariant v)
Definition: msp_msg.hpp:3924
Value< uint16_t > dist_alarm
Definition: msp_msg.hpp:2163
std::array< adjustmentRange, MAX_ADJUSTMENT_RANGE_COUNT > ranges
Definition: msp_msg.hpp:1471
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:4076
Value< uint16_t > cell_warning
Definition: msp_msg.hpp:5333
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:692
AccTrim(FirmwareVariant v)
Definition: msp_msg.hpp:4725
Value< uint8_t > stabilized_rate_r
Definition: msp_msg.hpp:5470
Value< uint16_t > min_throttle
Definition: msp_msg.hpp:3359
Value< uint16_t > acc_zero_z
Definition: msp_msg.hpp:678
SelectSetting(FirmwareVariant v)
Definition: msp_msg.hpp:4472
Value< uint8_t > wp_no
Definition: msp_msg.hpp:4439
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:1362
Value< uint32_t > reserved2
Definition: msp_msg.hpp:1805
BoxNames(FirmwareVariant v)
Definition: msp_msg.hpp:3446
FwConfig(FirmwareVariant v)
Definition: msp_msg.hpp:906
Value< float > amperage
Definition: msp_msg.hpp:3124
std::array< uint8_t, MAX_MAPPABLE_RX_INPUTS > map
Definition: msp_msg.hpp:1683
virtual std::ostream & print(std::ostream &s) const override
Definition: msp_msg.hpp:499
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:1050
Value< uint16_t > dterm_lpf_hz
Definition: msp_msg.hpp:2372
Value< int16_t > yaw
Definition: msp_msg.hpp:3059
Value< uint8_t > throttle_rc_expo
Definition: msp_msg.hpp:5464
Value< uint8_t > rate
Definition: msp_msg.hpp:4512
Value< uint8_t > rssi
Definition: msp_msg.hpp:4233
Value< float > lat
Definition: msp_msg.hpp:2985
Value< uint8_t > acc_hardware
Definition: msp_msg.hpp:2499
Value< uint16_t > p2
Definition: msp_msg.hpp:4446
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:2556
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:459
static const size_t BOARD_IDENTIFIER_LENGTH
Definition: msp_msg.hpp:296
ServoMixRules(FirmwareVariant v)
Definition: msp_msg.hpp:4774
Value< uint32_t > alt
Definition: msp_msg.hpp:4443
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4069
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:1754
Value< uint8_t > vbatPidCompensation
Definition: msp_msg.hpp:2439
SetBatteryConfig(FirmwareVariant v)
Definition: msp_msg.hpp:975
FcVersion(FirmwareVariant v)
Definition: msp_msg.hpp:451
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:4214
Value< uint8_t > patch_level
Definition: msp_msg.hpp:457
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4437
Value< uint8_t > yaw_deadband
Definition: msp_msg.hpp:3700
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4212
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:611
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:3119
Value< uint8_t > major
Definition: msp_msg.hpp:411
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:1820
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:3683
Value< uint8_t > heading_hold_rate_limit
Definition: msp_msg.hpp:541
Value< uint8_t > rssi_channel
Definition: msp_msg.hpp:3367
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:3907
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:639
Value< uint16_t > mid_rc
Definition: msp_msg.hpp:3358
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:659
Value< uint8_t > band
Definition: msp_msg.hpp:2256
std::vector< std::string > box_names
Definition: msp_msg.hpp:3450
ModeRanges(FirmwareVariant v)
Definition: msp_msg.hpp:1002
Value< int8_t > int8_val
Definition: msp_msg.hpp:5078
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4605
bool pack_into(ByteVector &data) const
Definition: msp_msg.hpp:3211
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:2110
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:1396
Value< uint8_t > wp_count
Definition: msp_msg.hpp:816
WriteEEPROM(FirmwareVariant v)
Definition: msp_msg.hpp:4885
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:2204
Value< uint32_t > u_id_2
Definition: msp_msg.hpp:4047
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:3708
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:2416
Value< uint8_t > axis_calibration_flags
Definition: msp_msg.hpp:690
BfConfig(FirmwareVariant v)
Definition: msp_msg.hpp:1750
virtual std::ostream & print(std::ostream &s) const override
Definition: msp_msg.hpp:3433
Value< uint8_t > gpsBaudrateIndx
Definition: msp_msg.hpp:1515
virtual std::ostream & print(std::ostream &s) const override
Definition: msp_msg.hpp:2914
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:1774
Value< uint8_t > led_aux_channel
Definition: msp_msg.hpp:3748
Value< uint8_t > NAV_error
Definition: msp_msg.hpp:3594
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4345
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:576
Value< uint16_t > tz_offset
Definition: msp_msg.hpp:4952
virtual std::ostream & print(std::ostream &s) const override
Definition: msp_msg.hpp:2852
Value< float > vbat
Definition: msp_msg.hpp:3121
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:1956
SetMotorConfig(FirmwareVariant v)
Definition: msp_msg.hpp:4650
CfSerialConfig(FirmwareVariant v)
Definition: msp_msg.hpp:1522
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4815
virtual std::ostream & print(std::ostream &s) const override
Definition: msp_msg.hpp:3465
Value< uint8_t > rth_allow_landing
Definition: msp_msg.hpp:833
bool isHealthy() const
Definition: msp_msg.hpp:2790
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:1579
bool pack_into(ByteVector &data) const
Definition: msp_msg.hpp:1345
Value< uint16_t > cell_min
Definition: msp_msg.hpp:5331
std::set< std::string > features
Definition: msp_msg.hpp:1076
Value< uint8_t > hardware_healthy
Definition: msp_msg.hpp:4014
static const size_t LED_DIRECTION_COUNT
Definition: msp_msg.hpp:316
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:5543
Value< uint16_t > midrc
Definition: msp_msg.hpp:1203
SensorAlignment(FirmwareVariant v)
Definition: msp_msg.hpp:3727
uint8_t crosstrack_gain
Definition: msp_msg.hpp:3629
Value< uint16_t > dterm_soft_notch_cutoff
Definition: msp_msg.hpp:2377
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:1794
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:3993
Value< uint16_t > pitch
Definition: msp_msg.hpp:1741
SetRxConfig(FirmwareVariant v)
Definition: msp_msg.hpp:1295
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:1299
Value< float > float_val
Definition: msp_msg.hpp:4999
static const size_t MAX_SIMULTANEOUS_ADJUSTMENT_COUNT
Definition: msp_msg.hpp:309
Value< float > lon
Definition: msp_msg.hpp:2986
Value< uint16_t > avg_system_load_pct
Definition: msp_msg.hpp:2760
std::array< Value< int16_t >, 3 > gyro
Definition: msp_msg.hpp:2835
Pid(FirmwareVariant v)
Definition: msp_msg.hpp:3287
static const std::vector< std::string > FEATURES
Definition: msp_msg.hpp:363
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4128
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:1358
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:1618
Value< uint8_t > rssi_source
Definition: msp_msg.hpp:4249
uint8_t ignore_throttle
Definition: msp_msg.hpp:3620
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:602
static const size_t BUILD_DATE_LENGTH
Definition: msp_msg.hpp:298
Value< uint16_t > time_alarm
Definition: msp_msg.hpp:2199
BoardName(FirmwareVariant v)
Definition: msp_msg.hpp:596
BatteryConfig(FirmwareVariant v)
Definition: msp_msg.hpp:957
SetMisc(FirmwareVariant v)
Definition: msp_msg.hpp:4399
Value< uint8_t > provider
Definition: msp_msg.hpp:3917
V2Frame(FirmwareVariant v)
Definition: msp_msg.hpp:4940
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:2456
static const size_t LED_MODE_COUNT
Definition: msp_msg.hpp:315
bool hasFlap() const
Definition: msp_msg.hpp:2625
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:5444
PidController(FirmwareVariant v)
Definition: msp_msg.hpp:1625
LoopTime(FirmwareVariant v)
Definition: msp_msg.hpp:1879
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:414
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:4589
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:1524
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:3941
static const size_t MAX_MAPPABLE_RX_INPUTS
Definition: msp_msg.hpp:313
Value< uint16_t > gyro_soft_notch_cutoff_1
Definition: msp_msg.hpp:2375
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4541
SetAccTrim(FirmwareVariant v)
Definition: msp_msg.hpp:4708
std::vector< CurrentMeter > meters
Definition: msp_msg.hpp:3813
Value< uint8_t > numSat
Definition: msp_msg.hpp:2984
virtual std::ostream & print(std::ostream &s) const override
Definition: msp_msg.hpp:2938
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:1720
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:3646
Value< uint16_t > throttle_pa_breakpoint
Definition: msp_msg.hpp:5466
Value< uint8_t > auto_disarm_delay
Definition: msp_msg.hpp:1644
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:1700
Value< uint32_t > lon
Definition: msp_msg.hpp:4442
bool hasAccelerometer() const
Definition: msp_msg.hpp:5217
virtual std::ostream & print(std::ostream &s) const override
Definition: msp_msg.hpp:3135
Value< uint8_t > pwm_inversion
Definition: msp_msg.hpp:2320
Value< uint16_t > fw_yaw_rate
Definition: msp_msg.hpp:1916
Value< uint8_t > motor_count
Definition: msp_msg.hpp:3960
FilterConfig(FirmwareVariant v)
Definition: msp_msg.hpp:2386
virtual std::ostream & print(std::ostream &s) const override
Definition: msp_msg.hpp:3069
Value< uint32_t > total_space_kb
Definition: msp_msg.hpp:2032
Value< uint32_t > offset
Definition: msp_msg.hpp:1825
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:2576
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:4403
Value< uint16_t > distanceToHome
Definition: msp_msg.hpp:3029
std::array< Value< uint8_t >, 3 > rcExpo
Definition: msp_msg.hpp:3149
Value< std::string > identifier
Definition: msp_msg.hpp:481
Value< uint32_t > lat
Definition: msp_msg.hpp:4441
Value< uint8_t > hw_rangefinder_status
Definition: msp_msg.hpp:4020
Value< uint8_t > fpvCamAngleDegrees
Definition: msp_msg.hpp:1218
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:1656
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:3518
Value< uint8_t > pitot_hardware
Definition: msp_msg.hpp:2503
Value< uint16_t > acc_task_frequency
Definition: msp_msg.hpp:539
uint8_t nav_rth_takeoff_heading
Definition: msp_msg.hpp:3616
Value< uint16_t > amperage
Definition: msp_msg.hpp:3848
RcDeadband(FirmwareVariant v)
Definition: msp_msg.hpp:3706
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:2908
Reboot(FirmwareVariant v)
Definition: msp_msg.hpp:1792
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:3945
virtual std::ostream & print(std::ostream &s) const override
Definition: msp_msg.hpp:2967
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:1141
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:1250
SetNavPosHold(FirmwareVariant v)
Definition: msp_msg.hpp:655
bool hasOpticalFlow() const
Definition: msp_msg.hpp:5229
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:5302
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:3508
VtxConfig(FirmwareVariant v)
Definition: msp_msg.hpp:2251
Value< uint8_t > v
Definition: msp_msg.hpp:1335
Value< uint8_t > major
Definition: msp_msg.hpp:455
Value< uint8_t > vbatmincellvoltage
Definition: msp_msg.hpp:947
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4317
Value< float > mag_declination
Definition: msp_msg.hpp:3369
WpMissionLoad(FirmwareVariant v)
Definition: msp_msg.hpp:783
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:5422
Value< uint16_t > emerg_descent_rate
Definition: msp_msg.hpp:840
SdcardSummary(FirmwareVariant v)
Definition: msp_msg.hpp:2024
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:1469
Value< uint8_t > mode
Definition: msp_msg.hpp:1189
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:520
Value< uint16_t > battery_cap_warn
Definition: msp_msg.hpp:2160
Value< uint8_t > opflow_hardware
Definition: msp_msg.hpp:2505
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:2237
std::array< uint8_t, 54 > font_data
Definition: msp_msg.hpp:2235
std::array< uint16_t, N_MOTOR > motor
Definition: msp_msg.hpp:2930
std::array< Value< int16_t >, 3 > acc
Definition: msp_msg.hpp:2834
LedStripModecolor(FirmwareVariant v)
Definition: msp_msg.hpp:3741
std::array< Value< float >, 3 > acc
Definition: msp_msg.hpp:2867
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4901
SetRthAndLandConfig(FirmwareVariant v)
Definition: msp_msg.hpp:869
Value< uint8_t > throttle_rc_mid
Definition: msp_msg.hpp:5463
SetSensorAlignment(FirmwareVariant v)
Definition: msp_msg.hpp:4610
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:2330
Status(FirmwareVariant v)
Definition: msp_msg.hpp:2756
static const size_t NAUX
Definition: msp_msg.hpp:355
Value< uint8_t > alt_hold_deadband
Definition: msp_msg.hpp:3701
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:744
Value< uint8_t > channel_count
Definition: msp_msg.hpp:4073
InavSetBatteryConfig(FirmwareVariant v)
Definition: msp_msg.hpp:5440
SetLedStripModecolor(FirmwareVariant v)
Definition: msp_msg.hpp:4627
Value< state_t > state
Definition: msp_msg.hpp:3849
SetArmingDisabled(FirmwareVariant v)
Definition: msp_msg.hpp:2569
std::set< size_t > box_mode_flags
Definition: msp_msg.hpp:2674
InavRateProfile(FirmwareVariant v)
Definition: msp_msg.hpp:5483
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:5515
Value< uint8_t > mspBaudrateIndx
Definition: msp_msg.hpp:1514
Value< uint16_t > throttle
Definition: msp_msg.hpp:1909
RssiConfig(FirmwareVariant v)
Definition: msp_msg.hpp:1430
SetServoConf(FirmwareVariant v)
Definition: msp_msg.hpp:4504
ApiVersion(FirmwareVariant v)
Definition: msp_msg.hpp:406
Value< uint16_t > yaw_p_limit
Definition: msp_msg.hpp:2437
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4270
LedColors(FirmwareVariant v)
Definition: msp_msg.hpp:1356
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4247
Value< uint16_t > epv
Definition: msp_msg.hpp:4108
Value< uint8_t > auto_config
Definition: msp_msg.hpp:3919
uint16_t wp_radius
Definition: msp_msg.hpp:3623
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:4614
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:3644
std::array< Value< uint8_t >, 3 > rcRates
Definition: msp_msg.hpp:3148
Value< uint8_t > led_strip_aux_channel
Definition: msp_msg.hpp:3750
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:2479
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:4928
Value< uint16_t > min
Definition: msp_msg.hpp:4509
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:2009
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:2139
std::ostream & rxConfigPrint(std::ostream &s) const
Definition: msp_msg.hpp:1222
PositionEstimationConfig(FirmwareVariant v)
Definition: msp_msg.hpp:738
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4629
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:637
Value< uint32_t > errors
Definition: msp_msg.hpp:4103
CopyProfile(FirmwareVariant v)
Definition: msp_msg.hpp:4170
SetOsdVideoConfig(FirmwareVariant v)
Definition: msp_msg.hpp:4135
Value< uint8_t > voltageMeterSource
Definition: msp_msg.hpp:951
SetLoopTime(FirmwareVariant v)
Definition: msp_msg.hpp:1892
Value< uint8_t > mode
Definition: msp_msg.hpp:1176
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4489
static const size_t BUILD_TIME_LENGTH
Definition: msp_msg.hpp:299
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:5143
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:709
Value< uint16_t > land_slowdown_minalt
Definition: msp_msg.hpp:838
virtual std::ostream & print(std::ostream &s) const override
Definition: msp_msg.hpp:3864
Value< uint8_t > gyro_lpf
Definition: msp_msg.hpp:544
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:2080
Value< uint16_t > min_throttle
Definition: msp_msg.hpp:3897
Value< uint8_t > vbatmaxcellvoltage
Definition: msp_msg.hpp:948
Value< uint8_t > version
Definition: msp_msg.hpp:2595
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:4545
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:4178
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:1926
Value< uint16_t > last_msg_dt
Definition: msp_msg.hpp:4102
FcVariant(FirmwareVariant v)
Definition: msp_msg.hpp:432
Value< uint16_t > flow_rate_x
Definition: msp_msg.hpp:5282
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:3729
Value< uint8_t > fix
Definition: msp_msg.hpp:2983
uint8_t nav_controls_heading
Definition: msp_msg.hpp:3613
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:5442
Value< uint8_t > rate
Definition: msp_msg.hpp:3561
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:787
Value< uint16_t > failsafe_throttle
Definition: msp_msg.hpp:3362
MagCalibration(FirmwareVariant v)
Definition: msp_msg.hpp:4392
Value< uint16_t > max_throttle
Definition: msp_msg.hpp:5322
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:1669
GpsSvInfo(FirmwareVariant v)
Definition: msp_msg.hpp:4067
DebugMessage(FirmwareVariant v)
Definition: msp_msg.hpp:4906
std::ostream & operator<<(std::ostream &s, const msp::msg::ImuSI &val)
Definition: msp_msg.hpp:5555
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4991
bool hasBarometer() const
Definition: msp_msg.hpp:5221
Value< uint32_t > reversed_sources
Definition: msp_msg.hpp:4515
Value< std::string > build_date
Definition: msp_msg.hpp:1803
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:3572
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4137
Value< uint16_t > rssi
Definition: msp_msg.hpp:3123
Value< uint16_t > dist_alarm
Definition: msp_msg.hpp:2201
Value< uint8_t > max_dive_angle
Definition: msp_msg.hpp:899
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:4780
Value< uint16_t > land_descent_rate
Definition: msp_msg.hpp:837
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:5087
Value< uint16_t > rth_altitude
Definition: msp_msg.hpp:836
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:4049
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:3752
virtual std::ostream & print(std::ostream &s) const override
Definition: msp_msg.hpp:5235
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:2600
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:3851
Value< uint8_t > rssi_channel
Definition: msp_msg.hpp:5328
Value< uint8_t > uint8_val
Definition: msp_msg.hpp:5077
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4430
bool unpack_from(const ByteVector &data)
Definition: msp_msg.hpp:4746
Value< uint16_t > acc_zero_x
Definition: msp_msg.hpp:676
static const size_t GIT_SHORT_REVISION_LENGTH
Definition: msp_msg.hpp:300
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:487
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:1842
SetTxInfo(FirmwareVariant v)
Definition: msp_msg.hpp:4229
Value< uint8_t > nav_flag
Definition: msp_msg.hpp:4448
Reserve1(FirmwareVariant v)
Definition: msp_msg.hpp:4892
Value< uint8_t > pit_mode
Definition: msp_msg.hpp:2289
Value< uint16_t > mAh_drawn
Definition: msp_msg.hpp:3804
SetCurrentMeterConfig(FirmwareVariant v)
Definition: msp_msg.hpp:1154
Value< uint16_t > battery_cap_warn
Definition: msp_msg.hpp:2198
SensorConfig(FirmwareVariant v)
Definition: msp_msg.hpp:2510
Value< uint8_t > mag_hardware
Definition: msp_msg.hpp:2501
Value< uint16_t > throttle_low_delay
Definition: msp_msg.hpp:1911
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:4693
Value< uint8_t > rssi_channel
Definition: msp_msg.hpp:1447
uint16_t nav_speed_max
Definition: msp_msg.hpp:3626
std::vector< RxFailChannelSettings > channels
Definition: msp_msg.hpp:1990
std::vector< EscData > esc_data
Definition: msp_msg.hpp:3961
Value< uint8_t > hw_compass_status
Definition: msp_msg.hpp:4017
Value< uint32_t > total_size
Definition: msp_msg.hpp:1824
Value< uint8_t > beacon_tone
Definition: msp_msg.hpp:4191
bool pack_into(ByteVector &data) const
Definition: msp_msg.hpp:4758
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4964
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:3482
FailsafeConfig(FirmwareVariant v)
Definition: msp_msg.hpp:1924
virtual std::ostream & print(std::ostream &s) const override
Definition: msp_msg.hpp:3101
SetOsdConfig(FirmwareVariant v)
Definition: msp_msg.hpp:2189
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:3926
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:5163
uint16_t rth_altitude
Definition: msp_msg.hpp:3631
Value< uint8_t > range_startStep
Definition: msp_msg.hpp:1459
CommonTz(FirmwareVariant v)
Definition: msp_msg.hpp:4948
RawGPS(FirmwareVariant v)
Definition: msp_msg.hpp:2979
uint8_t max_wp_number
Definition: msp_msg.hpp:3635
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:1400
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:434
CalibrationData(FirmwareVariant v)
Definition: msp_msg.hpp:686
virtual std::ostream & print(std::ostream &s) const override
Definition: msp_msg.hpp:5033
Value< uint16_t > min_rth_distance
Definition: msp_msg.hpp:829
Value< uint32_t > uint32_val
Definition: msp_msg.hpp:5081
uint8_t dont_reset_home_at_arm
Definition: msp_msg.hpp:3612
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4231
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4506
Value< uint8_t > stabilized_rate_y
Definition: msp_msg.hpp:5472
std::ostream & printRxMapSettings(std::ostream &s) const
Definition: msp_msg.hpp:1685
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:5344
Value< uint16_t > rssi
Definition: msp_msg.hpp:5306
Value< uint32_t > packet_count
Definition: msp_msg.hpp:4105
virtual std::ostream & print(std::ostream &s) const override
Definition: msp_msg.hpp:3041
ByteVector box_ids
Definition: msp_msg.hpp:3537
Value< uint8_t > profile_type
Definition: msp_msg.hpp:4174
Value< uint8_t > id
Definition: msp_msg.hpp:3771
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4873
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:1178
Value< uint8_t > rth_climb_first
Definition: msp_msg.hpp:830
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:4319
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:688
SetRxFailConfigs(FirmwareVariant v)
Definition: msp_msg.hpp:2007
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:2571
EscSensorData(FirmwareVariant v)
Definition: msp_msg.hpp:3956
Value< uint16_t > deadband3d_high
Definition: msp_msg.hpp:4569
uint8_t nav_tail_first
Definition: msp_msg.hpp:3615
Value< ServoMixRule > rule
Definition: msp_msg.hpp:4801
SetRtc(FirmwareVariant v)
Definition: msp_msg.hpp:4854
virtual std::ostream & print(std::ostream &s) const override
Definition: msp_msg.hpp:1730
Value< uint16_t > current_meter_offset
Definition: msp_msg.hpp:1744
Value< uint32_t > u_id_0
Definition: msp_msg.hpp:4045
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:811
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4710
Value< uint32_t > capacity_warning
Definition: msp_msg.hpp:5411
WpMissionSave(FirmwareVariant v)
Definition: msp_msg.hpp:796
bool set() const
Queries if the data has been set.
Definition: Value.hpp:53
Value< float > mag_declination
Definition: msp_msg.hpp:4691
Value< uint16_t > rth_abort_threshold
Definition: msp_msg.hpp:835
SetVoltageMeterConfig(FirmwareVariant v)
Definition: msp_msg.hpp:1594
Value< uint8_t > stabilized_rc_expo
Definition: msp_msg.hpp:5468
SetBlackboxConfig(FirmwareVariant v)
Definition: msp_msg.hpp:2078
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:4875
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:554
static const size_t MAX_NAME_LENGTH
Definition: msp_msg.hpp:302
Value< uint16_t > mag_declination
Definition: msp_msg.hpp:3943
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:1491
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:740
uint16_t nav_max_altitude
Definition: msp_msg.hpp:3625
virtual std::ostream & print(std::ostream &s) const override
Definition: msp_msg.hpp:528
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:2388
ArmingConfig(FirmwareVariant v)
Definition: msp_msg.hpp:1652
InavOpticalFlow(FirmwareVariant v)
Definition: msp_msg.hpp:5277
Value< uint16_t > amperage
Definition: msp_msg.hpp:5307
Value< std::string > name
Definition: msp_msg.hpp:485
std::vector< uint8_t >::iterator unpacking_iterator()
Gives an iterator to the next element ready for unpacking.
Definition: ByteVector.hpp:418
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4894
Value< uint8_t > startStep
Definition: msp_msg.hpp:996
Value< uint8_t > forward_from_channel
Definition: msp_msg.hpp:4514
Analog(FirmwareVariant v)
Definition: msp_msg.hpp:3117
Value< uint8_t > auxSwitchChannelIndex
Definition: msp_msg.hpp:1462
Value< uint8_t > adjustmentIndex
Definition: msp_msg.hpp:1457
SetServoMixRule(FirmwareVariant v)
Definition: msp_msg.hpp:4797
std::array< Value< uint8_t >, 3 > rates
Definition: msp_msg.hpp:3147
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:5158
Requests (1xx)
Definition: msp_msg.hpp:2590
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4337
Value< uint8_t > async_mode
Definition: msp_msg.hpp:538
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:1928
BeeperConfig(FirmwareVariant v)
Definition: msp_msg.hpp:4196
Value< uint8_t > esc_count
Definition: msp_msg.hpp:4828
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:4024
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:1102
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:2299
Value< uint8_t > key
Definition: msp_msg.hpp:2558
Value< uint8_t > esc_port_index
Definition: msp_msg.hpp:4826
Value< uint16_t > gyro_cycle_time
Definition: msp_msg.hpp:2761
Value< uint8_t > video_system
Definition: msp_msg.hpp:2195
Value< uint16_t > cell_max
Definition: msp_msg.hpp:5332
bool hasPitot() const
Definition: msp_msg.hpp:2788
Value< uint8_t > manual_rc_yaw_expo
Definition: msp_msg.hpp:5475
Value< uint8_t > currentMeterSource
Definition: msp_msg.hpp:952
virtual std::ostream & print(std::ostream &s) const override
Definition: msp_msg.hpp:3793
Value< uint32_t > rx_spi_id
Definition: msp_msg.hpp:1215
Value< uint16_t > acc_zero_y
Definition: msp_msg.hpp:677
SetRssiConfig(FirmwareVariant v)
Definition: msp_msg.hpp:1443
InavAnalog(FirmwareVariant v)
Definition: msp_msg.hpp:5300
std::vector< VoltageMeter > meters
Definition: msp_msg.hpp:3780
SetRawRc(FirmwareVariant v)
Definition: msp_msg.hpp:4268
Value< uint8_t > gps_baudrate
Definition: msp_msg.hpp:5326
Value< uint8_t > sub_cmd
Definition: msp_msg.hpp:4146
Value< uint16_t > rx_max_usec
Definition: msp_msg.hpp:1208
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:1252
WayPoint(FirmwareVariant v)
Definition: msp_msg.hpp:3506
Value< uint8_t > cfg_index
Definition: msp_msg.hpp:1415
virtual std::ostream & print(std::ostream &s) const override
Definition: msp_msg.hpp:467
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:1191
Value< uint8_t > current_profile
Definition: msp_msg.hpp:2675
Value< uint16_t > max
Definition: msp_msg.hpp:4510
Value< uint8_t > update
Definition: msp_msg.hpp:3031
Value< uint8_t > gps_ubx_sbas
Definition: msp_msg.hpp:5327
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:1881
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:4712
Value< uint8_t > aux_channel_index
Definition: msp_msg.hpp:995
Value< uint16_t > fw_pitch_angle
Definition: msp_msg.hpp:1915
SetPidController(FirmwareVariant v)
Definition: msp_msg.hpp:1638
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4198
Value< float > float_val
Definition: msp_msg.hpp:5082
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:4274
Value< uint8_t > range_endStep
Definition: msp_msg.hpp:1460
Value< uint8_t > transponder_count
Definition: msp_msg.hpp:2105
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:3710
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4144
virtual std::ostream & print(std::ostream &s) const override
Definition: msp_msg.hpp:3495
Value< uint8_t > dynamic_throttle_pid
Definition: msp_msg.hpp:3151
Value< float > dterm_setpoint_weight
Definition: msp_msg.hpp:2441
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4474
Value< uint8_t > rssi_alarm
Definition: msp_msg.hpp:2159
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:3175
BoardAlignment(FirmwareVariant v)
Definition: msp_msg.hpp:1098
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:2026
std::array< uint32_t, LED_MAX_STRIP_LENGTH > configs
Definition: msp_msg.hpp:1398
SetResetCurrPid(FirmwareVariant v)
Definition: msp_msg.hpp:4603
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:2981
PassthroughSerial(FirmwareVariant v)
Definition: msp_msg.hpp:4813
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:2514
virtual std::ostream & print(std::ostream &s) const override
Definition: msp_msg.hpp:422
Value< uint16_t > hdop
Definition: msp_msg.hpp:4106
Value< uint8_t > dest_profile_idx
Definition: msp_msg.hpp:4175
Value< uint8_t > wp_capabilites
Definition: msp_msg.hpp:813
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:785
Value< uint16_t > yaw
Definition: msp_msg.hpp:1742
std::vector< std::array< std::set< SwitchPosition >, NAUX > > box_pattern
Definition: msp_msg.hpp:3309
box_description box
Definition: msp_msg.hpp:1027
std::vector< GpsSvInfoSettings > sv_info
Definition: msp_msg.hpp:4074
Value< uint8_t > numSat
Definition: msp_msg.hpp:4292
OsdVideoConfig(FirmwareVariant v)
Definition: msp_msg.hpp:4126
Value< bool > wp_list_valid
Definition: msp_msg.hpp:815
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:552
Value< uint32_t > altitude_cm
Definition: msp_msg.hpp:1616
Value< uint8_t > control_rate_profile
Definition: msp_msg.hpp:3987
bool unpack_from(const ByteVector &data)
Definition: msp_msg.hpp:1337
Value< uint16_t > body_rate_y
Definition: msp_msg.hpp:5285
std::ostream & print(std::ostream &s) const
Definition: msp_msg.hpp:3156
Value< uint16_t > pidSumLimit
Definition: msp_msg.hpp:2442
Value< uint8_t > hw_pitometer_status
Definition: msp_msg.hpp:4021
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:3126
Value< uint8_t > cell_count
Definition: msp_msg.hpp:3844
Value< uint16_t > max_throttle
Definition: msp_msg.hpp:896
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:1117
Value< uint8_t > telemetryBaudrateIndx
Definition: msp_msg.hpp:1516
Value< uint8_t > minor
Definition: msp_msg.hpp:456
Value< uint8_t > NAV_state
Definition: msp_msg.hpp:3591
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:908
Value< uint32_t > axisAccelerationLimitYaw
Definition: msp_msg.hpp:2446
DataflashErase(FirmwareVariant v)
Definition: msp_msg.hpp:1870
Value< uint8_t > navflag
Definition: msp_msg.hpp:3516
SetBoardName(FirmwareVariant v)
Definition: msp_msg.hpp:609
std::string armingFlagToString(uint32_t flag)
Definition: msp_msg.hpp:264
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:1801
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:3448
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:4968
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:1139
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:979
Value< float > roll
Definition: msp_msg.hpp:5112
Value< uint16_t > land_slowdown_maxalt
Definition: msp_msg.hpp:839
SetMotor(FirmwareVariant v)
Definition: msp_msg.hpp:4539
Value< uint16_t > failsafe_throttle
Definition: msp_msg.hpp:5324
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4394
Value< uint8_t > command
Definition: msp_msg.hpp:2573
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:3291
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:1473
virtual std::ostream & print(std::ostream &s) const override
Definition: msp_msg.hpp:2627
Value< uint16_t > maxcheck
Definition: msp_msg.hpp:1202
std::size_t unpacking_remaining() const
Returns the number of bytes still avialable for unpacking.
Definition: ByteVector.hpp:448
Value< uint8_t > fix
Definition: msp_msg.hpp:4291
SetNavConfig(FirmwareVariant v)
Definition: msp_msg.hpp:4557
std::array< box_description, MAX_MODE_ACTIVATION_CONDITION_COUNT > boxes
Definition: msp_msg.hpp:1006
RxConfig(FirmwareVariant v)
Definition: msp_msg.hpp:1248
ResetConfig(FirmwareVariant v)
Definition: msp_msg.hpp:4428
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:5074
std::array< std::array< uint8_t, LED_DIRECTION_COUNT >, LED_MODE_COUNT > mode_colors
Definition: msp_msg.hpp:3746
Value< uint16_t > debug2
Definition: msp_msg.hpp:4924
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:1698
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4559
Value< uint32_t > timeouts
Definition: msp_msg.hpp:4104
SetHeading(FirmwareVariant v)
Definition: msp_msg.hpp:4487
virtual std::ostream & print(std::ostream &s) const override
Definition: msp_msg.hpp:1327
Value< uint8_t > motor_pwm_protocol
Definition: msp_msg.hpp:2315
Value< uint8_t > adjustmentFunction
Definition: msp_msg.hpp:1461
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:4858
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:4517
Value< uint16_t > uint16_val
Definition: msp_msg.hpp:5079
Value< uint16_t > h
Definition: msp_msg.hpp:1333
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:4729
Value< uint16_t > capacity_mAh
Definition: msp_msg.hpp:3845
std::vector< TransponderConfigSettings > transponder_data
Definition: msp_msg.hpp:2106
SetGpsConfig(FirmwareVariant v)
Definition: msp_msg.hpp:4668
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:1008
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4652
Value< uint8_t > gyro_sync_denom
Definition: msp_msg.hpp:2312
Value< uint16_t > max_throttle
Definition: msp_msg.hpp:3898
VoltageMeterConfig(FirmwareVariant v)
Definition: msp_msg.hpp:1577
Value< uint8_t > channel
Definition: msp_msg.hpp:2257
static const size_t MAX_MODE_ACTIVATION_CONDITION_COUNT
Definition: msp_msg.hpp:303
Value< std::string > name
Definition: msp_msg.hpp:613
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4401
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:657
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:1078
Feature(FirmwareVariant v)
Definition: msp_msg.hpp:1044
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:3311
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:3597
static const size_t MAX_ADJUSTMENT_RANGE_COUNT
Definition: msp_msg.hpp:308
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:1954
Value< uint16_t > avg_system_load_pct
Definition: msp_msg.hpp:3989
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:4200
Value< uint8_t > max_profiles
Definition: msp_msg.hpp:3986
Value< uint8_t > user_control_mode
Definition: msp_msg.hpp:623
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:2103
Value< uint16_t > deadband3d_low
Definition: msp_msg.hpp:3685
Value< uint16_t > stick_motion_threshold
Definition: msp_msg.hpp:1917
CurrentMeterConfig(FirmwareVariant v)
Definition: msp_msg.hpp:1137
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:3782
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:2390
Value< uint8_t > msp_version
Definition: msp_msg.hpp:2597
Set4WayIF(FirmwareVariant v)
Definition: msp_msg.hpp:4821
Response (2xx)
Definition: msp_msg.hpp:4267
Value< float > roll
Definition: msp_msg.hpp:3057
Value< uint8_t > temperature
Definition: msp_msg.hpp:3951
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:1297
SetVtxConfig(FirmwareVariant v)
Definition: msp_msg.hpp:2283
Value< uint16_t > min_distance
Definition: msp_msg.hpp:1918
AdjustmentRanges(FirmwareVariant v)
Definition: msp_msg.hpp:1467
SetRxMap(FirmwareVariant v)
Definition: msp_msg.hpp:1716
Value< uint16_t > max_manual_speed
Definition: msp_msg.hpp:626
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:2932
SetArmingConfig(FirmwareVariant v)
Definition: msp_msg.hpp:1667
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:1375
Debug(FirmwareVariant v)
Definition: msp_msg.hpp:4919
Value< uint8_t > rssi_channel
Definition: msp_msg.hpp:1434
Value< uint16_t > debug4
Definition: msp_msg.hpp:4926
virtual std::ostream & print(std::ostream &s) const override
Definition: msp_msg.hpp:3329
Value< uint8_t > capacity_units
Definition: msp_msg.hpp:5337
Value< uint8_t > supported
Definition: msp_msg.hpp:2059
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Definition: msp_msg.hpp:1418
Value< uint32_t > reserved1
Definition: msp_msg.hpp:1804
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:3905
std::array< HsvColor, LED_CONFIGURABLE_COLOR_COUNT > colors
Definition: msp_msg.hpp:1377
Value< int8_t > int8_val
Definition: msp_msg.hpp:4995
Value< float > lon
Definition: msp_msg.hpp:4294
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:5547
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:1528
Value< uint8_t > GPS_mode
Definition: msp_msg.hpp:3590
Value< uint8_t > disableRunawayTakeoff
Definition: msp_msg.hpp:2574
Value< uint16_t > rx_min_usec
Definition: msp_msg.hpp:1207
Value< uint16_t > servo_pwm_rate
Definition: msp_msg.hpp:2317
InavStatus(FirmwareVariant v)
Definition: msp_msg.hpp:5175
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Definition: msp_msg.hpp:4110
Value< uint16_t > flow_rate_y
Definition: msp_msg.hpp:5283
Value< uint8_t > mission_number
Definition: msp_msg.hpp:3593
Value< uint16_t > loiter_radius
Definition: msp_msg.hpp:901
Value< uint32_t > feature_mask
Definition: msp_msg.hpp:1738
BfBuildInfo(FirmwareVariant v)
Definition: msp_msg.hpp:1799
Value< uint16_t > roll
Definition: msp_msg.hpp:4702
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:2928
virtual ID id() const override
get the ID of the message
Definition: msp_msg.hpp:4566
Value< uint8_t > uint8_val
Definition: msp_msg.hpp:4994
Value< uint8_t > controller_id
Definition: msp_msg.hpp:1629
Value< uint8_t > itermThrottleGain
Definition: msp_msg.hpp:2443
RxFailConfigs(FirmwareVariant v)
Definition: msp_msg.hpp:1986
uint16_t safe_wp_distance
Definition: msp_msg.hpp:3624
Value< std::string > string_val
Definition: msp_msg.hpp:5083


msp
Author(s): Christian Rauch
autogenerated on Tue Oct 6 2020 03:39:02