AP_OpticalFlow: give access to AHRS from all backends

This commit is contained in:
Andrew Tridgell 2016-11-19 18:18:50 +11:00
parent def6e014cf
commit 0be1b1aac2
6 changed files with 10 additions and 11 deletions

View File

@ -30,10 +30,8 @@
#define OPTICALFLOW_ONBOARD_ID 1 #define OPTICALFLOW_ONBOARD_ID 1
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;
AP_OpticalFlow_Onboard::AP_OpticalFlow_Onboard(OpticalFlow &_frontend, AP_OpticalFlow_Onboard::AP_OpticalFlow_Onboard(OpticalFlow &_frontend) :
AP_AHRS_NavEKF& ahrs) : OpticalFlow_backend(_frontend)
OpticalFlow_backend(_frontend),
_ahrs(ahrs)
{} {}
void AP_OpticalFlow_Onboard::init(void) void AP_OpticalFlow_Onboard::init(void)
@ -102,7 +100,7 @@ void AP_OpticalFlow_Onboard::update()
void AP_OpticalFlow_Onboard::_get_gyro(float &rate_x, float &rate_y, void AP_OpticalFlow_Onboard::_get_gyro(float &rate_x, float &rate_y,
float &rate_z) float &rate_z)
{ {
Vector3f rates = _ahrs.get_gyro(); Vector3f rates = get_ahrs().get_gyro();
rate_x = rates.x; rate_x = rates.x;
rate_y = rates.y; rate_y = rates.y;
rate_z = rates.z; rate_z = rates.z;

View File

@ -24,11 +24,10 @@
class AP_OpticalFlow_Onboard : public OpticalFlow_backend class AP_OpticalFlow_Onboard : public OpticalFlow_backend
{ {
public: public:
AP_OpticalFlow_Onboard(OpticalFlow &_frontend, AP_AHRS_NavEKF &ahrs); AP_OpticalFlow_Onboard(OpticalFlow &_frontend);
void init(void); void init(void);
void update(void); void update(void);
private: private:
AP_AHRS &_ahrs;
void _get_gyro(float&, float&, float&); void _get_gyro(float&, float&, float&);
uint32_t _last_read_ms; uint32_t _last_read_ms;
}; };

View File

@ -87,10 +87,9 @@ void OpticalFlow::init(void)
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP ||\ #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP ||\
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_MINLURE ||\ CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_MINLURE ||\
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI
backend = new AP_OpticalFlow_Onboard(*this, _ahrs); backend = new AP_OpticalFlow_Onboard(*this);
#elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX #elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX
backend = new AP_OpticalFlow_Linux(*this, hal.i2c_mgr->get_device(HAL_OPTFLOW_PX4FLOW_I2C_BUS, HAL_OPTFLOW_PX4FLOW_I2C_ADDRESS)); backend = new AP_OpticalFlow_Linux(*this, hal.i2c_mgr->get_device(HAL_OPTFLOW_PX4FLOW_I2C_BUS, HAL_OPTFLOW_PX4FLOW_I2C_ADDRESS));
#endif #endif
} }

View File

@ -76,8 +76,8 @@ public:
} }
private: private:
OpticalFlow_backend *backend;
AP_AHRS_NavEKF &_ahrs; AP_AHRS_NavEKF &_ahrs;
OpticalFlow_backend *backend;
struct AP_OpticalFlow_Flags { struct AP_OpticalFlow_Flags {
uint8_t healthy : 1; // true if sensor is healthy uint8_t healthy : 1; // true if sensor is healthy

View File

@ -48,6 +48,9 @@ protected:
// get the yaw angle in radians // get the yaw angle in radians
float _yawAngleRad(void) const { return radians(float(frontend._yawAngle_cd) * 0.01f); } float _yawAngleRad(void) const { return radians(float(frontend._yawAngle_cd) * 0.01f); }
// get access to AHRS object
AP_AHRS_NavEKF &get_ahrs(void) { return frontend._ahrs; }
// semaphore for access to shared frontend data // semaphore for access to shared frontend data
AP_HAL::Semaphore *_sem; AP_HAL::Semaphore *_sem;
}; };