aboutsummaryrefslogtreecommitdiff
path: root/src/modules/position_estimator_inav
diff options
context:
space:
mode:
authorAnton Babushkin <anton.babushkin@me.com>2013-10-07 12:00:24 +0200
committerAnton Babushkin <anton.babushkin@me.com>2013-10-07 12:00:24 +0200
commitbda03cadc33594bacfdacc2cdfe531864fcf2376 (patch)
tree3bb8d01668f15998d6ac50e96ec6f8058ba7c8b4 /src/modules/position_estimator_inav
parent537484f60d37f7f04d2ecaeb4139e2c316565eb2 (diff)
parentc8c74ea7769ca0db190be81db2d8e1b960702b9d (diff)
downloadpx4-firmware-bda03cadc33594bacfdacc2cdfe531864fcf2376.tar.gz
px4-firmware-bda03cadc33594bacfdacc2cdfe531864fcf2376.tar.bz2
px4-firmware-bda03cadc33594bacfdacc2cdfe531864fcf2376.zip
Merge branch 'inav_fix' into inav_flow
Diffstat (limited to 'src/modules/position_estimator_inav')
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_main.c54
1 files changed, 28 insertions, 26 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 950a47fd9..3d43f89ad 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_main.c
+++ b/src/modules/position_estimator_inav/position_estimator_inav_main.c
@@ -81,7 +81,7 @@ static const hrt_abstime sonar_timeout = 150000; // sonar timeout = 150ms
static const hrt_abstime sonar_valid_timeout = 1000000; // assume that altitude == distance to surface during this time
static const hrt_abstime flow_timeout = 1000000; // optical flow topic timeout = 1s
static const uint32_t updates_counter_len = 1000000;
-static const uint32_t pub_interval = 4000; // limit publish rate to 250 Hz
+static const uint32_t pub_interval = 10000; // limit publish rate to 100 Hz
__EXPORT int position_estimator_inav_main(int argc, char *argv[]);
@@ -315,14 +315,8 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
}
/* main loop */
- struct pollfd fds[7] = {
- { .fd = parameter_update_sub, .events = POLLIN },
- { .fd = actuator_sub, .events = POLLIN },
- { .fd = armed_sub, .events = POLLIN },
+ struct pollfd fds[1] = {
{ .fd = vehicle_attitude_sub, .events = POLLIN },
- { .fd = sensor_combined_sub, .events = POLLIN },
- { .fd = optical_flow_sub, .events = POLLIN },
- { .fd = vehicle_gps_position_sub, .events = POLLIN }
};
if (!thread_should_exit) {
@@ -330,7 +324,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
}
while (!thread_should_exit) {
- int ret = poll(fds, 7, 10); // wait maximal this 10 ms = 100 Hz minimum rate
+ int ret = poll(fds, 1, 20); // wait maximal 20 ms = 50 Hz minimum rate
hrt_abstime t = hrt_absolute_time();
if (ret < 0) {
@@ -340,36 +334,42 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
continue;
} else if (ret > 0) {
+ /* act on attitude updates */
+
+ /* vehicle attitude */
+ orb_copy(ORB_ID(vehicle_attitude), vehicle_attitude_sub, &att);
+ attitude_updates++;
+
+ bool updated;
+
/* parameter update */
- if (fds[0].revents & POLLIN) {
- /* read from param to clear updated flag */
+ orb_check(parameter_update_sub, &updated);
+
+ if (updated) {
struct parameter_update_s update;
- orb_copy(ORB_ID(parameter_update), parameter_update_sub,
- &update);
- /* update parameters */
+ orb_copy(ORB_ID(parameter_update), parameter_update_sub, &update);
parameters_update(&pos_inav_param_handles, &params);
}
/* actuator */
- if (fds[1].revents & POLLIN) {
+ orb_check(actuator_sub, &updated);
+
+ if (updated) {
orb_copy(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_sub, &actuator);
}
/* armed */
- if (fds[2].revents & POLLIN) {
- orb_copy(ORB_ID(actuator_armed), armed_sub, &armed);
- }
+ orb_check(armed_sub, &updated);
- /* vehicle attitude */
- if (fds[3].revents & POLLIN) {
- orb_copy(ORB_ID(vehicle_attitude), vehicle_attitude_sub, &att);
- attitude_updates++;
+ if (updated) {
+ orb_copy(ORB_ID(actuator_armed), armed_sub, &armed);
}
/* sensor combined */
- if (fds[4].revents & POLLIN) {
- orb_copy(ORB_ID(sensor_combined), sensor_combined_sub, &sensor);
+ orb_check(sensor_combined_sub, &updated);
+ if (updated) {
+ orb_copy(ORB_ID(sensor_combined), sensor_combined_sub, &sensor);
if (sensor.accelerometer_counter > accel_counter) {
if (att.R_valid) {
/* correct accel bias, now only for Z */
@@ -406,7 +406,8 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
}
/* optical flow */
- if (fds[5].revents & POLLIN) {
+ orb_check(optical_flow_sub, &updated);
+ if (updated) {
orb_copy(ORB_ID(optical_flow), optical_flow_sub, &flow);
if (flow.ground_distance_m > 0.31f && flow.ground_distance_m < 4.0f && att.R[2][2] > 0.7 && (flow.ground_distance_m != sonar_prev || t < sonar_time + sonar_timeout)) {
@@ -488,7 +489,8 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
}
/* vehicle GPS position */
- if (fds[6].revents & POLLIN) {
+ orb_check(vehicle_gps_position_sub, &updated);
+ if (updated) {
orb_copy(ORB_ID(vehicle_gps_position), vehicle_gps_position_sub, &gps);
if (gps.fix_type >= 3) {