From ee00302b62f29941104097493023c9a9139cdf58 Mon Sep 17 00:00:00 2001 From: Matthias Badaire Date: Tue, 20 Jan 2015 17:36:46 +0100 Subject: [PATCH] Plane: 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 --- ArduPlane/Parameters.pde | 2 +- ArduPlane/system.pde | 5 ++--- 2 files changed, 3 insertions(+), 4 deletions(-) diff --git a/ArduPlane/Parameters.pde b/ArduPlane/Parameters.pde index 98e37eb681..2bb45f7498 100644 --- a/ArduPlane/Parameters.pde +++ b/ArduPlane/Parameters.pde @@ -64,7 +64,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 diff --git a/ArduPlane/system.pde b/ArduPlane/system.pde index 1af451051a..afc667951b 100644 --- a/ArduPlane/system.pde +++ b/ArduPlane/system.pde @@ -130,7 +130,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, SERIAL2_BUFSIZE); } @@ -687,8 +687,7 @@ static bool should_log(uint32_t mask) 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 }