Browse Source

Copter: Frsky telemtry change move parameter to init of the class

Parameter needs to be passed and use at the init of the class frsky telem
master
Matthias Badaire 10 years ago committed by Andrew Tridgell
parent
commit
a2d71d2811
  1. 2
      ArduCopter/Parameters.pde
  2. 5
      ArduCopter/system.pde

2
ArduCopter/Parameters.pde

@ -80,7 +80,7 @@ const AP_Param::Info var_info[] PROGMEM = { @@ -80,7 +80,7 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Param: SERIAL2_PROTOCOL
// @DisplayName: Serial2 protocol selection
// @Description: Control what protocol telemetry 2 port should be used for
// @Values: 1:GCS Mavlink,2:Frsky D-PORT
// @Values: 1:GCS Mavlink,2:Frsky D-PORT,3:Frsky S-PORT
// @User: Standard
GSCALAR(serial2_protocol, "SERIAL2_PROTOCOL", SERIAL2_MAVLINK),
#endif // FRSKY_TELEM_ENABLED

5
ArduCopter/system.pde

@ -170,7 +170,7 @@ static void init_ardupilot() @@ -170,7 +170,7 @@ static void init_ardupilot()
#if MAVLINK_COMM_NUM_BUFFERS > 2
if (g.serial2_protocol == SERIAL2_FRSKY_DPORT ||
g.serial2_protocol == SERIAL2_FRSKY_SPORT) {
frsky_telemetry.init(hal.uartD, g.serial2_protocol);
frsky_telemetry.init(hal.uartD, (AP_Frsky_Telem::FrSkyProtocol)g.serial2_protocol.get());
} else {
gcs[2].setup_uart(hal.uartD, map_baudrate(g.serial2_baud), 128, 128);
}
@ -439,8 +439,7 @@ static void check_usb_mux(void) @@ -439,8 +439,7 @@ static void check_usb_mux(void)
static void telemetry_send(void)
{
#if FRSKY_TELEM_ENABLED == ENABLED
frsky_telemetry.send_frames((uint8_t)control_mode,
(AP_Frsky_Telem::FrSkyProtocol)g.serial2_protocol.get());
frsky_telemetry.send_frames((uint8_t)control_mode);
#endif
}

Loading…
Cancel
Save