aboutsummaryrefslogtreecommitdiff
path: root/apps/mavlink/mavlink.c
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2012-10-17 18:27:21 +0200
committerLorenz Meier <lm@inf.ethz.ch>2012-10-17 18:27:21 +0200
commit6a48b91beae575ad4684151f08c75b079caffe5c (patch)
treebfb5c167bb3d0f3b7e084a1f295f3df46aaad788 /apps/mavlink/mavlink.c
parent2d631fb0059cecdc429c5847e8dbede82348d129 (diff)
downloadpx4-firmware-6a48b91beae575ad4684151f08c75b079caffe5c.tar.gz
px4-firmware-6a48b91beae575ad4684151f08c75b079caffe5c.tar.bz2
px4-firmware-6a48b91beae575ad4684151f08c75b079caffe5c.zip
Lowering default rates at 57600
Diffstat (limited to 'apps/mavlink/mavlink.c')
-rw-r--r--apps/mavlink/mavlink.c6
1 files changed, 3 insertions, 3 deletions
diff --git a/apps/mavlink/mavlink.c b/apps/mavlink/mavlink.c
index 075dc9e3b..293bbe00c 100644
--- a/apps/mavlink/mavlink.c
+++ b/apps/mavlink/mavlink.c
@@ -576,10 +576,10 @@ int mavlink_thread_main(int argc, char *argv[])
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_MANUAL_CONTROL, 1000);
} else if (baudrate >= 57600) {
/* 10 Hz / 100 ms */
- set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_RAW_IMU, 100);
- set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_HIGHRES_IMU, 100);
+ set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_RAW_IMU, 200);
+ set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_HIGHRES_IMU, 200);
/* 10 Hz / 100 ms ATTITUDE */
- set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_ATTITUDE, 100);
+ set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_ATTITUDE, 200);
/* 5 Hz / 200 ms */
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, 200);
/* 5 Hz / 200 ms */