@@ -162,7 +162,7 @@ extern const AP_HAL::HAL& hal;
162
162
#endif
163
163
164
164
const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
165
- #if HAL_HAVE_SERIAL0
165
+ #if HAL_HAVE_SERIAL0_PARAMS
166
166
// @Param: 0_BAUD
167
167
// @DisplayName: Serial0 baud rate
168
168
// @Description: The baud rate used on the USB console. Most stm32-based boards can support rates of up to 1500. If you setup a rate you cannot support and then can't connect to your board you should load a firmware from a different vehicle type. That will reset all your parameters to defaults.
@@ -179,7 +179,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
179
179
AP_GROUPINFO (" 0_PROTOCOL" , 11 , AP_SerialManager, state[0 ].protocol , SerialProtocol_MAVLink2),
180
180
#endif
181
181
182
- #if HAL_HAVE_SERIAL1
182
+ #if HAL_HAVE_SERIAL1_PARAMS
183
183
// @Param: 1_PROTOCOL
184
184
// @DisplayName: Telem1 protocol selection
185
185
// @Description: Control what protocol to use on the Telem1 port. Note that the Frsky options require external converter hardware. See the wiki for details.
@@ -197,7 +197,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
197
197
AP_GROUPINFO (" 1_BAUD" , 2 , AP_SerialManager, state[1 ].baud , DEFAULT_SERIAL1_BAUD),
198
198
#endif
199
199
200
- #if HAL_HAVE_SERIAL2
200
+ #if HAL_HAVE_SERIAL2_PARAMS
201
201
// @Param: 2_PROTOCOL
202
202
// @CopyFieldsFrom: SERIAL1_PROTOCOL
203
203
// @DisplayName: Telemetry 2 protocol selection
@@ -211,7 +211,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
211
211
AP_GROUPINFO (" 2_BAUD" , 4 , AP_SerialManager, state[2 ].baud , DEFAULT_SERIAL2_BAUD),
212
212
#endif
213
213
214
- #if HAL_HAVE_SERIAL3
214
+ #if HAL_HAVE_SERIAL3_PARAMS
215
215
// @Param: 3_PROTOCOL
216
216
// @CopyFieldsFrom: SERIAL1_PROTOCOL
217
217
// @DisplayName: Serial 3 (GPS) protocol selection
@@ -225,7 +225,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
225
225
AP_GROUPINFO (" 3_BAUD" , 6 , AP_SerialManager, state[3 ].baud , DEFAULT_SERIAL3_BAUD),
226
226
#endif
227
227
228
- #if HAL_HAVE_SERIAL4
228
+ #if HAL_HAVE_SERIAL4_PARAMS
229
229
// @Param: 4_PROTOCOL
230
230
// @CopyFieldsFrom: SERIAL1_PROTOCOL
231
231
// @DisplayName: Serial4 protocol selection
@@ -239,7 +239,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
239
239
AP_GROUPINFO (" 4_BAUD" , 8 , AP_SerialManager, state[4 ].baud , DEFAULT_SERIAL4_BAUD),
240
240
#endif
241
241
242
- #if HAL_HAVE_SERIAL5
242
+ #if HAL_HAVE_SERIAL5_PARAMS
243
243
// @Param: 5_PROTOCOL
244
244
// @CopyFieldsFrom: SERIAL1_PROTOCOL
245
245
// @DisplayName: Serial5 protocol selection
@@ -255,7 +255,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
255
255
256
256
// index 11 used by 0_PROTOCOL
257
257
258
- #if HAL_HAVE_SERIAL6
258
+ #if HAL_HAVE_SERIAL6_PARAMS
259
259
// @Param: 6_PROTOCOL
260
260
// @CopyFieldsFrom: SERIAL1_PROTOCOL
261
261
// @DisplayName: Serial6 protocol selection
@@ -269,7 +269,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
269
269
AP_GROUPINFO (" 6_BAUD" , 13 , AP_SerialManager, state[6 ].baud , DEFAULT_SERIAL6_BAUD),
270
270
#endif
271
271
272
- #if HAL_HAVE_SERIAL1
272
+ #if HAL_HAVE_SERIAL1_PARAMS
273
273
// @Param: 1_OPTIONS
274
274
// @DisplayName: Telem1 options
275
275
// @Description: Control over UART options. The InvertRX option controls invert of the receive pin. The InvertTX option controls invert of the transmit pin. The HalfDuplex option controls half-duplex (onewire) mode, where both transmit and receive is done on the transmit wire. The Swap option allows the RX and TX pins to be swapped on STM32F7 based boards.
@@ -279,35 +279,35 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
279
279
AP_GROUPINFO (" 1_OPTIONS" , 14 , AP_SerialManager, state[1 ].options , DEFAULT_SERIAL1_OPTIONS),
280
280
#endif
281
281
282
- #if HAL_HAVE_SERIAL2
282
+ #if HAL_HAVE_SERIAL2_PARAMS
283
283
// @Param: 2_OPTIONS
284
284
// @CopyFieldsFrom: SERIAL1_OPTIONS
285
285
// @DisplayName: Telem2 options
286
286
AP_GROUPINFO (" 2_OPTIONS" , 15 , AP_SerialManager, state[2 ].options , DEFAULT_SERIAL2_OPTIONS),
287
287
#endif
288
288
289
- #if HAL_HAVE_SERIAL3
289
+ #if HAL_HAVE_SERIAL3_PARAMS
290
290
// @Param: 3_OPTIONS
291
291
// @CopyFieldsFrom: SERIAL1_OPTIONS
292
292
// @DisplayName: Serial3 options
293
293
AP_GROUPINFO (" 3_OPTIONS" , 16 , AP_SerialManager, state[3 ].options , DEFAULT_SERIAL3_OPTIONS),
294
294
#endif
295
295
296
- #if HAL_HAVE_SERIAL4
296
+ #if HAL_HAVE_SERIAL4_PARAMS
297
297
// @Param: 4_OPTIONS
298
298
// @CopyFieldsFrom: SERIAL1_OPTIONS
299
299
// @DisplayName: Serial4 options
300
300
AP_GROUPINFO (" 4_OPTIONS" , 17 , AP_SerialManager, state[4 ].options , DEFAULT_SERIAL4_OPTIONS),
301
301
#endif
302
302
303
- #if HAL_HAVE_SERIAL5
303
+ #if HAL_HAVE_SERIAL5_PARAMS
304
304
// @Param: 5_OPTIONS
305
305
// @CopyFieldsFrom: SERIAL1_OPTIONS
306
306
// @DisplayName: Serial5 options
307
307
AP_GROUPINFO (" 5_OPTIONS" , 18 , AP_SerialManager, state[5 ].options , DEFAULT_SERIAL5_OPTIONS),
308
308
#endif
309
309
310
- #if HAL_HAVE_SERIAL6
310
+ #if HAL_HAVE_SERIAL6_PARAMS
311
311
// @Param: 6_OPTIONS
312
312
// @CopyFieldsFrom: SERIAL1_OPTIONS
313
313
// @DisplayName: Serial6 options
@@ -336,7 +336,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
336
336
// @User: Advanced
337
337
AP_GROUPINFO (" _PASSTIMO" , 22 , AP_SerialManager, passthru_timeout, 15 ),
338
338
339
- #if HAL_HAVE_SERIAL7
339
+ #if HAL_HAVE_SERIAL7_PARAMS
340
340
// @Param: 7_PROTOCOL
341
341
// @CopyFieldsFrom: SERIAL1_PROTOCOL
342
342
// @DisplayName: Serial7 protocol selection
@@ -355,7 +355,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
355
355
AP_GROUPINFO (" 7_OPTIONS" , 25 , AP_SerialManager, state[7 ].options , 0 ),
356
356
#endif
357
357
358
- #if HAL_HAVE_SERIAL8
358
+ #if HAL_HAVE_SERIAL8_PARAMS
359
359
// @Param: 8_PROTOCOL
360
360
// @CopyFieldsFrom: SERIAL1_PROTOCOL
361
361
// @DisplayName: Serial8 protocol selection
@@ -374,7 +374,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
374
374
AP_GROUPINFO (" 8_OPTIONS" , 28 , AP_SerialManager, state[8 ].options , 0 ),
375
375
#endif
376
376
377
- #if HAL_HAVE_SERIAL9
377
+ #if HAL_HAVE_SERIAL9_PARAMS
378
378
// @Param: 9_PROTOCOL
379
379
// @CopyFieldsFrom: SERIAL1_PROTOCOL
380
380
// @DisplayName: Serial9 protocol selection
0 commit comments