mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
AP_AHRS: add beacon object to ahrs
This commit is contained in:
parent
4482743af5
commit
b4961971e0
@ -24,6 +24,7 @@
|
||||
#include <inttypes.h>
|
||||
#include <AP_Compass/AP_Compass.h>
|
||||
#include <AP_Airspeed/AP_Airspeed.h>
|
||||
#include <AP_Beacon/AP_Beacon.h>
|
||||
#include <AP_GPS/AP_GPS.h>
|
||||
#include <AP_InertialSensor/AP_InertialSensor.h>
|
||||
#include <AP_Baro/AP_Baro.h>
|
||||
@ -57,6 +58,7 @@ public:
|
||||
_compass(nullptr),
|
||||
_optflow(nullptr),
|
||||
_airspeed(nullptr),
|
||||
_beacon(nullptr),
|
||||
_compass_last_update(0),
|
||||
_ins(ins),
|
||||
_baro(baro),
|
||||
@ -149,10 +151,18 @@ public:
|
||||
_airspeed = airspeed;
|
||||
}
|
||||
|
||||
void set_beacon(AP_Beacon *beacon) {
|
||||
_beacon = beacon;
|
||||
}
|
||||
|
||||
const AP_Airspeed *get_airspeed(void) const {
|
||||
return _airspeed;
|
||||
}
|
||||
|
||||
const AP_Beacon *get_beacon(void) const {
|
||||
return _beacon;
|
||||
}
|
||||
|
||||
const AP_GPS &get_gps() const {
|
||||
return _gps;
|
||||
}
|
||||
@ -513,6 +523,9 @@ protected:
|
||||
// pointer to airspeed object, if available
|
||||
AP_Airspeed * _airspeed;
|
||||
|
||||
// pointer to beacon object, if available
|
||||
AP_Beacon * _beacon;
|
||||
|
||||
// time in microseconds of last compass update
|
||||
uint32_t _compass_last_update;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user