mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
uncrustify libraries/AP_IMU/AP_IMU_INS.cpp
This commit is contained in:
parent
a5ed2f9a53
commit
5a2ec6843e
@ -171,19 +171,19 @@ AP_IMU_INS::_init_accel(void (*delay_cb)(unsigned long t), void (*flash_leds_cb)
|
|||||||
_ins->update();
|
_ins->update();
|
||||||
_ins->get_accels(ins_accel);
|
_ins->get_accels(ins_accel);
|
||||||
|
|
||||||
for (int j = 3; j <= 5; j++){
|
for (int j = 3; j <= 5; j++) {
|
||||||
prev[j] = _sensor_cal[j];
|
prev[j] = _sensor_cal[j];
|
||||||
adc_in = ins_accel[j-3];
|
adc_in = ins_accel[j-3];
|
||||||
_sensor_cal[j] = adc_in;
|
_sensor_cal[j] = adc_in;
|
||||||
}
|
}
|
||||||
|
|
||||||
for(int i = 0; i < 50; i++){ // We take some readings...
|
for(int i = 0; i < 50; i++) { // We take some readings...
|
||||||
|
|
||||||
delay_cb(20);
|
delay_cb(20);
|
||||||
_ins->update();
|
_ins->update();
|
||||||
_ins->get_accels(ins_accel);
|
_ins->get_accels(ins_accel);
|
||||||
|
|
||||||
for (int j = 3; j < 6; j++){
|
for (int j = 3; j < 6; j++) {
|
||||||
adc_in = ins_accel[j-3];
|
adc_in = ins_accel[j-3];
|
||||||
_sensor_cal[j] = _sensor_cal[j] * 0.9 + adc_in * 0.1;
|
_sensor_cal[j] = _sensor_cal[j] * 0.9 + adc_in * 0.1;
|
||||||
}
|
}
|
||||||
@ -213,7 +213,7 @@ AP_IMU_INS::_init_accel(void (*delay_cb)(unsigned long t), void (*flash_leds_cb)
|
|||||||
Serial.printf_P(PSTR(" "));
|
Serial.printf_P(PSTR(" "));
|
||||||
}
|
}
|
||||||
|
|
||||||
float
|
float
|
||||||
AP_IMU_INS::_calibrated(uint8_t channel, float ins_value)
|
AP_IMU_INS::_calibrated(uint8_t channel, float ins_value)
|
||||||
{
|
{
|
||||||
return ins_value - _sensor_cal[channel];
|
return ins_value - _sensor_cal[channel];
|
||||||
|
Loading…
Reference in New Issue
Block a user