mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_InertialSensor: use functor macros
Functor is not yet being used but let's make is macro fallback to the previous Delegate implementation for easy of transition between the two.
This commit is contained in:
parent
4c97d92982
commit
3aa46e3213
@ -221,7 +221,7 @@ bool AP_InertialSensor_L3G4200D::_init_sensor(void)
|
||||
i2c_sem->give();
|
||||
|
||||
// start the timer process to read samples
|
||||
hal.scheduler->register_timer_process(AP_HAL_MEMBERPROC(&AP_InertialSensor_L3G4200D::_accumulate));
|
||||
hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&AP_InertialSensor_L3G4200D::_accumulate, void));
|
||||
|
||||
_gyro_instance = _imu.register_gyro();
|
||||
_accel_instance = _imu.register_accel();
|
||||
|
@ -217,7 +217,7 @@ uint16_t AP_InertialSensor_L3GD20::_init_sensor( Sample_rate sample_rate )
|
||||
}
|
||||
|
||||
// start the timer process to read samples
|
||||
hal.scheduler->register_timer_process(AP_HAL_MEMBERPROC(&AP_InertialSensor_L3GD20::_poll_data));
|
||||
hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&AP_InertialSensor_L3GD20::_poll_data, void));
|
||||
|
||||
#if L3GD20_DEBUG
|
||||
_dump_registers();
|
||||
|
@ -258,7 +258,7 @@ uint16_t AP_InertialSensor_LSM303D::_init_sensor( Sample_rate sample_rate )
|
||||
}
|
||||
|
||||
// start the timer process to read samples
|
||||
hal.scheduler->register_timer_process(AP_HAL_MEMBERPROC(&AP_InertialSensor_LSM303D::_poll_data));
|
||||
hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&AP_InertialSensor_LSM303D::_poll_data, void));
|
||||
|
||||
#if LSM303D_DEBUG
|
||||
_dump_registers();
|
||||
|
@ -254,7 +254,7 @@ bool AP_InertialSensor_MPU6000::_init_sensor(void)
|
||||
hal.scheduler->resume_timer_procs();
|
||||
|
||||
// start the timer process to read samples
|
||||
hal.scheduler->register_timer_process(AP_HAL_MEMBERPROC(&AP_InertialSensor_MPU6000::_poll_data));
|
||||
hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&AP_InertialSensor_MPU6000::_poll_data, void));
|
||||
|
||||
#if MPU6000_DEBUG
|
||||
_dump_registers();
|
||||
|
@ -469,7 +469,7 @@ bool AP_InertialSensor_MPU9150::_init_sensor(void)
|
||||
_accel_instance = _imu.register_accel();
|
||||
|
||||
// start the timer process to read samples
|
||||
hal.scheduler->register_timer_process(AP_HAL_MEMBERPROC(&AP_InertialSensor_MPU9150::_accumulate));
|
||||
hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&AP_InertialSensor_MPU9150::_accumulate, void));
|
||||
|
||||
return true;
|
||||
|
||||
|
@ -249,7 +249,7 @@ bool AP_InertialSensor_MPU9250::_init_sensor(void)
|
||||
_product_id = AP_PRODUCT_ID_MPU9250;
|
||||
|
||||
// start the timer process to read samples
|
||||
hal.scheduler->register_timer_process(AP_HAL_MEMBERPROC(&AP_InertialSensor_MPU9250::_poll_data));
|
||||
hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&AP_InertialSensor_MPU9250::_poll_data, void));
|
||||
|
||||
#if MPU9250_DEBUG
|
||||
_dump_registers();
|
||||
|
@ -181,7 +181,7 @@ uint16_t AP_InertialSensor_LSM9DS0::_init_sensor( Sample_rate sample_rate)
|
||||
}
|
||||
|
||||
// start the timer process to read samples
|
||||
hal.scheduler->register_timer_process(AP_HAL_MEMBERPROC(&AP_InertialSensor_LSM9DS0::_poll_data));
|
||||
hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&AP_InertialSensor_LSM9DS0::_poll_data, void));
|
||||
|
||||
#if LSM9DS0_DEBUG
|
||||
_dump_registers();
|
||||
|
Loading…
Reference in New Issue
Block a user