Browse Source

Copter: added SERIAL2_BAUD and rename SERIAL3_BAUD to SERIAL1_BAUD

master
Andrew Tridgell 11 years ago
parent
commit
9c812d5028
  1. 2
      ArduCopter/APM_Config_mavlink_hil.h
  2. 2
      ArduCopter/GCS_Mavlink.pde
  3. 8
      ArduCopter/Parameters.h
  4. 15
      ArduCopter/Parameters.pde
  5. 7
      ArduCopter/config.h
  6. 12
      ArduCopter/system.pde

2
ArduCopter/APM_Config_mavlink_hil.h

@ -25,7 +25,7 @@ @@ -25,7 +25,7 @@
// the loop port. Alternatively, use a telemetry/HIL shim like FGShim
// https://ardupilot-mega.googlecode.com/svn/Tools/trunk/FlightGear
//
// The buad rate is controlled by SERIAL3_BAUD in this mode.
// The buad rate is controlled by SERIAL1_BAUD in this mode.
#define HIL_PORT 3

2
ArduCopter/GCS_Mavlink.pde

@ -2071,7 +2071,7 @@ GCS_MAVLINK::queued_param_send() @@ -2071,7 +2071,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);
}

8
ArduCopter/Parameters.h

@ -137,9 +137,10 @@ public: @@ -137,9 +137,10 @@ public:
k_param_gcs1,
k_param_sysid_this_mav,
k_param_sysid_my_gcs,
k_param_serial3_baud,
k_param_serial1_baud,
k_param_telem_delay,
k_param_gcs2,
k_param_serial2_baud,
//
// 140: Sensor parameters
@ -282,7 +283,10 @@ public: @@ -282,7 +283,10 @@ public:
//
AP_Int16 sysid_this_mav;
AP_Int16 sysid_my_gcs;
AP_Int8 serial3_baud;
AP_Int8 serial1_baud;
#if MAVLINK_COMM_NUM_BUFFERS > 2
AP_Int8 serial2_baud;
#endif
AP_Int8 telem_delay;
AP_Int16 rtl_altitude;

15
ArduCopter/Parameters.pde

@ -49,12 +49,21 @@ const AP_Param::Info var_info[] PROGMEM = { @@ -49,12 +49,21 @@ const AP_Param::Info var_info[] PROGMEM = {
// @User: Advanced
GSCALAR(sysid_my_gcs, "SYSID_MYGCS", 255),
// @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", SERIAL1_BAUD/1000),
#if MAVLINK_COMM_NUM_BUFFERS > 2
// @Param: SERIAL2_BAUD
// @DisplayName: Telemetry Baud Rate
// @Description: The baud rate used on the seconds telemetry port
// @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", SERIAL2_BAUD/1000),
#endif
// @Param: TELEM_DELAY
// @DisplayName: Telemetry startup delay

7
ArduCopter/config.h

@ -332,8 +332,11 @@ @@ -332,8 +332,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

12
ArduCopter/system.pde

@ -150,13 +150,15 @@ static void init_ardupilot() @@ -150,13 +150,15 @@ static void init_ardupilot()
// we have a 2nd serial port for telemetry on all boards except
// APM2. We actually do have one on APM2 but it isn't necessary as
// a MUX is used
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);
#endif
#if MAVLINK_COMM_NUM_BUFFERS > 2
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
// identify ourselves correctly with the ground station
mavlink_system.sysid = g.sysid_this_mav;
@ -529,7 +531,7 @@ static uint32_t map_baudrate(int8_t rate, uint32_t default_baud) @@ -529,7 +531,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;
}
@ -547,11 +549,11 @@ static void check_usb_mux(void) @@ -547,11 +549,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 (ap.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…
Cancel
Save