From 1118609024f440cb0ae11fd820a2de8adf6fd384 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 21 May 2014 12:38:53 +1000 Subject: [PATCH] Rover: change baudrates to 16 bit allows for much higher serial baud rates --- APMrover2/Parameters.h | 15 +++++++++------ 1 file changed, 9 insertions(+), 6 deletions(-) diff --git a/APMrover2/Parameters.h b/APMrover2/Parameters.h index 6ecb53c5ea..c9650c424e 100644 --- a/APMrover2/Parameters.h +++ b/APMrover2/Parameters.h @@ -51,6 +51,9 @@ public: // misc2 k_param_log_bitmask = 40, k_param_gps, + k_param_serial0_baud, + k_param_serial1_baud, + k_param_serial2_baud, // 110: Telemetry control @@ -59,12 +62,12 @@ public: k_param_gcs1, // stream rates for uartC k_param_sysid_this_mav, k_param_sysid_my_gcs, - k_param_serial0_baud, - k_param_serial1_baud, + k_param_serial0_baud_old, + k_param_serial1_baud_old, k_param_telem_delay, k_param_skip_gyro_cal, k_param_gcs2, // stream rates for uartD - k_param_serial2_baud, + k_param_serial2_baud_old, // // 130: Sensor parameters @@ -205,10 +208,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; AP_Int8 skip_gyro_cal;