airspeed sensors apply offset separately

This commit is contained in:
Daniel Agar 2017-06-21 19:24:02 -04:00
parent c45d369004
commit eb067291bf
12 changed files with 10 additions and 71 deletions

View File

@ -1,5 +1,4 @@
uint64 error_count # Number of errors detected by driver uint64 error_count # Number of errors detected by driver
float32 differential_pressure_raw_pa # Raw differential pressure reading (may be negative) float32 differential_pressure_raw_pa # Raw differential pressure reading (may be negative)
float32 differential_pressure_filtered_pa # Low pass filtered differential pressure reading float32 differential_pressure_filtered_pa # Low pass filtered differential pressure reading
float32 max_differential_pressure_pa # Maximum differential pressure reading
float32 temperature # Temperature provided by sensor, -1000.0f if unknown float32 temperature # Temperature provided by sensor, -1000.0f if unknown

View File

@ -80,7 +80,6 @@
Airspeed::Airspeed(int bus, int address, unsigned conversion_interval, const char *path) : Airspeed::Airspeed(int bus, int address, unsigned conversion_interval, const char *path) :
I2C("Airspeed", path, bus, address, 100000), I2C("Airspeed", path, bus, address, 100000),
_reports(nullptr), _reports(nullptr),
_max_differential_pressure_pa(0),
_sensor_ok(false), _sensor_ok(false),
_last_published_sensor_ok(true), /* initialize differently to force publication */ _last_published_sensor_ok(true), /* initialize differently to force publication */
_measure_ticks(0), _measure_ticks(0),

View File

@ -127,7 +127,6 @@ protected:
void update_status(); void update_status();
work_s _work; work_s _work;
float _max_differential_pressure_pa;
bool _sensor_ok; bool _sensor_ok;
bool _last_published_sensor_ok; bool _last_published_sensor_ok;
uint32_t _measure_ticks; uint32_t _measure_ticks;

View File

