Browse Source

Gimbal: only include for high performance CPUs

mission-4.1.18
Randy Mackay 10 years ago
parent
commit
8ced9cc904
  1. 7
      libraries/AP_Mount/AP_Gimbal.cpp
  2. 11
      libraries/AP_Mount/AP_Gimbal.h

7
libraries/AP_Mount/AP_Gimbal.cpp

@ -1,8 +1,11 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- // -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include <AP_Gimbal.h>
#if AP_AHRS_NAVEKF_AVAILABLE
#include <stdio.h> #include <stdio.h>
#include <AP_Common.h> #include <AP_Common.h>
#include <AP_Gimbal.h>
#include <GCS.h> #include <GCS.h>
#include <AP_SmallEKF.h> #include <AP_SmallEKF.h>
@ -189,3 +192,5 @@ bool AP_Gimbal::isCopterFlipped()
{ {
return (_ahrs.cos_roll()*_ahrs.cos_pitch() < 0.5f); return (_ahrs.cos_roll()*_ahrs.cos_pitch() < 0.5f);
} }
#endif // AP_AHRS_NAVEKF_AVAILABLE

11
libraries/AP_Mount/AP_Gimbal.h

@ -9,15 +9,18 @@
#ifndef __AP_GIMBAL_H__ #ifndef __AP_GIMBAL_H__
#define __AP_GIMBAL_H__ #define __AP_GIMBAL_H__
#include <AP_HAL.h>
#include <AP_AHRS.h>
#if AP_AHRS_NAVEKF_AVAILABLE
#include <AP_Math.h> #include <AP_Math.h>
#include <AP_Common.h> #include <AP_Common.h>
#include <AP_GPS.h> #include <AP_GPS.h>
#include <AP_AHRS.h>
#include <GCS_MAVLink.h> #include <GCS_MAVLink.h>
#include <AP_Mount.h>
#include <AP_SmallEKF.h> #include <AP_SmallEKF.h>
#include <AP_NavEKF.h> #include <AP_NavEKF.h>
#include <AP_Mount.h>
class AP_Gimbal class AP_Gimbal
{ {
@ -83,4 +86,6 @@ private:
}; };
#endif // AP_AHRS_NAVEKF_AVAILABLE
#endif // __AP_MOUNT_H__ #endif // __AP_MOUNT_H__

Loading…
Cancel
Save