aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorAndrew Tridgell <tridge@samba.org>2013-09-12 16:21:59 +1000
committerLorenz Meier <lm@inf.ethz.ch>2013-09-12 09:26:49 +0200
commit4893509344f9304060dabc8a9ecad28fe891dcf8 (patch)
tree6dd11e99adba8f4163a7a4274181a9ca85fd755c
parentc9b8a019eaae6ee7daf11835602059199369544e (diff)
downloadpx4-firmware-4893509344f9304060dabc8a9ecad28fe891dcf8.tar.gz
px4-firmware-4893509344f9304060dabc8a9ecad28fe891dcf8.tar.bz2
px4-firmware-4893509344f9304060dabc8a9ecad28fe891dcf8.zip
drivers: report error_count in drivers where possible
-rw-r--r--src/drivers/bma180/bma180.cpp1
-rw-r--r--src/drivers/ets_airspeed/ets_airspeed.cpp21
-rw-r--r--src/drivers/hmc5883/hmc5883.cpp1
-rw-r--r--src/drivers/l3gd20/l3gd20.cpp1
-rw-r--r--src/drivers/lsm303d/lsm303d.cpp1
-rw-r--r--src/drivers/mb12xx/mb12xx.cpp1
-rw-r--r--src/drivers/meas_airspeed/meas_airspeed.cpp4
-rw-r--r--src/drivers/mpu6000/mpu6000.cpp2
-rw-r--r--src/drivers/ms5611/ms5611.cpp1
9 files changed, 19 insertions, 14 deletions
diff --git a/src/drivers/bma180/bma180.cpp b/src/drivers/bma180/bma180.cpp
index f0044d36f..1590cc182 100644
--- a/src/drivers/bma180/bma180.cpp
+++ b/src/drivers/bma180/bma180.cpp
@@ -690,6 +690,7 @@ BMA180::measure()
* measurement flow without using the external interrupt.
*/
report.timestamp = hrt_absolute_time();
+ report.error_count = 0;
/*
* y of board is x of sensor and x of board is -y of sensor
* perform only the axis assignment here.
diff --git a/src/drivers/ets_airspeed/ets_airspeed.cpp b/src/drivers/ets_airspeed/ets_airspeed.cpp
index dd8436b10..084671ae2 100644
--- a/src/drivers/ets_airspeed/ets_airspeed.cpp
+++ b/src/drivers/ets_airspeed/ets_airspeed.cpp
@@ -153,35 +153,36 @@ ETSAirspeed::collect()
ret = transfer(nullptr, 0, &val[0], 2);
if (ret < 0) {
- log("error reading from sensor: %d", ret);
+ perf_count(_comms_errors);
return ret;
}
uint16_t diff_pres_pa = val[1] << 8 | val[0];
if (diff_pres_pa == 0) {
- // a zero value means the pressure sensor cannot give us a
- // value. We need to return, and not report a value or the
- // caller could end up using this value as part of an
- // average
- log("zero value from sensor");
- return -1;
+ // a zero value means the pressure sensor cannot give us a
+ // value. We need to return, and not report a value or the
+ // caller could end up using this value as part of an
+ // average
+ perf_count(_comms_errors);
+ log("zero value from sensor");
+ return -1;
}
if (diff_pres_pa < _diff_pres_offset + MIN_ACCURATE_DIFF_PRES_PA) {
diff_pres_pa = 0;
-
} else {
diff_pres_pa -= _diff_pres_offset;
}
// Track maximum differential pressure measured (so we can work out top speed).
if (diff_pres_pa > _max_differential_pressure_pa) {
- _max_differential_pressure_pa = diff_pres_pa;
+ _max_differential_pressure_pa = diff_pres_pa;
}
// XXX we may want to smooth out the readings to remove noise.
differential_pressure_s report;
report.timestamp = hrt_absolute_time();
+ report.error_count = perf_event_count(_comms_errors);
report.differential_pressure_pa = diff_pres_pa;
report.voltage = 0;
report.max_differential_pressure_pa = _max_differential_pressure_pa;
@@ -209,7 +210,7 @@ ETSAirspeed::cycle()
/* perform collection */
if (OK != collect()) {
- log("collection error");
+ perf_count(_comms_errors);
/* restart the measurement state machine */
start();
return;
diff --git a/src/drivers/hmc5883/hmc5883.cpp b/src/drivers/hmc5883/hmc5883.cpp
index 58a1593ed..de043db64 100644
--- a/src/drivers/hmc5883/hmc5883.cpp
+++ b/src/drivers/hmc5883/hmc5883.cpp
@@ -791,6 +791,7 @@ HMC5883::collect()
/* this should be fairly close to the end of the measurement, so the best approximation of the time */
new_report.timestamp = hrt_absolute_time();
+ new_report.error_count = perf_event_count(_comms_errors);
/*
* @note We could read the status register here, which could tell us that
diff --git a/src/drivers/l3gd20/l3gd20.cpp b/src/drivers/l3gd20/l3gd20.cpp
index 4c3b0ce51..ad6de0ab1 100644
--- a/src/drivers/l3gd20/l3gd20.cpp
+++ b/src/drivers/l3gd20/l3gd20.cpp
@@ -774,6 +774,7 @@ L3GD20::measure()
* 74 from all measurements centers them around zero.
*/
report.timestamp = hrt_absolute_time();
+ report.error_count = 0; // not recorded
switch (_orientation) {
diff --git a/src/drivers/lsm303d/lsm303d.cpp b/src/drivers/lsm303d/lsm303d.cpp
index a90cd0a3d..7244019b1 100644
--- a/src/drivers/lsm303d/lsm303d.cpp
+++ b/src/drivers/lsm303d/lsm303d.cpp
@@ -1252,6 +1252,7 @@ LSM303D::measure()
accel_report.timestamp = hrt_absolute_time();
+ accel_report.error_count = 0; // not reported
accel_report.x_raw = raw_accel_report.x;
accel_report.y_raw = raw_accel_report.y;
diff --git a/src/drivers/mb12xx/mb12xx.cpp b/src/drivers/mb12xx/mb12xx.cpp
index ccc5bc15e..c910e2890 100644
--- a/src/drivers/mb12xx/mb12xx.cpp
+++ b/src/drivers/mb12xx/mb12xx.cpp
@@ -490,6 +490,7 @@ MB12XX::collect()
/* this should be fairly close to the end of the measurement, so the best approximation of the time */
report.timestamp = hrt_absolute_time();
+ report.error_count = perf_event_count(_comms_errors);
report.distance = si_units;
report.valid = si_units > get_minimum_distance() && si_units < get_maximum_distance() ? 1 : 0;
diff --git a/src/drivers/meas_airspeed/meas_airspeed.cpp b/src/drivers/meas_airspeed/meas_airspeed.cpp
index 03d7bbfb9..ee45d46ac 100644
--- a/src/drivers/meas_airspeed/meas_airspeed.cpp
+++ b/src/drivers/meas_airspeed/meas_airspeed.cpp
@@ -138,7 +138,6 @@ MEASAirspeed::measure()
if (OK != ret) {
perf_count(_comms_errors);
- log("i2c::transfer returned %d", ret);
return ret;
}
@@ -161,7 +160,6 @@ MEASAirspeed::collect()
ret = transfer(nullptr, 0, &val[0], 4);
if (ret < 0) {
- log("error reading from sensor: %d", ret);
perf_count(_comms_errors);
perf_end(_sample_perf);
return ret;
@@ -207,6 +205,7 @@ MEASAirspeed::collect()
}
report.timestamp = hrt_absolute_time();
+ report.error_count = perf_event_count(_comms_errors);
report.temperature = temperature;
report.differential_pressure_pa = diff_press_pa;
report.voltage = 0;
@@ -235,7 +234,6 @@ MEASAirspeed::cycle()
/* perform collection */
if (OK != collect()) {
- log("collection error");
/* restart the measurement state machine */
start();
return;
diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp
index 14a3571de..70359110e 100644
--- a/src/drivers/mpu6000/mpu6000.cpp
+++ b/src/drivers/mpu6000/mpu6000.cpp
@@ -1186,7 +1186,7 @@ MPU6000::measure()
* Adjust and scale results to m/s^2.
*/
grb.timestamp = arb.timestamp = hrt_absolute_time();
-
+ grb.error_count = arb.error_count = 0; // not reported
/*
* 1) Scale raw value to SI units using scaling from datasheet.
diff --git a/src/drivers/ms5611/ms5611.cpp b/src/drivers/ms5611/ms5611.cpp
index 1c8a4d776..938786d3f 100644
--- a/src/drivers/ms5611/ms5611.cpp
+++ b/src/drivers/ms5611/ms5611.cpp
@@ -573,6 +573,7 @@ MS5611::collect()
struct baro_report report;
/* this should be fairly close to the end of the conversion, so the best approximation of the time */
report.timestamp = hrt_absolute_time();
+ report.error_count = perf_event_count(_comms_errors);
/* read the most recent measurement - read offset/size are hardcoded in the interface */
ret = _interface->read(0, (void *)&raw, 0);