mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 15:33:57 -04:00
AP_Mount: tidy includes
This commit is contained in:
parent
8930b5f6f5
commit
7ce739aeef
@ -19,8 +19,7 @@
|
|||||||
************************************************************/
|
************************************************************/
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL_Boards.h>
|
||||||
#include <AP_AHRS/AP_AHRS.h>
|
|
||||||
|
|
||||||
#ifndef HAL_MOUNT_ENABLED
|
#ifndef HAL_MOUNT_ENABLED
|
||||||
#define HAL_MOUNT_ENABLED !HAL_MINIMIZE_FEATURES
|
#define HAL_MOUNT_ENABLED !HAL_MINIMIZE_FEATURES
|
||||||
|
@ -2,6 +2,8 @@
|
|||||||
#if HAL_MOUNT_ENABLED
|
#if HAL_MOUNT_ENABLED
|
||||||
#include <AP_SerialManager/AP_SerialManager.h>
|
#include <AP_SerialManager/AP_SerialManager.h>
|
||||||
|
|
||||||
|
#include <AP_AHRS/AP_AHRS.h>
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
void AP_Mount_Alexmos::init()
|
void AP_Mount_Alexmos::init()
|
||||||
@ -305,4 +307,4 @@ void AP_Mount_Alexmos::read_incoming()
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif // HAL_MOUNT_ENABLED
|
#endif // HAL_MOUNT_ENABLED
|
||||||
|
@ -8,7 +8,6 @@
|
|||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <AP_Param/AP_Param.h>
|
#include <AP_Param/AP_Param.h>
|
||||||
#include <AP_Math/AP_Math.h>
|
#include <AP_Math/AP_Math.h>
|
||||||
#include <AP_AHRS/AP_AHRS.h>
|
|
||||||
#include "AP_Mount_Backend.h"
|
#include "AP_Mount_Backend.h"
|
||||||
|
|
||||||
|
|
||||||
|
@ -3,14 +3,14 @@
|
|||||||
*/
|
*/
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include "AP_Mount_Backend.h"
|
||||||
#include <AP_AHRS/AP_AHRS.h>
|
|
||||||
|
#if HAL_MOUNT_ENABLED
|
||||||
|
|
||||||
#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 <RC_Channel/RC_Channel.h>
|
#include <RC_Channel/RC_Channel.h>
|
||||||
#include "AP_Mount_Backend.h"
|
#include <AP_AHRS/AP_AHRS.h>
|
||||||
#if HAL_MOUNT_ENABLED
|
|
||||||
|
|
||||||
#define AP_MOUNT_STORM32_RESEND_MS 1000 // resend angle targets to gimbal once per second
|
#define AP_MOUNT_STORM32_RESEND_MS 1000 // resend angle targets to gimbal once per second
|
||||||
#define AP_MOUNT_STORM32_SEARCH_MS 60000 // search for gimbal for 1 minute after startup
|
#define AP_MOUNT_STORM32_SEARCH_MS 60000 // search for gimbal for 1 minute after startup
|
||||||
|
@ -6,8 +6,7 @@
|
|||||||
************************************************************/
|
************************************************************/
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL_Boards.h>
|
||||||
#include <AP_AHRS/AP_AHRS.h>
|
|
||||||
#include "AP_Mount.h"
|
#include "AP_Mount.h"
|
||||||
#if HAL_SOLO_GIMBAL_ENABLED
|
#if HAL_SOLO_GIMBAL_ENABLED
|
||||||
#include "SoloGimbalEKF.h"
|
#include "SoloGimbalEKF.h"
|
||||||
|
Loading…
Reference in New Issue
Block a user