aboutsummaryrefslogtreecommitdiff
path: root/src
diff options
context:
space:
mode:
authorJulian Oes <julian@oes.ch>2014-09-23 06:09:57 +1000
committerJulian Oes <julian@oes.ch>2014-09-23 06:09:57 +1000
commitca542902c5829a2dd8f688315646161d46b17300 (patch)
tree87a0709684db5098743a5ba59be7627255310516 /src
parent69eb222d4e2cf3d0894992a50a7a5822489f757f (diff)
parentd9bb3a51124cb3006f7548ac6ee629b48a939336 (diff)
downloadpx4-firmware-ca542902c5829a2dd8f688315646161d46b17300.tar.gz
px4-firmware-ca542902c5829a2dd8f688315646161d46b17300.tar.bz2
px4-firmware-ca542902c5829a2dd8f688315646161d46b17300.zip
Merge remote-tracking branch 'swissfang/master' into sbasdisable
Diffstat (limited to 'src')
-rw-r--r--src/modules/mavlink/mavlink_main.cpp25
1 files changed, 14 insertions, 11 deletions
diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp
index dd830071d..b9f486c95 100644
--- a/src/modules/mavlink/mavlink_main.cpp
+++ b/src/modules/mavlink/mavlink_main.cpp
@@ -1328,7 +1328,7 @@ Mavlink::task_main(int argc, char *argv[])
* make space for two messages plus off-by-one space as we use the empty element
* marker ring buffer approach.
*/
- if (OK != message_buffer_init(2 * sizeof(mavlink_message_t) + 1)) {
+ if (OK != message_buffer_init(10 * sizeof(mavlink_message_t) + 1)) {
errx(1, "can't allocate message buffer, exiting");
}
@@ -1382,21 +1382,23 @@ 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", 15.0f);
- configure_stream("VFR_HUD", 8.0f);
+ configure_stream("ATTITUDE", 4.0f);
+ configure_stream("VFR_HUD", 4.0f);
configure_stream("GPS_RAW_INT", 1.0f);
- configure_stream("GLOBAL_POSITION_INT", 3.0f);
- configure_stream("LOCAL_POSITION_NED", 3.0f);
+ configure_stream("GLOBAL_POSITION_INT", 1.0f);
+ configure_stream("LOCAL_POSITION_NED", 1.0f);
configure_stream("RC_CHANNELS_RAW", 1.0f);
- configure_stream("POSITION_TARGET_GLOBAL_INT", 3.0f);
- configure_stream("ATTITUDE_TARGET", 15.0f);
+ configure_stream("POSITION_TARGET_GLOBAL_INT", 1.0f);
+ configure_stream("ATTITUDE_TARGET", 1.0f);
configure_stream("DISTANCE_SENSOR", 0.5f);
- configure_stream("OPTICAL_FLOW", 20.0f);
+ //configure_stream("OPTICAL_FLOW", 20.0f);
break;
case MAVLINK_MODE_ONBOARD:
@@ -1405,8 +1407,9 @@ Mavlink::task_main(int argc, char *argv[])
configure_stream("ATTITUDE", 50.0f);
configure_stream("GLOBAL_POSITION_INT", 50.0f);
configure_stream("CAMERA_CAPTURE", 2.0f);
- configure_stream("ATTITUDE_TARGET", 50.0f);
- configure_stream("POSITION_TARGET_GLOBAL_INT", 20.0f);
+ configure_stream("ATTITUDE_TARGET", 10.0f);
+ configure_stream("POSITION_TARGET_GLOBAL_INT", 10.0f);
+ configure_stream("VFR_HUD", 10.0f);
break;
default:
@@ -1627,7 +1630,7 @@ Mavlink::start(int argc, char *argv[])
task_spawn_cmd(buf,
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
- 2700,
+ 5000,
(main_t)&Mavlink::start_helper,
(const char **)argv);