mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
Copter: change baudrates parameters to 16 bit
This commit is contained in:
parent
511e8beaed
commit
cc6fba4cad
@ -112,6 +112,9 @@ public:
|
||||
k_param_hybrid_brake_rate,
|
||||
k_param_hybrid_brake_angle_max,
|
||||
k_param_pilot_accel_z, // 48
|
||||
k_param_serial0_baud,
|
||||
k_param_serial1_baud,
|
||||
k_param_serial2_baud,
|
||||
|
||||
// 65: AP_Limits Library
|
||||
k_param_limits = 65, // deprecated - remove
|
||||
@ -162,10 +165,10 @@ public:
|
||||
k_param_gcs1,
|
||||
k_param_sysid_this_mav,
|
||||
k_param_sysid_my_gcs,
|
||||
k_param_serial1_baud,
|
||||
k_param_serial1_baud_old, // deprecated
|
||||
k_param_telem_delay,
|
||||
k_param_gcs2,
|
||||
k_param_serial2_baud,
|
||||
k_param_serial2_baud_old, // deprecated
|
||||
|
||||
//
|
||||
// 140: Sensor parameters
|
||||
@ -308,9 +311,10 @@ public:
|
||||
//
|
||||
AP_Int16 sysid_this_mav;
|
||||
AP_Int16 sysid_my_gcs;
|
||||
AP_Int8 serial1_baud;
|
||||
AP_Int16 serial0_baud;
|
||||
AP_Int16 serial1_baud;
|
||||
#if MAVLINK_COMM_NUM_BUFFERS > 2
|
||||
AP_Int8 serial2_baud;
|
||||
AP_Int16 serial2_baud;
|
||||
#endif
|
||||
AP_Int8 telem_delay;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user