1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2025-02-18 08:54:15 +01:00

LP-364 This commit adds MAVLink to revoproto target

This commit is contained in:
Vladimir Zidar 2016-07-22 15:21:15 +02:00 committed by Vladimir Zidar
parent b0dd2649bc
commit 5b8d168a12
4 changed files with 27 additions and 5 deletions

View File

@ -55,6 +55,7 @@ SRC += $(FLIGHTLIB)/notification.c
OPTMODULES += AutoTune
OPTMODULES += ComUsbBridge
OPTMODULES += UAVOMSPBridge
OPTMODULES += UAVOMavlinkBridge
# Include all camera options
CDEFS += -DUSE_INPUT_LPF -DUSE_GIMBAL_LPF -DUSE_GIMBAL_FF

View File

@ -330,6 +330,8 @@ uint32_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE];
#define PIOS_COM_MSP_TX_BUF_LEN 128
#define PIOS_COM_MSP_RX_BUF_LEN 64
#define PIOS_COM_MAVLINK_TX_BUF_LEN 128
uint32_t pios_com_aux_id = 0;
uint32_t pios_com_gps_id = 0;
uint32_t pios_com_telem_usb_id = 0;
@ -338,6 +340,7 @@ uint32_t pios_com_bridge_id = 0;
uint32_t pios_com_overo_id = 0;
uint32_t pios_com_hkosd_id = 0;
uint32_t pios_com_msp_id = 0;
uint32_t pios_com_mavlink_id = 0;
uintptr_t pios_uavo_settings_fs_id;
uintptr_t pios_user_fs_id;
@ -670,6 +673,9 @@ void PIOS_Board_Init(void)
case HWSETTINGS_RV_TELEMETRYPORT_MSP:
PIOS_Board_configure_com(&pios_usart_telem_cfg, PIOS_COM_MSP_RX_BUF_LEN, PIOS_COM_MSP_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_msp_id);
break;
case HWSETTINGS_RV_TELEMETRYPORT_MAVLINK:
PIOS_Board_configure_com(&pios_usart_telem_cfg, 0, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_mavlink_id);
break;
} /* hwsettings_rv_telemetryport */
/* Configure GPS port */
@ -697,6 +703,9 @@ void PIOS_Board_Init(void)
case HWSETTINGS_RV_GPSPORT_MSP:
PIOS_Board_configure_com(&pios_usart_gps_cfg, PIOS_COM_MSP_RX_BUF_LEN, PIOS_COM_MSP_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_msp_id);
break;
case HWSETTINGS_RV_GPSPORT_MAVLINK:
PIOS_Board_configure_com(&pios_usart_gps_cfg, 0, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_mavlink_id);
break;
} /* hwsettings_rv_gpsport */
/* Configure AUXPort */
@ -725,6 +734,9 @@ void PIOS_Board_Init(void)
case HWSETTINGS_RV_AUXPORT_MSP:
PIOS_Board_configure_com(&pios_usart_aux_cfg, PIOS_COM_MSP_RX_BUF_LEN, PIOS_COM_MSP_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_msp_id);
break;
case HWSETTINGS_RV_AUXPORT_MAVLINK:
PIOS_Board_configure_com(&pios_usart_aux_cfg, 0, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_mavlink_id);
break;
case HWSETTINGS_RV_AUXPORT_OSDHK:
PIOS_Board_configure_com(&pios_usart_hkosd_aux_cfg, PIOS_COM_HKOSD_RX_BUF_LEN, PIOS_COM_HKOSD_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_hkosd_id);
break;
@ -773,6 +785,9 @@ void PIOS_Board_Init(void)
case HWSETTINGS_RV_AUXSBUSPORT_MSP:
PIOS_Board_configure_com(&pios_usart_auxsbus_cfg, PIOS_COM_MSP_RX_BUF_LEN, PIOS_COM_MSP_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_msp_id);
break;
case HWSETTINGS_RV_AUXSBUSPORT_MAVLINK:
PIOS_Board_configure_com(&pios_usart_auxsbus_cfg, 0, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_mavlink_id);
break;
case HWSETTINGS_RV_AUXSBUSPORT_OSDHK:
PIOS_Board_configure_com(&pios_usart_hkosd_auxsbus_cfg, PIOS_COM_HKOSD_RX_BUF_LEN, PIOS_COM_HKOSD_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_hkosd_id);
break;
@ -835,6 +850,9 @@ void PIOS_Board_Init(void)
case HWSETTINGS_RV_FLEXIPORT_MSP:
PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_MSP_RX_BUF_LEN, PIOS_COM_MSP_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_msp_id);
break;
case HWSETTINGS_RV_FLEXIPORT_MAVLINK:
PIOS_Board_configure_com(&pios_usart_flexi_cfg, 0, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_mavlink_id);
break;
} /* hwsettings_rv_flexiport */

