APM:Libraries
params.h
Go to the documentation of this file.
1 
2 
3 /*
4  // @Param: MOTOR_LAYOUT
5  // @DisplayName: Motor layout scheme
6  // @Description: Selects how motors are numbered
7  // @Values: 0:ArduCopter, 1: Ardupilot with pins 2&3 for servos 2:OpenPilot,3:CleanFlight
8  // @User: Advanced
9  AP_GROUPINFO("_MOTOR_LAYOUT", 0, HAL_F4Light, _motor_layout, 0),
10 
11  // @Param: USE_SOFTSERIAL
12  // @DisplayName: Use SoftwareSerial driver
13  // @Description: Use SoftwareSerial driver instead SoftwareI2C on Input Port pins 7 & 8
14  // @Values: 0:disabled,1:enabled
15  // @User: Advanced
16  AP_GROUPINFO("_USE_SOFTSERIAL", 1, HAL_F4Light, _use_softserial, 0),
17 
18  // @Param: UART_SBUS
19  // @DisplayName: What UART to use as SBUS input
20  // @Description: Allows to use any UART as SBUS input
21  // @Values: 0:disabled,1:UART1, 2:UART2 etc
22  // @User: Advanced
23  AP_GROUPINFO("UART_SBUS", 3, AP_Param_Helper, _uart_sbus, 0), \
24 
25  // @Param: SERVO_MASK
26  // @DisplayName: Servo Mask of Input port
27  // @Description: Enable selected pins of Input port to be used as Servo Out
28  // @Values: 0:disabled,1:enable pin3 (PPM_1), 2: enable pin4 (PPM_2), 4: enable pin5 (UART6_TX) , 8: enable pin6 (UART6_RX), 16: enable pin7, 32: enable pin8
29  // @User: Advanced
30  AP_GROUPINFO("SERVO_MASK", 2, AP_Param_Helper, _servo_mask, 0) \
31 
32  // @Param: CONNECT_COM
33  // @DisplayName: connect to COM port
34  // @Description: Allows to connect USB to arbitrary UART, thus allowing to configure devices on that UARTs. Auto-reset.
35  // @Values: 0:disabled, 1:connect to port 1, 2:connect to port 2, etc
36  // @User: Advanced
37  AP_GROUPINFO("CONNECT_COM", 2, AP_Param_Helper, _connect_com, 0) \
38 
39  // @Param: CONNECT_ESC
40  // @DisplayName: connect to ESC inputs via 4wayIf
41  // @Description: Allows to connect USB to ESC inputs, thus allowing to configure ESC as on 4-wayIf. Auto-reset.
42  // @Values: 0:disabled, 1:connect uartA to ESC, 2: connect uartB to ESC, etc
43  // @User: Advanced
44  AP_GROUPINFO("CONNECT_ESC", 2, AP_Param_Helper, _connect_esc, 0) \
45 
46  // @Param: PWM_TYPE
47  // @DisplayName: PWM protocol used
48  // @Description: Allows to ignore MOT_PWM_TYPE param and set PWM protocol independently
49  // @Values: 0:use MOT_PWM_TYPE, 1:OneShot 2:OneShot125 3:OneShot42 4:PWM125
50  // @User: Advanced
51  AP_GROUPINFO("PWM_TYPE", 7, AP_Param_Helper, _pwm_type, 0)
52 
53  // @Param: RC_INPUT
54  // @DisplayName: Type of RC input
55  // @Description: allows to force specified RC input port
56  // @Values: 0:auto, 1:PPM1 (pin3), 2: PPM2 (pin4) etc
57  // @User: Advanced
58  AP_GROUPINFO("RC_INPUT", 9, AP_Param_Helper, _rc_input, 0)
59 
60  // @Param: AIBAO_FS
61  // @DisplayName: Support FailSafe for Walkera Aibao RC
62  // @Description: Allows to translate of Walkera Aibao RC FailSafe to Ardupilot's failsafe
63  // @Values: 0: not translate, 1:translate
64  // @User: Advanced
65  AP_GROUPINFO("AIBAO_FS", 7, AP_Param_Helper, _aibao_fs, 0)
66 
67  // @Param: RC_FS
68  // @DisplayName: Set time of RC failsafe
69  // @Description: if none of RC channel changes in that time, then failsafe triggers
70  // @Values: 0: turned off, >0 - time in seconds. Good values are starting 60s for digital protocols
71  // @User: Advanced
72  AP_GROUPINFO("RC_FS", 17, AP_Param_Helper, _rc_fs, 0)
73 
74 */
75 
76 // common parameters for all boards
77 #define F4LIGHT_HAL_VARINFO \
78  AP_GROUPINFO("MOTOR_LAYOUT", 1, AP_Param_Helper, _motor_layout, MOTOR_LAYOUT_DEFAULT), \
79  AP_GROUPINFO("SOFTSERIAL", 2, AP_Param_Helper, _use_softserial, 0), \
80  AP_GROUPINFO("UART_SBUS", 3, AP_Param_Helper, _uart_sbus, 0), \
81  AP_GROUPINFO("SERVO_MASK", 4, AP_Param_Helper, _servo_mask, 0), \
82  AP_GROUPINFO("CONNECT_COM", 5, AP_Param_Helper, _connect_com, 0), \
83  AP_GROUPINFO("PWM_TYPE", 7, AP_Param_Helper, _pwm_type, 0), \
84  AP_GROUPINFO("CONNECT_ESC", 6, AP_Param_Helper, _connect_esc, 0), \
85  AP_GROUPINFO("TIME_OFFSET", 8, AP_Param_Helper, _time_offset, 0), \
86  AP_GROUPINFO("CONSOLE_UART", 9, AP_Param_Helper, _console_uart, HAL_CONSOLE_PORT), \
87  AP_GROUPINFO("EE_DEFERRED", 10, AP_Param_Helper, _eeprom_deferred, 0), \
88  AP_GROUPINFO("RC_INPUT", 11, AP_Param_Helper, _rc_input, 0), \
89  AP_GROUPINFO("AIBAO_FS", 12, AP_Param_Helper, _aibao_fs, 0), \
90  AP_GROUPINFO("OVERCLOCK", 13, AP_Param_Helper, _overclock, 0), \
91  AP_GROUPINFO("CORRECT_GYRO", 14, AP_Param_Helper, _correct_gyro, 0), \
92  AP_GROUPINFO("RC_FS", 15, AP_Param_Helper, _rc_fs, 0), \
93  AP_GROUPINFO("BOOT_DFU", 16, AP_Param_Helper, _boot_dfu, 0),
94 
95 
96 // parameters
97 #define F4LIGHT_HAL_PARAMS \
98  AP_Int8 _motor_layout; \
99  AP_Int8 _uart_sbus; \
100  AP_Int8 _use_softserial; \
101  AP_Int8 _servo_mask; \
102  AP_Int8 _connect_com; \
103  AP_Int8 _connect_esc; \
104  AP_Int8 _pwm_type; \
105  AP_Int8 _time_offset; \
106  AP_Int8 _console_uart; \
107  AP_Int8 _eeprom_deferred; \
108  AP_Int8 _rc_input; \
109  AP_Int8 _aibao_fs; \
110  AP_Int8 _overclock; \
111  AP_Int8 _correct_gyro; \
112  AP_Int8 _rc_fs; \
113  AP_Int8 _boot_dfu;