30 enum class ID : uint16_t {
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 ";
363 static const std::vector<std::string>
FEATURES = {
"RX_PPM",
383 "CHANNEL_FORWARDING",
416 rc &= data.
unpack(protocol);
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;
439 return data.
unpack(identifier, data.size());
442 virtual std::ostream&
print(std::ostream& s)
const override {
443 s <<
"#FC variant:" << std::endl;
444 s <<
" Identifier: " << identifier << std::endl;
463 rc &= data.
unpack(patch_level);
467 virtual std::ostream&
print(std::ostream& s)
const override {
468 s <<
"#FC version:" << std::endl;
469 s <<
" Version: " << major <<
"." << minor <<
"." << patch_level
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);
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;
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);
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;
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);
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);
588 rc &= data->pack(uint32_t(0));
589 if(!rc) data.reset();
617 if(!data->pack(name, MAX_NAME_LENGTH)) data.reset();
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);
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();
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);
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();
740 virtual ID id()
const override {
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);
762 virtual ID id()
const override {
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();
789 if(!data->pack(uint8_t(0))) data.reset();
802 if(!data->pack(uint8_t(0))) data.reset();
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);
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);
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();
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);
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();
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);
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();
1006 std::array<box_description, MAX_MODE_ACTIVATION_CONDITION_COUNT>
boxes;
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);
1032 rc &= data->pack(mode_activation_condition_idx);
1033 rc &= data->pack(box.
id);
1036 rc &= data->pack(box.
endStep);
1037 if(!rc) data.reset();
1052 bool rc = data.
unpack(mask);
1055 for(
size_t ifeat(0); ifeat < FEATURES.size(); ifeat++) {
1056 if(mask & (1 << ifeat)) features.insert(FEATURES[ifeat]);
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;
1081 for(
size_t ifeat(0); ifeat < FEATURES.size(); ifeat++) {
1082 if(features.count(FEATURES[ifeat])) mask |= 1 << ifeat;
1084 if(!data->pack(mask)) data.reset();
1105 rc &= data.
unpack(pitch);
1120 rc &= data->pack(roll);
1121 rc &= data->pack(pitch);
1122 rc &= data->pack(yaw);
1123 if(!rc) data.reset();
1143 rc &= data.
unpack(currnet_scale);
1144 rc &= data.
unpack(current_offset);
1145 rc &= data.
unpack(current_type);
1146 rc &= data.
unpack(capacity);
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();
1179 return data.
unpack(mode);
1193 if(!data->pack(mode)) data.reset();
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
1234 s <<
" airModeActivateThreshold: " << airModeActivateThreshold
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
1240 s <<
" fpvCamAngleDegrees: " << fpvCamAngleDegrees << std::endl;
1241 s <<
" receiverType: " << receiverType << std::endl;
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);
1262 valid_data_groups += 1;
1263 rc &= data.
unpack(rx_min_usec);
1264 rc &= data.
unpack(rx_max_usec);
1267 valid_data_groups += 1;
1268 rc &= data.
unpack(rcInterpolation);
1269 rc &= data.
unpack(rcInterpolationInterval);
1270 rc &= data.
unpack(airModeActivateThreshold);
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);
1279 valid_data_groups += 1;
1280 rc &= data.
unpack(fpvCamAngleDegrees);
1283 valid_data_groups += 1;
1284 rc &= data.
unpack(receiverType);
1288 virtual std::ostream&
print(std::ostream& s)
const override {
1289 return rxConfigPrint(s);
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);
1323 if(!rc) data.reset();
1327 virtual std::ostream&
print(std::ostream& s)
const override {
1328 return rxConfigPrint(s);
1360 std::array<HsvColor, LED_CONFIGURABLE_COLOR_COUNT>
colors;
1364 for(
auto& c : colors) {
1377 std::array<HsvColor, LED_CONFIGURABLE_COLOR_COUNT>
colors;
1383 rc &= data->pack(colors[i].h);
1384 rc &= data->pack(colors[i].s);
1385 rc &= data->pack(colors[i].v);
1387 if(!rc) data.reset();
1398 std::array<uint32_t, LED_MAX_STRIP_LENGTH>
configs;
1403 rc &= data.
unpack(configs[i]);
1421 rc &= data->pack(cfg_index);
1422 rc &= data->pack(config);
1423 if(!rc) data.reset();
1437 return data.
unpack(rssi_channel);
1451 if(!data->pack(rssi_channel)) data.reset();
1471 std::array<adjustmentRange, MAX_ADJUSTMENT_RANGE_COUNT>
ranges;
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);
1499 rc &= data->pack(range_index);
1506 if(!rc) data.reset();
1538 if(rc) configs.push_back(tmp);
1540 return configs.size();
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);
1563 if(!rc) data.reset();
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);
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();
1619 return data.
unpack(altitude_cm);
1632 return data.
unpack(controller_id);
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;
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();
1683 std::array<uint8_t, MAX_MAPPABLE_RX_INPUTS>
map;
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;
1704 rc &= data.
unpack(map[i]);
1709 virtual std::ostream&
print(std::ostream& s)
const override {
1710 return printRxMapSettings(s);
1723 for(
const auto& channel : map) {
1724 rc &= data->pack(channel);
1726 if(!rc) data.reset();
1730 virtual std::ostream&
print(std::ostream& s)
const override {
1731 return printRxMapSettings(s);
1756 rc &= data.
unpack(mixer_mode);
1757 rc &= data.
unpack(feature_mask);
1758 rc &= data.
unpack(serialrx_provider);
1760 rc &= data.
unpack(pitch);
1762 rc &= data.
unpack(current_meter_scale);
1763 rc &= data.
unpack(current_meter_offset);
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();
1809 rc &= data.
unpack(build_date, 11);
1810 rc &= data.
unpack(reserved1);
1811 rc &= data.
unpack(reserved2);
1829 rc &= data.
unpack(flash_is_ready);
1830 rc &= data.
unpack(sectors);
1831 rc &= data.
unpack(total_size);
1832 rc &= data.
unpack(offset);
1852 rc &= data->pack(read_address);
1853 rc &= data->pack(read_size);
1854 rc &= data->pack(allow_compression);
1855 if(!rc) data.reset();
1861 rc &= data.
unpack(read_address);
1863 rc &= data.
consume(flash_data.size());
1886 return data.
unpack(loop_time);
1900 if(!data->pack(loop_time)) data.reset();
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);
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);
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);
1974 if(!rc) data.reset();
1999 channels.push_back(tmp);
2015 rc &= data.
unpack(channel);
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);
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);
2070 rc &= data.
unpack(p_ratio);
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();
2112 rc &= data.
unpack(transponder_count);
2113 if(!transponder_count())
return rc;
2114 for(uint8_t i = 0; i < transponder_count(); ++i) {
2118 transponder_data.push_back(tmp);
2120 rc &= data.
unpack(provider);
2121 if(!provider())
return rc;
2122 uint8_t data_len = transponder_data[provider() - 1].data_length();
2142 rc &= data->pack(provider);
2143 rc &= data->pack(provider_data);
2144 if(!rc) data.reset();
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);
2180 rc &= data.
unpack(item_pos[i]);
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);
2219 rc &= data->pack(item_pos);
2221 if(!rc) data.reset();
2240 rc &= data->pack(addr);
2241 for(
const auto& c : font_data) {
2242 rc &= data->pack(c);
2244 if(!rc) data.reset();
2266 rc &= data.
unpack(device_type);
2267 if(rc && (device_type() != 0xFF)) {
2269 rc &= data.
unpack(channel);
2270 rc &= data.
unpack(power_idx);
2271 rc &= data.
unpack(pit_mode);
2274 rc &= data.
unpack(frequency);
2292 if(band & 0xF8 || channel & 0xF8) {
2295 frequency = uint16_t(band - 1) & uint16_t((channel - 1) << 3);
2302 rc &= data->pack(frequency);
2303 rc &= data->pack(power);
2304 rc &= data->pack(pit_mode);
2305 if(!rc) data.reset();
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);
2341 pwm_inversion_set =
true;
2342 rc &= data.
unpack(pwm_inversion);
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();
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);
2403 dterm_filter_type_set =
true;
2404 rc &= data.
unpack(dterm_filter_type);
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();
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);
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();
2516 extended_contents =
false;
2517 rc &= data.
unpack(acc_hardware);
2518 rc &= data.
unpack(baro_hardware);
2519 rc &= data.
unpack(mag_hardware);
2521 extended_contents =
true;
2522 rc &= data.
unpack(pitot_hardware);
2523 rc &= data.
unpack(rangefinder_hardware);
2524 rc &= data.
unpack(opflow_hardware);
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);
2547 if(!rc) data.reset();
2562 if(!data->pack(key)) data.reset();
2579 rc &= data->pack(command);
2580 rc &= data->pack(disableRunawayTakeoff);
2581 if(!rc) data.reset();
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);
2621 bool hasBind()
const {
return has(Capability::BIND); }
2625 bool hasFlap()
const {
return has(Capability::FLAP); }
2627 virtual std::ostream&
print(std::ostream& s)
const override {
2631 s_type =
"Tricopter";
2634 s_type =
"Quadrocopter Plus";
2637 s_type =
"Quadrocopter X";
2640 s_type =
"BI-copter";
2643 s_type =
"UNDEFINED";
2647 s <<
"#Ident:" << std::endl;
2649 s <<
" MultiWii Version: " << version << std::endl
2650 <<
" MSP Version: " << msp_version << std::endl
2651 <<
" Type: " << s_type << std::endl
2652 <<
" Capabilities:" << std::endl;
2655 hasBind() ? s <<
"ON" : s <<
"OFF";
2659 hasDynBal() ? s <<
"ON" : s <<
"OFF";
2663 hasFlap() ? s <<
"ON" : s <<
"OFF";
2679 rc &= data.
unpack(cycle_time);
2680 rc &= data.
unpack(i2c_errors);
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);
2696 box_mode_flags.clear();
2699 for(
size_t ibox(0); ibox <
sizeof(flag) * CHAR_BIT; ibox++) {
2700 if(flag & (1 << ibox)) box_mode_flags.insert(ibox);
2703 rc &= data.
unpack(current_profile);
2709 rc &= data.
pack(cycle_time);
2710 rc &= data.
pack(i2c_errors);
2714 for(
const auto& s : sensors) {
2716 case Sensor::Accelerometer:
2717 sensor_pack() |= (1 << 0);
2719 case Sensor::Barometer:
2720 sensor_pack() |= (1 << 1);
2722 case Sensor::Magnetometer:
2723 sensor_pack() |= (1 << 2);
2726 sensor_pack() |= (1 << 3);
2729 sensor_pack() |= (1 << 4);
2731 case Sensor::OpticalFlow:
2732 sensor_pack() |= (1 << 5);
2735 sensor_pack() |= (1 << 6);
2737 case Sensor::GeneralHealth:
2738 sensor_pack() |= (1 << 15);
2742 rc &= data.
pack(sensor_pack);
2746 for(
const auto& b : box_mode_flags) {
2747 box_pack() |= (1 << b);
2749 rc &= data.
pack(box_pack);
2765 rc &= StatusBase::unpack_from(data);
2768 rc &= data.
unpack(avg_system_load_pct);
2769 rc &= data.
unpack(gyro_cycle_time);
2775 return sensors.count(Sensor::Accelerometer);
2782 bool hasGPS()
const {
return sensors.count(Sensor::GPS); }
2784 bool hasSonar()
const {
return sensors.count(Sensor::Sonar); }
2788 bool hasPitot()
const {
return sensors.count(Sensor::Pitot); }
2790 bool isHealthy()
const {
return sensors.count(Sensor::GeneralHealth); }
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;
2798 s <<
" Accelerometer: ";
2799 hasAccelerometer() ? s <<
"ON" : s <<
"OFF";
2802 s <<
" Barometer: ";
2803 hasBarometer() ? s <<
"ON" : s <<
"OFF";
2806 s <<
" Magnetometer: ";
2807 hasMagnetometer() ? s <<
"ON" : s <<
"OFF";
2811 hasGPS() ? s <<
"ON" : s <<
"OFF";
2815 hasSonar() ? s <<
"ON" : s <<
"OFF";
2818 s <<
" Active Boxes (by ID):";
2819 for(
const size_t box_id : box_mode_flags) {
2834 std::array<Value<int16_t>, 3>
acc;
2835 std::array<Value<int16_t>, 3>
gyro;
2836 std::array<Value<int16_t>, 3>
mag;
2840 for(
auto& a : acc) {
2843 for(
auto& g : gyro) {
2846 for(
auto& m : mag) {
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]
2867 std::array<Value<float>, 3>
acc;
2869 std::array<Value<float>, 3>
mag;
2873 const float gyro_unit,
2874 const float magn_gain,
2875 const float si_unit_1g
2877 for(
int i = 0; i < 3; ++i) {
2878 acc[i] = raw.
acc[i]() / acc_1g * si_unit_1g;
2880 for(
int i = 0; i < 3; ++i) {
2881 gyro[i] = raw.
gyro[i]() * gyro_unit;
2883 for(
int i = 0; i < 3; ++i) {
2884 mag[i] = raw.
mag[i]() * magn_gain;
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;
2910 for(
auto& s : servo) rc &= data.
unpack(s);
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;
2934 for(
auto& m : motor) rc &= data.
unpack(m);
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;
2961 rc &= data.
unpack(rc_data);
2962 if(rc) channels.push_back(rc_data);
2964 return !channels.empty();
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) {
2972 s <<
" " << std::endl;
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);
3005 rc &= data.
unpack<uint16_t>(hdop, 100);
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;
3035 rc &= data.
unpack(distanceToHome);
3036 rc &= data.
unpack(directionToHome);
3037 rc &= data.
unpack(update);
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;
3063 rc &= data.
unpack<int16_t>(roll, 10);
3064 rc &= data.
unpack<int16_t>(pitch, 10);
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;
3092 rc &= data.
unpack<int32_t>(altitude, 100);
3093 rc &= data.
unpack<int16_t>(vario, 100);
3095 baro_altitude_set =
true;
3096 rc &= data.
unpack<int32_t>(baro_altitude, 100);
3101 virtual std::ostream&
print(std::ostream& s)
const override {
3102 s <<
"#Altitude:" << std::endl;
3103 s <<
" Altitude: " << altitude <<
" m, var: " << vario <<
" m/s" 3105 s <<
" Barometer: ";
3106 if(baro_altitude_set)
3128 rc &= data.
unpack<uint8_t>(vbat, 10);
3129 rc &= data.
unpack<uint16_t>(powerMeterSum, 1000);
3131 rc &= data.
unpack<int8_t>(amperage, 100);
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;
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]
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;
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]);
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]);
3190 rc &= data.
unpack(rcRates[2]);
3191 rc &= data.
unpack(rcRates[1]);
3192 rc &= data.
unpack(rcExpo[1]);
3221 std::array<Value<PidTerms>,
3222 static_cast<uint8_t
>(PID_Element::PID_ITEM_COUNT)>
3225 std::ostream&
print(std::ostream& s)
const {
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
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
3261 s <<
" Position: " << entry[PID_POS_XY]().P <<
"\t| " 3262 << entry[PID_POS_XY]().I <<
"\t| " << entry[PID_POS_XY]().D
3264 s <<
" PositionR: " << entry[PID_VEL_XY]().P <<
"\t| " 3265 << entry[PID_VEL_XY]().I <<
"\t| " << entry[PID_VEL_XY]().D
3267 s <<
" NavR: " << entry[PID_SURFACE]().P <<
"\t| " 3268 << entry[PID_SURFACE]().I <<
"\t| " << entry[PID_SURFACE]().D
3270 s <<
" Level: " << entry[PID_LEVEL]().P <<
"\t| " 3271 << entry[PID_LEVEL]().I <<
"\t| " << entry[PID_LEVEL]().D
3273 s <<
" Magn: " << entry[PID_HEADING]().P <<
"\t| " 3274 << entry[PID_HEADING]().I <<
"\t| " << entry[PID_HEADING]().D
3276 s <<
" Vel: " << entry[PID_VEL_Z]().P <<
"\t| " 3277 << entry[PID_VEL_Z]().I <<
"\t| " << entry[PID_VEL_Z]().D
3294 i < static_cast<uint8_t>(PID_Element::PID_ITEM_COUNT);
3296 rc &= data.
unpack(entry[i]);
3312 box_pattern.clear();
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)))
3324 box_pattern.push_back(aux_sp);
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++) {
3333 for(
size_t iaux(0); iaux < box_pattern[ibox].size(); iaux++) {
3334 s <<
"aux" << iaux + 1 <<
": ";
3343 if(box_pattern[ibox][iaux].count(
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;
3379 s <<
" Magnetic Declination: " << mag_declination <<
" deg" 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;
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);
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);
3429 for(
auto& pin : pwm_pin) rc &= data.
unpack(pin);
3433 virtual std::ostream&
print(std::ostream& s)
const override {
3434 s <<
"#Motor pins:" << std::endl;
3436 s <<
" Motor " << imotor <<
": pin " << size_t(pwm_pin[imotor]())
3457 std::stringstream ss(str);
3459 while(getline(ss, bname,
';')) {
3460 box_names.push_back(bname);
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;
3487 std::stringstream ss(str);
3489 while(getline(ss, pname,
';')) {
3490 pid_names.push_back(pname);
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;
3520 rc &= data.
unpack(wp_no);
3523 rc &= data.
unpack(altHold);
3524 rc &= data.
unpack(heading);
3525 rc &= data.
unpack(staytime);
3526 rc &= data.
unpack(navflag);
3542 for(uint8_t bi : data) box_ids.push_back(bi);
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;
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);
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);
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);
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);
3658 rc &= data.
unpack(ignore_throttle);
3659 rc &= data.
unpack(takeover_baro);
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);
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);
3673 rc &= data.
unpack(max_wp_number);
3674 rc &= data.
unpack(checksum);
3691 rc &= data.
unpack(deadband3d_low);
3692 rc &= data.
unpack(deadband3d_high);
3693 rc &= data.
unpack(neutral_3d);
3712 rc &= data.
unpack(deadband);
3713 rc &= data.
unpack(yaw_deadband);
3714 rc &= data.
unpack(alt_hold_deadband);
3715 rc &= data.
unpack(deadband3d_throttle);
3733 rc &= data.
unpack(gyro_align);
3734 rc &= data.
unpack(acc_align);
3735 rc &= data.
unpack(mag_align);
3745 std::array<std::array<uint8_t, LED_DIRECTION_COUNT>, LED_MODE_COUNT>
3754 for(
auto& mode : mode_colors) {
3755 for(
auto& color : mode) {
3756 rc &= data.
unpack(color);
3759 for(
auto& special : special_colors) {
3760 rc &= data.
unpack(special);
3763 rc &= data.
unpack(led_aux_channel);
3764 rc &= data.
unpack(reserved);
3765 rc &= data.
unpack(led_strip_aux_channel);
3783 const size_t nmeter = data.size() / 2;
3784 meters.resize(nmeter);
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);
3793 virtual std::ostream&
print(std::ostream& s)
const override {
3794 s <<
"#Voltages (" << meters.size() <<
"):" << std::endl;
3796 s << meter.id <<
": " << meter.voltage <<
"V" << std::endl;
3816 const size_t nmeter = data.size() / 5;
3817 meters.resize(nmeter);
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);
3827 virtual std::ostream&
print(std::ostream& s)
const override {
3828 s <<
"#Current (" << meters.size() <<
"):" << std::endl;
3830 s << meter.id <<
": " << meter.mAh_drawn <<
"mAh (" 3831 << meter.amperage <<
"A)" << std::endl;
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);
3859 rc &= data.
unpack(state_tmp);
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;
3879 case state_t::CRITICAL:
3882 case state_t::NOT_PRESENT:
3909 rc &= data.
unpack(min_throttle);
3910 rc &= data.
unpack(max_throttle);
3911 rc &= data.
unpack(min_command);
3930 rc &= data.
unpack(provider);
3931 rc &= data.
unpack(sbas_mode);
3932 rc &= data.
unpack(auto_config);
3933 rc &= data.
unpack(auto_baud);
3946 return data.
unpack(mag_declination);
3969 rc &= data.
unpack(motor_count);
3970 for(
int i = 0; i < motor_count(); ++i) {
3974 esc_data.push_back(esc);
3995 rc &= StatusBase::unpack_from(data);
3997 rc &= data.
unpack(avg_system_load_pct);
3998 rc &= data.
unpack(arming_flags);
3999 rc &= data.
unpack(acc_calibration_axis_flags);
4002 rc &= data.
unpack(max_profiles);
4003 rc &= data.
unpack(control_rate_profile);
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);
4051 rc &= data.
unpack(u_id_0);
4052 rc &= data.
unpack(u_id_1);
4053 rc &= data.
unpack(u_id_2);
4083 rc &= data.
unpack(channel_count);
4084 for(uint8_t i = 0; i < channel_count(); ++i) {
4112 rc &= data.
unpack(last_msg_dt);
4113 rc &= data.
unpack(errors);
4114 rc &= data.
unpack(timeouts);
4115 rc &= data.
unpack(packet_count);
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);
4162 if(!rc) data.reset();
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();
4202 rc &= data.
unpack(beeper_off_mask);
4203 rc &= data.
unpack(beacon_tone);
4217 rc &= data->pack(beeper_off_mask);
4218 if(beacon_tone.set()) {
4219 rc &= data->pack(beacon_tone);
4221 if(!rc) data.reset();
4237 if(!data->pack(rssi)) data.reset();
4254 rc &= data.
unpack(rssi_source);
4255 rc &= data.
unpack(rtc_date_time_status);
4277 for(
const uint16_t& c : channels) {
4278 rc &= data->pack(c);
4280 if(!rc) data.reset();
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();
4323 i < static_cast<uint8_t>(PID_Element::PID_ITEM_COUNT);
4325 rc &= data->pack(entry[i]);
4327 if(!rc) data.reset();
4350 rc &= data->pack(rcRates[0]);
4351 rc &= data->pack(rcExpo[0]);
4352 for(
const auto& r : rates) {
4353 rc &= data->pack(r);
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);
4361 if(!rcExpo[2].
set())
goto packing_finished;
4362 rc &= data->pack(rcExpo[2]);
4368 if(!rcRates[2].
set())
goto packing_finished;
4369 rc &= data->pack(rcRates[2]);
4371 if(!rcRates[1].
set())
goto packing_finished;
4372 rc &= data->pack(rcRates[1]);
4374 if(!rcExpo[1].
set())
goto packing_finished;
4375 rc &= data->pack(rcExpo[1]);
4378 if(!rc) data.reset();
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();
4453 rc &= data->pack(wp_no);
4455 rc &= data->pack(action);
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);
4463 rc &= data->pack(p3);
4465 rc &= data->pack(nav_flag);
4480 if(!data->pack(current_setting)) data.reset();
4495 if(!data->pack(heading)) data.reset();
4496 assert(data->size() == 2);
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);
4527 rc &= data->pack(tmp);
4528 rc &= data->pack(tmp);
4530 rc &= data->pack(forward_from_channel);
4531 rc &= data->pack(reversed_sources);
4532 if(!rc) data.reset();
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();
4575 rc &= data->pack(deadband3d_low);
4576 rc &= data->pack(deadband3d_high);
4577 rc &= data->pack(neutral_3d);
4578 if(!rc) data.reset();
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();
4617 rc &= data->pack(gyro_align);
4618 rc &= data->pack(acc_align);
4619 rc &= data->pack(mag_align);
4620 if(!rc) data.reset();
4638 rc &= data->pack(mode_idx);
4639 rc &= data->pack(fun_idx);
4640 rc &= data->pack(color);
4641 if(!rc) data.reset();
4657 rc &= data->pack(min_throttle);
4658 rc &= data->pack(max_throttle);
4659 rc &= data->pack(min_command);
4660 if(!rc) data.reset();
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();
4695 if(!data->pack<uint16_t>(mag_declination, 10)) data.reset();
4715 rc &= data->pack(pitch);
4716 rc &= data->pack(roll);
4717 if(!rc) data.reset();
4731 rc &= data.
unpack(pitch);
4748 rc &= data.
unpack(target_channel);
4749 rc &= data.
unpack(input_source);
4751 rc &= data.
unpack(speed);
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);
4786 rules.push_back(rule);
4805 if(!data->pack(rule)) data.reset();
4833 if(esc_mode.
set()) {
4834 rc &= data->pack(esc_mode);
4835 rc &= data->pack(esc_port_index);
4837 if(!rc) data.reset();
4842 return data.
unpack(esc_count);
4861 rc &= data->pack(secs);
4862 rc &= data->pack(millis);
4863 if(!rc) data.reset();
4878 rc &= data.
unpack(millis);
4913 return data.
unpack(debug_msg);
4930 rc &= data.
unpack(debug1);
4931 rc &= data.
unpack(debug2);
4932 rc &= data.
unpack(debug3);
4933 rc &= data.
unpack(debug4);
4955 return data.
unpack(tz_offset);
4970 if(!data->pack(tz_offset)) data.reset();
5007 rc &= data->pack(setting_name);
5008 if(!rc) data.reset();
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);
5033 virtual std::ostream&
print(std::ostream& s)
const override {
5034 s <<
"#Setting:" << std::endl;
5035 s <<
" " << setting_name <<
": ";
5037 switch(expected_data_type) {
5038 case DATA_TYPE::UINT8:
5041 case DATA_TYPE::INT8:
5044 case DATA_TYPE::UINT16:
5047 case DATA_TYPE::INT16:
5050 case DATA_TYPE::UINT32:
5053 case DATA_TYPE::FLOAT:
5056 case DATA_TYPE::STRING:
5090 rc &= data->pack(setting_name);
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();
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);
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);
5166 rc &= data->pack(index);
5167 rc &= data->pack(mixer);
5168 if(!rc) data.reset();
5185 rc &= data.
unpack(cycle_time);
5186 rc &= data.
unpack(i2c_errors);
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);
5201 rc &= data.
unpack(avg_system_load_pct);
5202 rc &= data.
unpack(config_profile);
5204 rc &= data.
unpack(arming_flags);
5207 box_mode_flags.clear();
5210 for(
size_t ibox(0); ibox <
sizeof(flag) * CHAR_BIT; ibox++) {
5211 if(flag & (1 << ibox)) box_mode_flags.insert(ibox);
5218 return sensors.count(Sensor::Accelerometer);
5225 bool hasGPS()
const {
return sensors.count(Sensor::GPS); }
5227 bool hasSonar()
const {
return sensors.count(Sensor::Sonar); }
5231 bool hasPitot()
const {
return sensors.count(Sensor::Pitot); }
5233 bool isHealthy()
const {
return sensors.count(Sensor::GeneralHealth); }
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 <<
"%" 5242 s <<
" I2C errors: " << i2c_errors << std::endl;
5243 s <<
" Sensors:" << std::endl;
5245 s <<
" Accelerometer: ";
5246 hasAccelerometer() ? s <<
"ON" : s <<
"OFF";
5249 s <<
" Barometer: ";
5250 hasBarometer() ? s <<
"ON" : s <<
"OFF";
5253 s <<
" Magnetometer: ";
5254 hasMagnetometer() ? s <<
"ON" : s <<
"OFF";
5258 hasGPS() ? s <<
"ON" : s <<
"OFF";
5262 hasSonar() ? s <<
"ON" : s <<
"OFF";
5265 s <<
" Active Boxes (by ID):";
5266 for(
const size_t box_id : box_mode_flags) {
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);
5311 rc &= data.
unpack(battery_voltage);
5312 rc &= data.
unpack(mAh_drawn);
5314 rc &= data.
unpack(amperage);
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);
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();
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);
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();
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);
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);
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);
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);
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);
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();
5548 return data.
unpack(speed);
5556 return val.
print(s);
5559 #endif // MSP_MSG_HPP virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Value< uint8_t > vbatwarningcellvoltage
virtual ID id() const override
get the ID of the message
Definition of a pure virtual class used to indicate that a child class can pack itself into a ByteVec...
Value< uint8_t > identifier
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Value< std::string > debug_msg
Value< uint8_t > manual_rate_p
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Value< uint8_t > throttle_expo
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
virtual ID id() const override
get the ID of the message
virtual ID id() const override
get the ID of the message
Value< uint8_t > rssi_alarm
virtual ID id() const override
get the ID of the message
BoardInfo(FirmwareVariant v)
Value< uint8_t > pit_mode
Value< uint16_t > tpa_breakpoint
Value< uint8_t > gps_min_sats
DATA_TYPE expected_data_type
virtual ID id() const override
get the ID of the message
Value< uint16_t > neutral_3d
virtual ID id() const override
get the ID of the message
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Value< uint8_t > deadband
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
virtual ID id() const override
get the ID of the message
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
virtual std::ostream & print(std::ostream &s) const override
Altitude(FirmwareVariant v)
virtual ID id() const override
get the ID of the message
Value< uint8_t > rth_alt_control_mode
TransponderConfig(FirmwareVariant v)
Value< uint8_t > off_delay
virtual ID id() const override
get the ID of the message
Value< uint16_t > tz_offset
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Value< uint16_t > mag_declination
NavConfig(FirmwareVariant v)
virtual ID id() const override
get the ID of the message
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Value< uint8_t > servo_idx
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Value< uint8_t > config_profile
Value< uint16_t > neg_alt_alarm
SetSensorConfig(FirmwareVariant v)
virtual ID id() const override
get the ID of the message
Value< uint16_t > min_throttle
virtual ID id() const override
get the ID of the message
Value< uint8_t > serialrx_provider
SetBfConfig(FirmwareVariant v)
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
virtual ID id() const override
get the ID of the message
Value< uint8_t > multiwii_current_meter_output
Value< uint16_t > yaw_lpf_hz
Value< uint8_t > raw_quality
Value< uint16_t > neg_alt_alarm
virtual ID id() const override
get the ID of the message
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
SetRcTuning(FirmwareVariant v)
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Value< uint8_t > max_waypoints
bool unpack(T &val) const
Extracts little endian integers from the ByteVector. Consumes a number of bytes matching sizeof(T)...
SetCalibrationData(FirmwareVariant v)
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Value< uint16_t > avg_system_load_pct
Value< uint8_t > gps_provider
std::array< Value< float >, 3 > gyro
virtual ID id() const override
get the ID of the message
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Value< uint8_t > mag_align
virtual ID id() const override
get the ID of the message
Value< uint32_t > arming_flags
virtual ID id() const override
get the ID of the message
WpGetInfo(FirmwareVariant v)
Value< uint8_t > use_thr_mid_for_althold
Value< uint8_t > gps_ubx_sbas
bool hasMagnetometer() const
static const size_t LED_SPECIAL_COLOR_COUNT
static const size_t OSD_ITEM_COUNT
virtual std::ostream & print(std::ostream &s) const override
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
virtual ID id() const override
get the ID of the message
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Motor3dConfig(FirmwareVariant v)
Value< uint32_t > capacity_critical
virtual ID id() const override
get the ID of the message
virtual ID id() const override
get the ID of the message
bool unpack_from(const ByteVector &data)
virtual ID id() const override
get the ID of the message
Value< uint16_t > rollPitchItermIgnoreRate
SetFilterConfig(FirmwareVariant v)
std::vector< std::string > pid_names
static const size_t LED_CONFIGURABLE_COLOR_COUNT
virtual bool decode(const ByteVector &) override
Decode message contents from a ByteVector.
virtual ID id() const override
get the ID of the message
virtual std::ostream & print(std::ostream &s) const override
Value< uint16_t > neutral_3d
SetAdvancedConfig(FirmwareVariant v)
Value< std::string > identifier
Value< uint16_t > max_manual_climb_rate
Value< uint8_t > auto_baud
virtual ID id() const override
get the ID of the message
virtual ID id() const override
get the ID of the message
virtual ID id() const override
get the ID of the message
Value< uint16_t > read_size
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Value< uint8_t > range_index
Value< uint8_t > imu_small_angle
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Value< uint8_t > sbas_mode
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
std::array< uint16_t, N_SERVO > servo
SetFailsafeConfig(FirmwareVariant v)
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
SetTransponderConfig(FirmwareVariant v)
Value< uint8_t > deltaMethod
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
virtual ID id() const override
get the ID of the message
StatusEx(FirmwareVariant v)
virtual ID id() const override
get the ID of the message
Value< uint8_t > peripheralBaudrateIndx
virtual ID id() const override
get the ID of the message
virtual ID id() const override
get the ID of the message
virtual ID id() const override
get the ID of the message
virtual bool pack_into(ByteVector &data) const
virtual ID id() const override
get the ID of the message
static const size_t N_MOTOR
Value< uint16_t > frequency
virtual ID id() const override
get the ID of the message
Value< uint8_t > heading_hold_error_lpf_freq
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
SetCfSerialConfig(FirmwareVariant v)
Value< uint8_t > acc_soft_lpf_hz
std::array< uint16_t, N_MOTOR > motor
virtual ID id() const override
get the ID of the message
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Value< uint16_t > batteryCapacity
Value< uint8_t > hw_optical_flow_status
virtual ID id() const override
get the ID of the message
SetBeeperConfig(FirmwareVariant v)
std::set< Capability > capabilities
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Value< uint8_t > stabilized_rc_yaw_expo
Value< uint8_t > provider
Value< uint32_t > capacity_warning
std::ostream & print(std::ostream &s) const
virtual ID id() const override
get the ID of the message
virtual ID id() const override
get the ID of the message
virtual ID id() const override
get the ID of the message
Value< uint16_t > loop_time
std::vector< MotorMixer > mixer
virtual ID id() const override
get the ID of the message
Value< uint8_t > osd_support
Value< uint16_t > min_command
Reserve2(FirmwareVariant v)
InavMisc(FirmwareVariant v)
virtual ID id() const override
get the ID of the message
virtual bool decode(const ByteVector &) override
Decode message contents from a ByteVector.
VoltageMeters(FirmwareVariant v)
virtual ID id() const override
get the ID of the message
DataflashRead(FirmwareVariant v)
virtual ID id() const override
get the ID of the message
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Value< uint8_t > gps_provider
virtual ID id() const override
get the ID of the message
Value< uint8_t > max_bank_angle
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Value< uint8_t > acc_calibration_axis_flags
virtual ID id() const override
get the ID of the message
TxInfo(FirmwareVariant v)
SetRawGPS(FirmwareVariant v)
Value< std::string > name
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
InavBatteryConfig(FirmwareVariant v)
Value< uint8_t > spektrum_sat_bind
Value< uint32_t > capacity
Value< uint16_t > alt_alarm
virtual ID id() const override
get the ID of the message
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Value< uint8_t > stabilized_rate_p
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
SetAdjustmentRange(FirmwareVariant v)
virtual ID id() const override
get the ID of the message
virtual ID id() const override
get the ID of the message
Value< uint32_t > axisAccelerationLimitRollPitch
virtual ID id() const override
get the ID of the message
std::vector< uint16_t > channels
virtual ID id() const override
get the ID of the message
virtual ID id() const override
get the ID of the message
CommonSetTz(FirmwareVariant v)
Value< uint16_t > current_offset
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
MotorConfig(FirmwareVariant v)
Value< uint8_t > auxChannelIndex
CompGPS(FirmwareVariant v)
std::set< Sensor > sensors
Value< uint8_t > hw_acc_status
virtual ID id() const override
get the ID of the message
Value< uint16_t > yaw_jump_prevention_limit
Value< uint8_t > src_profile_idx
Value< uint16_t > body_rate_x
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
virtual ID id() const override
get the ID of the message
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
virtual ID id() const override
get the ID of the message
virtual ID id() const override
get the ID of the message
virtual ID id() const override
get the ID of the message
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Value< uint16_t > staytime
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Value< uint8_t > mixer_mode
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Value< uint8_t > gps_baudrate
OsdConfig(FirmwareVariant v)
virtual ID id() const override
get the ID of the message
Value< uint16_t > item_pos
virtual ID id() const override
get the ID of the message
Value< uint16_t > voltage_scale
bool unpack_from(const ByteVector &data)
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
virtual ID id() const override
get the ID of the message
Value< float > w_xy_gps_p
BuildInfo(FirmwareVariant v)
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
bool dterm_filter_type_set
Value< float > ground_course
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Value< uint32_t > capacity
Value< uint8_t > reserved
InavPid(FirmwareVariant v)
virtual ID id() const override
get the ID of the message
Value< uint8_t > max_climb_angle
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Value< uint8_t > gyro_soft_lpf_hz
virtual ID id() const override
get the ID of the message
virtual ID id() const override
get the ID of the message
Value< uint8_t > throttle_mid
virtual ID id() const override
get the ID of the message
Value< uint16_t > dterm_soft_notch_hz
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
std::set< std::string > features
Value< uint16_t > time_alarm
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Value< uint16_t > mAh_drawn
Value< uint8_t > disarm_kill_switch
virtual ID id() const override
get the ID of the message
virtual ID id() const override
get the ID of the message
Value< uint8_t > battery_voltage
Value< uint16_t > deadband3d_high
Value< uint16_t > heading
Value< uint8_t > video_system
Value< uint16_t > min_command
SetRcDeadband(FirmwareVariant v)
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Value< uint8_t > protocol
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
virtual ID id() const override
get the ID of the message
SetMixer(FirmwareVariant v)
Value< uint8_t > mode_activation_condition_idx
Value< float > w_xy_gps_v
Value< uint16_t > current_offset
std::vector< CfSerialConfigSettings > configs
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
AccCalibration(FirmwareVariant v)
Value< uint16_t > loop_time
virtual ID id() const override
get the ID of the message
bool hasOpticalFlow() const
Value< uint16_t > cruise_throttle
Value< uint8_t > device_type
virtual ID id() const override
get the ID of the message
Value< std::string > setting_name
CommonSetMotorMixer(FirmwareVariant v)
Value< uint8_t > hw_baro_status
Value< uint16_t > hover_throttle
Value< uint8_t > esc_mode
Value< uint8_t > setpointRelaxRatio
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Value< uint16_t > min_throttle
DATA_TYPE expected_data_type
virtual ID id() const override
get the ID of the message
virtual ID id() const override
get the ID of the message
NavStatus(FirmwareVariant v)
Value< uint8_t > throttle_dyn_pid
Value< uint8_t > rtc_date_time_status
virtual ID id() const override
get the ID of the message
Value< uint16_t > arming_flags
bool set_freq(uint8_t band, uint8_t channel)
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
ActiveBoxes(FirmwareVariant v)
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Value< std::string > setting_name
Value< uint8_t > procedure
virtual ID id() const override
get the ID of the message
virtual ID id() const override
get the ID of the message
SetLedColors(FirmwareVariant v)
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
virtual ID id() const override
get the ID of the message
virtual ID id() const override
get the ID of the message
Value< uint8_t > recovery_delay
Value< uint16_t > motor_pwm_rate
SetModeRange(FirmwareVariant v)
Value< uint16_t > gyro_soft_notch_hz_1
Value< uint8_t > max_bank_angle
Value< int16_t > int16_val
Value< uint8_t > rate_denom
virtual ID id() const override
get the ID of the message
Value< uint16_t > mincheck
SonarAltitude(FirmwareVariant v)
Value< uint8_t > kill_switch
Value< uint8_t > last_error
Value< uint8_t > use_unsynced_pwm
virtual std::ostream & print(std::ostream &s) const override
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Value< uint16_t > cycle_time
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
virtual ID id() const override
get the ID of the message
std::vector< Value< ServoMixRule > > rules
Value< uint16_t > max_auto_speed
Value< uint8_t > pitch_to_throttle
Value< uint8_t > comms_capabilites
bool unpack_from(const ByteVector &data)
ServoConf(FirmwareVariant v)
Value< uint8_t > osd_flags
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
std::array< Value< int16_t >, 3 > mag
AdvancedConfig(FirmwareVariant v)
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Value< uint16_t > currnet_scale
NavPosHold(FirmwareVariant v)
bool hasAccelerometer() const
SetPositionEstimationConfig(FirmwareVariant v)
Value< uint8_t > cell_max_dV
Value< uint16_t > fw_roll_angle
virtual ID id() const override
get the ID of the message
virtual ID id() const override
get the ID of the message
Value< uint8_t > rth_climb_ignore_emerg
Value< uint32_t > beeper_off_mask
static const size_t LED_MAX_STRIP_LENGTH
Value< float > baro_altitude
virtual ID id() const override
get the ID of the message
Value< std::string > shortGitRevision
Value< uint8_t > min_distance_procedure
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
std::array< uint8_t, LED_SPECIAL_COLOR_COUNT > special_colors
PidNames(FirmwareVariant v)
bool pack(const T &val)
Packs integer types into the ByteVector. Ensures little endian packing.
RcTuning(FirmwareVariant v)
Value< uint8_t > pid_process_denom
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
virtual ID id() const override
get the ID of the message
virtual ID id() const override
get the ID of the message
Value< uint8_t > rx_spi_protocol
virtual std::ostream & print(std::ostream &s) const override
Value< uint8_t > rangefinder_hardware
Value< std::string > string_val
virtual ID id() const override
get the ID of the message
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Value< uint32_t > altHold
LedStripConfigs(FirmwareVariant v)
Value< uint8_t > capacity_units
std::vector< CfSerialConfigSettings > configs
bool pack_into(ByteVector &data) const
Value< uint8_t > mission_action
SetInavPid(FirmwareVariant v)
Value< uint16_t > functionMask
Value< uint16_t > airModeActivateThreshold
Value< uint8_t > rx_spi_rf_channel_count
Value< float > ground_speed
Value< uint8_t > serialrx_provider
virtual std::ostream & print(std::ostream &s) const override
Value< uint32_t > capacity_critical
CurrentMeters(FirmwareVariant v)
bool has(const Capability &cap) const
InavAirSpeed(FirmwareVariant v)
MotorPins(FirmwareVariant v)
Value< uint16_t > i2c_errors
SensorStatus(FirmwareVariant v)
Value< float > powerMeterSum
Value< uint16_t > acc_gain_z
virtual ID id() const override
get the ID of the message
virtual ID id() const override
get the ID of the message
Value< float > voltage_scale
Value< uint8_t > rcInterpolation
Value< uint16_t > acc_gain_x
BlackboxConfig(FirmwareVariant v)
OsdCharWrite(FirmwareVariant v)
RawImu(FirmwareVariant v)
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
std::vector< uint16_t > channels
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
virtual std::ostream & print(std::ostream &s) const override
std::ostream & print(std::ostream &s) const
virtual ID id() const override
get the ID of the message
Value< uint32_t > uint32_val
BatteryState(FirmwareVariant v)
Value< uint8_t > reserved
InavSetMisc(FirmwareVariant v)
virtual ID id() const override
get the ID of the message
virtual ID id() const override
get the ID of the message
std::array< uint16_t, OSD_ITEM_COUNT > item_pos
Value< uint16_t > frequency
SetBox(FirmwareVariant v)
Value< uint32_t > free_space_kb
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
RthAndLandConfig(FirmwareVariant v)
SetPidAdvanced(FirmwareVariant v)
Value< uint16_t > max_auto_climb_rate
FirmwareVariant
Enum of firmware variants.
Value< uint8_t > hw_gyro_status
PidAdvanced(FirmwareVariant v)
Value< uint8_t > hw_gps_status
bool consume(std::size_t count) const
Manually consumes data, thus skipping the values.
CompassConfig(FirmwareVariant v)
Attitude(FirmwareVariant v)
Value< uint8_t > scale_dV
Value< uint16_t > mAh_drawn
Value< uint16_t > deadband3d_low
Value< uint16_t > directionToHome
SetCompassConfig(FirmwareVariant v)
InavSetRateProfile(FirmwareVariant v)
Value< uint16_t > attitude_task_frequency
DataflashSummary(FirmwareVariant v)
SetBoardAlignment(FirmwareVariant v)
Value< uint16_t > uint16_val
virtual ID id() const override
get the ID of the message
Value< uint8_t > current_type
SetMotor3dConf(FirmwareVariant v)
SetPid(FirmwareVariant v)
Value< uint16_t > altitude
Displayport(FirmwareVariant v)
virtual ID id() const override
get the ID of the message
Value< int16_t > int16_val
Value< uint16_t > gyro_soft_notch_cutoff_2
CommonMotorMixer(FirmwareVariant v)
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
std::array< HsvColor, LED_CONFIGURABLE_COLOR_COUNT > colors
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
bool hasMagnetometer() const
Value< uint16_t > alt_alarm
virtual ID id() const override
get the ID of the message
Value< std::string > buildDate
CameraControl(FirmwareVariant v)
Value< uint8_t > cell_min_dV
virtual ID id() const override
get the ID of the message
Value< uint8_t > baro_hardware
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
SetFwConfig(FirmwareVariant v)
ImuSI(RawImu raw, const float acc_1g, const float gyro_unit, const float magn_gain, const float si_unit_1g)
Value< uint16_t > min_command
Value< uint8_t > power_idx
virtual ID id() const override
get the ID of the message
Value< uint16_t > current_meter_scale
Value< std::string > buildTime
virtual ID id() const override
get the ID of the message
bool hasBarometer() const
virtual std::ostream & print(std::ostream &s) const override
virtual ID id() const override
get the ID of the message
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
CommonSetting(FirmwareVariant v)
Value< uint32_t > read_address
Value< uint32_t > sectors
Value< uint16_t > deadband3d_throttle
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
virtual ID id() const override
get the ID of the message
Value< uint16_t > yawItermIgnoreRate
SetFeature(FirmwareVariant v)
static const size_t N_SERVO
Value< uint8_t > rcInterpolationInterval
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
virtual ID id() const override
get the ID of the message
Value< uint16_t > version
virtual ID id() const override
get the ID of the message
Value< uint16_t > p_ratio
Value< uint16_t > acc_gain_y
Value< uint8_t > rate_num
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Value< uint8_t > receiverType
std::ostream & print(std::ostream &s) const
virtual ID id() const override
get the ID of the message
std::array< Value< float >, 3 > mag
Value< uint8_t > dterm_filter_type
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
GpsStatistics(FirmwareVariant v)
std::unique_ptr< ByteVector > ByteVectorUptr
virtual ID id() const override
get the ID of the message
BoxIds(FirmwareVariant v)
SetLedStripConfig(FirmwareVariant v)
CommonSetSetting(FirmwareVariant v)
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Value< uint16_t > gyro_soft_notch_hz_2
Value< uint16_t > max_throttle
GpsConfig(FirmwareVariant v)
Value< uint16_t > dist_alarm
std::array< adjustmentRange, MAX_ADJUSTMENT_RANGE_COUNT > ranges
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Value< uint16_t > cell_warning
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
AccTrim(FirmwareVariant v)
Value< uint8_t > stabilized_rate_r
Value< uint16_t > min_throttle
Value< uint16_t > acc_zero_z
SelectSetting(FirmwareVariant v)
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Value< uint32_t > reserved2
BoxNames(FirmwareVariant v)
FwConfig(FirmwareVariant v)
std::array< uint8_t, MAX_MAPPABLE_RX_INPUTS > map
virtual std::ostream & print(std::ostream &s) const override
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Value< uint16_t > dterm_lpf_hz
Value< uint8_t > throttle_rc_expo
Value< uint8_t > acc_hardware
virtual ID id() const override
get the ID of the message
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
static const size_t BOARD_IDENTIFIER_LENGTH
ServoMixRules(FirmwareVariant v)
virtual ID id() const override
get the ID of the message
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Value< uint8_t > vbatPidCompensation
SetBatteryConfig(FirmwareVariant v)
FcVersion(FirmwareVariant v)
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Value< uint8_t > patch_level
virtual ID id() const override
get the ID of the message
Value< uint8_t > yaw_deadband
virtual ID id() const override
get the ID of the message
virtual ID id() const override
get the ID of the message
virtual ID id() const override
get the ID of the message
virtual ID id() const override
get the ID of the message
virtual ID id() const override
get the ID of the message
Value< uint8_t > heading_hold_rate_limit
Value< uint8_t > rssi_channel
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
std::vector< std::string > box_names
ModeRanges(FirmwareVariant v)
virtual ID id() const override
get the ID of the message
bool pack_into(ByteVector &data) const
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
virtual ID id() const override
get the ID of the message
Value< uint8_t > wp_count
WriteEEPROM(FirmwareVariant v)
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
virtual ID id() const override
get the ID of the message
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Value< uint8_t > axis_calibration_flags
BfConfig(FirmwareVariant v)
virtual std::ostream & print(std::ostream &s) const override
Value< uint8_t > gpsBaudrateIndx
virtual std::ostream & print(std::ostream &s) const override
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Value< uint16_t > current_scale
Value< uint8_t > led_aux_channel
Value< uint8_t > NAV_error
virtual ID id() const override
get the ID of the message
Value< float > w_z_baro_p
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Value< uint16_t > tz_offset
virtual std::ostream & print(std::ostream &s) const override
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
SetMotorConfig(FirmwareVariant v)
CfSerialConfig(FirmwareVariant v)
virtual ID id() const override
get the ID of the message
virtual std::ostream & print(std::ostream &s) const override
Value< uint8_t > rth_allow_landing
virtual ID id() const override
get the ID of the message
bool pack_into(ByteVector &data) const
Value< uint16_t > cell_min
std::set< std::string > features
Value< uint8_t > hardware_healthy
static const size_t LED_DIRECTION_COUNT
Value< uint8_t > manual_rate_r
virtual ID id() const override
get the ID of the message
SensorAlignment(FirmwareVariant v)
Value< uint16_t > dterm_soft_notch_cutoff
virtual ID id() const override
get the ID of the message
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
SetRxConfig(FirmwareVariant v)
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
static const size_t MAX_SIMULTANEOUS_ADJUSTMENT_COUNT
Value< uint16_t > avg_system_load_pct
Value< uint16_t > voltage_scale
std::array< Value< int16_t >, 3 > gyro
static const std::vector< std::string > FEATURES
virtual ID id() const override
get the ID of the message
virtual ID id() const override
get the ID of the message
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Value< uint8_t > rssi_source
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
static const size_t BUILD_DATE_LENGTH
Value< uint16_t > time_alarm
BoardName(FirmwareVariant v)
BatteryConfig(FirmwareVariant v)
SetMisc(FirmwareVariant v)
Value< uint8_t > provider
V2Frame(FirmwareVariant v)
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
static const size_t LED_MODE_COUNT
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
PidController(FirmwareVariant v)
LoopTime(FirmwareVariant v)
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
virtual ID id() const override
get the ID of the message
virtual ID id() const override
get the ID of the message
static const size_t MAX_MAPPABLE_RX_INPUTS
Value< uint16_t > gyro_soft_notch_cutoff_1
virtual ID id() const override
get the ID of the message
SetAccTrim(FirmwareVariant v)
std::vector< CurrentMeter > meters
virtual std::ostream & print(std::ostream &s) const override
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Value< uint16_t > throttle_pa_breakpoint
Value< uint8_t > auto_disarm_delay
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
bool hasAccelerometer() const
virtual std::ostream & print(std::ostream &s) const override
Value< uint8_t > pwm_inversion
Value< uint16_t > fw_yaw_rate
Value< uint8_t > motor_count
FilterConfig(FirmwareVariant v)
virtual std::ostream & print(std::ostream &s) const override
Value< uint32_t > total_space_kb
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Value< uint16_t > distanceToHome
Value< uint8_t > gyro_sync
std::array< Value< uint8_t >, 3 > rcExpo
Value< std::string > identifier
Value< uint8_t > hw_rangefinder_status
Value< uint8_t > fpvCamAngleDegrees
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Value< uint8_t > pitot_hardware
Value< uint16_t > acc_task_frequency
uint8_t nav_rth_takeoff_heading
Value< uint16_t > amperage
RcDeadband(FirmwareVariant v)
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Reboot(FirmwareVariant v)
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
virtual std::ostream & print(std::ostream &s) const override
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
virtual ID id() const override
get the ID of the message
SetNavPosHold(FirmwareVariant v)
bool hasOpticalFlow() const
virtual ID id() const override
get the ID of the message
virtual ID id() const override
get the ID of the message
VtxConfig(FirmwareVariant v)
Value< uint8_t > vbatmincellvoltage
virtual ID id() const override
get the ID of the message
Value< float > mag_declination
WpMissionLoad(FirmwareVariant v)
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Value< uint16_t > emerg_descent_rate
SdcardSummary(FirmwareVariant v)
virtual ID id() const override
get the ID of the message
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Value< uint16_t > battery_cap_warn
Value< uint8_t > opflow_hardware
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
std::array< uint8_t, 54 > font_data
std::array< uint16_t, N_MOTOR > motor
std::array< Value< int16_t >, 3 > acc
LedStripModecolor(FirmwareVariant v)
std::array< Value< float >, 3 > acc
Value< uint8_t > gyro_align
virtual ID id() const override
get the ID of the message
SetRthAndLandConfig(FirmwareVariant v)
Value< uint8_t > throttle_rc_mid
SetSensorAlignment(FirmwareVariant v)
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Status(FirmwareVariant v)
Value< uint8_t > alt_hold_deadband
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Value< uint8_t > channel_count
InavSetBatteryConfig(FirmwareVariant v)
SetLedStripModecolor(FirmwareVariant v)
SetArmingDisabled(FirmwareVariant v)
std::set< size_t > box_mode_flags
InavRateProfile(FirmwareVariant v)
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Value< uint8_t > mspBaudrateIndx
Value< uint16_t > throttle
Value< bool > use_gps_vel_NED
SetServoConf(FirmwareVariant v)
ApiVersion(FirmwareVariant v)
Value< uint16_t > yaw_p_limit
virtual ID id() const override
get the ID of the message
LedColors(FirmwareVariant v)
virtual ID id() const override
get the ID of the message
Value< uint8_t > auto_config
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
virtual ID id() const override
get the ID of the message
std::array< Value< uint8_t >, 3 > rcRates
Value< uint8_t > led_strip_aux_channel
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
virtual ID id() const override
get the ID of the message
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
std::ostream & rxConfigPrint(std::ostream &s) const
PositionEstimationConfig(FirmwareVariant v)
virtual ID id() const override
get the ID of the message
virtual ID id() const override
get the ID of the message
CopyProfile(FirmwareVariant v)
SetOsdVideoConfig(FirmwareVariant v)
Value< uint8_t > voltageMeterSource
SetLoopTime(FirmwareVariant v)
Value< uint8_t > provider
virtual ID id() const override
get the ID of the message
static const size_t BUILD_TIME_LENGTH
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
virtual ID id() const override
get the ID of the message
Value< uint16_t > land_slowdown_minalt
virtual std::ostream & print(std::ostream &s) const override
Value< uint8_t > gyro_lpf
virtual ID id() const override
get the ID of the message
Value< uint16_t > min_throttle
Value< uint8_t > vbatmaxcellvoltage
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
virtual ID id() const override
get the ID of the message
Value< uint16_t > last_msg_dt
FcVariant(FirmwareVariant v)
Value< uint16_t > flow_rate_x
virtual ID id() const override
get the ID of the message
uint8_t nav_controls_heading
virtual ID id() const override
get the ID of the message
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Value< uint16_t > failsafe_throttle
Value< uint16_t > cell_max
MagCalibration(FirmwareVariant v)
Value< uint16_t > max_throttle
virtual ID id() const override
get the ID of the message
GpsSvInfo(FirmwareVariant v)
DebugMessage(FirmwareVariant v)
std::ostream & operator<<(std::ostream &s, const msp::msg::ImuSI &val)
virtual ID id() const override
get the ID of the message
bool hasBarometer() const
Value< uint32_t > reversed_sources
Value< std::string > build_date
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
virtual ID id() const override
get the ID of the message
Value< uint16_t > dist_alarm
Value< uint8_t > max_dive_angle
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Value< uint16_t > land_descent_rate
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Value< uint16_t > rth_altitude
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
virtual std::ostream & print(std::ostream &s) const override
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Value< uint8_t > rssi_channel
Value< uint8_t > uint8_val
virtual ID id() const override
get the ID of the message
bool unpack_from(const ByteVector &data)
Value< uint16_t > acc_zero_x
static const size_t GIT_SHORT_REVISION_LENGTH
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
virtual ID id() const override
get the ID of the message
SetTxInfo(FirmwareVariant v)
Value< uint8_t > nav_flag
Reserve1(FirmwareVariant v)
Value< uint8_t > pit_mode
Value< uint16_t > mAh_drawn
SetCurrentMeterConfig(FirmwareVariant v)
Value< uint16_t > battery_cap_warn
SensorConfig(FirmwareVariant v)
Value< uint8_t > mag_hardware
Value< uint16_t > throttle_low_delay
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
std::vector< RxFailChannelSettings > channels
std::vector< EscData > esc_data
Value< uint8_t > hw_compass_status
Value< uint32_t > total_size
Value< uint8_t > beacon_tone
bool pack_into(ByteVector &data) const
virtual ID id() const override
get the ID of the message
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
FailsafeConfig(FirmwareVariant v)
virtual std::ostream & print(std::ostream &s) const override
SetOsdConfig(FirmwareVariant v)
virtual ID id() const override
get the ID of the message
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Value< uint8_t > range_startStep
CommonTz(FirmwareVariant v)
RawGPS(FirmwareVariant v)
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
virtual ID id() const override
get the ID of the message
CalibrationData(FirmwareVariant v)
virtual std::ostream & print(std::ostream &s) const override
Value< uint16_t > min_rth_distance
Value< uint32_t > uint32_val
uint8_t dont_reset_home_at_arm
virtual ID id() const override
get the ID of the message
virtual ID id() const override
get the ID of the message
Value< uint8_t > stabilized_rate_y
std::ostream & printRxMapSettings(std::ostream &s) const
virtual ID id() const override
get the ID of the message
Value< uint32_t > packet_count
virtual std::ostream & print(std::ostream &s) const override
Value< uint8_t > profile_type
virtual ID id() const override
get the ID of the message
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Value< uint8_t > rth_climb_first
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Value< uint8_t > provider
virtual ID id() const override
get the ID of the message
SetRxFailConfigs(FirmwareVariant v)
virtual ID id() const override
get the ID of the message
EscSensorData(FirmwareVariant v)
Value< uint16_t > deadband3d_high
Value< ServoMixRule > rule
SetRtc(FirmwareVariant v)
virtual std::ostream & print(std::ostream &s) const override
Value< uint16_t > current_meter_offset
virtual ID id() const override
get the ID of the message
virtual ID id() const override
get the ID of the message
Value< uint32_t > capacity_warning
WpMissionSave(FirmwareVariant v)
bool set() const
Queries if the data has been set.
Value< float > mag_declination
Value< uint16_t > rth_abort_threshold
SetVoltageMeterConfig(FirmwareVariant v)
Value< uint8_t > stabilized_rc_expo
SetBlackboxConfig(FirmwareVariant v)
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
static const size_t MAX_NAME_LENGTH
Value< uint16_t > mag_declination
virtual ID id() const override
get the ID of the message
bool imu_small_angle_valid
virtual ID id() const override
get the ID of the message
uint16_t nav_max_altitude
Value< uint8_t > manual_rc_expo
virtual std::ostream & print(std::ostream &s) const override
virtual ID id() const override
get the ID of the message
Value< uint8_t > rth_tail_first
ArmingConfig(FirmwareVariant v)
InavOpticalFlow(FirmwareVariant v)
Value< uint16_t > amperage
Value< std::string > name
std::vector< uint8_t >::iterator unpacking_iterator()
Gives an iterator to the next element ready for unpacking.
virtual ID id() const override
get the ID of the message
Value< uint8_t > startStep
Value< uint8_t > forward_from_channel
Analog(FirmwareVariant v)
Value< uint8_t > auxSwitchChannelIndex
Value< uint8_t > adjustmentIndex
SetServoMixRule(FirmwareVariant v)
std::array< Value< uint8_t >, 3 > rates
virtual ID id() const override
get the ID of the message
virtual ID id() const override
get the ID of the message
Value< uint8_t > async_mode
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
BeeperConfig(FirmwareVariant v)
Value< uint8_t > esc_count
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Value< uint8_t > esc_port_index
Value< uint16_t > gyro_cycle_time
Value< uint8_t > video_system
Value< uint16_t > cell_max
Value< uint8_t > manual_rc_yaw_expo
Value< uint8_t > currentMeterSource
virtual std::ostream & print(std::ostream &s) const override
Value< uint32_t > rx_spi_id
Value< uint16_t > acc_zero_y
InavAnalog(FirmwareVariant v)
std::vector< VoltageMeter > meters
SetRawRc(FirmwareVariant v)
Value< uint8_t > gps_baudrate
Value< uint16_t > rx_max_usec
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
WayPoint(FirmwareVariant v)
Value< uint8_t > cfg_index
virtual std::ostream & print(std::ostream &s) const override
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Value< uint8_t > current_profile
Value< uint8_t > gps_ubx_sbas
virtual ID id() const override
get the ID of the message
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Value< uint8_t > aux_channel_index
Value< uint16_t > fw_pitch_angle
SetPidController(FirmwareVariant v)
virtual ID id() const override
get the ID of the message
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Value< uint8_t > range_endStep
Value< uint8_t > transponder_count
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
virtual ID id() const override
get the ID of the message
virtual std::ostream & print(std::ostream &s) const override
Value< uint8_t > dynamic_throttle_pid
Value< float > dterm_setpoint_weight
Value< uint16_t > capacity
virtual ID id() const override
get the ID of the message
Value< uint8_t > rssi_alarm
virtual ID id() const override
get the ID of the message
BoardAlignment(FirmwareVariant v)
virtual ID id() const override
get the ID of the message
std::array< uint32_t, LED_MAX_STRIP_LENGTH > configs
SetResetCurrPid(FirmwareVariant v)
virtual ID id() const override
get the ID of the message
PassthroughSerial(FirmwareVariant v)
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Value< uint8_t > mode_idx
virtual std::ostream & print(std::ostream &s) const override
Value< uint8_t > dest_profile_idx
Value< uint8_t > wp_capabilites
virtual ID id() const override
get the ID of the message
std::vector< std::array< std::set< SwitchPosition >, NAUX > > box_pattern
std::vector< GpsSvInfoSettings > sv_info
OsdVideoConfig(FirmwareVariant v)
Value< bool > wp_list_valid
virtual ID id() const override
get the ID of the message
Value< uint32_t > altitude_cm
Value< uint8_t > control_rate_profile
bool unpack_from(const ByteVector &data)
Value< uint16_t > body_rate_y
std::ostream & print(std::ostream &s) const
Value< uint16_t > pidSumLimit
Value< uint8_t > hw_pitometer_status
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Value< uint8_t > cell_count
Value< uint16_t > max_throttle
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Value< uint8_t > telemetryBaudrateIndx
Value< uint8_t > NAV_state
virtual ID id() const override
get the ID of the message
Value< uint32_t > axisAccelerationLimitYaw
DataflashErase(FirmwareVariant v)
SetBoardName(FirmwareVariant v)
std::string armingFlagToString(uint32_t flag)
virtual ID id() const override
get the ID of the message
virtual ID id() const override
get the ID of the message
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Value< uint8_t > manual_rate_y
virtual ID id() const override
get the ID of the message
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Value< uint16_t > land_slowdown_maxalt
SetMotor(FirmwareVariant v)
Value< uint16_t > failsafe_throttle
virtual ID id() const override
get the ID of the message
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
virtual std::ostream & print(std::ostream &s) const override
Value< uint16_t > maxcheck
std::size_t unpacking_remaining() const
Returns the number of bytes still avialable for unpacking.
SetNavConfig(FirmwareVariant v)
std::array< box_description, MAX_MODE_ACTIVATION_CONDITION_COUNT > boxes
RxConfig(FirmwareVariant v)
ResetConfig(FirmwareVariant v)
virtual ID id() const override
get the ID of the message
std::array< std::array< uint8_t, LED_DIRECTION_COUNT >, LED_MODE_COUNT > mode_colors
virtual ID id() const override
get the ID of the message
virtual ID id() const override
get the ID of the message
Value< uint32_t > timeouts
SetHeading(FirmwareVariant v)
virtual std::ostream & print(std::ostream &s) const override
Value< uint8_t > motor_pwm_protocol
Value< uint8_t > adjustmentFunction
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Value< uint16_t > uint16_val
Value< uint8_t > data_length
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Value< uint16_t > capacity_mAh
std::vector< TransponderConfigSettings > transponder_data
SetGpsConfig(FirmwareVariant v)
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
virtual ID id() const override
get the ID of the message
Value< uint8_t > gyro_sync_denom
Value< uint16_t > cell_warning
Value< uint16_t > max_throttle
VoltageMeterConfig(FirmwareVariant v)
static const size_t MAX_MODE_ACTIVATION_CONDITION_COUNT
Value< std::string > name
virtual ID id() const override
get the ID of the message
virtual ID id() const override
get the ID of the message
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Feature(FirmwareVariant v)
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Value< uint8_t > cell_warning_dV
static const size_t MAX_ADJUSTMENT_RANGE_COUNT
virtual ID id() const override
get the ID of the message
Value< uint16_t > avg_system_load_pct
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Value< uint8_t > max_profiles
Value< uint8_t > user_control_mode
virtual ID id() const override
get the ID of the message
Value< uint16_t > deadband3d_low
Value< uint16_t > stick_motion_threshold
CurrentMeterConfig(FirmwareVariant v)
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Value< uint8_t > msp_version
Set4WayIF(FirmwareVariant v)
Value< uint8_t > temperature
virtual ID id() const override
get the ID of the message
SetVtxConfig(FirmwareVariant v)
Value< uint16_t > min_distance
AdjustmentRanges(FirmwareVariant v)
SetRxMap(FirmwareVariant v)
Value< uint16_t > max_manual_speed
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
SetArmingConfig(FirmwareVariant v)
virtual ID id() const override
get the ID of the message
Value< uint8_t > acc_align
virtual std::ostream & print(std::ostream &s) const override
Value< uint8_t > capacity_units
Value< uint8_t > supported
virtual ByteVectorUptr encode() const override
Encode all data into a ByteVector.
Value< uint32_t > reserved1
virtual ID id() const override
get the ID of the message
std::array< HsvColor, LED_CONFIGURABLE_COLOR_COUNT > colors
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Value< uint8_t > GPS_mode
Value< uint8_t > disableRunawayTakeoff
Value< uint16_t > rx_min_usec
Value< uint16_t > servo_pwm_rate
InavStatus(FirmwareVariant v)
virtual bool decode(const ByteVector &data) override
Decode message contents from a ByteVector.
Value< uint16_t > flow_rate_y
Value< uint8_t > mission_number
Value< uint16_t > loiter_radius
Value< uint32_t > feature_mask
BfBuildInfo(FirmwareVariant v)
virtual ID id() const override
get the ID of the message
virtual ID id() const override
get the ID of the message
Value< uint16_t > cell_min
Value< uint8_t > uint8_val
Value< uint8_t > controller_id
Value< uint8_t > itermThrottleGain
RxFailConfigs(FirmwareVariant v)
uint16_t safe_wp_distance
Value< std::string > string_val