aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mavlink
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2014-10-07 10:12:56 +0200
committerThomas Gubler <thomasgubler@gmail.com>2014-10-07 10:12:56 +0200
commitc7f7de352d7e0f2921526e33077c6da6a46b404a (patch)
tree6d9bf75a03303ffdef851914c5d5e8677a318bbe /src/modules/mavlink
parentba2f55c3d7f5872aaf07e20b58b15df85417d43a (diff)
downloadpx4-firmware-c7f7de352d7e0f2921526e33077c6da6a46b404a.tar.gz
px4-firmware-c7f7de352d7e0f2921526e33077c6da6a46b404a.tar.bz2
px4-firmware-c7f7de352d7e0f2921526e33077c6da6a46b404a.zip
revert some of the OBC rate changes
Diffstat (limited to 'src/modules/mavlink')
-rw-r--r--src/modules/mavlink/mavlink_main.cpp17
1 files changed, 7 insertions, 10 deletions
diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp
index 34596320f..4738d1ea7 100644
--- a/src/modules/mavlink/mavlink_main.cpp
+++ b/src/modules/mavlink/mavlink_main.cpp
@@ -1382,28 +1382,25 @@ Mavlink::task_main(int argc, char *argv[])
_mission_manager->set_verbose(_verbose);
LL_APPEND(_streams, _mission_manager);
-
-
switch (_mode) {
case MAVLINK_MODE_NORMAL:
configure_stream("SYS_STATUS", 1.0f);
configure_stream("GPS_GLOBAL_ORIGIN", 0.5f);
configure_stream("HIGHRES_IMU", 1.0f);
- configure_stream("ATTITUDE", 4.0f);
- configure_stream("VFR_HUD", 4.0f);
+ configure_stream("ATTITUDE", 10.0f);
+ configure_stream("VFR_HUD", 8.0f);
configure_stream("GPS_RAW_INT", 1.0f);
- configure_stream("GLOBAL_POSITION_INT", 1.0f);
- configure_stream("LOCAL_POSITION_NED", 1.0f);
+ configure_stream("GLOBAL_POSITION_INT", 3.0f);
+ configure_stream("LOCAL_POSITION_NED", 3.0f);
configure_stream("RC_CHANNELS_RAW", 1.0f);
- configure_stream("POSITION_TARGET_GLOBAL_INT", 1.0f);
- configure_stream("ATTITUDE_TARGET", 1.0f);
+ configure_stream("POSITION_TARGET_GLOBAL_INT", 3.0f);
+ configure_stream("ATTITUDE_TARGET", 3.0f);
configure_stream("DISTANCE_SENSOR", 0.5f);
- //configure_stream("OPTICAL_FLOW", 20.0f);
+ configure_stream("OPTICAL_FLOW", 5.0f);
break;
case MAVLINK_MODE_ONBOARD:
configure_stream("SYS_STATUS", 1.0f);
- // XXX OBC change back: We need to be bandwidth-efficient here too
configure_stream("ATTITUDE", 50.0f);
configure_stream("GLOBAL_POSITION_INT", 50.0f);
configure_stream("CAMERA_CAPTURE", 2.0f);