@ -171,18 +171,12 @@ ETSAirspeed::collect()
// The raw value still should be compensated for the known offset // The raw value still should be compensated for the known offset
diff_pres_pa_raw -= _diff_pres_offset; diff_pres_pa_raw -= _diff_pres_offset;
// Track maximum differential pressure measured (so we can work out top speed).
if (diff_pres_pa_raw > _max_differential_pressure_pa) {
_max_differential_pressure_pa = diff_pres_pa_raw;
}
report.error_count = perf_event_count(_comms_errors); report.error_count = perf_event_count(_comms_errors);
// XXX we may want to smooth out the readings to remove noise. // XXX we may want to smooth out the readings to remove noise.
report.differential_pressure_filtered_pa = diff_pres_pa_raw; report.differential_pressure_filtered_pa = diff_pres_pa_raw;
report.differential_pressure_raw_pa = diff_pres_pa_raw; report.differential_pressure_raw_pa = diff_pres_pa_raw;
report.temperature = -1000.0f; report.temperature = -1000.0f;
report.max_differential_pressure_pa = _max_differential_pressure_pa;
if (_airspeed_pub != nullptr && !(_pub_blocked)) { if (_airspeed_pub != nullptr && !(_pub_blocked)) {
/* publish it */ /* publish it */

View File

@ -234,9 +234,6 @@ MEASAirspeed::collect()
// correct for 5V rail voltage if possible // correct for 5V rail voltage if possible
voltage_correction(diff_press_pa_raw, temperature); voltage_correction(diff_press_pa_raw, temperature);
// the raw value still should be compensated for the known offset
diff_press_pa_raw -= _diff_pres_offset;
/* /*
With the above calculation the MS4525 sensor will produce a With the above calculation the MS4525 sensor will produce a
positive number when the top port is used as a dynamic port positive number when the top port is used as a dynamic port
@ -245,18 +242,11 @@ MEASAirspeed::collect()
struct differential_pressure_s report; struct differential_pressure_s report;
/* track maximum differential pressure measured (so we can work out top speed). */
if (diff_press_pa_raw > _max_differential_pressure_pa) {
_max_differential_pressure_pa = diff_press_pa_raw;
}
report.timestamp = hrt_absolute_time(); report.timestamp = hrt_absolute_time();
report.error_count = perf_event_count(_comms_errors); report.error_count = perf_event_count(_comms_errors);
report.temperature = temperature; report.temperature = temperature;
report.differential_pressure_filtered_pa = _filter.apply(diff_press_pa_raw); report.differential_pressure_filtered_pa = _filter.apply(diff_press_pa_raw) - _diff_pres_offset;
report.differential_pressure_raw_pa = diff_press_pa_raw - _diff_pres_offset;
report.differential_pressure_raw_pa = diff_press_pa_raw;
report.max_differential_pressure_pa = _max_differential_pressure_pa;
if (_airspeed_pub != nullptr && !(_pub_blocked)) { if (_airspeed_pub != nullptr && !(_pub_blocked)) {
/* publish it */ /* publish it */

View File

@ -244,26 +244,17 @@ MS5525::collect()
const float diff_press_PSI = P * 0.0001f; const float diff_press_PSI = P * 0.0001f;
// 1 PSI = 6894.76 Pascals // 1 PSI = 6894.76 Pascals
const float PSI_to_Pa = 6894.757f; static constexpr float PSI_to_Pa = 6894.757f;
float diff_press_pa_raw = diff_press_PSI * PSI_to_Pa; const float diff_press_pa_raw = diff_press_PSI * PSI_to_Pa;
const float temperature_c = TEMP * 0.01f; const float temperature_c = TEMP * 0.01f;
// the raw value still should be compensated for the known offset
diff_press_pa_raw -= _diff_pres_offset;
/* track maximum differential pressure measured (so we can work out top speed). */
if (diff_press_pa_raw > _max_differential_pressure_pa) {
_max_differential_pressure_pa = diff_press_pa_raw;
}
differential_pressure_s diff_pressure = { differential_pressure_s diff_pressure = {
.timestamp = hrt_absolute_time(), .timestamp = hrt_absolute_time(),
.error_count = perf_event_count(_comms_errors), .error_count = perf_event_count(_comms_errors),
.differential_pressure_raw_pa = diff_press_pa_raw, .differential_pressure_raw_pa = diff_press_pa_raw - _diff_pres_offset,
.differential_pressure_filtered_pa = _filter.apply(diff_press_pa_raw), .differential_pressure_filtered_pa = _filter.apply(diff_press_pa_raw) - _diff_pres_offset,
.max_differential_pressure_pa = _max_differential_pressure_pa, .temperature = temperature_c,
.temperature = temperature_c
}; };
if (_airspeed_pub != nullptr && !(_pub_blocked)) { if (_airspeed_pub != nullptr && !(_pub_blocked)) {

View File

@ -134,25 +134,15 @@ SDP3X::collect()
float diff_press_pa_raw = static_cast<float>(P) / static_cast<float>(_scale); float diff_press_pa_raw = static_cast<float>(P) / static_cast<float>(_scale);
float temperature_c = temp / static_cast<float>(SDP3X_SCALE_TEMPERATURE); float temperature_c = temp / static_cast<float>(SDP3X_SCALE_TEMPERATURE);
// the raw value still should be compensated for the known offset
diff_press_pa_raw -= _diff_pres_offset;
differential_pressure_s report; differential_pressure_s report;
// track maximum differential pressure measured (so we can work out top speed).
if (diff_press_pa_raw > _max_differential_pressure_pa) {
_max_differential_pressure_pa = diff_press_pa_raw;
}
report.timestamp = hrt_absolute_time(); report.timestamp = hrt_absolute_time();
report.error_count = perf_event_count(_comms_errors); report.error_count = perf_event_count(_comms_errors);
report.temperature = temperature_c; report.temperature = temperature_c;
report.differential_pressure_filtered_pa = _filter.apply(diff_press_pa_raw); report.differential_pressure_filtered_pa = _filter.apply(diff_press_pa_raw) - _diff_pres_offset;
report.differential_pressure_raw_pa = diff_press_pa_raw; report.differential_pressure_raw_pa = diff_press_pa_raw - _diff_pres_offset;
report.max_differential_pressure_pa = _max_differential_pressure_pa;
if (_airspeed_pub != nullptr && !(_pub_blocked)) { if (_airspeed_pub != nullptr && !(_pub_blocked)) {
// publish it
orb_publish(ORB_ID(differential_pressure), _airspeed_pub, &report); orb_publish(ORB_ID(differential_pressure), _airspeed_pub, &report);
} }

View File

@ -2040,7 +2040,6 @@ int sdlog2_thread_main(int argc, char *argv[])
log_msg.body.log_DPRS.error_count = buf.diff_pres.error_count; log_msg.body.log_DPRS.error_count = buf.diff_pres.error_count;
log_msg.body.log_DPRS.differential_pressure_raw_pa = buf.diff_pres.differential_pressure_raw_pa; log_msg.body.log_DPRS.differential_pressure_raw_pa = buf.diff_pres.differential_pressure_raw_pa;
log_msg.body.log_DPRS.differential_pressure_filtered_pa = buf.diff_pres.differential_pressure_filtered_pa; log_msg.body.log_DPRS.differential_pressure_filtered_pa = buf.diff_pres.differential_pressure_filtered_pa;
log_msg.body.log_DPRS.max_differential_pressure_pa = buf.diff_pres.max_differential_pressure_pa;
log_msg.body.log_DPRS.temperature = buf.diff_pres.temperature; log_msg.body.log_DPRS.temperature = buf.diff_pres.temperature;
LOGBUFFER_WRITE_AND_COUNT(DPRS); LOGBUFFER_WRITE_AND_COUNT(DPRS);
} }

View File

@ -629,7 +629,6 @@ struct log_DPRS_s {
uint64_t error_count; uint64_t error_count;
float differential_pressure_raw_pa; float differential_pressure_raw_pa;
float differential_pressure_filtered_pa; float differential_pressure_filtered_pa;
float max_differential_pressure_pa;
float temperature; float temperature;
}; };

View File

@ -75,7 +75,6 @@ AirspeedSim::AirspeedSim(int bus, int address, unsigned conversion_interval, con
VDev("AIRSPEEDSIM", path), VDev("AIRSPEEDSIM", path),
_reports(nullptr), _reports(nullptr),
_retries(0), _retries(0),
_max_differential_pressure_pa(0),
_sensor_ok(false), _sensor_ok(false),
_last_published_sensor_ok(true), /* initialize differently to force publication */ _last_published_sensor_ok(true), /* initialize differently to force publication */
_measure_ticks(0), _measure_ticks(0),

View File

@ -123,7 +123,6 @@ protected:
void update_status(); void update_status();
struct work_s _work; struct work_s _work;
float _max_differential_pressure_pa;
bool _sensor_ok; bool _sensor_ok;
bool _last_published_sensor_ok; bool _last_published_sensor_ok;
unsigned _measure_ticks; unsigned _measure_ticks;

View File

@ -194,18 +194,11 @@ MEASAirspeedSim::collect()
struct differential_pressure_s report; struct differential_pressure_s report;
/* track maximum differential pressure measured (so we can work out top speed). */
if (diff_press_pa_raw > _max_differential_pressure_pa) {
_max_differential_pressure_pa = diff_press_pa_raw;
}
report.timestamp = hrt_absolute_time(); report.timestamp = hrt_absolute_time();
report.error_count = perf_event_count(_comms_errors); report.error_count = perf_event_count(_comms_errors);
report.temperature = temperature; report.temperature = temperature;
report.differential_pressure_filtered_pa = _filter.apply(diff_press_pa_raw); report.differential_pressure_filtered_pa = _filter.apply(diff_press_pa_raw);
report.differential_pressure_raw_pa = diff_press_pa_raw; report.differential_pressure_raw_pa = diff_press_pa_raw;
report.max_differential_pressure_pa = _max_differential_pressure_pa;
if (_airspeed_pub != nullptr && !(_pub_blocked)) { if (_airspeed_pub != nullptr && !(_pub_blocked)) {
/* publish it */ /* publish it */
@ -281,18 +274,6 @@ MEASAirspeedSim::cycle()
USEC2TICK(CONVERSION_INTERVAL)); USEC2TICK(CONVERSION_INTERVAL));
} }
/**
correct for 5V rail voltage if the system_power ORB topic is
available
See http://uav.tridgell.net/MS4525/MS4525-offset.png for a graph of
offset versus voltage for 3 sensors
*/
void
MEASAirspeedSim::voltage_correction(float &diff_press_pa, float &temperature)
{
}
/** /**
* Local functions in support of the shell command. * Local functions in support of the shell command.
*/ */