mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
ArduCopter: implement parameter CopyFieldsFrom and use it
This commit is contained in:
parent
798cc2633f
commit
6816ea3fe5
@ -264,38 +264,33 @@ const AP_Param::Info Copter::var_info[] = {
|
|||||||
GSCALAR(flight_mode1, "FLTMODE1", (uint8_t)FLIGHT_MODE_1),
|
GSCALAR(flight_mode1, "FLTMODE1", (uint8_t)FLIGHT_MODE_1),
|
||||||
|
|
||||||
// @Param: FLTMODE2
|
// @Param: FLTMODE2
|
||||||
|
// @CopyFieldsFrom: FLTMODE1
|
||||||
// @DisplayName: Flight Mode 2
|
// @DisplayName: Flight Mode 2
|
||||||
// @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >1230, <= 1360
|
// @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >1230, <= 1360
|
||||||
// @CopyValuesFrom: FLTMODE1
|
|
||||||
// @User: Standard
|
|
||||||
GSCALAR(flight_mode2, "FLTMODE2", (uint8_t)FLIGHT_MODE_2),
|
GSCALAR(flight_mode2, "FLTMODE2", (uint8_t)FLIGHT_MODE_2),
|
||||||
|
|
||||||
// @Param: FLTMODE3
|
// @Param: FLTMODE3
|
||||||
|
// @CopyFieldsFrom: FLTMODE1
|
||||||
// @DisplayName: Flight Mode 3
|
// @DisplayName: Flight Mode 3
|
||||||
// @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >1360, <= 1490
|
// @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >1360, <= 1490
|
||||||
// @CopyValuesFrom: FLTMODE1
|
|
||||||
// @User: Standard
|
|
||||||
GSCALAR(flight_mode3, "FLTMODE3", (uint8_t)FLIGHT_MODE_3),
|
GSCALAR(flight_mode3, "FLTMODE3", (uint8_t)FLIGHT_MODE_3),
|
||||||
|
|
||||||
// @Param: FLTMODE4
|
// @Param: FLTMODE4
|
||||||
|
// @CopyFieldsFrom: FLTMODE1
|
||||||
// @DisplayName: Flight Mode 4
|
// @DisplayName: Flight Mode 4
|
||||||
// @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >1490, <= 1620
|
// @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >1490, <= 1620
|
||||||
// @CopyValuesFrom: FLTMODE1
|
|
||||||
// @User: Standard
|
|
||||||
GSCALAR(flight_mode4, "FLTMODE4", (uint8_t)FLIGHT_MODE_4),
|
GSCALAR(flight_mode4, "FLTMODE4", (uint8_t)FLIGHT_MODE_4),
|
||||||
|
|
||||||
// @Param: FLTMODE5
|
// @Param: FLTMODE5
|
||||||
|
// @CopyFieldsFrom: FLTMODE1
|
||||||
// @DisplayName: Flight Mode 5
|
// @DisplayName: Flight Mode 5
|
||||||
// @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >1620, <= 1749
|
// @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >1620, <= 1749
|
||||||
// @CopyValuesFrom: FLTMODE1
|
|
||||||
// @User: Standard
|
|
||||||
GSCALAR(flight_mode5, "FLTMODE5", (uint8_t)FLIGHT_MODE_5),
|
GSCALAR(flight_mode5, "FLTMODE5", (uint8_t)FLIGHT_MODE_5),
|
||||||
|
|
||||||
// @Param: FLTMODE6
|
// @Param: FLTMODE6
|
||||||
|
// @CopyFieldsFrom: FLTMODE1
|
||||||
// @DisplayName: Flight Mode 6
|
// @DisplayName: Flight Mode 6
|
||||||
// @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >=1750
|
// @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >=1750
|
||||||
// @CopyValuesFrom: FLTMODE1
|
|
||||||
// @User: Standard
|
|
||||||
GSCALAR(flight_mode6, "FLTMODE6", (uint8_t)FLIGHT_MODE_6),
|
GSCALAR(flight_mode6, "FLTMODE6", (uint8_t)FLIGHT_MODE_6),
|
||||||
|
|
||||||
// @Param: FLTMODE_CH
|
// @Param: FLTMODE_CH
|
||||||
|
Loading…
Reference in New Issue
Block a user