AP_HAL_Linux: fix include order

Sort include alphabetically and make them in order:

Main header
system headers
library headers
local headers

While reordering, change a include of endian.h to our sparse-endian.h
which is more reliant to toolchain changes.
This commit is contained in:
Lucas De Marchi 2016-05-17 23:26:57 -03:00
parent 45c6b750f2
commit 71e10c9132
46 changed files with 436 additions and 449 deletions

View File

@ -1,5 +1,3 @@
#include <AP_HAL/AP_HAL.h>
#include "AnalogIn.h"
using namespace Linux;

View File

@ -1,5 +1,3 @@
#include <AP_HAL/AP_HAL.h>
#include "AnalogIn_ADS1115.h"
AnalogSource_ADS1115::AnalogSource_ADS1115(int16_t pin):

View File

@ -1,9 +1,9 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include <AP_HAL/AP_HAL.h>
#include "AnalogIn_IIO.h"
extern const AP_HAL::HAL& hal;
#include <AP_HAL/AP_HAL.h>
extern const AP_HAL::HAL &hal;
const char* AnalogSource_IIO::analog_sources[] = {
"in_voltage0_raw",

View File

@ -1,12 +1,12 @@
#include <AP_HAL/AP_HAL.h>
#include "AnalogIn_Navio2.h"
#include <cstdio>
#include <cstdlib>
#include <errno.h>
#include <unistd.h>
#include <AP_HAL/AP_HAL.h>
#include "AnalogIn_Navio2.h"
static const AP_HAL::HAL &hal = AP_HAL::get_HAL();
#define ADC_BASE_PATH "/sys/kernel/rcio/adc"

View File

@ -13,11 +13,11 @@
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include <AP_HAL/AP_HAL.h>
#include "GPIO.h"
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
#include "CameraSensor_Mt9v117.h"
#include "GPIO.h"
/* Cam sensor register definitions */
#define CHIP_ID 0x0

View File

@ -1,11 +1,12 @@
#include <errno.h>
#include <fcntl.h>
#include <stdio.h>
#include <unistd.h>
#include <AP_HAL/AP_HAL.h>
#include "ConsoleDevice.h"
#include <stdio.h>
#include <errno.h>
#include <unistd.h>
#include <fcntl.h>
ConsoleDevice::ConsoleDevice()
{

View File

@ -1,4 +1,5 @@
#include <AP_HAL/AP_HAL.h>
#include "GPIO.h"
using namespace Linux;

View File

@ -7,19 +7,18 @@
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO2 || \
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXFMINI
#include "GPIO.h"
#include "Util_RPI.h"
#include <errno.h>
#include <fcntl.h>
#include <poll.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <errno.h>
#include <unistd.h>
#include <fcntl.h>
#include <poll.h>
#include <sys/mman.h>
#include <sys/stat.h>
#include <unistd.h>
#include "GPIO.h"
#include "Util_RPI.h"
using namespace Linux;

View File

@ -1,8 +1,8 @@
#pragma once
#include "AP_HAL_Linux.h"
#include <AP_HAL/AP_HAL.h>
#include "AP_HAL_Linux.h"
#include "GPIO.h"
class Linux::DigitalSource_Sysfs : public AP_HAL::DigitalSource {

View File

@ -1,17 +1,16 @@
#include <assert.h>
#include "HAL_Linux_Class.h"
#include "AP_HAL_Linux_Private.h"
#include <stdio.h>
#include <stdlib.h>
#include <unistd.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/utility/getopt_cpp.h>
#include <stdio.h>
#include <unistd.h>
#include <stdlib.h>
#include <AP_HAL_Empty/AP_HAL_Empty.h>
#include <AP_HAL_Empty/AP_HAL_Empty_Private.h>
#include "AP_HAL_Linux_Private.h"
#include "HAL_Linux_Class.h"
using namespace Linux;
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO || \

View File

@ -17,15 +17,16 @@
#include <AP_HAL/AP_HAL.h>
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
#include <stdio.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <fcntl.h>
#include <unistd.h>
#include <linux/limits.h>
#include <string.h>
#include <cmath>
#include <fcntl.h>
#include <linux/limits.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <sys/stat.h>
#include <sys/types.h>
#include <unistd.h>
#include "Heat_Pwm.h"
extern const AP_HAL::HAL& hal;

View File

@ -1,24 +1,24 @@
#include <dirent.h>
#include <errno.h>
#include <fcntl.h>
#include <limits.h>
#include <linux/i2c-dev.h>
#ifndef I2C_SMBUS_BLOCK_MAX
#include <linux/i2c.h>
#endif
#include <stdio.h>
#include <stdlib.h>
#include <sys/ioctl.h>
#include <sys/stat.h>
#include <sys/types.h>
#include <unistd.h>
#include <AP_HAL/AP_HAL.h>
#include "I2CDriver.h"
#include "Util.h"
#include <errno.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <dirent.h>
#include <fcntl.h>
#include <unistd.h>
#include <stdio.h>
#include <stdlib.h>
#include <limits.h>
#include <sys/ioctl.h>
#include <linux/i2c-dev.h>
#ifndef I2C_SMBUS_BLOCK_MAX
#include <linux/i2c.h>
#endif
extern const AP_HAL::HAL& hal;
extern const AP_HAL::HAL &hal;
using namespace Linux;
@ -258,16 +258,13 @@ bool I2CDriver::do_transfer(uint8_t addr, const uint8_t *send,
if (send_len == 0 && recv_len) {
msg_rdwr.msgs = &i2cmsg[1];
msg_rdwr.nmsgs = 1;
}
else if (send_len && recv_len == 0) {
} else if (send_len && recv_len == 0) {
msg_rdwr.msgs = &i2cmsg[0];
msg_rdwr.nmsgs = 1;
}
else if (send_len && recv_len) {
}else if (send_len && recv_len) {
msg_rdwr.msgs = &i2cmsg[0];
msg_rdwr.nmsgs = 2;
}
else {
} else {
return false;
}
return ioctl(_fake_dev->get_fd(), I2C_RDWR, &msg_rdwr) == (int)msg_rdwr.nmsgs;

View File

@ -19,14 +19,14 @@
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI
#include "OpticalFlow_Onboard.h"
#include <vector>
#include <stdio.h>
#include <pthread.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <fcntl.h>
#include <unistd.h>
#include <linux/v4l2-mediabus.h>
#include <pthread.h>
#include <stdio.h>
#include <sys/stat.h>
#include <sys/types.h>
#include <unistd.h>
#include <vector>
#include "CameraSensor_Mt9v117.h"
#include "GPIO.h"

View File

@ -15,8 +15,6 @@
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include <AP_HAL/AP_HAL.h>
#include "PWM_Sysfs.h"
#include <errno.h>
@ -26,6 +24,7 @@
#include <stdlib.h>
#include <unistd.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Math/AP_Math.h>
static const AP_HAL::HAL &hal = AP_HAL::get_HAL();

View File

@ -15,14 +15,12 @@
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include <AP_HAL/AP_HAL.h>
#if !defined(PERF_LTTNG)
#include <limits.h>
#include <time.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Math/AP_Math.h>
#include "AP_HAL_Linux.h"

View File

@ -12,21 +12,22 @@
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include <AP_HAL/AP_HAL.h>
#pragma GCC diagnostic ignored "-Wcast-align"
#if defined(PERF_LTTNG)
#define TRACEPOINT_CREATE_PROBES
#define TRACEPOINT_DEFINE
#include "Perf_Lttng_TracePoints.h"
#include <string.h>
#include "Perf_Lttng.h"
#include <AP_HAL/AP_HAL.h>
#include "AP_HAL_Linux.h"
#include "Perf_Lttng_TracePoints.h"
#include "Perf_Lttng.h"
#include "Util.h"
#pragma GCC diagnostic ignored "-Wcast-align"
using namespace Linux;
Perf_Lttng::Perf_Lttng(AP_HAL::Util::perf_counter_type type, const char *name)

View File

@ -1,20 +1,20 @@
#include <stdio.h>
#include <sys/time.h>
#include <errno.h>
#include <fcntl.h>
#include <poll.h>
#include <stdint.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <errno.h>
#include <unistd.h>
#include <fcntl.h>
#include <poll.h>
#include <sys/mman.h>
#include <sys/stat.h>
#include <stdint.h>
#include <sys/time.h>
#include <unistd.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/utility/dsm.h>
#include "RCInput.h"
#include "sbus.h"
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/utility/dsm.h>
extern const AP_HAL::HAL& hal;

View File

@ -14,18 +14,17 @@
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI
#include <stdio.h>
#include <sys/time.h>
#include <errno.h>
#include <fcntl.h>
#include <poll.h>
#include <stdint.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <errno.h>
#include <unistd.h>
#include <fcntl.h>
#include <poll.h>
#include <sys/mman.h>
#include <sys/stat.h>
#include <stdint.h>
#include <sys/time.h>
#include <unistd.h>
#include "RCInput.h"
#include "RCInput_AioPRU.h"

View File

@ -4,18 +4,17 @@
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBOARD || \
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI
#include <stdio.h>
#include <sys/time.h>
#include <errno.h>
#include <fcntl.h>
#include <poll.h>
#include <stdint.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <errno.h>
#include <unistd.h>
#include <fcntl.h>
#include <poll.h>
#include <sys/mman.h>
#include <sys/stat.h>
#include <stdint.h>
#include <sys/time.h>
#include <unistd.h>
#include "GPIO.h"
#include "RCInput.h"

View File

@ -4,28 +4,26 @@
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBRAIN2 || \
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BH || \
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXFMINI
#include <assert.h>
#include <errno.h>
#include <fcntl.h>
#include <pthread.h>
#include <stdint.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <sys/ioctl.h>
#include <sys/mman.h>
#include <sys/stat.h>
#include <sys/time.h>
#include <sys/types.h>
#include <time.h>
#include <unistd.h>
#include "GPIO.h"
#include "RCInput_RPI.h"
#include "Util_RPI.h"
#include <stdio.h>
#include <stdlib.h>
#include <unistd.h>
#include <fcntl.h>
#include <stdint.h>
#include <sys/ioctl.h>
#include <pthread.h>
#include <string.h>
#include <errno.h>
#include <stdint.h>
#include <time.h>
#include <sys/time.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <sys/mman.h>
#include <assert.h>
//Parametres
#define RCIN_RPI_BUFFER_LENGTH 8
#define RCIN_RPI_SAMPLE_FREQ 500

View File

@ -2,14 +2,14 @@
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RASPILOT
#include <stdio.h>
#include <errno.h>
#include <stdlib.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <fcntl.h>
#include <unistd.h>
#include <assert.h>
#include <errno.h>
#include <fcntl.h>
#include <stdio.h>
#include <stdlib.h>
#include <sys/stat.h>
#include <sys/types.h>
#include <unistd.h>
#include "RCInput_Raspilot.h"

View File

@ -1,5 +1,3 @@
#include <AP_HAL/AP_HAL.h>
#include "RCInput_UART.h"
#include <errno.h>
@ -11,6 +9,8 @@
#include <termios.h>
#include <unistd.h>
#include <AP_HAL/AP_HAL.h>
#define MAGIC 0x55AA
using namespace Linux;

View File

@ -1,7 +1,8 @@
#include <stdio.h>
#include <AP_HAL/AP_HAL.h>
#include "RCInput_UDP.h"
#include <stdio.h>
extern const AP_HAL::HAL& hal;

View File

@ -1,17 +1,16 @@
#include <AP_HAL/AP_HAL.h>
#include <stdio.h>
#include <sys/time.h>
#include <errno.h>
#include <fcntl.h>
#include <poll.h>
#include <stdint.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <errno.h>
#include <unistd.h>
#include <fcntl.h>
#include <poll.h>
#include <sys/mman.h>
#include <sys/stat.h>
#include <stdint.h>
#include <sys/time.h>
#include <unistd.h>
#include <AP_HAL/AP_HAL.h>
#include "GPIO.h"
#include "RCInput.h"

View File

@ -8,19 +8,18 @@
// GNU General Public License for more details.
// You should have received a copy of the GNU General Public License
// along with this program. If not, see <http://www.gnu.org/licenses/>.
#include "RCOutput_AioPRU.h"
#include <fcntl.h>
#include <signal.h>
#include <stdint.h>
#include <stdio.h>
#include <stdlib.h>
#include <sys/mman.h>
#include <unistd.h>
#include <AP_HAL/AP_HAL.h>
#include "RCOutput_AioPRU.h"
#include <fcntl.h>
#include <unistd.h>
#include <stdlib.h>
#include <stdio.h>
#include <stdint.h>
#include <sys/mman.h>
#include <signal.h>
#include "../../Tools/Linux_HAL_Essentials/pru/aiopru/RcAioPRU_bin.h"
using namespace Linux;

View File

@ -1,15 +1,17 @@
#include <AP_HAL/AP_HAL.h>
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
#include <endian.h>
#include <stdio.h>
#include <sys/time.h>
#include <poll.h>
#include <unistd.h>
#include <stdlib.h>
#include <errno.h>
#include <sys/mman.h>
#include <poll.h>
#include <pthread.h>
#include <stdio.h>
#include <stdlib.h>
#include <sys/mman.h>
#include <sys/time.h>
#include <unistd.h>
#include <AP_HAL/utility/sparse-endian.h>
#include "RCOutput_Bebop.h"
#include "Util.h"

View File

@ -1,17 +1,18 @@
#include "RCOutput_PCA9685.h"
#include <cmath>
#include <dirent.h>
#include <fcntl.h>
#include <stdint.h>
#include <stdio.h>
#include <stdlib.h>
#include <sys/stat.h>
#include <sys/types.h>
#include <unistd.h>
#include <AP_HAL/AP_HAL.h>
#include "GPIO.h"
#include "RCOutput_PCA9685.h"
#include <sys/types.h>
#include <sys/stat.h>
#include <fcntl.h>
#include <unistd.h>
#include <dirent.h>
#include <stdlib.h>
#include <stdio.h>
#include <stdint.h>
#include <cmath>
#include "GPIO.h"
#define PCA9685_RA_MODE1 0x00
#define PCA9685_RA_MODE2 0x01
@ -243,6 +244,7 @@ uint16_t RCOutput_PCA9685::read(uint8_t ch)
void RCOutput_PCA9685::read(uint16_t* period_us, uint8_t len)
{
for (int i = 0; i < len; i++)
for (int i = 0; i < len; i++) {
period_us[i] = read(0 + i);
}
}

View File

@ -1,22 +1,22 @@
#include "RCOutput_PRU.h"
#include <dirent.h>
#include <fcntl.h>
#include <linux/spi/spidev.h>
#include <signal.h>
#include <stdint.h>
#include <stdio.h>
#include <stdlib.h>
#include <sys/ioctl.h>
#include <sys/mman.h>
#include <sys/stat.h>
#include <sys/types.h>
#include <unistd.h>
#include <AP_HAL/AP_HAL.h>
#include "RCOutput_PRU.h"
#include <sys/types.h>
#include <sys/stat.h>
#include <fcntl.h>
#include <unistd.h>
#include <dirent.h>
#include <stdlib.h>
#include <stdio.h>
#include <stdint.h>
#include <sys/ioctl.h>
#include <linux/spi/spidev.h>
#include <sys/mman.h>
#include <signal.h>
using namespace Linux;
#define PWM_CHAN_COUNT 12
static const uint8_t chan_pru_map[]= {10,8,11,9,7,6,5,4,3,2,1,0}; //chan_pru_map[CHANNEL_NUM] = PRU_REG_R30/31_NUM;

View File

@ -1,20 +1,21 @@
#include <AP_HAL/AP_HAL.h>
#include "GPIO.h"
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RASPILOT
#include "RCOutput_Raspilot.h"
#include <sys/types.h>
#include <sys/stat.h>
#include <fcntl.h>
#include <unistd.h>
#include <dirent.h>
#include <stdlib.h>
#include <stdio.h>
#include <stdint.h>
#include <cmath>
#include <dirent.h>
#include <fcntl.h>
#include <stdint.h>
#include <stdio.h>
#include <stdlib.h>
#include <sys/stat.h>
#include <sys/types.h>
#include <unistd.h>
#include "px4io_protocol.h"
#include "GPIO.h"
using namespace Linux;

View File

@ -15,12 +15,10 @@
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include <AP_HAL/AP_HAL.h>
#include "RCOutput_Sysfs.h"
#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Math/AP_Math.h>
namespace Linux {

View File

@ -2,18 +2,20 @@
#include <AP_HAL/AP_HAL.h>
#include "RCOutput_ZYNQ.h"
#include <sys/types.h>
#include <sys/stat.h>
#include <fcntl.h>
#include <unistd.h>
#include <dirent.h>
#include <stdlib.h>
#include <stdio.h>
#include <stdint.h>
#include <sys/ioctl.h>
#include <fcntl.h>
#include <linux/spi/spidev.h>
#include <sys/mman.h>
#include <signal.h>
#include <stdint.h>
#include <stdio.h>
#include <stdlib.h>
#include <sys/ioctl.h>
#include <sys/mman.h>
#include <sys/stat.h>
#include <sys/types.h>
#include <unistd.h>
using namespace Linux;
#define PWM_CHAN_COUNT 8 // FIXME

View File

@ -1,10 +1,9 @@
#include <AP_HAL/AP_HAL.h>
#include "RPIOUARTDriver.h"
#include <stdlib.h>
#include <cstdio>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/utility/RingBuffer.h>
#include "px4io_protocol.h"

View File

@ -1,16 +1,18 @@
#include "SPIDriver.h"
#include <errno.h>
#include <fcntl.h>
#include <linux/spi/spidev.h>
#include <stdint.h>
#include <stdio.h>
#include <sys/ioctl.h>
#include <sys/stat.h>
#include <sys/types.h>
#include <unistd.h>
#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>
#include "SPIDriver.h"
#include <sys/types.h>
#include <sys/stat.h>
#include <fcntl.h>
#include <unistd.h>
#include <stdio.h>
#include <stdint.h>
#include <errno.h>
#include <sys/ioctl.h>
#include <linux/spi/spidev.h>
#include "GPIO.h"
using namespace Linux;

View File

@ -1,8 +1,9 @@
#include <AP_HAL/AP_HAL.h>
#include "SPIUARTDriver.h"
#include <stdlib.h>
#include <cstdio>
#include "SPIUARTDriver.h"
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/utility/RingBuffer.h>
extern const AP_HAL::HAL& hal;

View File

@ -1,9 +1,10 @@
#pragma once
#include <pthread.h>
#include <AP_HAL/AP_HAL_Boards.h>
#include "AP_HAL_Linux.h"
#include <pthread.h>
class Linux::Semaphore : public AP_HAL::Semaphore {
public:

View File

@ -1,14 +1,15 @@
#include <AP_HAL/AP_HAL.h>
#include "Storage.h"
#include <assert.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <fcntl.h>
#include <unistd.h>
#include <errno.h>
#include <fcntl.h>
#include <stdio.h>
#include <sys/stat.h>
#include <sys/types.h>
#include <unistd.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Vehicle/AP_Vehicle_Type.h>
#include "Storage.h"
using namespace Linux;

View File

@ -1,13 +1,14 @@
#include <AP_HAL/AP_HAL.h>
#include <assert.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <errno.h>
#include <fcntl.h>
#include <inttypes.h>
#include <unistd.h>
#include <errno.h>
#include <stdio.h>
#include <sys/stat.h>
#include <sys/types.h>
#include <unistd.h>
#include <AP_HAL/AP_HAL.h>
#include "Storage.h"
using namespace Linux;

View File

@ -1,12 +1,12 @@
#include <AP_HAL/AP_HAL.h>
#include <stdio.h>
#include <unistd.h>
#include <errno.h>
#include <stdlib.h>
#include "TCPServerDevice.h"
#include <errno.h>
#include <stdio.h>
#include <stdlib.h>
#include <unistd.h>
#include <AP_HAL/AP_HAL.h>
extern const AP_HAL::HAL& hal;
TCPServerDevice::TCPServerDevice(const char *ip, uint16_t port, bool wait):

View File

@ -1,23 +1,23 @@
#include <AP_HAL/AP_HAL.h>
#include "ToneAlarm.h"
#include <stdio.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <fcntl.h>
#include <unistd.h>
#include <stdlib.h>
#include <iostream>
#include <stdio.h>
#include <stdlib.h>
#include <sys/stat.h>
#include <sys/types.h>
#include <unistd.h>
#include <AP_HAL/AP_HAL.h>
using namespace Linux;
extern const AP_HAL::HAL& hal;
static uint16_t notes[] = { 0,
NOTE_C4, NOTE_CS4, NOTE_D4, NOTE_DS4, NOTE_E4, NOTE_F4, NOTE_FS4, NOTE_G4, NOTE_GS4, NOTE_A4, NOTE_AS4, NOTE_B4,
NOTE_C5, NOTE_CS5, NOTE_D5, NOTE_DS5, NOTE_E5, NOTE_F5, NOTE_FS5, NOTE_G5, NOTE_GS5, NOTE_A5, NOTE_AS5, NOTE_B5,
NOTE_C6, NOTE_CS6, NOTE_D6, NOTE_DS6, NOTE_E6, NOTE_F6, NOTE_FS6, NOTE_G6, NOTE_GS6, NOTE_A6, NOTE_AS6, NOTE_B6,
NOTE_C7, NOTE_CS7, NOTE_D7, NOTE_DS7, NOTE_E7, NOTE_F7, NOTE_FS7, NOTE_G7, NOTE_GS7, NOTE_A7, NOTE_AS7, NOTE_B7
NOTE_C4, NOTE_CS4, NOTE_D4, NOTE_DS4, NOTE_E4, NOTE_F4, NOTE_FS4, NOTE_G4, NOTE_GS4, NOTE_A4, NOTE_AS4, NOTE_B4,
NOTE_C5, NOTE_CS5, NOTE_D5, NOTE_DS5, NOTE_E5, NOTE_F5, NOTE_FS5, NOTE_G5, NOTE_GS5, NOTE_A5, NOTE_AS5, NOTE_B5,
NOTE_C6, NOTE_CS6, NOTE_D6, NOTE_DS6, NOTE_E6, NOTE_F6, NOTE_FS6, NOTE_G6, NOTE_GS6, NOTE_A6, NOTE_AS6, NOTE_B6,
NOTE_C7, NOTE_CS7, NOTE_D7, NOTE_DS7, NOTE_E7, NOTE_F7, NOTE_FS7, NOTE_G7, NOTE_GS7, NOTE_A7, NOTE_AS7, NOTE_B7
};
//List of RTTTL tones

View File

@ -1,20 +1,13 @@
#include <AP_HAL/AP_HAL.h>
#include <termios.h>
#include <stdio.h>
#include <errno.h>
#include <unistd.h>
#include <fcntl.h>
#include <poll.h>
#include "UARTDevice.h"
#include <termios.h>
#include <stdio.h>
#include <errno.h>
#include <unistd.h>
#include <fcntl.h>
#include <poll.h>
#include <stdio.h>
#include <termios.h>
#include <unistd.h>
#include <AP_HAL/AP_HAL.h>
UARTDevice::UARTDevice(const char *device_path):
_device_path(device_path)
@ -23,7 +16,6 @@ UARTDevice::UARTDevice(const char *device_path):
UARTDevice::~UARTDevice()
{
}
bool UARTDevice::close()

View File

@ -1,32 +1,31 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: -*- nil -*-
#include <AP_HAL/AP_HAL.h>
#include "UARTDriver.h"
#include <stdio.h>
#include <errno.h>
#include <termios.h>
#include <stdlib.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <fcntl.h>
#include <unistd.h>
#include <poll.h>
#include <arpa/inet.h>
#include <assert.h>
#include <sys/ioctl.h>
#include <sys/socket.h>
#include <errno.h>
#include <fcntl.h>
#include <netinet/in.h>
#include <netinet/tcp.h>
#include <poll.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <arpa/inet.h>
#include <sys/ioctl.h>
#include <sys/socket.h>
#include <sys/stat.h>
#include <sys/types.h>
#include <termios.h>
#include <unistd.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/utility/RingBuffer.h>
#include "UARTDevice.h"
#include "UDPDevice.h"
#include "ConsoleDevice.h"
#include "TCPServerDevice.h"
#include "UARTDevice.h"
#include "UARTQFlight.h"
#include "UDPDevice.h"
extern const AP_HAL::HAL& hal;

View File

@ -1,10 +1,10 @@
#include <AP_HAL/AP_HAL.h>
#include "UDPDevice.h"
#include <fcntl.h>
#include <stdio.h>
#include <sys/ioctl.h>
#include <fcntl.h>
#include "UDPDevice.h"
#include <AP_HAL/AP_HAL.h>
UDPDevice::UDPDevice(const char *ip, uint16_t port, bool bcast):
_ip(ip),

View File

@ -1,22 +1,21 @@
#include <errno.h>
#include <fcntl.h>
#include <stdarg.h>
#include <stdio.h>
#include <stdlib.h>
#include <sys/stat.h>
#include <time.h>
#include <unistd.h>
#include <AP_HAL/AP_HAL.h>
#include <stdio.h>
#include <stdarg.h>
#include <sys/stat.h>
#include <unistd.h>
#include <stdlib.h>
#include <errno.h>
#include <time.h>
#include <fcntl.h>
extern const AP_HAL::HAL& hal;
#include "Heat_Pwm.h"
#include "ToneAlarm_Raspilot.h"
#include "Util.h"
#include "Heat_Pwm.h"
using namespace Linux;
extern const AP_HAL::HAL& hal;
static int state;
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RASPILOT

View File

@ -38,8 +38,8 @@
#include <stdint.h>
#include <stdbool.h>
#include "sbus.h"
#include "sbus.h"
#define SBUS_FRAME_SIZE 25
#define SBUS_INPUT_CHANNELS 16