ArduCopter: Get barometer data in terms of AP_Baro interface

* Major change: Log.pde Log_Write_Control_Tuning has changed significantly
* MS5611 has no concept of RawPres and _offset_press
* Log the get_pressure() instead. (If we don't trust the barometer, what's the point?)
This commit is contained in:
Pat Hickey 2011-11-29 20:37:50 -08:00
parent 39fe9075d9
commit 6dbd6b4181
4 changed files with 21 additions and 24 deletions

View File

@ -796,7 +796,7 @@ static void medium_loop()
// Do an extra baro read
// ---------------------
#if HIL_MODE != HIL_MODE_ATTITUDE
barometer.Read();
barometer.read();
#endif
// agmatthews - USERHOOKS

View File

@ -237,9 +237,9 @@ static void NOINLINE send_raw_imu2(mavlink_channel_t chan)
mavlink_msg_scaled_pressure_send(
chan,
micros(),
(float)barometer.Press/100.0,
(float)(barometer.Press-ground_pressure)/100.0,
(int)(barometer.Temp*10));
(float)barometer.get_pressure()/100.0,
(float)(barometer.get_pressure()-ground_pressure)/100.0,
(int)(barometer.get_temperature()*10));
}
static void NOINLINE send_raw_imu3(mavlink_channel_t chan)
@ -251,8 +251,8 @@ static void NOINLINE send_raw_imu3(mavlink_channel_t chan)
mag_offsets.y,
mag_offsets.z,
compass.get_declination(),
barometer.RawPress,
barometer.RawTemp,
barometer.get_raw_pressure(),
barometer.get_raw_temp(),
imu.gx(), imu.gy(), imu.gz(),
imu.ax(), imu.ay(), imu.az());
}

View File

@ -22,7 +22,7 @@ static void init_barometer(void)
gcs_update(); // look for inbound hil packets for initialization
#endif
ground_temperature = barometer.Temp;
ground_temperature = barometer.get_temperature();
int i;
// We take some readings...
@ -30,7 +30,7 @@ static void init_barometer(void)
delay(20);
// get new data from absolute pressure sensor
barometer.Read();
barometer.read();
//Serial.printf("init %ld, %d, -, %ld, %ld\n", barometer.RawTemp, barometer.Temp, barometer.RawPress, barometer.Press);
}
@ -43,9 +43,9 @@ static void init_barometer(void)
#endif
// Get initial data from absolute pressure sensor
barometer.Read();
ground_pressure = barometer.Press;
ground_temperature = (ground_temperature * 9 + barometer.Temp) / 10;
barometer.read();
ground_pressure = barometer.get_pressure();
ground_temperature = (ground_temperature * 9 + barometer.get_temperature()) / 10;
//Serial.printf("init %ld, %d, -, %ld, %ld, -, %d, %ld\n", barometer.RawTemp, barometer.Temp, barometer.RawPress, barometer.Press, ground_temperature, ground_pressure);
}
@ -90,8 +90,8 @@ static int32_t read_barometer(void)
{
float x, scaling, temp;
barometer.Read();
abs_pressure = barometer.Press;
barometer.read();
abs_pressure = barometer.get_pressure();
//Serial.printf("%ld, %ld, %ld, %ld\n", barometer.RawTemp, barometer.RawPress, barometer.Press, abs_pressure);

View File

@ -875,17 +875,14 @@ test_baro(uint8_t argc, const Menu::arg *argv)
while(1){
delay(100);
barometer.Read();
delay(100);
baro_alt = read_barometer();
int temp_alt = (barometer._offset_press - barometer.RawPress) << 1; // invert and scale
baro_rate = (temp_alt - old_baro_alt) * 10;
old_baro_alt = temp_alt;
// 1 2 3 4 5 1 2 3 4 5
Serial.printf_P(PSTR("Baro: %dcm, rate:%d, %ld, %ld, %d\n"), baro_alt, climb_rate, barometer.RawTemp, barometer.RawPress, temp_alt);
//Serial.printf_P(PSTR("Baro, %d, %ld, %ld, %ld, %ld\n"), baro_alt, barometer.RawTemp, barometer.RawTemp2, barometer.RawPress, barometer.RawPress2);
int32_t alt = read_barometer(); /* calls barometer.read() */
int32_t pres = barometer.get_pressure();
int16_t temp = barometer.get_temperature();
int32_t raw_pres = barometer.get_raw_pressure();
int32_t raw_temp = barometer.get_raw_temp();
Serial.printf_P(PSTR("alt: %ldcm, pres: %ldmbar, temp: %d/100degC,"
" raw pres: %ld, raw temp: %ld\n"),
alt, pres ,temp, raw_pres, raw_temp);
if(Serial.available() > 0){
return (0);
}