diff options
author | Lorenz Meier <lm@inf.ethz.ch> | 2012-09-07 12:49:31 +0200 |
---|---|---|
committer | Lorenz Meier <lm@inf.ethz.ch> | 2012-09-07 12:49:31 +0200 |
commit | 1538247a72f37a2f969aa5c41f7a07da4ae31d35 (patch) | |
tree | 53a53c88e2f1d7150af9f6670eac326e37bb98c0 /apps/mavlink | |
parent | 5066ce1e9132f94bfcabaee3e16c3d9aac4801e8 (diff) | |
download | px4-firmware-1538247a72f37a2f969aa5c41f7a07da4ae31d35.tar.gz px4-firmware-1538247a72f37a2f969aa5c41f7a07da4ae31d35.tar.bz2 px4-firmware-1538247a72f37a2f969aa5c41f7a07da4ae31d35.zip |
Sensor sending rate fixes
Diffstat (limited to 'apps/mavlink')
-rw-r--r-- | apps/mavlink/mavlink.c | 10 |
1 files changed, 5 insertions, 5 deletions
diff --git a/apps/mavlink/mavlink.c b/apps/mavlink/mavlink.c index 0df881339..7289bd7a8 100644 --- a/apps/mavlink/mavlink.c +++ b/apps/mavlink/mavlink.c @@ -1550,8 +1550,8 @@ int mavlink_thread_main(int argc, char *argv[]) /* all subscriptions are now active, set up initial guess about rate limits */ if (baudrate >= 921600) { - /* 500 Hz / 2 ms */ - set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_HIGHRES_IMU, 2); + /* 200 Hz / 5 ms */ + set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_HIGHRES_IMU, 5); /* 200 Hz / 5 ms */ set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, 5); set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, 5); @@ -1561,11 +1561,11 @@ int mavlink_thread_main(int argc, char *argv[]) set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_MANUAL_CONTROL, 200); } else if (baudrate >= 460800) { /* 200 Hz / 5 ms */ - set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_HIGHRES_IMU, 10); - /* 100 Hz / 10 ms */ + set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_HIGHRES_IMU, 5); + /* 50 Hz / 10 ms */ set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_SCALED_IMU, 20); set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_ATTITUDE, 20); - /* 20 Hz / 20 ms */ + /* 20 Hz / 50 ms */ set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, 50); set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, 50); /* 2 Hz */ |