mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
small correction to imu lib
git-svn-id: https://arducopter.googlecode.com/svn/trunk@728 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
de51162e81
commit
6272955567
@ -82,7 +82,7 @@ AP_IMU::init(void)
|
|||||||
for(int i = 0; i < 200; i++){ // We take some readings...
|
for(int i = 0; i < 200; i++){ // We take some readings...
|
||||||
for (int j = 0; j < 6; j++) {
|
for (int j = 0; j < 6; j++) {
|
||||||
_adc_in[j] = APM_ADC.Ch(_sensors[j]);
|
_adc_in[j] = APM_ADC.Ch(_sensors[j]);
|
||||||
_adc_in[j] -= _gyro_temp_curve(j, tc_temp); // Subtract temp compensated typical gyro bias
|
_adc_in[j] -= _gyro_temp_curve[j][tc_temp]; // Subtract temp compensated typical gyro bias
|
||||||
if (_sensor_signs[j] < 0)
|
if (_sensor_signs[j] < 0)
|
||||||
temp = (_adc_offset[j] - _adc_in[j]);
|
temp = (_adc_offset[j] - _adc_in[j]);
|
||||||
else
|
else
|
||||||
@ -119,7 +119,7 @@ AP_IMU::get_gyro(void)
|
|||||||
|
|
||||||
for (int i = 0; i < 3; i++) {
|
for (int i = 0; i < 3; i++) {
|
||||||
_adc_in[i] = APM_ADC.Ch(_sensors[i]);
|
_adc_in[i] = APM_ADC.Ch(_sensors[i]);
|
||||||
_adc_in[i] -= _gyro_temp_curve(i, tc_temp); // Subtract temp compensated typical gyro bias
|
_adc_in[i] -= _gyro_temp_curve[i][tc_temp]; // Subtract temp compensated typical gyro bias
|
||||||
if (_sensor_signs[i] < 0)
|
if (_sensor_signs[i] < 0)
|
||||||
temp = (_adc_offset[i] - _adc_in[i]);
|
temp = (_adc_offset[i] - _adc_in[i]);
|
||||||
else
|
else
|
||||||
|
Loading…
Reference in New Issue
Block a user