2 * This file is part of Cleanflight and Betaflight.
4 * Cleanflight and Betaflight are free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
10 * Cleanflight and Betaflight are distributed in the hope that they
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
23 // FC configuration (defined by cleanflight v1)
24 #define PG_FAILSAFE_CONFIG 1 // struct OK
25 #define PG_BOARD_ALIGNMENT 2 // struct OK
26 #define PG_GIMBAL_CONFIG 3 // struct OK
27 #define PG_MOTOR_MIXER 4 // two structs mixerConfig_t servoMixerConfig_t
28 #define PG_BLACKBOX_CONFIG 5 // struct OK
29 #define PG_MOTOR_CONFIG 6 // struct OK
30 #define PG_SENSOR_SELECTION_CONFIG 7 // struct OK
31 #define PG_SENSOR_ALIGNMENT_CONFIG 8 // struct OK
32 #define PG_SENSOR_TRIMS 9 // struct OK
33 #define PG_GYRO_CONFIG 10 // PR outstanding, need to think about pid_process_denom
34 #define PG_BATTERY_CONFIG 11 // struct OK
35 #define PG_CONTROL_RATE_PROFILES 12 // struct OK, needs to be split out of rc_controls.h into rate_profile.h
36 #define PG_SERIAL_CONFIG 13 // struct OK
37 #define PG_PID_PROFILE 14 // struct OK, CF differences
38 #define PG_ARMING_CONFIG 16 // structs OK, CF naming differences
39 #define PG_TRANSPONDER_CONFIG 17 // struct OK
40 #define PG_SYSTEM_CONFIG 18 // just has i2c_highspeed
41 #define PG_FEATURE_CONFIG 19 // just has enabledFeatures
42 #define PG_MIXER_CONFIG 20 // Cleanflight has single struct mixerConfig_t, betaflight has mixerConfig_t and servoMixerConfig_t
43 #define PG_SERVO_MIXER 21 // Cleanflight has servoParam_t for each servo, betaflight has single servoParam_t
44 #define PG_IMU_CONFIG 22 // Cleanflight has imuConfig_t, betaflight has imuRuntimeConfig_t with additional parameters
45 #define PG_PROFILE_SELECTION 23 // just contains current_profile_index
46 #define PG_RX_CONFIG 24 // betaflight rxConfig_t contains different values
47 #define PG_RC_CONTROLS_CONFIG 25 // Cleanflight has more parameters in rcControlsConfig_t
48 #define PG_MOTOR_3D_CONFIG 26 // Cleanflight has motor3DConfig_t, betaflight has flight3DConfig_t with more parameters
49 #define PG_LED_STRIP_CONFIG 27 // structs OK
50 #define PG_COLOR_CONFIG 28 // part of led strip, structs OK
51 #define PG_AIRPLANE_CONFIG 29 // struct OK
52 #define PG_GPS_CONFIG 30 // struct OK
53 #define PG_TELEMETRY_CONFIG 31 // betaflight has more and different data in telemetryConfig_t
54 #define PG_FRSKY_TELEMETRY_CONFIG 32 // Cleanflight has split data out of PG_TELEMETRY_CONFIG
55 #define PG_HOTT_TELEMETRY_CONFIG 33 // Cleanflight has split data out of PG_TELEMETRY_CONFIG
56 #define PG_NAVIGATION_CONFIG 34 // structs OK
57 #define PG_ACCELEROMETER_CONFIG 35 // no accelerometerConfig_t in betaflight
58 #define PG_RATE_PROFILE_SELECTION 36 // part of profile in betaflight
59 //#define PG_ADJUSTMENT_PROFILE 37 // array needs to be made into struct
60 #define PG_ADJUSTMENT_RANGE_CONFIG 37
61 #define PG_BAROMETER_CONFIG 38 // structs OK
62 #define PG_THROTTLE_CORRECTION_CONFIG 39
63 #define PG_COMPASS_CONFIG 40 // structs OK
64 #define PG_MODE_ACTIVATION_PROFILE 41 // array needs to be made into struct
65 //#define PG_SERVO_PROFILE 42
66 #define PG_SERVO_PARAMS 42
67 //#define PG_FAILSAFE_CHANNEL_CONFIG 43 // structs OK
68 #define PG_RX_FAILSAFE_CHANNEL_CONFIG 43
69 //#define PG_CHANNEL_RANGE_CONFIG 44 // structs OK
70 #define PG_RX_CHANNEL_RANGE_CONFIG 44
71 #define PG_MODE_COLOR_CONFIG 45 // part of led strip, structs OK
72 #define PG_SPECIAL_COLOR_CONFIG 46 // part of led strip, structs OK
73 #define PG_PILOT_CONFIG 47 // does not exist in betaflight
74 #define PG_MSP_SERVER_CONFIG 48 // does not exist in betaflight
75 #define PG_VOLTAGE_METER_CONFIG 49 // renamed from PG_VOLTAGE_METER_CONFIG // deprecated
76 #define PG_AMPERAGE_METER_CONFIG 50 // renamed from PG_AMPERAGE_METER_CONFIG // deprecated
77 #define PG_DEBUG_CONFIG 51 // does not exist in betaflight
78 #define PG_SERVO_CONFIG 52
79 #define PG_IBUS_TELEMETRY_CONFIG 53 // CF 1.x
80 //#define PG_VTX_CONFIG 54 // CF 1.x
82 // Driver configuration
83 #define PG_DRIVER_PWM_RX_CONFIG 100 // does not exist in betaflight
84 #define PG_DRIVER_FLASHCHIP_CONFIG 101 // does not exist in betaflight
87 // cleanflight v2 specific parameter group ids start at 256
88 #define PG_CURRENT_SENSOR_ADC_CONFIG 256
89 #define PG_CURRENT_SENSOR_VIRTUAL_CONFIG 257
90 #define PG_VOLTAGE_SENSOR_ADC_CONFIG 258
91 #define PG_VTX_SETTINGS_CONFIG 259
94 // betaflight specific parameter group ids start at 500
95 #define PG_BETAFLIGHT_START 500
96 #define PG_MODE_ACTIVATION_OPERATOR_CONFIG 500
97 #define PG_OSD_CONFIG 501
98 #define PG_BEEPER_CONFIG 502
99 #define PG_BEEPER_DEV_CONFIG 503
100 #define PG_PID_CONFIG 504
101 #define PG_STATUS_LED_CONFIG 505
102 #define PG_FLASH_CONFIG 506
103 #define PG_PPM_CONFIG 507
104 #define PG_PWM_CONFIG 508
105 #define PG_SERIAL_PIN_CONFIG 509
106 #define PG_ADC_CONFIG 510
107 #define PG_SDCARD_CONFIG 511
108 #define PG_DISPLAY_PORT_MSP_CONFIG 512
109 #define PG_DISPLAY_PORT_MAX7456_CONFIG 513
110 #define PG_VCD_CONFIG 514
111 #define PG_VTX_CONFIG 515
112 #define PG_SONAR_CONFIG 516
113 #define PG_ESC_SENSOR_CONFIG 517
114 #define PG_I2C_CONFIG 518
115 #define PG_DASHBOARD_CONFIG 519
116 #define PG_SPI_PIN_CONFIG 520
117 #define PG_ESCSERIAL_CONFIG 521
118 #define PG_CAMERA_CONTROL_CONFIG 522
119 #define PG_RX_FRSKY_SPI_CONFIG 523
120 #define PG_MAX7456_CONFIG 524
121 #define PG_FLYSKY_CONFIG 525
122 #define PG_TIME_CONFIG 526
123 #define PG_RANGEFINDER_CONFIG 527 // iNav
124 #define PG_TRICOPTER_CONFIG 528
125 #define PG_PINIO_CONFIG 529
126 #define PG_PINIOBOX_CONFIG 530
127 #define PG_USB_CONFIG 531
128 #define PG_SDIO_CONFIG 532
129 #define PG_DISPLAY_PORT_CRSF_CONFIG 533
130 #define PG_BETAFLIGHT_END 533
133 // OSD configuration (subject to change)
134 #define PG_OSD_FONT_CONFIG 2047
135 #define PG_OSD_VIDEO_CONFIG 2046
136 #define PG_OSD_ELEMENT_CONFIG 2045
139 // 4095 is currently the highest number that can be used for a PGN due to the top 4 bits of the 16 bit value being reserved for the version when the PG is stored in an EEPROM.
140 #define PG_RESERVED_FOR_TESTING_1 4095
141 #define PG_RESERVED_FOR_TESTING_2 4094
142 #define PG_RESERVED_FOR_TESTING_3 4093