AP_OpticalFlow: rename for AHRS restructuring

This commit is contained in:
Peter Barker 2021-07-20 22:16:31 +10:00 committed by Peter Barker
parent 48e9fa7ebd
commit ed5303d1b8
6 changed files with 10 additions and 10 deletions

View File

@ -98,7 +98,7 @@ void AP_OpticalFlow_CXOF::update(void)
// record gyro values as long as they are being used
// the sanity check of dt below ensures old gyro values are not used
if (gyro_sum_count < 1000) {
const Vector3f& gyro = AP::ahrs_navekf().get_gyro();
const Vector3f& gyro = AP::ahrs().get_gyro();
gyro_sum.x += gyro.x;
gyro_sum.y += gyro.y;
gyro_sum_count++;

View File

@ -285,7 +285,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 = AP::ahrs_navekf().get_gyro();
const Vector3f &gyro = AP::ahrs().get_gyro();
{
WITH_SEMAPHORE(_sem);

View File

@ -100,7 +100,7 @@ void AP_OpticalFlow_UPFLOW::update(void)
gyro_sum.zero();
gyro_sum_count = 0;
}
const Vector3f& gyro = AP::ahrs_navekf().get_gyro();
const Vector3f& gyro = AP::ahrs().get_gyro();
gyro_sum.x += gyro.x;
gyro_sum.y += gyro.y;
gyro_sum_count++;

View File

@ -203,7 +203,7 @@ void OpticalFlow::update_state(const OpticalFlow_state &state)
_last_update_ms = AP_HAL::millis();
// write to log and send to EKF if new data has arrived
AP::ahrs_navekf().writeOptFlowMeas(quality(),
AP::ahrs().writeOptFlowMeas(quality(),
_state.flowRate,
_state.bodyRate,
_last_update_ms,

View File

@ -30,7 +30,7 @@
#endif
class OpticalFlow_backend;
class AP_AHRS_NavEKF;
class AP_AHRS;
class OpticalFlow
{

View File

@ -27,7 +27,7 @@ public:
AP_InertialSensor ins;
AP_SerialManager serial_manager;
RangeFinder sonar;
AP_AHRS_NavEKF ahrs{AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF};
AP_AHRS ahrs{AP_AHRS::FLAG_ALWAYS_USE_EKF};
};
static DummyVehicle vehicle;