mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 07:13:56 -04:00
AP_Mount: replace header guard with pragma once
This commit is contained in:
parent
7d9153feb8
commit
3a771bf0e3
@ -19,8 +19,7 @@
|
|||||||
* Comments: All angles in degrees * 100, distances in meters*
|
* Comments: All angles in degrees * 100, distances in meters*
|
||||||
* unless otherwise stated. *
|
* unless otherwise stated. *
|
||||||
************************************************************/
|
************************************************************/
|
||||||
#ifndef __AP_MOUNT_H__
|
#pragma once
|
||||||
#define __AP_MOUNT_H__
|
|
||||||
|
|
||||||
#include <AP_Math/AP_Math.h>
|
#include <AP_Math/AP_Math.h>
|
||||||
#include <AP_Common/AP_Common.h>
|
#include <AP_Common/AP_Common.h>
|
||||||
@ -186,5 +185,3 @@ protected:
|
|||||||
|
|
||||||
DataFlash_Class *_dataflash;
|
DataFlash_Class *_dataflash;
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // __AP_MOUNT_H__
|
|
||||||
|
@ -3,9 +3,7 @@
|
|||||||
/*
|
/*
|
||||||
Alexmos Serial controlled mount backend class
|
Alexmos Serial controlled mount backend class
|
||||||
*/
|
*/
|
||||||
|
#pragma once
|
||||||
#ifndef __AP_MOUNT_ALEXMOS_H__
|
|
||||||
#define __AP_MOUNT_ALEXMOS_H__
|
|
||||||
|
|
||||||
#include "AP_Mount.h"
|
#include "AP_Mount.h"
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
@ -319,5 +317,3 @@ private:
|
|||||||
// confirmed that last command was ok
|
// confirmed that last command was ok
|
||||||
bool _last_command_confirmed : 1;
|
bool _last_command_confirmed : 1;
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif
|
|
||||||
|
@ -18,9 +18,7 @@
|
|||||||
Mount driver backend class. Each supported mount type
|
Mount driver backend class. Each supported mount type
|
||||||
needs to have an object derived from this class.
|
needs to have an object derived from this class.
|
||||||
*/
|
*/
|
||||||
|
#pragma once
|
||||||
#ifndef __AP_MOUNT_BACKEND_H__
|
|
||||||
#define __AP_MOUNT_BACKEND_H__
|
|
||||||
|
|
||||||
#include <AP_Common/AP_Common.h>
|
#include <AP_Common/AP_Common.h>
|
||||||
#include "AP_Mount.h"
|
#include "AP_Mount.h"
|
||||||
@ -100,5 +98,3 @@ protected:
|
|||||||
uint8_t _instance; // this instance's number
|
uint8_t _instance; // this instance's number
|
||||||
Vector3f _angle_ef_target_rad; // desired earth-frame roll, tilt and vehicle-relative pan angles in radians
|
Vector3f _angle_ef_target_rad; // desired earth-frame roll, tilt and vehicle-relative pan angles in radians
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // __AP_MOUNT_BACKEND_H__
|
|
||||||
|
@ -3,9 +3,7 @@
|
|||||||
/*
|
/*
|
||||||
SToRM32 mount backend class
|
SToRM32 mount backend class
|
||||||
*/
|
*/
|
||||||
|
#pragma once
|
||||||
#ifndef __AP_MOUNT_STORM32_H__
|
|
||||||
#define __AP_MOUNT_STORM32_H__
|
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <AP_AHRS/AP_AHRS.h>
|
#include <AP_AHRS/AP_AHRS.h>
|
||||||
@ -58,5 +56,3 @@ private:
|
|||||||
mavlink_channel_t _chan; // mavlink channel used to communicate with gimbal. Currently hard-coded to Telem2
|
mavlink_channel_t _chan; // mavlink channel used to communicate with gimbal. Currently hard-coded to Telem2
|
||||||
uint32_t _last_send; // system time of last do_mount_control sent to gimbal
|
uint32_t _last_send; // system time of last do_mount_control sent to gimbal
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // __AP_MOUNT_STORM32_H__
|
|
||||||
|
@ -3,9 +3,7 @@
|
|||||||
/*
|
/*
|
||||||
SToRM32 mount using serial protocol backend class
|
SToRM32 mount using serial protocol backend class
|
||||||
*/
|
*/
|
||||||
|
#pragma once
|
||||||
#ifndef __AP_MOUNT_STORM32_SERIAL_H__
|
|
||||||
#define __AP_MOUNT_STORM32_SERIAL_H__
|
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <AP_AHRS/AP_AHRS.h>
|
#include <AP_AHRS/AP_AHRS.h>
|
||||||
@ -153,5 +151,3 @@ private:
|
|||||||
// keep the last _current_angle values
|
// keep the last _current_angle values
|
||||||
Vector3l _current_angle;
|
Vector3l _current_angle;
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // __AP_MOUNT_STORM32_SERIAL_H__
|
|
||||||
|
@ -3,9 +3,7 @@
|
|||||||
/*
|
/*
|
||||||
Servo controlled mount backend class
|
Servo controlled mount backend class
|
||||||
*/
|
*/
|
||||||
|
#pragma once
|
||||||
#ifndef __AP_MOUNT_SERVO_H__
|
|
||||||
#define __AP_MOUNT_SERVO_H__
|
|
||||||
|
|
||||||
#include <AP_Math/AP_Math.h>
|
#include <AP_Math/AP_Math.h>
|
||||||
#include <AP_Common/AP_Common.h>
|
#include <AP_Common/AP_Common.h>
|
||||||
@ -80,5 +78,3 @@ private:
|
|||||||
|
|
||||||
uint32_t _last_check_servo_map_ms; // system time of latest call to check_servo_map function
|
uint32_t _last_check_servo_map_ms; // system time of latest call to check_servo_map function
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // __AP_MOUNT_SERVO_H__
|
|
||||||
|
@ -3,9 +3,7 @@
|
|||||||
/*
|
/*
|
||||||
MAVLink enabled mount backend class
|
MAVLink enabled mount backend class
|
||||||
*/
|
*/
|
||||||
|
#pragma once
|
||||||
#ifndef __AP_MOUNT_SOLOGIMBAL_H__
|
|
||||||
#define __AP_MOUNT_SOLOGIMBAL_H__
|
|
||||||
|
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
@ -66,5 +64,3 @@ private:
|
|||||||
};
|
};
|
||||||
|
|
||||||
#endif // AP_AHRS_NAVEKF_AVAILABLE
|
#endif // AP_AHRS_NAVEKF_AVAILABLE
|
||||||
|
|
||||||
#endif // __AP_MOUNT_SOLOGIMBAL_H__
|
|
||||||
|
@ -6,8 +6,7 @@
|
|||||||
* Author: Arthur Benemann, Paul Riseborough; *
|
* Author: Arthur Benemann, Paul Riseborough; *
|
||||||
* *
|
* *
|
||||||
************************************************************/
|
************************************************************/
|
||||||
#ifndef __SOLOGIMBAL_H__
|
#pragma once
|
||||||
#define __SOLOGIMBAL_H__
|
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <AP_AHRS/AP_AHRS.h>
|
#include <AP_AHRS/AP_AHRS.h>
|
||||||
@ -158,5 +157,3 @@ private:
|
|||||||
};
|
};
|
||||||
|
|
||||||
#endif // AP_AHRS_NAVEKF_AVAILABLE
|
#endif // AP_AHRS_NAVEKF_AVAILABLE
|
||||||
|
|
||||||
#endif // __AP_MOUNT_H__
|
|
||||||
|
@ -17,9 +17,7 @@
|
|||||||
You should have received a copy of the GNU General Public License
|
You should have received a copy of the GNU General Public License
|
||||||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
|
#pragma once
|
||||||
#ifndef _SOLO_GIMBAL_EKF_
|
|
||||||
#define _SOLO_GIMBAL_EKF_
|
|
||||||
|
|
||||||
#include <AP_Math/AP_Math.h>
|
#include <AP_Math/AP_Math.h>
|
||||||
#include <AP_InertialSensor/AP_InertialSensor.h>
|
#include <AP_InertialSensor/AP_InertialSensor.h>
|
||||||
@ -172,5 +170,3 @@ private:
|
|||||||
// Force symmmetry and non-negative diagonals on state covarinace matrix
|
// Force symmmetry and non-negative diagonals on state covarinace matrix
|
||||||
void fixCovariance();
|
void fixCovariance();
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // _SOLO_GIMBAL_EKF_
|
|
||||||
|
@ -1,5 +1,4 @@
|
|||||||
#ifndef __SOLOGIMBAL_PARAMETERS__
|
#pragma once
|
||||||
#define __SOLOGIMBAL_PARAMETERS__
|
|
||||||
#include <AP_Math/AP_Math.h>
|
#include <AP_Math/AP_Math.h>
|
||||||
#include <AP_Common/AP_Common.h>
|
#include <AP_Common/AP_Common.h>
|
||||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||||
@ -89,6 +88,3 @@ private:
|
|||||||
|
|
||||||
mavlink_channel_t _chan;
|
mavlink_channel_t _chan;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
#endif // __SOLOGIMBAL_PARAMETERS__
|
|
||||||
|
Loading…
Reference in New Issue
Block a user