mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Baro: added get_pressure_samples() interface
this returns how many samples were used to calculate the last pressure
This commit is contained in:
parent
1a42b10255
commit
209136386b
@ -30,6 +30,10 @@ class AP_Baro
|
|||||||
// of the last calibrate() call
|
// of the last calibrate() call
|
||||||
float get_altitude(void);
|
float get_altitude(void);
|
||||||
|
|
||||||
|
// return how many pressure samples were used to obtain
|
||||||
|
// the last pressure reading
|
||||||
|
uint8_t get_pressure_samples(void) { return _pressure_samples; }
|
||||||
|
|
||||||
// get current climb rate in meters/s. A positive number means
|
// get current climb rate in meters/s. A positive number means
|
||||||
// going up
|
// going up
|
||||||
float get_climb_rate(void);
|
float get_climb_rate(void);
|
||||||
@ -42,6 +46,7 @@ class AP_Baro
|
|||||||
|
|
||||||
protected:
|
protected:
|
||||||
uint32_t _last_update;
|
uint32_t _last_update;
|
||||||
|
uint8_t _pressure_samples;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
AP_Int16 _ground_temperature;
|
AP_Int16 _ground_temperature;
|
||||||
|
@ -11,7 +11,9 @@ class AP_Baro_BMP085 : public AP_Baro
|
|||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
AP_Baro_BMP085(bool apm2_hardware):
|
AP_Baro_BMP085(bool apm2_hardware):
|
||||||
_apm2_hardware(apm2_hardware) {}; // Constructor
|
_apm2_hardware(apm2_hardware) {
|
||||||
|
_pressure_samples = 1;
|
||||||
|
}; // Constructor
|
||||||
|
|
||||||
|
|
||||||
/* AP_Baro public interface: */
|
/* AP_Baro public interface: */
|
||||||
|
@ -1,16 +1,7 @@
|
|||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||||
|
|
||||||
extern "C" {
|
#include <FastSerial.h>
|
||||||
// AVR LibC Includes
|
#include <AP_Baro.h>
|
||||||
#include <inttypes.h>
|
|
||||||
#include <avr/interrupt.h>
|
|
||||||
}
|
|
||||||
#if defined(ARDUINO) && ARDUINO >= 100
|
|
||||||
#include "Arduino.h"
|
|
||||||
#else
|
|
||||||
#include "WConstants.h"
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#include "AP_Baro_BMP085_hil.h"
|
#include "AP_Baro_BMP085_hil.h"
|
||||||
|
|
||||||
// Constructors ////////////////////////////////////////////////////////////////
|
// Constructors ////////////////////////////////////////////////////////////////
|
||||||
@ -32,26 +23,33 @@ uint8_t AP_Baro_BMP085_HIL::read()
|
|||||||
{
|
{
|
||||||
uint8_t result = 0;
|
uint8_t result = 0;
|
||||||
|
|
||||||
if (BMP085_State == 1){
|
if (_count != 0) {
|
||||||
BMP085_State++;
|
result = 1;
|
||||||
}else{
|
Press = _pressure_sum / _count;
|
||||||
|
Temp = _temperature_sum / _count;
|
||||||
if (BMP085_State == 5){
|
_pressure_samples = _count;
|
||||||
BMP085_State = 1; // Start again from state = 1
|
_count = 0;
|
||||||
result = 1; // New pressure reading
|
_pressure_sum = 0;
|
||||||
}else{
|
_temperature_sum = 0;
|
||||||
BMP085_State++;
|
|
||||||
result = 1; // New pressure reading
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
return(result);
|
|
||||||
|
return result;
|
||||||
}
|
}
|
||||||
|
|
||||||
void AP_Baro_BMP085_HIL::setHIL(float _Temp, float _Press)
|
void AP_Baro_BMP085_HIL::setHIL(float _Temp, float _Press)
|
||||||
{
|
{
|
||||||
// TODO: map floats to raw
|
_count++;
|
||||||
Temp = _Temp;
|
_pressure_sum += _Press;
|
||||||
Press = _Press;
|
_temperature_sum += _Temp;
|
||||||
|
if (_count == 128) {
|
||||||
|
// we have summed 128 values. This only happens
|
||||||
|
// when we stop reading the barometer for a long time
|
||||||
|
// (more than 1.2 seconds)
|
||||||
|
_count = 64;
|
||||||
|
_pressure_sum /= 2;
|
||||||
|
_temperature_sum /= 2;
|
||||||
|
}
|
||||||
|
|
||||||
healthy = true;
|
healthy = true;
|
||||||
_last_update = millis();
|
_last_update = millis();
|
||||||
}
|
}
|
||||||
|
@ -9,12 +9,14 @@ class AP_Baro_BMP085_HIL : public AP_Baro
|
|||||||
{
|
{
|
||||||
private:
|
private:
|
||||||
uint8_t BMP085_State;
|
uint8_t BMP085_State;
|
||||||
int16_t Temp;
|
int32_t Temp;
|
||||||
int32_t Press;
|
int32_t Press;
|
||||||
|
int32_t _pressure_sum;
|
||||||
|
int32_t _temperature_sum;
|
||||||
|
uint8_t _count;
|
||||||
|
|
||||||
public:
|
public:
|
||||||
AP_Baro_BMP085_HIL(); // Constructor
|
AP_Baro_BMP085_HIL(); // Constructor
|
||||||
//int Altitude;
|
|
||||||
|
|
||||||
bool init(AP_PeriodicProcess * scheduler);
|
bool init(AP_PeriodicProcess * scheduler);
|
||||||
uint8_t read();
|
uint8_t read();
|
||||||
|
@ -175,7 +175,7 @@ void AP_Baro_MS5611::_update(uint32_t tnow)
|
|||||||
_s_D2 += _spi_read_adc(); // On state 0 we read temp
|
_s_D2 += _spi_read_adc(); // On state 0 we read temp
|
||||||
_d2_count++;
|
_d2_count++;
|
||||||
if (_d2_count == 32) {
|
if (_d2_count == 32) {
|
||||||
// we have summed 128 values. This only happens
|
// we have summed 32 values. This only happens
|
||||||
// when we stop reading the barometer for a long time
|
// when we stop reading the barometer for a long time
|
||||||
// (more than 1.2 seconds)
|
// (more than 1.2 seconds)
|
||||||
_s_D2 >>= 1;
|
_s_D2 >>= 1;
|
||||||
@ -226,6 +226,7 @@ uint8_t AP_Baro_MS5611::read()
|
|||||||
if (d2count != 0) {
|
if (d2count != 0) {
|
||||||
D2 = sD2 / d2count;
|
D2 = sD2 / d2count;
|
||||||
}
|
}
|
||||||
|
_pressure_samples = d1count;
|
||||||
_raw_press = D1;
|
_raw_press = D1;
|
||||||
_raw_temp = D2;
|
_raw_temp = D2;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user