mirror of https://github.com/ArduPilot/ardupilot
Rover: changed SERIAL3_BAUD to SERIAL1_BAUD
and add SERIAL2_BAUD for systems that have it
This commit is contained in:
parent
a05a32dbda
commit
fe0e627304
|
@ -1904,7 +1904,7 @@ GCS_MAVLINK::queued_param_send()
|
|||
|
||||
// use at most 30% of bandwidth on parameters. The constant 26 is
|
||||
// 1/(1000 * 1/8 * 0.001 * 0.3)
|
||||
bytes_allowed = g.serial3_baud * (tnow - _queued_parameter_send_time_ms) * 26;
|
||||
bytes_allowed = g.serial1_baud * (tnow - _queued_parameter_send_time_ms) * 26;
|
||||
if (bytes_allowed > comm_get_txspace(chan)) {
|
||||
bytes_allowed = comm_get_txspace(chan);
|
||||
}
|
||||
|
|
|
@ -48,10 +48,11 @@ public:
|
|||
k_param_sysid_this_mav,
|
||||
k_param_sysid_my_gcs,
|
||||
k_param_serial0_baud,
|
||||
k_param_serial3_baud,
|
||||
k_param_serial1_baud,
|
||||
k_param_telem_delay,
|
||||
k_param_skip_gyro_cal,
|
||||
k_param_gcs2, // stream rates for uartD
|
||||
k_param_serial2_baud,
|
||||
|
||||
//
|
||||
// 130: Sensor parameters
|
||||
|
@ -186,7 +187,10 @@ public:
|
|||
AP_Int16 sysid_this_mav;
|
||||
AP_Int16 sysid_my_gcs;
|
||||
AP_Int8 serial0_baud;
|
||||
AP_Int8 serial3_baud;
|
||||
AP_Int8 serial1_baud;
|
||||
#if MAVLINK_COMM_NUM_BUFFERS > 2
|
||||
AP_Int8 serial2_baud;
|
||||
#endif
|
||||
AP_Int8 telem_delay;
|
||||
AP_Int8 skip_gyro_cal;
|
||||
|
||||
|
|
|
@ -56,17 +56,26 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||
|
||||
// @Param: SERIAL0_BAUD
|
||||
// @DisplayName: USB Console Baud Rate
|
||||
// @Description: The baud rate used on the first serial port
|
||||
// @Description: The baud rate used on the USB console
|
||||
// @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),
|
||||
GSCALAR(serial0_baud, "SERIAL0_BAUD", 115),
|
||||
|
||||
// @Param: SERIAL3_BAUD
|
||||
// @Param: SERIAL1_BAUD
|
||||
// @DisplayName: Telemetry Baud Rate
|
||||
// @Description: The baud rate used on the telemetry port
|
||||
// @Description: The baud rate used on the first telemetry port
|
||||
// @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200
|
||||
// @User: Standard
|
||||
GSCALAR(serial3_baud, "SERIAL3_BAUD", SERIAL3_BAUD/1000),
|
||||
GSCALAR(serial1_baud, "SERIAL1_BAUD", 57),
|
||||
|
||||
#if MAVLINK_COMM_NUM_BUFFERS > 2
|
||||
// @Param: SERIAL2_BAUD
|
||||
// @DisplayName: Telemetry Baud Rate
|
||||
// @Description: The baud rate used on the second telemetry port (where available)
|
||||
// @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200
|
||||
// @User: Standard
|
||||
GSCALAR(serial2_baud, "SERIAL2_BAUD", 57),
|
||||
#endif
|
||||
|
||||
// @Param: TELEM_DELAY
|
||||
// @DisplayName: Telemetry startup delay
|
||||
|
|
|
@ -132,8 +132,11 @@
|
|||
#ifndef SERIAL0_BAUD
|
||||
# define SERIAL0_BAUD 115200
|
||||
#endif
|
||||
#ifndef SERIAL3_BAUD
|
||||
# define SERIAL3_BAUD 57600
|
||||
#ifndef SERIAL1_BAUD
|
||||
# define SERIAL1_BAUD 57600
|
||||
#endif
|
||||
#ifndef SERIAL2_BAUD
|
||||
# define SERIAL2_BAUD 57600
|
||||
#endif
|
||||
|
||||
#ifndef CH7_OPTION
|
||||
|
|
|
@ -126,14 +126,16 @@ static void init_ardupilot()
|
|||
check_usb_mux();
|
||||
|
||||
// we have a 2nd serial port for telemetry
|
||||
hal.uartC->begin(map_baudrate(g.serial3_baud, SERIAL3_BAUD), 128, 128);
|
||||
hal.uartC->begin(map_baudrate(g.serial1_baud, SERIAL1_BAUD), 128, 128);
|
||||
gcs[1].init(hal.uartC);
|
||||
|
||||
#if MAVLINK_COMM_NUM_BUFFERS > 2
|
||||
// we may have a 3rd serial port for telemetry
|
||||
if (hal.uartD != NULL) {
|
||||
hal.uartD->begin(map_baudrate(g.serial3_baud, SERIAL3_BAUD), 128, 128);
|
||||
hal.uartD->begin(map_baudrate(g.serial2_baud, SERIAL2_BAUD), 128, 128);
|
||||
gcs[2].init(hal.uartD);
|
||||
}
|
||||
#endif
|
||||
|
||||
mavlink_system.sysid = g.sysid_this_mav;
|
||||
|
||||
|
@ -414,7 +416,7 @@ static uint32_t map_baudrate(int8_t rate, uint32_t default_baud)
|
|||
case 111: return 111100;
|
||||
case 115: return 115200;
|
||||
}
|
||||
cliSerial->println_P(PSTR("Invalid SERIAL3_BAUD"));
|
||||
cliSerial->println_P(PSTR("Invalid baudrate"));
|
||||
return default_baud;
|
||||
}
|
||||
|
||||
|
@ -433,11 +435,11 @@ static void check_usb_mux(void)
|
|||
// the APM2 has a MUX setup where the first serial port switches
|
||||
// between USB and a TTL serial connection. When on USB we use
|
||||
// SERIAL0_BAUD, but when connected as a TTL serial port we run it
|
||||
// at SERIAL3_BAUD.
|
||||
// at SERIAL1_BAUD.
|
||||
if (usb_connected) {
|
||||
hal.uartA->begin(SERIAL0_BAUD);
|
||||
} else {
|
||||
hal.uartA->begin(map_baudrate(g.serial3_baud, SERIAL3_BAUD));
|
||||
hal.uartA->begin(map_baudrate(g.serial1_baud, SERIAL1_BAUD));
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue