mirror of https://github.com/ArduPilot/ardupilot
apm2: fixed for new barometer code
This commit is contained in:
parent
a99a1dbc9a
commit
d5c23c83cf
|
@ -436,12 +436,13 @@ static void NOINLINE send_raw_imu1(mavlink_channel_t chan)
|
|||
|
||||
static void NOINLINE send_raw_imu2(mavlink_channel_t chan)
|
||||
{
|
||||
int32_t pressure = barometer.get_pressure();
|
||||
mavlink_msg_scaled_pressure_send(
|
||||
chan,
|
||||
micros(),
|
||||
(float)barometer.Press/100.0,
|
||||
(float)(barometer.Press-g.ground_pressure)/100.0,
|
||||
(int)(barometer.Temp*10));
|
||||
pressure/100.0,
|
||||
(pressure - g.ground_pressure)/100.0,
|
||||
barometer.get_temperature());
|
||||
}
|
||||
|
||||
static void NOINLINE send_raw_imu3(mavlink_channel_t chan)
|
||||
|
@ -453,8 +454,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());
|
||||
}
|
||||
|
|
|
@ -12,11 +12,11 @@ static void init_barometer(void)
|
|||
int ground_temperature;
|
||||
|
||||
while(ground_pressure == 0){
|
||||
barometer.Read(); // Get initial data from absolute pressure sensor
|
||||
ground_pressure = barometer.Press;
|
||||
ground_temperature = barometer.Temp;
|
||||
barometer.read(); // Get initial data from absolute pressure sensor
|
||||
ground_pressure = barometer.get_pressure();
|
||||
ground_temperature = barometer.get_temperature();
|
||||
mavlink_delay(20);
|
||||
//Serial.printf("barometer.Press %ld\n", barometer.Press);
|
||||
//Serial.printf("barometer.Press %ld\n", barometer.get_pressure());
|
||||
}
|
||||
|
||||
for(int i = 0; i < 30; i++){ // We take some readings...
|
||||
|
@ -25,9 +25,9 @@ static void init_barometer(void)
|
|||
gcs_update(); // look for inbound hil packets
|
||||
#endif
|
||||
|
||||
barometer.Read(); // Get initial data from absolute pressure sensor
|
||||
ground_pressure = (ground_pressure * 9l + barometer.Press) / 10l;
|
||||
ground_temperature = (ground_temperature * 9 + barometer.Temp) / 10;
|
||||
barometer.read(); // Get initial data from absolute pressure sensor
|
||||
ground_pressure = (ground_pressure * 9l + barometer.get_pressure()) / 10l;
|
||||
ground_temperature = (ground_temperature * 9 + barometer.get_temperature()) / 10;
|
||||
|
||||
mavlink_delay(20);
|
||||
if(flashcount == 5) {
|
||||
|
@ -57,11 +57,11 @@ static long read_barometer(void)
|
|||
{
|
||||
float x, scaling, temp;
|
||||
|
||||
barometer.Read(); // Get new data from absolute pressure sensor
|
||||
barometer.read(); // Get new data from absolute pressure sensor
|
||||
|
||||
|
||||
//abs_pressure = (abs_pressure + barometer.Press) >> 1; // Small filtering
|
||||
abs_pressure = ((float)abs_pressure * .7) + ((float)barometer.Press * .3); // large filtering
|
||||
//abs_pressure = (abs_pressure + barometer.get_pressure()) >> 1; // Small filtering
|
||||
abs_pressure = ((float)abs_pressure * .7) + ((float)barometer.get_pressure() * .3); // large filtering
|
||||
scaling = (float)g.ground_pressure / (float)abs_pressure;
|
||||
temp = ((float)g.ground_temperature) + 273.15f;
|
||||
x = log(scaling) * temp * 29271.267f;
|
||||
|
|
Loading…
Reference in New Issue