AP_Mount: remove use of AP_Mount.h from headers

This commit is contained in:
Peter Barker 2023-05-26 14:16:12 +10:00 committed by Randy Mackay
parent c30cfb00b6
commit 487ed8d888
4 changed files with 26 additions and 14 deletions

View File

@ -19,16 +19,22 @@
*/ */
#pragma once #pragma once
#include "AP_Mount.h" #include "AP_Mount_config.h"
#if HAL_MOUNT_ENABLED #if HAL_MOUNT_ENABLED
#include <GCS_MAVLink/GCS_MAVLink.h>
#include <AP_Common/AP_Common.h> #include <AP_Common/AP_Common.h>
#include <AP_Common/Location.h>
#include <RC_Channel/RC_Channel.h> #include <RC_Channel/RC_Channel.h>
#include <AP_Camera/AP_Camera_shareddefs.h>
#include "AP_Mount_Params.h"
class AP_Mount_Backend class AP_Mount_Backend
{ {
public: public:
// Constructor // Constructor
AP_Mount_Backend(AP_Mount &frontend, AP_Mount_Params &params, uint8_t instance) : AP_Mount_Backend(class AP_Mount &frontend, class AP_Mount_Params &params, uint8_t instance) :
_frontend(frontend), _frontend(frontend),
_params(params), _params(params),
_instance(instance) _instance(instance)

View File

@ -6,16 +6,18 @@
************************************************************/ ************************************************************/
#pragma once #pragma once
#include <AP_HAL/AP_HAL_Boards.h> #include "AP_Mount_config.h"
#include "AP_Mount.h"
#if HAL_SOLO_GIMBAL_ENABLED #if HAL_SOLO_GIMBAL_ENABLED
#include "SoloGimbalEKF.h"
#include <AP_Math/AP_Math.h>
#include <AP_Common/AP_Common.h>
#include <GCS_MAVLink/GCS_MAVLink.h>
#include <AP_AccelCal/AP_AccelCal.h> #include <AP_AccelCal/AP_AccelCal.h>
#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL_Boards.h>
#include <AP_Math/AP_Math.h>
#include <GCS_MAVLink/GCS_MAVLink.h>
#include "SoloGimbal_Parameters.h" #include "SoloGimbal_Parameters.h"
#include "SoloGimbalEKF.h"
enum gimbal_state_t { enum gimbal_state_t {
GIMBAL_STATE_NOT_PRESENT = 0, GIMBAL_STATE_NOT_PRESENT = 0,

View File

@ -18,11 +18,12 @@
*/ */
#pragma once #pragma once
#include "AP_Mount_config.h"
#if HAL_SOLO_GIMBAL_ENABLED
#include <AP_Math/AP_Math.h> #include <AP_Math/AP_Math.h>
#include <AP_Param/AP_Param.h> #include <AP_Param/AP_Param.h>
//#include <AP_NavEKF2/AP_NavEKF2.h>
#include "AP_Mount.h"
#if HAL_SOLO_GIMBAL_ENABLED
#include <AP_Math/vectorN.h> #include <AP_Math/vectorN.h>
class SoloGimbalEKF class SoloGimbalEKF

View File

@ -1,9 +1,12 @@
#pragma once #pragma once
#include "AP_Mount_config.h"
#if HAL_SOLO_GIMBAL_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 <GCS_MAVLink/GCS_MAVLink.h> #include <GCS_MAVLink/GCS_MAVLink.h>
#include "AP_Mount.h"
#if HAL_SOLO_GIMBAL_ENABLED
enum gmb_param_state_t { enum gmb_param_state_t {
GMB_PARAMSTATE_NOT_YET_READ=0, // parameter has yet to be initialized GMB_PARAMSTATE_NOT_YET_READ=0, // parameter has yet to be initialized