Copter: 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
c7cd1c9fde
commit
147e91877e
@ -21,6 +21,7 @@
|
||||
// uncomment the lines below to save on flash space if compiling for the APM using Arduino IDE. Top items save the most flash space
|
||||
#if (CONFIG_HAL_BOARD == HAL_BOARD_APM2 || CONFIG_HAL_BOARD == HAL_BOARD_APM1)
|
||||
# define CLI_ENABLED DISABLED // disable the CLI (command-line-interface) to save 21K of flash space
|
||||
# define FRSKY_TELEM_ENABLED DISABLED // disable the FRSKY TELEM
|
||||
#endif
|
||||
//#define LOGGING_ENABLED DISABLED // disable dataflash logging to save 11K of flash space
|
||||
//#define MOUNT DISABLED // disable the camera gimbal to save 8K of flash space
|
||||
|
@ -144,6 +144,7 @@
|
||||
#include <AP_Notify.h> // Notify library
|
||||
#include <AP_BattMonitor.h> // Battery monitor library
|
||||
#include <AP_BoardConfig.h> // board configuration library
|
||||
#include <AP_Frsky_Telem.h>
|
||||
#if SPRAYER == ENABLED
|
||||
#include <AC_Sprayer.h> // crop sprayer library
|
||||
#endif
|
||||
@ -554,6 +555,11 @@ static Vector3f flip_orig_attitude; // original copter attitude before f
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
static AP_BattMonitor battery;
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// FrSky telemetry support
|
||||
#if FRSKY_TELEM_ENABLED == ENABLED
|
||||
static AP_Frsky_Telem frsky_telemetry(ahrs, battery);
|
||||
#endif
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// Altitude
|
||||
@ -810,6 +816,9 @@ static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = {
|
||||
{ fifty_hz_logging_loop, 8, 22 },
|
||||
{ perf_update, 4000, 20 },
|
||||
{ read_receiver_rssi, 40, 5 },
|
||||
#if FRSKY_TELEM_ENABLED == ENABLED
|
||||
{ telemetry_send, 80, 10 },
|
||||
#endif
|
||||
#ifdef USERHOOK_FASTLOOP
|
||||
{ userhook_FastLoop, 4, 10 },
|
||||
#endif
|
||||
@ -872,6 +881,9 @@ static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = {
|
||||
{ fifty_hz_logging_loop, 2, 220 },
|
||||
{ perf_update, 1000, 200 },
|
||||
{ read_receiver_rssi, 10, 50 },
|
||||
#if FRSKY_TELEM_ENABLED == ENABLED
|
||||
{ telemetry_send, 20, 100 },
|
||||
#endif
|
||||
#ifdef USERHOOK_FASTLOOP
|
||||
{ userhook_FastLoop, 1, 100 },
|
||||
#endif
|
||||
|
@ -174,6 +174,7 @@ public:
|
||||
k_param_telem_delay,
|
||||
k_param_gcs2,
|
||||
k_param_serial2_baud_old, // deprecated
|
||||
k_param_telem2_protocol,
|
||||
|
||||
//
|
||||
// 140: Sensor parameters
|
||||
@ -320,6 +321,7 @@ public:
|
||||
AP_Int16 serial1_baud;
|
||||
#if MAVLINK_COMM_NUM_BUFFERS > 2
|
||||
AP_Int16 serial2_baud;
|
||||
AP_Int8 telem2_protocol;
|
||||
#endif
|
||||
AP_Int8 telem_delay;
|
||||
|
||||
|
@ -72,8 +72,19 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
// @Description: The baud rate used on the second telemetry port. The APM2 can support all baudrates up to 115, and also can support 500. The PX4 can support rates of up to 1500. If you setup a rate you cannot support on APM2 and then can't connect to your board you should load a firmware from a different vehicle type. That will reset all your parameters to defaults.
|
||||
// @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: TELEM2_PROTOCOL
|
||||
// @DisplayName: TELEM2 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),
|
||||
#endif // FRSKY_TELEM_ENABLED
|
||||
|
||||
#endif // MAVLINK_COMM_NUM_BUFFERS
|
||||
|
||||
// @Param: TELEM_DELAY
|
||||
// @DisplayName: Telemetry startup delay
|
||||
|
0
ArduCopter/Telemetry.pde
Normal file
0
ArduCopter/Telemetry.pde
Normal file
@ -747,6 +747,11 @@
|
||||
# define CLI_ENABLED ENABLED
|
||||
#endif
|
||||
|
||||
//use this to completely disable FRSKY TELEM
|
||||
#ifndef FRSKY_TELEM_ENABLED
|
||||
# define FRSKY_TELEM_ENABLED ENABLED
|
||||
#endif
|
||||
|
||||
/*
|
||||
build a firmware version string.
|
||||
GIT_VERSION comes from Makefile builds
|
||||
|
@ -406,4 +406,11 @@ enum FlipState {
|
||||
#define FS_GPS_ALTHOLD 2 // switch to ALTHOLD mode on GPS failsafe
|
||||
#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
|
||||
};
|
||||
|
||||
#endif // _DEFINES_H
|
||||
|
@ -169,8 +169,14 @@ static void init_ardupilot()
|
||||
// a MUX is used
|
||||
gcs[1].setup_uart(hal.uartC, map_baudrate(g.serial1_baud), 128, 128);
|
||||
#endif
|
||||
|
||||
#if MAVLINK_COMM_NUM_BUFFERS > 2
|
||||
gcs[2].setup_uart(hal.uartD, map_baudrate(g.serial2_baud), 128, 128);
|
||||
if (g.telem2_protocol == TELEM2_FRSKY_DPORT ||
|
||||
g.telem2_protocol == TELEM2_FRSKY_SPORT) {
|
||||
frsky_telemetry.init(hal.uartD, g.telem2_protocol);
|
||||
} else {
|
||||
gcs[2].setup_uart(hal.uartD, map_baudrate(g.serial2_baud), 128, 128);
|
||||
}
|
||||
#endif
|
||||
|
||||
// identify ourselves correctly with the ground station
|
||||
@ -383,3 +389,13 @@ static void check_usb_mux(void)
|
||||
#endif
|
||||
}
|
||||
|
||||
/*
|
||||
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.telem2_protocol.get());
|
||||
#endif
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user