AP_HAL_Linux: replace header guard with pragma once

This commit is contained in:
Lucas De Marchi 2016-02-17 23:25:26 -02:00
parent dbf2aedf1e
commit 705393b30c
37 changed files with 37 additions and 170 deletions

View File

@ -1,6 +1,4 @@
#ifndef __AP_HAL_LINUX_H__
#define __AP_HAL_LINUX_H__
#pragma once
/* Your layer exports should depend on AP_HAL.h ONLY. */
#include <AP_HAL/AP_HAL.h>
@ -25,5 +23,3 @@
#include "HAL_Linux_Class.h"
#endif // CONFIG_HAL_BOARD
#endif //__AP_HAL_LINUX_H__

View File

@ -1,6 +1,4 @@
#ifndef __AP_HAL_LINUX_NAMESPACE_H__
#define __AP_HAL_LINUX_NAMESPACE_H__
#pragma once
namespace Linux {
class UARTDriver;
@ -57,6 +55,3 @@ namespace Linux {
class Flow_PX4;
class Perf_Lttng;
}
#endif // __AP_HAL_LINUX_NAMESPACE_H__

View File

@ -1,6 +1,4 @@
#ifndef __AP_HAL_LINUX_PRIVATE_H__
#define __AP_HAL_LINUX_PRIVATE_H__
#pragma once
/* Umbrella header for all private headers of the AP_HAL_Linux module.
* Only import this header from inside AP_HAL_Linux
@ -46,5 +44,3 @@
#include "VideoIn.h"
#include "OpticalFlow_Onboard.h"
#include "Flow_PX4.h"
#endif // __AP_HAL_LINUX_PRIVATE_H__

View File

@ -1,6 +1,4 @@
#ifndef __AP_HAL_LINUX_ANALOGIN_H__
#define __AP_HAL_LINUX_ANALOGIN_H__
#pragma once
#include "AP_HAL_Linux.h"
@ -29,4 +27,3 @@ public:
float board_voltage(void) { return 0.0f; }
};
#endif // __AP_HAL_LINUX_ANALOGIN_H__

View File

@ -1,5 +1,4 @@
#ifndef __AP_HAL_LINUX_CONSOLEDEVICE_UDP_H__
#define __AP_HAL_LINUX_CONSOLEDEVICE_UDP_H__
#pragma once
#include "SerialDevice.h"
#include <AP_HAL/utility/Socket.h>
@ -21,5 +20,3 @@ private:
int _wr_fd = -1;
bool _closed = true;
};
#endif

View File

@ -1,5 +1,4 @@
#ifndef __AP_HAL_LINUX_GPIO_H__
#define __AP_HAL_LINUX_GPIO_H__
#pragma once
#include "AP_HAL_Linux.h"
@ -32,4 +31,3 @@ private:
#endif
#endif // CONFIG_HAL_BOARD == HAL_BOARD_LINUX
#endif // __AP_HAL_LINUX_GPIO_H__

View File

@ -1,6 +1,4 @@
#ifndef __AP_HAL_LINUX_GPIO_BBB_H__
#define __AP_HAL_LINUX_GPIO_BBB_H__
#pragma once
#include "AP_HAL_Linux.h"
@ -133,5 +131,3 @@ public:
/* return true if USB cable is connected */
bool usb_connected(void);
};
#endif // __AP_HAL_LINUX_GPIO_BBB_H__

View File

@ -1,5 +1,4 @@
#ifndef __AP_HAL_LINUX_GPIO_RPI_H__
#define __AP_HAL_LINUX_GPIO_RPI_H__
#pragma once
#include <stdint.h>
#include "AP_HAL_Linux.h"
@ -98,5 +97,3 @@ public:
/* return true if USB cable is connected */
bool usb_connected(void);
};
#endif // __AP_HAL_LINUX_GPIO_RPI_H__

View File

@ -13,12 +13,9 @@
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef __HEAT_H__
#define __HEAT_H__
#pragma once
class Linux::Heat {
public:
virtual void set_imu_temp(float current) { }
};
#endif

View File

@ -13,9 +13,7 @@
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef __HEAT_PWM_H__
#define __HEAT_PWM_H__
#pragma once
#include "AP_HAL_Linux.h"
#include "PWM_Sysfs.h"
@ -36,4 +34,3 @@ private:
float _sum_error;
float _target;
};
#endif

