mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-04 23:18:29 -04:00
AP_AHRS: Reduce scope of AP_Baro.h
This commit is contained in:
parent
1a7502b413
commit
1226eb825a
@ -19,6 +19,7 @@
|
|||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <AP_Logger/AP_Logger.h>
|
#include <AP_Logger/AP_Logger.h>
|
||||||
#include <AP_GPS/AP_GPS.h>
|
#include <AP_GPS/AP_GPS.h>
|
||||||
|
#include <AP_Baro/AP_Baro.h>
|
||||||
#include <AP_NMEA_Output/AP_NMEA_Output.h>
|
#include <AP_NMEA_Output/AP_NMEA_Output.h>
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
@ -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()
|
void AP_AHRS::update_nmea_out()
|
||||||
{
|
{
|
||||||
|
@ -26,7 +26,6 @@
|
|||||||
#include <AP_Airspeed/AP_Airspeed.h>
|
#include <AP_Airspeed/AP_Airspeed.h>
|
||||||
#include <AP_Beacon/AP_Beacon.h>
|
#include <AP_Beacon/AP_Beacon.h>
|
||||||
#include <AP_InertialSensor/AP_InertialSensor.h>
|
#include <AP_InertialSensor/AP_InertialSensor.h>
|
||||||
#include <AP_Baro/AP_Baro.h>
|
|
||||||
#include <AP_Param/AP_Param.h>
|
#include <AP_Param/AP_Param.h>
|
||||||
#include <AP_Common/Location.h>
|
#include <AP_Common/Location.h>
|
||||||
|
|
||||||
@ -301,9 +300,7 @@ public:
|
|||||||
}
|
}
|
||||||
|
|
||||||
// get apparent to true airspeed ratio
|
// get apparent to true airspeed ratio
|
||||||
float get_EAS2TAS(void) const {
|
float get_EAS2TAS(void) const;
|
||||||
return AP::baro().get_EAS2TAS();
|
|
||||||
}
|
|
||||||
|
|
||||||
// return true if airspeed comes from an airspeed sensor, as
|
// return true if airspeed comes from an airspeed sensor, as
|
||||||
// opposed to an IMU estimate
|
// opposed to an IMU estimate
|
||||||
|
@ -24,6 +24,7 @@
|
|||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <GCS_MAVLink/GCS.h>
|
#include <GCS_MAVLink/GCS.h>
|
||||||
#include <AP_GPS/AP_GPS.h>
|
#include <AP_GPS/AP_GPS.h>
|
||||||
|
#include <AP_Baro/AP_Baro.h>
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
|
@ -25,6 +25,7 @@
|
|||||||
#include <GCS_MAVLink/GCS.h>
|
#include <GCS_MAVLink/GCS.h>
|
||||||
#include <AP_Module/AP_Module.h>
|
#include <AP_Module/AP_Module.h>
|
||||||
#include <AP_GPS/AP_GPS.h>
|
#include <AP_GPS/AP_GPS.h>
|
||||||
|
#include <AP_Baro/AP_Baro.h>
|
||||||
|
|
||||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||||
|
|
||||||
|
@ -9,6 +9,7 @@
|
|||||||
#include <AP_RangeFinder/AP_RangeFinder.h>
|
#include <AP_RangeFinder/AP_RangeFinder.h>
|
||||||
#include <AP_Logger/AP_Logger.h>
|
#include <AP_Logger/AP_Logger.h>
|
||||||
#include <AP_GPS/AP_GPS.h>
|
#include <AP_GPS/AP_GPS.h>
|
||||||
|
#include <AP_Baro/AP_Baro.h>
|
||||||
|
|
||||||
void setup();
|
void setup();
|
||||||
void loop();
|
void loop();
|
||||||
|
Loading…
Reference in New Issue
Block a user