mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AHRS: make airspeed sensor available to AHRS
this will be used for long term dead-reckoning
This commit is contained in:
parent
c2dc920d02
commit
f95b06a880
@ -12,6 +12,7 @@
|
||||
#include <AP_Math.h>
|
||||
#include <inttypes.h>
|
||||
#include <AP_Compass.h>
|
||||
#include <AP_Airspeed.h>
|
||||
#include <AP_GPS.h>
|
||||
#include <AP_IMU.h>
|
||||
#include <AP_Baro.h>
|
||||
@ -46,6 +47,7 @@ public:
|
||||
void set_fly_forward(bool b) { _fly_forward = b; }
|
||||
void set_compass(Compass *compass) { _compass = compass; }
|
||||
void set_barometer(AP_Baro *barometer) { _barometer = barometer; }
|
||||
void set_airspeed(AP_Airspeed *airspeed) { _airspeed = airspeed; }
|
||||
|
||||
// Methods
|
||||
virtual void update(void) = 0;
|
||||
@ -90,9 +92,12 @@ public:
|
||||
//static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
protected:
|
||||
// pointer to compass object, if enabled
|
||||
// pointer to compass object, if available
|
||||
Compass * _compass;
|
||||
|
||||
// pointer to airspeed object, if available
|
||||
AP_Airspeed * _airspeed;
|
||||
|
||||
// time in microseconds of last compass update
|
||||
uint32_t _compass_last_update;
|
||||
|
||||
|
@ -32,7 +32,7 @@ public:
|
||||
float get_airspeed_cm(void) { return _airspeed*100; }
|
||||
|
||||
// return true if airspeed is enabled, and airspeed use is set
|
||||
bool use(void) { return _enable && _use; }
|
||||
bool use(void) { return _enable && _use && _offset != 0; }
|
||||
|
||||
// return true if airspeed is enabled
|
||||
bool enabled(void) { return _enable; }
|
||||
|
Loading…
Reference in New Issue
Block a user