AP_AHRS: remove handling of beacon

This commit is contained in:
Peter Barker 2019-06-27 11:56:36 +10:00 committed by Randy Mackay
parent 04ebb9de0b
commit 2bcaaf5aaf

View File

@ -165,18 +165,10 @@ 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;
}
// get the index of the current primary accelerometer sensor
virtual uint8_t get_primary_accel_index(void) const {
return AP::ins().get_primary_accel();
@ -645,9 +637,6 @@ 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;