Browse Source

AP_OpticalFlow: use AHRS singleton

mission-4.1.18
Peter Barker 7 years ago committed by Andrew Tridgell
parent
commit
e88358ccc6
  1. 2
      libraries/AP_OpticalFlow/AP_OpticalFlow_Pixart.cpp
  2. 4
      libraries/AP_OpticalFlow/OpticalFlow.cpp
  3. 3
      libraries/AP_OpticalFlow/OpticalFlow.h
  4. 3
      libraries/AP_OpticalFlow/OpticalFlow_backend.h

2
libraries/AP_OpticalFlow/AP_OpticalFlow_Pixart.cpp

@ -289,7 +289,7 @@ void AP_OpticalFlow_Pixart::timer(void) @@ -289,7 +289,7 @@ void AP_OpticalFlow_Pixart::timer(void)
uint32_t dt_us = last_burst_us - integral.last_frame_us;
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);

4
libraries/AP_OpticalFlow/OpticalFlow.cpp

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

3
libraries/AP_OpticalFlow/OpticalFlow.h

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

3
libraries/AP_OpticalFlow/OpticalFlow_backend.h

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

Loading…
Cancel
Save