View File

@ -127,6 +127,8 @@ extern uint32_t pios_com_bridge_id;
extern uint32_t pios_com_vcp_id;
extern uint32_t pios_com_hkosd_id;
extern uint32_t pios_com_msp_id;
extern uint32_t pios_com_mavlink_id;
#define PIOS_COM_AUX (pios_com_aux_id)
#define PIOS_COM_GPS (pios_com_gps_id)
#define PIOS_COM_TELEM_USB (pios_com_telem_usb_id)
@ -136,6 +138,7 @@ extern uint32_t pios_com_msp_id;
#define PIOS_COM_DEBUG PIOS_COM_AUX
#define PIOS_COM_OSDHK (pios_com_hkosd_id)
#define PIOS_COM_MSP (pios_com_msp_id)
#define PIOS_COM_MAVLINK (pios_com_mavlink_id)
// ------------------------
// TELEMETRY

View File

@ -5,11 +5,11 @@
<field name="CC_MainPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,S.Bus,DSM,DebugConsole,ComBridge,OsdHk,MSP,MAVLink" defaultvalue="Telemetry"/>
<field name="CC_FlexiPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,I2C,PPM,DSM,EX.Bus,HoTT SUMD,HoTT SUMH,SRXL,DebugConsole,ComBridge,OsdHk,MSP,MAVLink" defaultvalue="Disabled"/>
<field name="RV_RcvrPort" units="function" type="enum" elements="1" options="Disabled,PWM,PPM,PPM+Outputs,Outputs" defaultvalue="PWM"/>
<field name="RV_AuxPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,DSM,ComAux,ComBridge,OsdHk,MSP" defaultvalue="Disabled"/>
<field name="RV_AuxSBusPort" units="function" type="enum" elements="1" options="Disabled,S.Bus,DSM,ComAux,ComBridge,OsdHk,MSP" defaultvalue="Disabled"/>
<field name="RV_FlexiPort" units="function" type="enum" elements="1" options="Disabled,I2C,DSM,ComAux,ComBridge,MSP" defaultvalue="Disabled"/>
<field name="RV_TelemetryPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,ComAux,ComBridge,MSP" defaultvalue="Telemetry"/>
<field name="RV_GPSPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,ComAux,ComBridge,MSP" defaultvalue="GPS"/>
<field name="RV_AuxPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,DSM,ComAux,ComBridge,OsdHk,MSP,MAVLink" defaultvalue="Disabled"/>
<field name="RV_AuxSBusPort" units="function" type="enum" elements="1" options="Disabled,S.Bus,DSM,ComAux,ComBridge,OsdHk,MSP,MAVLink" defaultvalue="Disabled"/>
<field name="RV_FlexiPort" units="function" type="enum" elements="1" options="Disabled,I2C,DSM,ComAux,ComBridge,MSP,MAVLink" defaultvalue="Disabled"/>
<field name="RV_TelemetryPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,ComAux,ComBridge,MSP,MAVLink" defaultvalue="Telemetry"/>
<field name="RV_GPSPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,ComAux,ComBridge,MSP,MAVLink" defaultvalue="GPS"/>
<field name="RM_RcvrPort" units="function" type="enum" elements="1" options="Disabled,PWM,PPM,PPM+PWM,PPM+Telemetry,PPM+Outputs,Outputs,Telemetry,ComBridge,MSP,MAVLink"
defaultvalue="PWM"