mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-28 19:48:31 -04:00
AP_OpticalFlow_Onboard: remove gyro_cb
Not needed anymore
This commit is contained in:
parent
710875d3b9
commit
677a2f600f
@ -37,9 +37,7 @@ AP_OpticalFlow_Onboard::AP_OpticalFlow_Onboard(OpticalFlow &_frontend) :
|
||||
void AP_OpticalFlow_Onboard::init(void)
|
||||
{
|
||||
/* register callback to get gyro data */
|
||||
hal.opticalflow->init(
|
||||
FUNCTOR_BIND_MEMBER(&AP_OpticalFlow_Onboard::_get_gyro,
|
||||
void, float&, float&, float&));
|
||||
hal.opticalflow->init();
|
||||
}
|
||||
|
||||
void AP_OpticalFlow_Onboard::update()
|
||||
@ -102,13 +100,4 @@ void AP_OpticalFlow_Onboard::update()
|
||||
#endif
|
||||
}
|
||||
|
||||
void AP_OpticalFlow_Onboard::_get_gyro(float &rate_x, float &rate_y,
|
||||
float &rate_z)
|
||||
{
|
||||
Vector3f rates = get_ahrs().get_gyro();
|
||||
rate_x = rates.x;
|
||||
rate_y = rates.y;
|
||||
rate_z = rates.z;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
@ -28,6 +28,5 @@ public:
|
||||
void init(void);
|
||||
void update(void);
|
||||
private:
|
||||
void _get_gyro(float&, float&, float&);
|
||||
uint32_t _last_read_ms;
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user