aboutsummaryrefslogtreecommitdiff
path: root/apps/mavlink
diff options
context:
space:
mode:
authorpx4dev <px4@purgatory.org>2013-01-19 13:17:28 -0800
committerpx4dev <px4@purgatory.org>2013-01-19 13:17:28 -0800
commitc1a1207b9a8636b136197b2b92bbf914f7a928cc (patch)
tree702e4d46cefd1edf6aa1e4ba1b4d6a2e4d5d52ff /apps/mavlink
parent7eb7836d2db3fa30b65f5ae72054b3fdc3582a6c (diff)
parenteffc3001f4bcc5a2e2510ee5d16e44b1e8188911 (diff)
downloadpx4-firmware-c1a1207b9a8636b136197b2b92bbf914f7a928cc.tar.gz
px4-firmware-c1a1207b9a8636b136197b2b92bbf914f7a928cc.tar.bz2
px4-firmware-c1a1207b9a8636b136197b2b92bbf914f7a928cc.zip
Merge pull request #171 from PX4/fault_detection
Attitude / position estimation and controller improvements
Diffstat (limited to 'apps/mavlink')
-rw-r--r--apps/mavlink/mavlink_receiver.c19
-rw-r--r--apps/mavlink/orb_listener.c2
2 files changed, 13 insertions, 8 deletions
diff --git a/apps/mavlink/mavlink_receiver.c b/apps/mavlink/mavlink_receiver.c
index fa63c419f..9491ce7e3 100644
--- a/apps/mavlink/mavlink_receiver.c
+++ b/apps/mavlink/mavlink_receiver.c
@@ -318,9 +318,11 @@ handle_message(mavlink_message_t *msg)
static uint16_t hil_frames = 0;
static uint64_t old_timestamp = 0;
+ /* sensors general */
+ hil_sensors.timestamp = imu.time_usec;
+
/* hil gyro */
static const float mrad2rad = 1.0e-3f;
- hil_sensors.timestamp = timestamp;
hil_sensors.gyro_counter = hil_counter;
hil_sensors.gyro_raw[0] = imu.xgyro;
hil_sensors.gyro_raw[1] = imu.ygyro;
@@ -367,8 +369,8 @@ handle_message(mavlink_message_t *msg)
hil_frames += 1 ;
// output
- if ((timestamp - old_timestamp) > 1000000) {
- printf("receiving hil imu at %d hz\n", hil_frames);
+ if ((timestamp - old_timestamp) > 10000000) {
+ printf("receiving hil imu at %d hz\n", hil_frames/10);
old_timestamp = timestamp;
hil_frames = 0;
}
@@ -412,8 +414,8 @@ handle_message(mavlink_message_t *msg)
hil_frames += 1 ;
// output
- if ((timestamp - old_timestamp) > 1000000) {
- printf("receiving hil gps at %d hz\n", hil_frames);
+ if ((timestamp - old_timestamp) > 10000000) {
+ printf("receiving hil gps at %d hz\n", hil_frames/10);
old_timestamp = timestamp;
hil_frames = 0;
}
@@ -429,6 +431,9 @@ handle_message(mavlink_message_t *msg)
static uint16_t hil_frames = 0;
static uint64_t old_timestamp = 0;
+ /* sensors general */
+ hil_sensors.timestamp = press.time_usec;
+
/* baro */
/* TODO, set ground_press/ temp during calib */
static const float ground_press = 1013.25f; // mbar
@@ -454,8 +459,8 @@ handle_message(mavlink_message_t *msg)
hil_frames += 1 ;
// output
- if ((timestamp - old_timestamp) > 1000000) {
- printf("receiving hil pressure at %d hz\n", hil_frames);
+ if ((timestamp - old_timestamp) > 10000000) {
+ printf("receiving hil pressure at %d hz\n", hil_frames/10);
old_timestamp = timestamp;
hil_frames = 0;
}
diff --git a/apps/mavlink/orb_listener.c b/apps/mavlink/orb_listener.c
index 8920714ef..ec5149745 100644
--- a/apps/mavlink/orb_listener.c
+++ b/apps/mavlink/orb_listener.c
@@ -718,7 +718,7 @@ uorb_receive_start(void)
/* --- GLOBAL POS VALUE --- */
mavlink_subs.global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position));
- orb_set_interval(mavlink_subs.global_pos_sub, 1000); /* 1Hz active updates */
+ orb_set_interval(mavlink_subs.global_pos_sub, 100); /* 10 Hz active updates */
/* --- LOCAL POS VALUE --- */
mavlink_subs.local_pos_sub = orb_subscribe(ORB_ID(vehicle_local_position));