mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
AP_OpticalFlow: give access to AHRS from all backends
This commit is contained in:
parent
def6e014cf
commit
0be1b1aac2
@ -30,10 +30,8 @@
|
||||
#define OPTICALFLOW_ONBOARD_ID 1
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
AP_OpticalFlow_Onboard::AP_OpticalFlow_Onboard(OpticalFlow &_frontend,
|
||||
AP_AHRS_NavEKF& ahrs) :
|
||||
OpticalFlow_backend(_frontend),
|
||||
_ahrs(ahrs)
|
||||
AP_OpticalFlow_Onboard::AP_OpticalFlow_Onboard(OpticalFlow &_frontend) :
|
||||
OpticalFlow_backend(_frontend)
|
||||
{}
|
||||
|
||||
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,
|
||||
float &rate_z)
|
||||
{
|
||||
Vector3f rates = _ahrs.get_gyro();
|
||||
Vector3f rates = get_ahrs().get_gyro();
|
||||
rate_x = rates.x;
|
||||
rate_y = rates.y;
|
||||
rate_z = rates.z;
|
||||
|
@ -24,11 +24,10 @@
|
||||
class AP_OpticalFlow_Onboard : public OpticalFlow_backend
|
||||
{
|
||||
public:
|
||||
AP_OpticalFlow_Onboard(OpticalFlow &_frontend, AP_AHRS_NavEKF &ahrs);
|
||||
AP_OpticalFlow_Onboard(OpticalFlow &_frontend);
|
||||
void init(void);
|
||||
void update(void);
|
||||
private:
|
||||
AP_AHRS &_ahrs;
|
||||
void _get_gyro(float&, float&, float&);
|
||||
uint32_t _last_read_ms;
|
||||
};
|
||||
|
@ -75,7 +75,7 @@ extern const AP_HAL::HAL& hal;
|
||||
|
||||
// constructor
|
||||
AP_OpticalFlow_Pixart::AP_OpticalFlow_Pixart(OpticalFlow &_frontend) :
|
||||
OpticalFlow_backend(_frontend)
|
||||
OpticalFlow_backend(_frontend)
|
||||
{
|
||||
_dev = std::move(hal.spi->get_device("external0m3"));
|
||||
}
|
||||
|
@ -87,10 +87,9 @@ void OpticalFlow::init(void)
|
||||
#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_BBBMINI
|
||||
backend = new AP_OpticalFlow_Onboard(*this, _ahrs);
|
||||
backend = new AP_OpticalFlow_Onboard(*this);
|
||||
#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));
|
||||
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -76,8 +76,8 @@ public:
|
||||
}
|
||||
|
||||
private:
|
||||
OpticalFlow_backend *backend;
|
||||
AP_AHRS_NavEKF &_ahrs;
|
||||
OpticalFlow_backend *backend;
|
||||
|
||||
struct AP_OpticalFlow_Flags {
|
||||
uint8_t healthy : 1; // true if sensor is healthy
|
||||
|
@ -48,6 +48,9 @@ protected:
|
||||
// get the yaw angle in radians
|
||||
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
|
||||
AP_HAL::Semaphore *_sem;
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user