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

LP-364 Cosmetic changes including (in)famous uncrustify.

This commit is contained in:
Vladimir Zidar 2016-07-22 15:40:54 +02:00 committed by Vladimir Zidar
parent 5b8d168a12
commit 12c6c9b2fe
4 changed files with 7 additions and 12 deletions

View File

@ -1,12 +1,12 @@
/**
******************************************************************************
* @addtogroup TauLabsModules TauLabs Modules
* @addtogroup OpenPilotModules OpenPilot Modules
* @{
* @addtogroup UAVOMavlinkBridge UAVO to Mavlink Bridge Module
* @{
*
* @file UAVOMavlinkBridge.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2016.
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016.
* dRonin, http://dRonin.org/, Copyright (C) 2015-2016
* Tau Labs, http://taulabs.org, Copyright (C) 2013-2014
* @brief Bridges selected UAVObjects to Mavlink
@ -56,11 +56,6 @@
#include "receiverstatus.h"
#include "manualcontrolsettings.h"
// #include "pios_thread.h"
// #include "pios_modules.h"
// #include <pios_hal.h>
#include "custom_types.h"
#define OPLINK_LOW_RSSI -110

View File

@ -330,7 +330,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_TX_BUF_LEN 128
uint32_t pios_com_aux_id = 0;
uint32_t pios_com_gps_id = 0;

View File

@ -26,7 +26,7 @@
<field name="GPSSpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200,230400" defaultvalue="57600"/>
<field name="ComUsbBridgeSpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="57600"/>
<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="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"/>

View File

@ -33,7 +33,7 @@
<elementname>OSDGen</elementname>
<elementname>UAVOMSPBridge</elementname>
<elementname>AutoTune</elementname>
<elementname>UAVOMavlinkBridge</elementname>
<elementname>UAVOMAVLinkBridge</elementname>
</elementnames>
</field>
<field name="Running" units="bool" type="enum">
@ -68,7 +68,7 @@
<elementname>OSDGen</elementname>
<elementname>UAVOMSPBridge</elementname>
<elementname>AutoTune</elementname>
<elementname>UAVOMavlinkBridge</elementname>
<elementname>UAVOMAVLinkBridge</elementname>
</elementnames>
<options>
<option>False</option>
@ -107,7 +107,7 @@
<elementname>OSDGen</elementname>
<elementname>UAVOMSPBridge</elementname>
<elementname>AutoTune</elementname>
<elementname>UAVOMavlinkBridge</elementname>
<elementname>UAVOMAVLinkBridge</elementname>
</elementnames>
</field>
<access gcs="readonly" flight="readwrite"/>