Copter: rename TELEM2_PROTOCOL to SERIAL2_PROTOCOL

this matches SERIAL2_BAUD
This commit is contained in:
Andrew Tridgell 2014-07-30 14:49:10 +10:00
parent 30b9c60938
commit 3ccac6736d
4 changed files with 13 additions and 13 deletions

View File

@ -174,7 +174,7 @@ public:
k_param_telem_delay,
k_param_gcs2,
k_param_serial2_baud_old, // deprecated
k_param_telem2_protocol,
k_param_serial2_protocol,
//
// 140: Sensor parameters
@ -321,7 +321,7 @@ public:
AP_Int16 serial1_baud;
#if MAVLINK_COMM_NUM_BUFFERS > 2
AP_Int16 serial2_baud;
AP_Int8 telem2_protocol;
AP_Int8 serial2_protocol;
#endif
AP_Int8 telem_delay;

View File

@ -76,12 +76,12 @@ const AP_Param::Info var_info[] PROGMEM = {
GSCALAR(serial2_baud, "SERIAL2_BAUD", SERIAL2_BAUD/1000),
#if FRSKY_TELEM_ENABLED == ENABLED
// @Param: TELEM2_PROTOCOL
// @DisplayName: TELEM2 protocol selection
// @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
// @User: Standard
GSCALAR(telem2_protocol, "TELEM2_PROTOCOL", TELEM2_MAVLINK),
GSCALAR(serial2_protocol, "SERIAL2_PROTOCOL", SERIAL2_MAVLINK),
#endif // FRSKY_TELEM_ENABLED
#endif // MAVLINK_COMM_NUM_BUFFERS

View File

@ -407,10 +407,10 @@ enum FlipState {
#define FS_GPS_LAND_EVEN_STABILIZE 3 // switch to LAND mode on GPS failsafe even if in a manual flight mode like Stabilize
enum Telem2Protocol {
TELEM2_MAVLINK = 1,
TELEM2_FRSKY_DPORT = 2,
TELEM2_FRSKY_SPORT = 3 // not supported yet
enum Serial2Protocol {
SERIAL2_MAVLINK = 1,
SERIAL2_FRSKY_DPORT = 2,
SERIAL2_FRSKY_SPORT = 3 // not supported yet
};
#endif // _DEFINES_H

View File

@ -171,9 +171,9 @@ static void init_ardupilot()
#endif
#if MAVLINK_COMM_NUM_BUFFERS > 2
if (g.telem2_protocol == TELEM2_FRSKY_DPORT ||
g.telem2_protocol == TELEM2_FRSKY_SPORT) {
frsky_telemetry.init(hal.uartD, g.telem2_protocol);
if (g.serial2_protocol == SERIAL2_FRSKY_DPORT ||
g.serial2_protocol == SERIAL2_FRSKY_SPORT) {
frsky_telemetry.init(hal.uartD, g.serial2_protocol);
} else {
gcs[2].setup_uart(hal.uartD, map_baudrate(g.serial2_baud), 128, 128);
}
@ -396,6 +396,6 @@ static void telemetry_send(void)
{
#if FRSKY_TELEM_ENABLED == ENABLED
frsky_telemetry.send_frames((uint8_t)control_mode,
(AP_Frsky_Telem::FrSkyProtocol)g.telem2_protocol.get());
(AP_Frsky_Telem::FrSkyProtocol)g.serial2_protocol.get());
#endif
}