mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
Plane: added new SERIAL0_BAUD parameter
this is useful on PX4
This commit is contained in:
parent
af8f576c67
commit
86f667f6cc
@ -87,6 +87,7 @@ public:
|
||||
k_param_sysid_my_gcs,
|
||||
k_param_serial3_baud,
|
||||
k_param_telem_delay,
|
||||
k_param_serial0_baud,
|
||||
|
||||
// 120: Fly-by-wire control
|
||||
//
|
||||
@ -234,6 +235,7 @@ public:
|
||||
//
|
||||
AP_Int16 sysid_this_mav;
|
||||
AP_Int16 sysid_my_gcs;
|
||||
AP_Int8 serial0_baud;
|
||||
AP_Int8 serial3_baud;
|
||||
AP_Int8 telem_delay;
|
||||
|
||||
|
@ -19,6 +19,13 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
GSCALAR(sysid_this_mav, "SYSID_THISMAV", MAV_SYSTEM_ID),
|
||||
GSCALAR(sysid_my_gcs, "SYSID_MYGCS", 255),
|
||||
|
||||
// @Param: SERIAL0_BAUD
|
||||
// @DisplayName: Telemetry Baud Rate
|
||||
// @Description: The baud rate used on the main uart
|
||||
// @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200
|
||||
// @User: Standard
|
||||
GSCALAR(serial0_baud, "SERIAL0_BAUD", SERIAL0_BAUD/1000),
|
||||
|
||||
// @Param: SERIAL3_BAUD
|
||||
// @DisplayName: Telemetry Baud Rate
|
||||
// @Description: The baud rate used on the telemetry port
|
||||
|
@ -110,6 +110,9 @@ static void init_ardupilot()
|
||||
//
|
||||
load_parameters();
|
||||
|
||||
// reset the uartA baud rate after parameter load
|
||||
hal.uartA->begin(map_baudrate(g.serial0_baud, SERIAL0_BAUD));
|
||||
|
||||
// keep a record of how many resets have happened. This can be
|
||||
// used to detect in-flight resets
|
||||
g.num_resets.set_and_save(g.num_resets+1);
|
||||
|
Loading…
Reference in New Issue
Block a user