aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mavlink
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2014-01-12 12:57:53 +0100
committerLorenz Meier <lm@inf.ethz.ch>2014-01-12 12:57:53 +0100
commite421260f7c3e2a3f7145c2f643f8440060a84777 (patch)
treee91e6cf7bedcdec979caf4b1cc4685450b606e29 /src/modules/mavlink
parent0d3a743f75d50163568203a413d8e72dac6636c5 (diff)
downloadpx4-firmware-e421260f7c3e2a3f7145c2f643f8440060a84777.tar.gz
px4-firmware-e421260f7c3e2a3f7145c2f643f8440060a84777.tar.bz2
px4-firmware-e421260f7c3e2a3f7145c2f643f8440060a84777.zip
Removed bogus sensor counters, replaced them with proper timestamps
Diffstat (limited to 'src/modules/mavlink')
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp11
-rw-r--r--src/modules/mavlink/orb_listener.c24
2 files changed, 17 insertions, 18 deletions
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index 7b6fad658..37e5b8c61 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -388,7 +388,6 @@ handle_message(mavlink_message_t *msg)
hil_sensors.gyro_rad_s[0] = imu.xgyro;
hil_sensors.gyro_rad_s[1] = imu.ygyro;
hil_sensors.gyro_rad_s[2] = imu.zgyro;
- hil_sensors.gyro_counter = hil_counter;
/* accelerometer */
static const float mg2ms2 = 9.8f / 1000.0f;
@@ -400,7 +399,7 @@ handle_message(mavlink_message_t *msg)
hil_sensors.accelerometer_m_s2[2] = imu.zacc;
hil_sensors.accelerometer_mode = 0; // TODO what is this?
hil_sensors.accelerometer_range_m_s2 = 32.7f; // int16
- hil_sensors.accelerometer_counter = hil_counter;
+ hil_sensors.accelerometer_timestamp = hil_sensors.timestamp;
/* adc */
hil_sensors.adc_voltage_v[0] = 0.0f;
@@ -418,17 +417,17 @@ handle_message(mavlink_message_t *msg)
hil_sensors.magnetometer_range_ga = 32.7f; // int16
hil_sensors.magnetometer_mode = 0; // TODO what is this
hil_sensors.magnetometer_cuttoff_freq_hz = 50.0f;
- hil_sensors.magnetometer_counter = hil_counter;
+ hil_sensors.magnetometer_timestamp = hil_sensors.timestamp;
/* baro */
hil_sensors.baro_pres_mbar = imu.abs_pressure;
hil_sensors.baro_alt_meter = imu.pressure_alt;
hil_sensors.baro_temp_celcius = imu.temperature;
- hil_sensors.baro_counter = hil_counter;
+ hil_sensors.baro_timestamp = hil_sensors.timestamp;
/* differential pressure */
hil_sensors.differential_pressure_pa = imu.diff_pressure * 1e2f; //from hPa to Pa
- hil_sensors.differential_pressure_counter = hil_counter;
+ hil_sensors.differential_pressure_timestamp = hil_sensors.timestamp;
/* airspeed from differential pressure, ambient pressure and temp */
struct airspeed_s airspeed;
@@ -829,7 +828,7 @@ receive_thread(void *arg)
while (!thread_should_exit) {
if (poll(fds, 1, timeout) > 0) {
- if (nread < sizeof(buf)) {
+ if (nread < (ssize_t)sizeof(buf)) {
/* to avoid reading very small chunks wait for data before reading */
usleep(1000);
}
diff --git a/src/modules/mavlink/orb_listener.c b/src/modules/mavlink/orb_listener.c
index 92b1b45be..4a4ebf709 100644
--- a/src/modules/mavlink/orb_listener.c
+++ b/src/modules/mavlink/orb_listener.c
@@ -181,33 +181,33 @@ l_sensor_combined(const struct listener *l)
/* mark individual fields as changed */
uint16_t fields_updated = 0;
- static unsigned accel_counter = 0;
- static unsigned gyro_counter = 0;
- static unsigned mag_counter = 0;
- static unsigned baro_counter = 0;
+ static hrt_abstime accel_counter = 0;
+ static hrt_abstime gyro_counter = 0;
+ static hrt_abstime mag_counter = 0;
+ static hrt_abstime baro_counter = 0;
- if (accel_counter != raw.accelerometer_counter) {
+ if (accel_counter != raw.accelerometer_timestamp) {
/* mark first three dimensions as changed */
fields_updated |= (1 << 0) | (1 << 1) | (1 << 2);
- accel_counter = raw.accelerometer_counter;
+ accel_counter = raw.accelerometer_timestamp;
}
- if (gyro_counter != raw.gyro_counter) {
+ if (gyro_counter != raw.timestamp) {
/* mark second group dimensions as changed */
fields_updated |= (1 << 3) | (1 << 4) | (1 << 5);
- gyro_counter = raw.gyro_counter;
+ gyro_counter = raw.timestamp;
}
- if (mag_counter != raw.magnetometer_counter) {
+ if (mag_counter != raw.magnetometer_timestamp) {
/* mark third group dimensions as changed */
fields_updated |= (1 << 6) | (1 << 7) | (1 << 8);
- mag_counter = raw.magnetometer_counter;
+ mag_counter = raw.magnetometer_timestamp;
}
- if (baro_counter != raw.baro_counter) {
+ if (baro_counter != raw.baro_timestamp) {
/* mark last group dimensions as changed */
fields_updated |= (1 << 9) | (1 << 11) | (1 << 12);
- baro_counter = raw.baro_counter;
+ baro_counter = raw.baro_timestamp;
}
if (gcs_link)