mirror of https://github.com/ArduPilot/ardupilot
AP_InertialSensor: Formalise and document Flymaple Gyro scaling factor
This commit is contained in:
parent
db2b7ed4e3
commit
d11f952ef1
|
@ -153,6 +153,8 @@ bool AP_InertialSensor_Flymaple::update(void)
|
|||
}
|
||||
Vector3f accel_scale = _accel_scale.get();
|
||||
|
||||
// FIXME:
|
||||
hal.gpio->write(4, 1);
|
||||
hal.scheduler->suspend_timer_procs();
|
||||
|
||||
// base the time on the gyro timestamp, as that is what is
|
||||
|
@ -188,6 +190,9 @@ bool AP_InertialSensor_Flymaple::update(void)
|
|||
_gyro *= FLYMAPLE_GYRO_SCALE_R_S;
|
||||
_gyro -= _gyro_offset;
|
||||
|
||||
// FIXME:
|
||||
hal.gpio->write(4, 0);
|
||||
|
||||
#if 0
|
||||
// whats this all about????
|
||||
if (_last_filter_hz != _mpu6000_filter) {
|
||||
|
@ -251,8 +256,6 @@ void AP_InertialSensor_Flymaple::_accumulate(void)
|
|||
_gyro_sum_count++;
|
||||
_last_gyro_timestamp = hal.scheduler->micros();
|
||||
}
|
||||
// FIXME:
|
||||
hal.gpio->write(4, 0);
|
||||
|
||||
_in_accumulate = false;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue