AP_OpticalFlow: use AHRS singleton

This commit is contained in:
Peter Barker 2018-09-02 16:54:04 +10:00 committed by Andrew Tridgell
parent 12c67ecaab
commit e88358ccc6
4 changed files with 3 additions and 9 deletions

View File

@ -289,7 +289,7 @@ void AP_OpticalFlow_Pixart::timer(void)
uint32_t dt_us = last_burst_us - integral.last_frame_us; uint32_t dt_us = last_burst_us - integral.last_frame_us;
float dt = dt_us * 1.0e-6; float dt = dt_us * 1.0e-6;
const Vector3f &gyro = get_ahrs().get_gyro(); const Vector3f &gyro = AP::ahrs_navekf().get_gyro();
{ {
WITH_SEMAPHORE(_sem); WITH_SEMAPHORE(_sem);

View File

@ -69,9 +69,7 @@ const AP_Param::GroupInfo OpticalFlow::var_info[] = {
}; };
// default constructor // default constructor
OpticalFlow::OpticalFlow(AP_AHRS_NavEKF &ahrs) OpticalFlow::OpticalFlow()
: _ahrs(ahrs),
_last_update_ms(0)
{ {
_singleton = this; _singleton = this;

View File

@ -30,7 +30,7 @@ class OpticalFlow
friend class OpticalFlow_backend; friend class OpticalFlow_backend;
public: public:
OpticalFlow(AP_AHRS_NavEKF& ahrs); OpticalFlow();
/* Do not allow copies */ /* Do not allow copies */
OpticalFlow(const OpticalFlow &other) = delete; OpticalFlow(const OpticalFlow &other) = delete;
@ -87,7 +87,6 @@ private:
static OpticalFlow *_singleton; static OpticalFlow *_singleton;
AP_AHRS_NavEKF &_ahrs;
OpticalFlow_backend *backend; OpticalFlow_backend *backend;
struct AP_OpticalFlow_Flags { struct AP_OpticalFlow_Flags {

View File

@ -51,9 +51,6 @@ protected:
// apply yaw angle to a vector // apply yaw angle to a vector
void _applyYaw(Vector2f &v); void _applyYaw(Vector2f &v);
// get access to AHRS object
AP_AHRS_NavEKF &get_ahrs(void) { return frontend._ahrs; }
// get ADDR parameter value // get ADDR parameter value
uint8_t get_address(void) const { return frontend._address; } uint8_t get_address(void) const { return frontend._address; }