AP_Mount: include cleanups
This commit is contained in:
parent
bc5839c1f4
commit
4bdac4afc5
@ -2,9 +2,6 @@
|
||||
|
||||
#if HAL_MOUNT_ALEXMOS_ENABLED
|
||||
#include <AP_SerialManager/AP_SerialManager.h>
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
void AP_Mount_Alexmos::init()
|
||||
{
|
||||
|
@ -2,6 +2,7 @@
|
||||
|
||||
#if HAL_MOUNT_GREMSY_ENABLED
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
@ -11,8 +11,6 @@
|
||||
|
||||
#if HAL_MOUNT_GREMSY_ENABLED
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
|
@ -13,8 +13,6 @@
|
||||
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <RC_Channel/RC_Channel.h>
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
|
||||
class AP_Mount_SToRM32 : public AP_Mount_Backend
|
||||
{
|
||||
|
@ -6,8 +6,6 @@
|
||||
#include <GCS_MAVLink/include/mavlink/v2.0/checksum.h>
|
||||
#include <AP_SerialManager/AP_SerialManager.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
AP_Mount_SToRM32_serial::AP_Mount_SToRM32_serial(AP_Mount &frontend, AP_Mount_Params ¶ms, uint8_t instance) :
|
||||
AP_Mount_Backend(frontend, params, instance),
|
||||
_reply_type(ReplyType_UNKNOWN)
|
||||
|
@ -12,10 +12,8 @@
|
||||
#if HAL_MOUNT_STORM32SERIAL_ENABLED
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
|
||||
#define AP_MOUNT_STORM32_SERIAL_RESEND_MS 1000 // resend angle targets to gimbal once per second
|
||||
|
||||
|
@ -1,6 +1,9 @@
|
||||
#include "AP_Mount_Servo.h"
|
||||
#if HAL_MOUNT_SERVO_ENABLED
|
||||
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
// init - performs any required initialisation for this instance
|
||||
|
@ -13,8 +13,6 @@
|
||||
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
#include <SRV_Channel/SRV_Channel.h>
|
||||
|
||||
class AP_Mount_Servo : public AP_Mount_Backend
|
||||
|
@ -1,5 +1,3 @@
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
#include "AP_Mount_SoloGimbal.h"
|
||||
#if HAL_SOLO_GIMBAL_ENABLED
|
||||
|
||||
@ -8,8 +6,6 @@
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
AP_Mount_SoloGimbal::AP_Mount_SoloGimbal(AP_Mount &frontend, AP_Mount_Params ¶ms, uint8_t instance) :
|
||||
AP_Mount_Backend(frontend, params, instance),
|
||||
_gimbal()
|
||||
|
@ -5,7 +5,6 @@
|
||||
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
|
||||
#include "AP_Mount_Backend.h"
|
||||
#if HAL_SOLO_GIMBAL_ENABLED
|
||||
|
Loading…
Reference in New Issue
Block a user