mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
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
This commit is contained in:
parent
a2d71d2811
commit
ee00302b62
@ -64,7 +64,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||||||
// @Param: SERIAL2_PROTOCOL
|
// @Param: SERIAL2_PROTOCOL
|
||||||
// @DisplayName: SERIAL2 protocol selection
|
// @DisplayName: SERIAL2 protocol selection
|
||||||
// @Description: Control what protocol telemetry 2 port should be used for
|
// @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
|
// @User: Standard
|
||||||
GSCALAR(serial2_protocol, "SERIAL2_PROTOCOL", SERIAL2_MAVLINK),
|
GSCALAR(serial2_protocol, "SERIAL2_PROTOCOL", SERIAL2_MAVLINK),
|
||||||
#endif // FRSKY_TELEM_ENABLED
|
#endif // FRSKY_TELEM_ENABLED
|
||||||
|
@ -130,7 +130,7 @@ static void init_ardupilot()
|
|||||||
#if MAVLINK_COMM_NUM_BUFFERS > 2
|
#if MAVLINK_COMM_NUM_BUFFERS > 2
|
||||||
if (g.serial2_protocol == SERIAL2_FRSKY_DPORT ||
|
if (g.serial2_protocol == SERIAL2_FRSKY_DPORT ||
|
||||||
g.serial2_protocol == SERIAL2_FRSKY_SPORT) {
|
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 {
|
} else {
|
||||||
gcs[2].setup_uart(hal.uartD, map_baudrate(g.serial2_baud), 128, SERIAL2_BUFSIZE);
|
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)
|
static void telemetry_send(void)
|
||||||
{
|
{
|
||||||
#if FRSKY_TELEM_ENABLED == ENABLED
|
#if FRSKY_TELEM_ENABLED == ENABLED
|
||||||
frsky_telemetry.send_frames((uint8_t)control_mode,
|
frsky_telemetry.send_frames((uint8_t)control_mode);
|
||||||
(AP_Frsky_Telem::FrSkyProtocol)g.serial2_protocol.get());
|
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user