View File

@ -1,6 +1,4 @@
#ifndef __AP_HAL_LINUX_I2CDRIVER_H__
#define __AP_HAL_LINUX_I2CDRIVER_H__
#pragma once
#include <vector>
@ -56,5 +54,3 @@ private:
uint8_t _addr;
bool _print_ioctl_error = true;
};
#endif // __AP_HAL_LINUX_I2CDRIVER_H__

View File

@ -1,6 +1,4 @@
#ifndef __AP_HAL_LINUX_RCINPUT_H__
#define __AP_HAL_LINUX_RCINPUT_H__
#pragma once
#include "AP_HAL_Linux.h"
@ -77,5 +75,3 @@ public:
#include "RCInput_PRU.h"
#include "RCInput_ZYNQ.h"
#endif // __AP_HAL_LINUX_RCINPUT_H__

View File

@ -8,10 +8,7 @@
// 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/>.
#ifndef __AP_HAL_LINUX_RCINPUT_AIOPRU_H__
#define __AP_HAL_LINUX_RCINPUT_AIOPRU_H__
#pragma once
/*
This class implements RCInput on the BeagleBoneBlack with a PRU
@ -44,5 +41,3 @@ public:
};
volatile struct ring_buffer *ring_buffer;
};
#endif // __AP_HAL_LINUX_RCINPUT_AIOPRU_H__

View File

@ -1,6 +1,4 @@
#ifndef __AP_HAL_LINUX_RCINPUT_PRU_H__
#define __AP_HAL_LINUX_RCINPUT_PRU_H__
#pragma once
/*
This class implements RCInput on the BeagleBoneBlack with a PRU
@ -35,5 +33,3 @@ public:
// time spent in the low state
uint16_t _s0_time;
};
#endif // __AP_HAL_LINUX_RCINPUT_PRU_H__

View File

@ -1,5 +1,4 @@
#ifndef __AP_HAL_LINUX_RCINPUT_RPI_H__
#define __AP_HAL_LINUX_RCINPUT_RPI_H__
#pragma once
#include "AP_HAL_Linux.h"
#include "RCInput.h"
@ -130,5 +129,3 @@ private:
void deinit() override;
};
#endif // __AP_HAL_LINUX_RCINPUT_RPI_H__

View File

@ -1,6 +1,4 @@
#ifndef __AP_HAL_LINUX_RCINPUT_RASPILOT_H__
#define __AP_HAL_LINUX_RCINPUT_RASPILOT_H__
#pragma once
#include "AP_HAL_Linux.h"
#include "RCInput.h"
@ -18,5 +16,3 @@ private:
void _poll_data(void);
};
#endif // __AP_HAL_LINUX_RCINPUT_RASPILOT_H__

View File

@ -1,6 +1,4 @@
#ifndef _AP_HAL_LINUX_RCINPUT_UDP_H
#define _AP_HAL_LINUX_RCINPUT_UDP_H
#pragma once
#include "RCInput.h"
#include <AP_HAL/utility/Socket.h>
@ -21,4 +19,3 @@ private:
uint64_t _last_buf_ts;
uint16_t _last_buf_seq;
};
#endif // _AP_HAL_LINUX_RCINPUT_UDP_H

View File

@ -1,5 +1,4 @@
#ifndef _RCINPUT_UDP_PROTOCOL_H
#define _RCINPUT_UDP_PROTOCOL_H
#pragma once
#define RCINPUT_UDP_NUM_CHANNELS 8
#define RCINPUT_UDP_VERSION 2
@ -10,5 +9,3 @@ struct __attribute__((packed)) rc_udp_packet {
uint16_t sequence;
uint16_t pwms[RCINPUT_UDP_NUM_CHANNELS];
};
#endif

View File

@ -1,6 +1,4 @@
#ifndef __AP_HAL_LINUX_RCINPUT_ZYNQ_H__
#define __AP_HAL_LINUX_RCINPUT_ZYNQ_H__
#pragma once
/*
This class implements RCInput on the ZYNQ / ZyboPilot platform with custom
@ -28,5 +26,3 @@ public:
// time spent in the low state
uint32_t _s0_time;
};
#endif // __AP_HAL_LINUX_RCINPUT_ZYNQ_H__

View File

@ -8,10 +8,7 @@
// 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/>.
#ifndef __AP_HAL_LINUX_RCOUTPUT_AIOPRU_H__
#define __AP_HAL_LINUX_RCOUTPUT_AIOPRU_H__
#pragma once
#include "AP_HAL_Linux.h"
#define RCOUT_PRUSS_RAM_BASE 0x4a302000
@ -43,5 +40,3 @@ private:
volatile struct pwm *pwm;
};
#endif // __AP_HAL_LINUX_RCOUTPUT_AIOPRU_H__

View File

@ -1,5 +1,4 @@
#ifndef __AP_HAL_LINUX_RCOUTPUT_BEBOP_H__
#define __AP_HAL_LINUX_RCOUTPUT_BEBOP_H__
#pragma once
#include "AP_HAL_Linux.h"
@ -108,5 +107,3 @@ private:
void _run_rcout();
static void *_control_thread(void *arg);
};
#endif // __AP_HAL_LINUX_RCOUTPUT_BEBOP_H__

View File

@ -1,6 +1,4 @@
#ifndef __AP_HAL_LINUX_RCOUTPUT_PCA9685_H__
#define __AP_HAL_LINUX_RCOUTPUT_PCA9685_H__
#pragma once
#include "AP_HAL_Linux.h"
@ -43,5 +41,3 @@ private:
int16_t _oe_pin_number;
uint16_t _pending_write_mask;
};
#endif // __AP_HAL_LINUX_RCOUTPUT_PCA9685_H__

View File

@ -1,6 +1,4 @@
#ifndef __AP_HAL_LINUX_RCOUTPUT_PRU_H__
#define __AP_HAL_LINUX_RCOUTPUT_PRU_H__
#pragma once
#include "AP_HAL_Linux.h"
#define RCOUT_PRUSS_SHAREDRAM_BASE 0x4a310000
@ -39,5 +37,3 @@ private:
volatile struct pwm_cmd *sharedMem_cmd;
};
#endif // __AP_HAL_LINUX_RCOUTPUT_PRU_H__

View File

@ -1,6 +1,4 @@
#ifndef __AP_HAL_LINUX_RCOUTPUT_RASPILOT_H__
#define __AP_HAL_LINUX_RCOUTPUT_RASPILOT_H__
#pragma once
#include "AP_HAL_Linux.h"
@ -25,5 +23,3 @@ private:
uint16_t _frequency;
uint16_t _period_us[8];
};
#endif // __AP_HAL_LINUX_RCOUTPUT_RASPILOT_H__

View File

@ -1,6 +1,4 @@
#ifndef __AP_HAL_LINUX_RCOUTPUT_ZYNQ_H__
#define __AP_HAL_LINUX_RCOUTPUT_ZYNQ_H__
#pragma once
#include "AP_HAL_Linux.h"
#define RCOUT_ZYNQ_PWM_BASE 0x43c00000 //FIXME hardcoding is the devil's work
@ -38,5 +36,3 @@ private:
};
volatile struct pwm_cmd *sharedMem_cmd;
};
#endif // __AP_HAL_LINUX_RCOUTPUT_ZYNQ_H__

View File

@ -1,5 +1,4 @@
#ifndef __AP_HAL_LINUX_RPIOUARTDRIVER_H__
#define __AP_HAL_LINUX_RPIOUARTDRIVER_H__
#pragma once
#include "AP_HAL_Linux.h"
@ -37,5 +36,3 @@ private:
bool _need_set_baud;
uint32_t _baudrate;
};
#endif //__AP_HAL_LINUX_RPIOUARTDRIVER_H__

View File

@ -1,5 +1,4 @@
#ifndef __AP_HAL_LINUX_SPIUARTDRIVER_H__
#define __AP_HAL_LINUX_SPIUARTDRIVER_H__
#pragma once
#include "AP_HAL_Linux.h"
@ -28,5 +27,3 @@ private:
uint8_t *_buffer;
bool _external;
};
#endif //__AP_HAL_LINUX_SPIUARTDRIVER_H__

View File

@ -1,6 +1,4 @@
#ifndef __AP_HAL_LINUX_SEMAPHORE_H__
#define __AP_HAL_LINUX_SEMAPHORE_H__
#pragma once
#include <AP_HAL/AP_HAL_Boards.h>
@ -20,5 +18,3 @@ private:
pthread_mutex_t _lock;
};
#endif // CONFIG_HAL_BOARD
#endif // __AP_HAL_LINUX_SEMAPHORE_H__

View File

@ -1,5 +1,4 @@
#ifndef __AP_HAL_LINUX_SERIALDEVICE_H__
#define __AP_HAL_LINUX_SERIALDEVICE_H__
#pragma once
#include <stdint.h>
#include <stdlib.h>
@ -15,5 +14,3 @@ public:
virtual void set_blocking(bool blocking) = 0;
virtual void set_speed(uint32_t speed) = 0;
};
#endif

View File

@ -1,5 +1,4 @@
#ifndef __AP_HAL_LINUX_STORAGE_H__
#define __AP_HAL_LINUX_STORAGE_H__
#pragma once
#define LINUX_STORAGE_USE_FRAM 0
@ -44,6 +43,3 @@ protected:
};
#include "Storage_FRAM.h"
#endif // __AP_HAL_LINUX_STORAGE_H__

View File

@ -1,5 +1,4 @@
#ifndef __AP_HAL_LINUX_STORAGE_FRAM_H__
#define __AP_HAL_LINUX_STORAGE_FRAM_H__
#pragma once
#include <AP_HAL/AP_HAL.h>
#include "AP_HAL_Linux_Namespace.h"
@ -37,4 +36,3 @@ private:
AP_HAL::SPIDeviceDriver *_spi;
AP_HAL::Semaphore *_spi_sem;
};
#endif // __AP_HAL_LINUX_STORAGE_H__

View File

@ -1,5 +1,4 @@
#ifndef __AP_HAL_LINUX_TCPCLIENTDEVICE_H__
#define __AP_HAL_LINUX_TCPCLIENTDEVICE_H__
#pragma once
#include "SerialDevice.h"
#include <AP_HAL/utility/Socket.h>
@ -25,5 +24,3 @@ private:
bool _blocking = false;
uint32_t _last_bind_warning = 0;
};
#endif

View File

@ -1,5 +1,4 @@
#ifndef __TONE_ALARM_DRIVER_H__
#define __TONE_ALARM_DRIVER_H__
#pragma once
#include <AP_HAL/AP_HAL.h>
#include "AP_HAL_Linux_Namespace.h"
@ -140,5 +139,3 @@ private:
int8_t tune_num;
uint8_t tune_pos;
};
#endif

View File

@ -1,5 +1,4 @@
#ifndef __AP_HAL_LINUX_UARTDEVICE_UDP_H__
#define __AP_HAL_LINUX_UARTDEVICE_UDP_H__
#pragma once
#include "SerialDevice.h"
#include <AP_HAL/utility/Socket.h>
@ -22,5 +21,3 @@ private:
int _fd = -1;
const char *_device_path;
};
#endif

View File

@ -1,6 +1,4 @@
#ifndef __AP_HAL_LINUX_UARTDRIVER_H__
#define __AP_HAL_LINUX_UARTDRIVER_H__
#pragma once
#include "AP_HAL_Linux.h"
@ -93,5 +91,3 @@ protected:
virtual int _read_fd(uint8_t *buf, uint16_t n);
};
#endif // __AP_HAL_LINUX_UARTDRIVER_H__

View File

@ -1,5 +1,4 @@
#ifndef __AP_HAL_LINUX_UDPDEVICE_UDP_H__
#define __AP_HAL_LINUX_UDPDEVICE_UDP_H__
#pragma once
#include "SerialDevice.h"
#include <AP_HAL/utility/Socket.h>
@ -22,5 +21,3 @@ private:
bool _bcast;
bool _connected = false;
};
#endif

View File

@ -1,6 +1,4 @@
#ifndef __AP_HAL_LINUX_UTIL_H__
#define __AP_HAL_LINUX_UTIL_H__
#pragma once
#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>
@ -84,7 +82,3 @@ private:
const char* custom_terrain_directory = NULL;
static const char *_hw_names[UTIL_NUM_HARDWARES];
};
#endif // __AP_HAL_LINUX_UTIL_H__