Plane: changed baudrate parameters to 16 bit

This commit is contained in:
Andrew Tridgell 2014-05-21 12:40:02 +10:00
parent 63da53c842
commit 94d528e548
1 changed files with 9 additions and 6 deletions

View File

@ -107,6 +107,9 @@ public:
k_param_gps,
k_param_autotune_level,
k_param_rally,
k_param_serial0_baud,
k_param_serial1_baud,
k_param_serial2_baud,
// 100: Arming parameters
k_param_arming = 100,
@ -122,11 +125,11 @@ public:
k_param_gcs1, // stream rates for uartC
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_serial0_baud,
k_param_serial0_baud_old, // deprecated
k_param_gcs2, // stream rates for uartD
k_param_serial2_baud,
k_param_serial2_baud_old, // deprecated
// 120: Fly-by-wire control
//
@ -293,10 +296,10 @@ public:
//
AP_Int16 sysid_this_mav;
AP_Int16 sysid_my_gcs;
AP_Int8 serial0_baud;
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;