mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2025-01-18 03:52:11 +01:00
LP-437 - Support for Revolution
This commit is contained in:
parent
0af373a8c7
commit
14080021b2
@ -260,6 +260,7 @@ 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
|
||||
#define PIOS_COM_MAVLINK_RX_BUF_LEN 128
|
||||
|
||||
#if defined(PIOS_INCLUDE_DEBUG_CONSOLE)
|
||||
#define PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN 40
|
||||
@ -279,6 +280,7 @@ uint32_t pios_com_mavlink_id = 0;
|
||||
|
||||
#if defined(PIOS_INCLUDE_RFM22B)
|
||||
uint32_t pios_rfm22b_id = 0;
|
||||
#include <pios_rfm22b_com.h>
|
||||
#endif
|
||||
|
||||
uintptr_t pios_uavo_settings_fs_id;
|
||||
@ -997,6 +999,32 @@ void PIOS_Board_Init(void)
|
||||
|
||||
/* Reinitialize the modem. */
|
||||
PIOS_RFM22B_Reinit(pios_rfm22b_id);
|
||||
|
||||
uint8_t hwsettings_radioaux;
|
||||
HwSettingsRadioAuxStreamGet(&hwsettings_radioaux);
|
||||
// TODO: this is in preparation for full mavlink support and is used by LP-368
|
||||
uint16_t mavlink_rx_size = PIOS_COM_MAVLINK_RX_BUF_LEN;
|
||||
|
||||
switch (hwsettings_radioaux) {
|
||||
case HWSETTINGS_RADIOAUXSTREAM_DEBUGCONSOLE:
|
||||
case HWSETTINGS_RADIOAUXSTREAM_DISABLED:
|
||||
break;
|
||||
case HWSETTINGS_RADIOAUXSTREAM_MAVLINK:
|
||||
{
|
||||
uint8_t *auxrx_buffer = 0;
|
||||
if (mavlink_rx_size) {
|
||||
auxrx_buffer = (uint8_t *)pios_malloc(mavlink_rx_size);
|
||||
}
|
||||
uint8_t *auxtx_buffer = (uint8_t *)pios_malloc(PIOS_COM_MAVLINK_TX_BUF_LEN);
|
||||
PIOS_Assert(auxrx_buffer);
|
||||
PIOS_Assert(auxtx_buffer);
|
||||
if (PIOS_COM_Init(&pios_com_mavlink_id, &pios_rfm22b_aux_com_driver, pios_rfm22b_id,
|
||||
auxrx_buffer, mavlink_rx_size,
|
||||
auxtx_buffer, PIOS_COM_BRIDGE_TX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
} else {
|
||||
oplinkStatus.LinkState = OPLINKSTATUS_LINKSTATE_DISABLED;
|
||||
|
@ -28,7 +28,8 @@
|
||||
<field name="MSPSpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="115200"/>
|
||||
<field name="MAVLinkSpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="57600"/>
|
||||
<field name="USB_HIDPort" units="function" type="enum" elements="1" options="USBTelemetry,RCTransmitter,Disabled" defaultvalue="USBTelemetry"/>
|
||||
<field name="USB_VCPPort" units="function" type="enum" elements="1" options="USBTelemetry,ComBridge,DebugConsole,Disabled" defaultvalue="Disabled"/>
|
||||
<field name="USB_VCPPort" units="function" type="enum" elements="1" options="USBTelemetry,ComBridge,DebugConsole,Disabled,MAVLink" defaultvalue="Disabled"/>
|
||||
<field name="RadioAuxStream" units="function" type="enum" elements="1" options="DebugConsole,Disabled,MAVLink" defaultvalue="Disabled"/>
|
||||
|
||||
<field name="OptionalModules" units="" type="enum" elementnames="CameraStab,CameraControl,GPS,Fault,Altitude,Airspeed,TxPID,Battery,Overo,MagBaro,OsdHk,AutoTune" options="Disabled,Enabled" defaultvalue="Disabled"/>
|
||||
<field name="ADCRouting" units="" type="enum" elementnames="adc0,adc1,adc2,adc3,adc4,adc5,adc6,adc7" options="Disabled,BatteryVoltage,BatteryCurrent,AnalogAirspeed,Generic" defaultvalue="Disabled"/>
|
||||
|
Loading…
x
Reference in New Issue
Block a user