mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
AP_AHRS: make optflow available via AHRS
same pattern as compass and airspeed sensor
This commit is contained in:
parent
51cd64b3b2
commit
70c2aeca42
@ -26,6 +26,7 @@
|
||||
#include <inttypes.h>
|
||||
#include <AP_Compass.h>
|
||||
#include <AP_Airspeed.h>
|
||||
#include <AP_OpticalFlow.h>
|
||||
#include <AP_GPS.h>
|
||||
#include <AP_InertialSensor.h>
|
||||
#include <AP_Baro.h>
|
||||
@ -63,6 +64,7 @@ public:
|
||||
yaw_sensor(0),
|
||||
_vehicle_class(AHRS_VEHICLE_UNKNOWN),
|
||||
_compass(NULL),
|
||||
_optflow(NULL),
|
||||
_airspeed(NULL),
|
||||
_compass_last_update(0),
|
||||
_ins(ins),
|
||||
@ -136,6 +138,14 @@ public:
|
||||
const Compass* get_compass() const {
|
||||
return _compass;
|
||||
}
|
||||
|
||||
void set_optflow(const OpticalFlow *optflow) {
|
||||
_optflow = optflow;
|
||||
}
|
||||
|
||||
const OpticalFlow* get_optflow() const {
|
||||
return _optflow;
|
||||
}
|
||||
|
||||
// allow for runtime change of orientation
|
||||
// this makes initial config easier
|
||||
@ -393,6 +403,9 @@ protected:
|
||||
// pointer to compass object, if available
|
||||
Compass * _compass;
|
||||
|
||||
// pointer to OpticalFlow object, if available
|
||||
const OpticalFlow *_optflow;
|
||||
|
||||
// pointer to airspeed object, if available
|
||||
AP_Airspeed * _airspeed;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user