aboutsummaryrefslogtreecommitdiff
path: root/src/modules/position_estimator_inav
diff options
context:
space:
mode:
authorAnton Babushkin <anton.babushkin@me.com>2014-03-19 20:01:01 +0400
committerAnton Babushkin <anton.babushkin@me.com>2014-03-19 20:01:01 +0400
commit9b71e660ad86cb2ecec4db93795f417a9ba0fddd (patch)
treec7bd62f4e4b260f03c6103e9d322e2b3f84d11c2 /src/modules/position_estimator_inav
parent068b7526b74c9bbcc31acc28f0d578ed9c0f97b1 (diff)
parent295f87f22cc471fccb44e3f3dee3e8fcab263de2 (diff)
downloadpx4-firmware-9b71e660ad86cb2ecec4db93795f417a9ba0fddd.tar.gz
px4-firmware-9b71e660ad86cb2ecec4db93795f417a9ba0fddd.tar.bz2
px4-firmware-9b71e660ad86cb2ecec4db93795f417a9ba0fddd.zip
Merge branch 'beta_mavlink2' into mpc_local_pos_mavlink
Diffstat (limited to 'src/modules/position_estimator_inav')
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_main.c16
1 files changed, 8 insertions, 8 deletions
diff --git a/src/modules/position_estimator_inav/position_estimator_inav_main.c b/src/modules/position_estimator_inav/position_estimator_inav_main.c
index fc394fda6..caf2f840c 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_main.c
+++ b/src/modules/position_estimator_inav/position_estimator_inav_main.c
@@ -207,8 +207,8 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
bool landed = true;
hrt_abstime landed_time = 0;
- uint32_t accel_counter = 0;
- uint32_t baro_counter = 0;
+ hrt_abstime accel_timestamp = 0;
+ hrt_abstime baro_timestamp = 0;
bool ref_inited = false;
hrt_abstime ref_init_start = 0;
@@ -319,8 +319,8 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
if (fds_init[0].revents & POLLIN) {
orb_copy(ORB_ID(sensor_combined), sensor_combined_sub, &sensor);
- if (wait_baro && sensor.baro_counter != baro_counter) {
- baro_counter = sensor.baro_counter;
+ if (wait_baro && sensor.baro_timestamp != baro_timestamp) {
+ baro_timestamp = sensor.baro_timestamp;
/* mean calculation over several measurements */
if (baro_init_cnt < baro_init_num) {
@@ -393,7 +393,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
if (updated) {
orb_copy(ORB_ID(sensor_combined), sensor_combined_sub, &sensor);
- if (sensor.accelerometer_counter != accel_counter) {
+ if (sensor.accelerometer_timestamp != accel_timestamp) {
if (att.R_valid) {
/* correct accel bias */
sensor.accelerometer_m_s2[0] -= acc_bias[0];
@@ -417,13 +417,13 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
memset(corr_acc, 0, sizeof(corr_acc));
}
- accel_counter = sensor.accelerometer_counter;
+ accel_timestamp = sensor.accelerometer_timestamp;
accel_updates++;
}
- if (sensor.baro_counter != baro_counter) {
+ if (sensor.baro_timestamp != baro_timestamp) {
corr_baro = baro_offset - sensor.baro_alt_meter - z_est[0];
- baro_counter = sensor.baro_counter;
+ baro_timestamp = sensor.baro_timestamp;
baro_updates++;
}
}