mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2025-02-26 15:54:15 +01:00
LP-117 FRsky SPort: modifications to compile with current "next"
This commit is contained in:
parent
94231327d7
commit
19318e88a8
@ -216,6 +216,7 @@ bool frsky_encode_t1(struct frsky_settings *frsky, uint32_t *value, bool test_pr
|
|||||||
t1 = 300;
|
t1 = 300;
|
||||||
break;
|
break;
|
||||||
case GPSPOSITIONSENSOR_STATUS_FIX3D:
|
case GPSPOSITIONSENSOR_STATUS_FIX3D:
|
||||||
|
case GPSPOSITIONSENSOR_STATUS_FIX3DDGNSS:
|
||||||
if (hl_set == HOMELOCATION_SET_TRUE) {
|
if (hl_set == HOMELOCATION_SET_TRUE) {
|
||||||
t1 = 500;
|
t1 = 500;
|
||||||
} else {
|
} else {
|
||||||
|
@ -1,12 +1,13 @@
|
|||||||
/**
|
/**
|
||||||
******************************************************************************
|
******************************************************************************
|
||||||
* @addtogroup TauLabsModules TauLabs Modules
|
* @addtogroup OpenPilotModules OpenPilot Modules
|
||||||
* @{
|
* @{
|
||||||
* @addtogroup UAVOFrSKYSPortBridge UAVO to FrSKY S.PORT Bridge Module
|
* @addtogroup UAVOFrSKYSPortBridge UAVO to FrSKY S.PORT Bridge Module
|
||||||
* @{
|
* @{
|
||||||
*
|
*
|
||||||
* @file uavofrskysportbridge.c
|
* @file uavofrskysportbridge.c
|
||||||
* @author Tau Labs, http://taulabs.org, Copyright (C) 2014
|
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2017-2019
|
||||||
|
* Tau Labs, http://taulabs.org, Copyright (C) 2014
|
||||||
* @brief Bridges selected UAVObjects to FrSKY Smart Port bus
|
* @brief Bridges selected UAVObjects to FrSKY Smart Port bus
|
||||||
*
|
*
|
||||||
* Since there is no public documentation of SmartPort protocol available,
|
* Since there is no public documentation of SmartPort protocol available,
|
||||||
@ -35,6 +36,8 @@
|
|||||||
|
|
||||||
#include "frsky_packing.h"
|
#include "frsky_packing.h"
|
||||||
|
|
||||||
|
#include "pios_board_io.h"
|
||||||
|
|
||||||
#include "barosensor.h"
|
#include "barosensor.h"
|
||||||
#include "flightbatterysettings.h"
|
#include "flightbatterysettings.h"
|
||||||
#include "flightbatterystate.h"
|
#include "flightbatterystate.h"
|
||||||
@ -277,7 +280,12 @@ static int32_t uavoFrSKYSPortBridgeInitialize(void)
|
|||||||
frsky->last_poll_time = PIOS_DELAY_GetuS();
|
frsky->last_poll_time = PIOS_DELAY_GetuS();
|
||||||
frsky->scheduled_item = -1;
|
frsky->scheduled_item = -1;
|
||||||
frsky->com = PIOS_COM_FRSKY_SPORT;
|
frsky->com = PIOS_COM_FRSKY_SPORT;
|
||||||
frsky->ignore_echo = true; // This has to be true when RX & TX hw serial lines are connected. Otherwise false.
|
frsky->ignore_echo = true; // This has to be true when RX & TX hw serial lines are connected. Otherwise false. (enforced below by setting half duplex. this makes internal connection between rx and tx
|
||||||
|
// connect TX pin of flight controller to UNINVERTED SPort
|
||||||
|
// (F4 based controllers do not have TX inversion capability.
|
||||||
|
// Use external inverter or solder to uninverted receiver pin)
|
||||||
|
// TODO: Add code/PIOS driver to enable inversion for F3 based convertes
|
||||||
|
// TODO: implement FPORT driver
|
||||||
frsky->schedule_nr = 1;
|
frsky->schedule_nr = 1;
|
||||||
|
|
||||||
uint8_t i;
|
uint8_t i;
|
||||||
@ -290,6 +298,9 @@ static int32_t uavoFrSKYSPortBridgeInitialize(void)
|
|||||||
FrSKYSPortTelemetrySettingsUpdatedCb(0);
|
FrSKYSPortTelemetrySettingsUpdatedCb(0);
|
||||||
|
|
||||||
PIOS_COM_ChangeBaud(frsky->com, FRSKY_SPORT_BAUDRATE);
|
PIOS_COM_ChangeBaud(frsky->com, FRSKY_SPORT_BAUDRATE);
|
||||||
|
bool param = true;
|
||||||
|
PIOS_COM_Ioctl(frsky->com, PIOS_IOCTL_USART_SET_HALFDUPLEX, ¶m);
|
||||||
|
|
||||||
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
@ -108,6 +108,10 @@ uint32_t pios_com_debug_id; /* DebugConsole */
|
|||||||
uint32_t pios_com_hott_id;
|
uint32_t pios_com_hott_id;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef PIOS_INCLUDE_FRSKY_SPORT
|
||||||
|
uint32_t pios_com_frsky_sport_id;
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifdef PIOS_INCLUDE_USB
|
#ifdef PIOS_INCLUDE_USB
|
||||||
|
|
||||||
uint32_t pios_com_telem_usb_id; /* USB telemetry */
|
uint32_t pios_com_telem_usb_id; /* USB telemetry */
|
||||||
@ -433,6 +437,13 @@ static const struct uart_function uart_function_map[] = {
|
|||||||
.rcvr_group = MANUALCONTROLSETTINGS_CHANNELGROUPS_SBUS,
|
.rcvr_group = MANUALCONTROLSETTINGS_CHANNELGROUPS_SBUS,
|
||||||
},
|
},
|
||||||
# endif /* PIOS_INCLUDE_SBUS */
|
# endif /* PIOS_INCLUDE_SBUS */
|
||||||
|
# ifdef PIOS_INCLUDE_FRSKY_SPORT
|
||||||
|
[PIOS_BOARD_IO_UART_FRSKY_SPORT] = {
|
||||||
|
.com_id = &pios_com_frsky_sport_id,
|
||||||
|
.com_rx_buf_len = PIOS_COM_FRSKY_SPORT_RX_BUF_LEN,
|
||||||
|
.com_tx_buf_len = PIOS_COM_FRSKY_SPORT_TX_BUF_LEN,
|
||||||
|
},
|
||||||
|
# endif
|
||||||
#endif /* PIOS_INCLUDE_RCVR */
|
#endif /* PIOS_INCLUDE_RCVR */
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -173,16 +173,28 @@ extern uint32_t pios_com_frsky_sensorhub_id;
|
|||||||
# define PIOS_COM_FRSKY_SENSORHUB_TX_BUF_LEN 128
|
# define PIOS_COM_FRSKY_SENSORHUB_TX_BUF_LEN 128
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/* Frsky Sport */
|
||||||
|
#ifdef PIOS_INCLUDE_FRSKY_SPORT
|
||||||
|
extern uint32_t pios_com_frsky_sport_id;
|
||||||
|
# define PIOS_COM_FRSKY_SPORT (pios_com_frsky_sport_id)
|
||||||
|
# ifndef PIOS_COM_FRSKY_SPORT_RX_BUF_LEN
|
||||||
|
# define PIOS_COM_FRSKY_SPORT_RX_BUF_LEN 16
|
||||||
|
# endif
|
||||||
|
# ifndef PIOS_COM_FRSKY_SPORT_TX_BUF_LEN
|
||||||
|
# define PIOS_COM_FRSKY_SPORT_TX_BUF_LEN 16
|
||||||
|
# endif
|
||||||
|
#endif
|
||||||
|
|
||||||
/* USB VCP */
|
/* USB VCP */
|
||||||
extern uint32_t pios_com_vcp_id;
|
extern uint32_t pios_com_vcp_id;
|
||||||
#define PIOS_COM_VCP (pios_com_vcp_id)
|
#define PIOS_COM_VCP (pios_com_vcp_id)
|
||||||
|
|
||||||
|
|
||||||
#ifdef PIOS_INCLUDE_DEBUG_CONSOLE
|
#ifdef PIOS_INCLUDE_DEBUG_CONSOLE
|
||||||
extern uint32_t pios_com_debug_id;
|
extern uint32_t pios_com_debug_id;
|
||||||
#define PIOS_COM_DEBUG (pios_com_debug_id)
|
#define PIOS_COM_DEBUG (pios_com_debug_id)
|
||||||
#ifndef PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN
|
#ifndef PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN
|
||||||
# define PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN 40
|
# define PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN 40
|
||||||
#endif
|
#endif
|
||||||
#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */
|
#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */
|
||||||
|
|
||||||
@ -215,9 +227,9 @@ typedef enum {
|
|||||||
PIOS_BOARD_IO_UART_SRXL, /* rcvr */
|
PIOS_BOARD_IO_UART_SRXL, /* rcvr */
|
||||||
PIOS_BOARD_IO_UART_IBUS, /* rcvr */
|
PIOS_BOARD_IO_UART_IBUS, /* rcvr */
|
||||||
PIOS_BOARD_IO_UART_EXBUS, /* rcvr */
|
PIOS_BOARD_IO_UART_EXBUS, /* rcvr */
|
||||||
// PIOS_BOARD_IO_UART_FRSKY_SPORT_TELEMETRY, /* com */
|
|
||||||
PIOS_BOARD_IO_UART_HOTT_BRIDGE, /* com */
|
PIOS_BOARD_IO_UART_HOTT_BRIDGE, /* com */
|
||||||
PIOS_BOARD_IO_UART_FRSKY_SENSORHUB, /* com */
|
PIOS_BOARD_IO_UART_FRSKY_SENSORHUB, /* com */
|
||||||
|
PIOS_BOARD_IO_UART_FRSKY_SPORT, /* com */
|
||||||
} PIOS_BOARD_IO_UART_Function;
|
} PIOS_BOARD_IO_UART_Function;
|
||||||
|
|
||||||
|
|
||||||
|
@ -162,6 +162,7 @@
|
|||||||
#define PIOS_INCLUDE_GPS_DJI_PARSER
|
#define PIOS_INCLUDE_GPS_DJI_PARSER
|
||||||
#define PIOS_GPS_SETS_HOMELOCATION
|
#define PIOS_GPS_SETS_HOMELOCATION
|
||||||
#define PIOS_INCLUDE_FRSKY_SENSORHUB
|
#define PIOS_INCLUDE_FRSKY_SENSORHUB
|
||||||
|
#define PIOS_INCLUDE_FRSKY_SPORT
|
||||||
|
|
||||||
/* Stabilization options */
|
/* Stabilization options */
|
||||||
#define PIOS_QUATERNION_STABILIZATION
|
#define PIOS_QUATERNION_STABILIZATION
|
||||||
|
@ -75,6 +75,7 @@ static const PIOS_BOARD_IO_UART_Function flexiio_function_map[] = {
|
|||||||
[HWSETTINGS_RM_RCVRPORT_IBUS] = PIOS_BOARD_IO_UART_IBUS,
|
[HWSETTINGS_RM_RCVRPORT_IBUS] = PIOS_BOARD_IO_UART_IBUS,
|
||||||
[HWSETTINGS_RM_RCVRPORT_FRSKYSENSORHUB] = PIOS_BOARD_IO_UART_FRSKY_SENSORHUB,
|
[HWSETTINGS_RM_RCVRPORT_FRSKYSENSORHUB] = PIOS_BOARD_IO_UART_FRSKY_SENSORHUB,
|
||||||
[HWSETTINGS_RM_RCVRPORT_HOTTTELEMETRY] = PIOS_BOARD_IO_UART_HOTT_BRIDGE,
|
[HWSETTINGS_RM_RCVRPORT_HOTTTELEMETRY] = PIOS_BOARD_IO_UART_HOTT_BRIDGE,
|
||||||
|
[HWSETTINGS_RM_RCVRPORT_FRSKYSPORT] = PIOS_BOARD_IO_UART_FRSKY_SPORT,
|
||||||
};
|
};
|
||||||
|
|
||||||
static const PIOS_BOARD_IO_UART_Function main_function_map[] = {
|
static const PIOS_BOARD_IO_UART_Function main_function_map[] = {
|
||||||
@ -89,6 +90,7 @@ static const PIOS_BOARD_IO_UART_Function main_function_map[] = {
|
|||||||
[HWSETTINGS_RM_MAINPORT_MAVLINK] = PIOS_BOARD_IO_UART_MAVLINK,
|
[HWSETTINGS_RM_MAINPORT_MAVLINK] = PIOS_BOARD_IO_UART_MAVLINK,
|
||||||
[HWSETTINGS_RM_MAINPORT_FRSKYSENSORHUB] = PIOS_BOARD_IO_UART_FRSKY_SENSORHUB,
|
[HWSETTINGS_RM_MAINPORT_FRSKYSENSORHUB] = PIOS_BOARD_IO_UART_FRSKY_SENSORHUB,
|
||||||
[HWSETTINGS_RM_MAINPORT_HOTTTELEMETRY] = PIOS_BOARD_IO_UART_HOTT_BRIDGE,
|
[HWSETTINGS_RM_MAINPORT_HOTTTELEMETRY] = PIOS_BOARD_IO_UART_HOTT_BRIDGE,
|
||||||
|
[HWSETTINGS_RM_MAINPORT_FRSKYSPORT] = PIOS_BOARD_IO_UART_FRSKY_SPORT,
|
||||||
};
|
};
|
||||||
|
|
||||||
static const PIOS_BOARD_IO_UART_Function flexi_function_map[] = {
|
static const PIOS_BOARD_IO_UART_Function flexi_function_map[] = {
|
||||||
@ -107,6 +109,7 @@ static const PIOS_BOARD_IO_UART_Function flexi_function_map[] = {
|
|||||||
[HWSETTINGS_RM_FLEXIPORT_MAVLINK] = PIOS_BOARD_IO_UART_MAVLINK,
|
[HWSETTINGS_RM_FLEXIPORT_MAVLINK] = PIOS_BOARD_IO_UART_MAVLINK,
|
||||||
[HWSETTINGS_RM_FLEXIPORT_FRSKYSENSORHUB] = PIOS_BOARD_IO_UART_FRSKY_SENSORHUB,
|
[HWSETTINGS_RM_FLEXIPORT_FRSKYSENSORHUB] = PIOS_BOARD_IO_UART_FRSKY_SENSORHUB,
|
||||||
[HWSETTINGS_RM_FLEXIPORT_HOTTTELEMETRY] = PIOS_BOARD_IO_UART_HOTT_BRIDGE,
|
[HWSETTINGS_RM_FLEXIPORT_HOTTTELEMETRY] = PIOS_BOARD_IO_UART_HOTT_BRIDGE,
|
||||||
|
[HWSETTINGS_RM_FLEXIPORT_FRSKYSPORT] = PIOS_BOARD_IO_UART_FRSKY_SPORT,
|
||||||
};
|
};
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
Loading…
x
Reference in New Issue
Block a user