Browse Source

AP_AHRS: Reduce scope of AP_Baro.h

master
Michael du Breuil 6 years ago committed by Peter Barker
parent
commit
1226eb825a
  1. 5
      libraries/AP_AHRS/AP_AHRS.cpp
  2. 5
      libraries/AP_AHRS/AP_AHRS.h
  3. 1
      libraries/AP_AHRS/AP_AHRS_DCM.cpp
  4. 1
      libraries/AP_AHRS/AP_AHRS_NavEKF.cpp
  5. 1
      libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp

5
libraries/AP_AHRS/AP_AHRS.cpp

@ -19,6 +19,7 @@ @@ -19,6 +19,7 @@
#include <AP_HAL/AP_HAL.h>
#include <AP_Logger/AP_Logger.h>
#include <AP_GPS/AP_GPS.h>
#include <AP_Baro/AP_Baro.h>
#include <AP_NMEA_Output/AP_NMEA_Output.h>
extern const AP_HAL::HAL& hal;
@ -503,6 +504,10 @@ void AP_AHRS::Log_Write_Home_And_Origin() @@ -503,6 +504,10 @@ void AP_AHRS::Log_Write_Home_And_Origin()
}
}
// get apparent to true airspeed ratio
float AP_AHRS::get_EAS2TAS(void) const {
return AP::baro().get_EAS2TAS();
}
void AP_AHRS::update_nmea_out()
{

5
libraries/AP_AHRS/AP_AHRS.h

@ -26,7 +26,6 @@ @@ -26,7 +26,6 @@
#include <AP_Airspeed/AP_Airspeed.h>
#include <AP_Beacon/AP_Beacon.h>
#include <AP_InertialSensor/AP_InertialSensor.h>
#include <AP_Baro/AP_Baro.h>
#include <AP_Param/AP_Param.h>
#include <AP_Common/Location.h>
@ -301,9 +300,7 @@ public: @@ -301,9 +300,7 @@ public:
}
// get apparent to true airspeed ratio
float get_EAS2TAS(void) const {
return AP::baro().get_EAS2TAS();
}
float get_EAS2TAS(void) const;
// return true if airspeed comes from an airspeed sensor, as
// opposed to an IMU estimate

1
libraries/AP_AHRS/AP_AHRS_DCM.cpp

@ -24,6 +24,7 @@ @@ -24,6 +24,7 @@
#include <AP_HAL/AP_HAL.h>
#include <GCS_MAVLink/GCS.h>
#include <AP_GPS/AP_GPS.h>
#include <AP_Baro/AP_Baro.h>
extern const AP_HAL::HAL& hal;

1
libraries/AP_AHRS/AP_AHRS_NavEKF.cpp

@ -25,6 +25,7 @@ @@ -25,6 +25,7 @@
#include <GCS_MAVLink/GCS.h>
#include <AP_Module/AP_Module.h>
#include <AP_GPS/AP_GPS.h>
#include <AP_Baro/AP_Baro.h>
#if AP_AHRS_NAVEKF_AVAILABLE

1
libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp

@ -9,6 +9,7 @@ @@ -9,6 +9,7 @@
#include <AP_RangeFinder/AP_RangeFinder.h>
#include <AP_Logger/AP_Logger.h>
#include <AP_GPS/AP_GPS.h>
#include <AP_Baro/AP_Baro.h>
void setup();
void loop();

Loading…
Cancel
Save