mirror of https://github.com/ArduPilot/ardupilot
AP_AHRS: remove optical flow pointer from AP_AHRS
Nothing was ever using it.
This commit is contained in:
parent
28bbe4b776
commit
e141578376
|
@ -116,14 +116,6 @@ public:
|
||||||
return _compass;
|
return _compass;
|
||||||
}
|
}
|
||||||
|
|
||||||
void set_optflow(const OpticalFlow *optflow) {
|
|
||||||
_optflow = optflow;
|
|
||||||
}
|
|
||||||
|
|
||||||
const OpticalFlow* get_optflow() const {
|
|
||||||
return _optflow;
|
|
||||||
}
|
|
||||||
|
|
||||||
// allow for runtime change of orientation
|
// allow for runtime change of orientation
|
||||||
// this makes initial config easier
|
// this makes initial config easier
|
||||||
void update_orientation();
|
void update_orientation();
|
||||||
|
@ -665,9 +657,6 @@ protected:
|
||||||
// pointer to compass object, if available
|
// pointer to compass object, if available
|
||||||
Compass * _compass;
|
Compass * _compass;
|
||||||
|
|
||||||
// pointer to OpticalFlow object, if available
|
|
||||||
const OpticalFlow *_optflow;
|
|
||||||
|
|
||||||
// pointer to airspeed object, if available
|
// pointer to airspeed object, if available
|
||||||
|
|
||||||
// time in microseconds of last compass update
|
// time in microseconds of last compass update
|
||||||
|
|
Loading…
Reference in New Issue