Add include guard in headers files (#8108)

Signed-off-by: Sugnan Prabhu S <sugnan.prabhu.s@intel.com>
This commit is contained in:
Sugnan Prabhu 2017-10-11 19:17:52 +05:30 committed by Daniel Agar
parent 553c8b38d2
commit 81809be7cd
28 changed files with 56 additions and 1 deletions

View File

@ -31,6 +31,8 @@
*
****************************************************************************/
#pragma once
#include <drivers/device/i2c.h>
#include <drivers/drv_airspeed.h>
#include <drivers/drv_hrt.h>

View File

@ -1,3 +1,5 @@
#pragma once
/*
* I2C busses
*/

View File

@ -38,6 +38,8 @@
* @author Mark Charlebois <charlebm@gmail.com>
*/
#pragma once
#include <px4_tasks.h>
#include <drivers/drv_device.h>
#include "device.h"

View File

@ -41,6 +41,7 @@
* @author Nicolae Rosia <nicolae.rosia@gmail.com>
*/
#pragma once
class LinuxGPIO
{

View File

@ -33,6 +33,8 @@
*
****************************************************************************/
#pragma once
#include <sys/types.h>
#include <sys/stat.h>
#include <sys/ipc.h>

View File

@ -37,6 +37,8 @@
* Shared defines for the mpl3115a2 driver.
*/
#pragma once
#define MPL3115A2_REG_WHO_AM_I 0x0c
#define MPL3115A2_WHO_AM_I 0xC4

View File

@ -38,6 +38,8 @@
* Declarations of parser for the Lightware SF0x laser rangefinder series
*/
#pragma once
enum SF0X_PARSE_STATE {
SF0X_PARSE_STATE0_UNSYNC = 0,
SF0X_PARSE_STATE1_SYNC,
@ -48,4 +50,4 @@ enum SF0X_PARSE_STATE {
SF0X_PARSE_STATE6_GOT_CARRIAGE_RETURN
};
int sf0x_parser(char c, char *parserbuf, unsigned *parserbuf_index, enum SF0X_PARSE_STATE *state, float *dist);
int sf0x_parser(char c, char *parserbuf, unsigned *parserbuf_index, enum SF0X_PARSE_STATE *state, float *dist);

View File

@ -47,6 +47,9 @@
*
* @author Roman Bapst <bapstroman@gmail.com>
*/
#pragma once
#include <lib/mathlib/mathlib.h>
#define SigmoidFunction(val) 1/(1 + expf(-val))

View File

@ -35,6 +35,8 @@
* @file terrain_estimator.h
*/
#pragma once
#include <lib/mathlib/mathlib.h>
#include "matrix/Matrix.hpp"
#include <uORB/topics/sensor_combined.h>

View File

@ -31,6 +31,8 @@
*
****************************************************************************/
#pragma once
#include <stdint.h>
#include <drivers/drv_hrt.h>

View File

@ -34,6 +34,8 @@
/// @file calibration_routines.h
/// @authot Don Gagne <don@thegagnes.com>
#pragma once
/**
* Least-squares fit of a sphere to a set of points.
*

View File

@ -30,6 +30,8 @@
*
****************************************************************************/
#pragma once
#include "microRTPS_transport.h"
#include <cinttypes>

View File

@ -5,6 +5,8 @@
* Author: Anton Babushkin <rk3dov@gmail.com>
*/
#pragma once
#include <stdbool.h>
#include <drivers/drv_hrt.h>

View File

@ -39,6 +39,8 @@
* Parameters definition for position_estimator_inav
*/
#pragma once
#include <systemlib/param/param.h>
struct position_estimator_inav_params {

View File

@ -37,6 +37,8 @@
* General defines and structures for the PX4IO module firmware.
*/
#pragma once
#include <px4_config.h>
#include <stdbool.h>

View File

@ -40,6 +40,8 @@
* @author Beat Küng <beat-kueng@gmx.net>
*/
#pragma once
#include <systemlib/param/param.h>
#include <mathlib/mathlib.h>

View File

@ -31,6 +31,7 @@
*
****************************************************************************/
#pragma once
#include <stdint.h>

View File

@ -31,6 +31,8 @@
*
****************************************************************************/
#pragma once
#include <stdint.h>
#include <systemlib/battery.h>

View File

@ -36,5 +36,7 @@
*
* A simulated Barometer.
*/
#pragma once
#include "VirtDevObj.hpp"

View File

@ -36,6 +36,8 @@
* @author Mark Charlebois <charlebm@gmail.com>
*/
#pragma once
__BEGIN_DECLS
// The commands to run are specified in a target file: commands_<target>.c
extern const char *get_commands(void);

View File

@ -38,6 +38,8 @@
* @author Thomas Gubler <thomasgubler@gmail.com>
*/
#pragma once
#include "ros/ros.h"
#include <gazebo_msgs/ModelStates.h>
#include <sensor_msgs/Imu.h>

View File

@ -38,6 +38,8 @@
* @author Thomas Gubler <thomasgubler@gmail.com>
*/
#pragma once
#include "ros/ros.h"
#include <px4/manual_control_setpoint.h>
#include <px4/vehicle_control_mode.h>

View File

@ -39,6 +39,8 @@
* @author Thomas Gubler <thomasgubler@gmail.com>
*/
#pragma once
#include "ros/ros.h"
#include <px4/manual_control_setpoint.h>

View File

@ -39,6 +39,8 @@
* @author Thomas Gubler <thomasgubler@gmail.com>
*/
#pragma once
#include "ros/ros.h"
#include <px4/manual_control_setpoint.h>

View File

@ -38,6 +38,8 @@
* @author Thomas Gubler <thomasgubler@gmail.com>
*/
#pragma once
#include "ros/ros.h"
#include <px4/manual_control_setpoint.h>
#include <sensor_msgs/Joy.h>

View File

@ -40,6 +40,8 @@
* @author Thomas Gubler <thomasgubler@gmail.com>
*/
#pragma once
#include "ros/ros.h"
#include <mavconn/interface.h>
#include <px4/vehicle_attitude.h>

View File

@ -38,6 +38,8 @@
* @author Thomas Gubler <thomasgubler@gmail.com>
*/
#pragma once
#include "ros/ros.h"
#include <gazebo_msgs/ModelStates.h>
#include <sensor_msgs/Imu.h>

View File

@ -31,6 +31,8 @@
*
****************************************************************************/
#pragma once
#define MAX_SHMEM_PARAMS 2000 //MAP_SIZE - (LOCK_SIZE - sizeof(struct shmem_info))
#define PARAM_BUFFER_SIZE (MAX_SHMEM_PARAMS / 8 + 1)