mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
Rover: Add SERIAL2_PROTOCOL for GCS and FRSky telemtry
This allows selection of protocol type on telem2. The default is MAVLink, but can be selected as FrSky protocol
This commit is contained in:
parent
874ef65d74
commit
57253fc2ee
@ -79,6 +79,7 @@
|
||||
|
||||
#include <AP_Arming.h>
|
||||
#include <AP_BoardConfig.h>
|
||||
#include <AP_Frsky_Telem.h>
|
||||
#include <AP_ServoRelayEvents.h>
|
||||
|
||||
#include <AP_Rally.h>
|
||||
@ -460,6 +461,12 @@ static int32_t altitude_error_cm;
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
static AP_BattMonitor battery;
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// FrSky telemetry support
|
||||
#if FRSKY_TELEM_ENABLED == ENABLED
|
||||
static AP_Frsky_Telem frsky_telemetry(ahrs, battery);
|
||||
#endif
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// Airspeed Sensors
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
@ -766,6 +773,10 @@ static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = {
|
||||
{ compass_save, 3000, 2500 },
|
||||
{ update_logging1, 5, 1700 },
|
||||
{ update_logging2, 5, 1700 },
|
||||
#if FRSKY_TELEM_ENABLED == ENABLED
|
||||
{ telemetry_send, 10, 100 },
|
||||
#endif
|
||||
|
||||
};
|
||||
|
||||
// setup the var_info table
|
||||
|
@ -138,6 +138,7 @@ public:
|
||||
k_param_serial0_baud_old, // deprecated
|
||||
k_param_gcs2, // stream rates for uartD
|
||||
k_param_serial2_baud_old, // deprecated
|
||||
k_param_serial2_protocol,
|
||||
|
||||
// 120: Fly-by-wire control
|
||||
//
|
||||
@ -308,6 +309,7 @@ public:
|
||||
AP_Int16 serial1_baud;
|
||||
#if MAVLINK_COMM_NUM_BUFFERS > 2
|
||||
AP_Int16 serial2_baud;
|
||||
AP_Int8 serial2_protocol;
|
||||
#endif
|
||||
AP_Int8 telem_delay;
|
||||
|
||||
|
@ -59,7 +59,17 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
// @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,500:500000,921:921600,1500:1500000
|
||||
// @User: Standard
|
||||
GSCALAR(serial2_baud, "SERIAL2_BAUD", SERIAL2_BAUD/1000),
|
||||
#endif
|
||||
|
||||
#if FRSKY_TELEM_ENABLED == ENABLED
|
||||
// @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(serial2_protocol, "SERIAL2_PROTOCOL", SERIAL2_MAVLINK),
|
||||
#endif // FRSKY_TELEM_ENABLED
|
||||
|
||||
#endif // MAVLINK_COMM_NUM_BUFFERS
|
||||
|
||||
// @Param: AUTOTUNE_LEVEL
|
||||
// @DisplayName: Autotune level
|
||||
|
@ -77,6 +77,9 @@
|
||||
#ifndef CAMERA
|
||||
# define CAMERA DISABLED
|
||||
#endif
|
||||
#ifndef FRSKY_TELEM_ENABLED
|
||||
# define FRSKY_TELEM_ENABLED DISABLED
|
||||
#endif
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
@ -123,6 +126,18 @@
|
||||
# define SERIAL2_BAUD 57600
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// FrSky telemetry support
|
||||
//
|
||||
|
||||
#ifndef FRSKY_TELEM_ENABLED
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
# define FRSKY_TELEM_ENABLED DISABLED
|
||||
#else
|
||||
# define FRSKY_TELEM_ENABLED ENABLED
|
||||
#endif
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
@ -211,4 +211,10 @@ enum {
|
||||
ATT_CONTROL_APMCONTROL = 1
|
||||
};
|
||||
|
||||
enum Telem2Protocol {
|
||||
SERIAL2_MAVLINK = 1,
|
||||
SERIAL2_FRSKY_DPORT = 2,
|
||||
SERIAL2_FRSKY_SPORT = 3 // not supported yet
|
||||
};
|
||||
|
||||
#endif // _DEFINES_H
|
||||
|
@ -119,7 +119,12 @@ static void init_ardupilot()
|
||||
gcs[1].setup_uart(hal.uartC, map_baudrate(g.serial1_baud), 128, SERIAL1_BUFSIZE);
|
||||
|
||||
#if MAVLINK_COMM_NUM_BUFFERS > 2
|
||||
gcs[2].setup_uart(hal.uartD, map_baudrate(g.serial2_baud), 128, SERIAL2_BUFSIZE);
|
||||
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, SERIAL2_BUFSIZE);
|
||||
}
|
||||
#endif
|
||||
|
||||
mavlink_system.sysid = g.sysid_this_mav;
|
||||
@ -618,3 +623,14 @@ static bool should_log(uint32_t mask)
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
||||
/*
|
||||
send FrSky telemetry. Should be called at 5Hz by scheduler
|
||||
*/
|
||||
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());
|
||||
#endif
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user