aboutsummaryrefslogtreecommitdiff
path: root/apps
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2012-11-05 09:45:25 +0100
committerLorenz Meier <lm@inf.ethz.ch>2012-11-05 09:45:25 +0100
commitec43e7b7be69e4445c08ff8821de700e449a8f70 (patch)
treec7264d529026f88f72fc70dad5ad4d193f02cad9 /apps
parent7fbad5adea0a022d71d8c5c4453cda1244e154b3 (diff)
downloadpx4-firmware-ec43e7b7be69e4445c08ff8821de700e449a8f70.tar.gz
px4-firmware-ec43e7b7be69e4445c08ff8821de700e449a8f70.tar.bz2
px4-firmware-ec43e7b7be69e4445c08ff8821de700e449a8f70.zip
Increased output rates at 115200 baud
Diffstat (limited to 'apps')
-rw-r--r--apps/mavlink/mavlink.c15
1 files changed, 7 insertions, 8 deletions
diff --git a/apps/mavlink/mavlink.c b/apps/mavlink/mavlink.c
index 7d8232b3a..9b2cfcbba 100644
--- a/apps/mavlink/mavlink.c
+++ b/apps/mavlink/mavlink.c
@@ -589,16 +589,15 @@ int mavlink_thread_main(int argc, char *argv[])
/* 2 Hz */
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_MANUAL_CONTROL, 100);
} else if (baudrate >= 115200) {
- /* 50 Hz / 20 ms */
- set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_HIGHRES_IMU, 200);
- set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_RAW_IMU, 200);
/* 20 Hz / 50 ms */
- set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_ATTITUDE, 200);
- set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, 200);
- /* 10 Hz / 100 ms */
+ set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_HIGHRES_IMU, 50);
+ set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_RAW_IMU, 50);
+ set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_ATTITUDE, 50);
+ set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, 50);
+ /* 5 Hz / 100 ms */
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, 200);
- /* 1 Hz */
- set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_MANUAL_CONTROL, 1000);
+ /* 2 Hz */
+ set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_MANUAL_CONTROL, 500);
} else if (baudrate >= 57600) {
/* 10 Hz / 100 ms */
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_RAW_IMU, 300);