aboutsummaryrefslogtreecommitdiff
path: root/apps/mavlink
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2012-11-27 17:24:33 +0100
committerLorenz Meier <lm@inf.ethz.ch>2012-11-27 17:24:33 +0100
commitcaf0fefa32b5441f1093de460cbc77f6d3aa2f92 (patch)
tree4972211af7a087b5393a2446f4af20bc4647da75 /apps/mavlink
parentdc72d467d4abe3d18bbf02091eb4eaddb4f491d2 (diff)
downloadpx4-firmware-caf0fefa32b5441f1093de460cbc77f6d3aa2f92.tar.gz
px4-firmware-caf0fefa32b5441f1093de460cbc77f6d3aa2f92.tar.bz2
px4-firmware-caf0fefa32b5441f1093de460cbc77f6d3aa2f92.zip
Cleaned up different uorb topics, cleaned up excessive stack sizes
Diffstat (limited to 'apps/mavlink')
-rw-r--r--apps/mavlink/mavlink.c2
-rw-r--r--apps/mavlink/mavlink_receiver.c4
-rw-r--r--apps/mavlink/orb_listener.c4
-rw-r--r--apps/mavlink/orb_topics.h1
4 files changed, 7 insertions, 4 deletions
diff --git a/apps/mavlink/mavlink.c b/apps/mavlink/mavlink.c
index b393620e2..81b907bcd 100644
--- a/apps/mavlink/mavlink.c
+++ b/apps/mavlink/mavlink.c
@@ -735,7 +735,7 @@ int mavlink_main(int argc, char *argv[])
mavlink_task = task_spawn("mavlink",
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
- 6000,
+ 2048,
mavlink_thread_main,
(const char**)argv);
exit(0);
diff --git a/apps/mavlink/mavlink_receiver.c b/apps/mavlink/mavlink_receiver.c
index 6b4375445..dd011aeed 100644
--- a/apps/mavlink/mavlink_receiver.c
+++ b/apps/mavlink/mavlink_receiver.c
@@ -202,6 +202,8 @@ handle_message(mavlink_message_t *msg)
mavlink_vicon_position_estimate_t pos;
mavlink_msg_vicon_position_estimate_decode(msg, &pos);
+ vicon_position.timestamp = hrt_absolute_time();
+
vicon_position.x = pos.x;
vicon_position.y = pos.y;
vicon_position.z = pos.z;
@@ -427,4 +429,4 @@ receive_start(int uart)
pthread_t thread;
pthread_create(&thread, &receiveloop_attr, receive_thread, &uart);
return thread;
-} \ No newline at end of file
+}
diff --git a/apps/mavlink/orb_listener.c b/apps/mavlink/orb_listener.c
index 4567a08f8..a067460d8 100644
--- a/apps/mavlink/orb_listener.c
+++ b/apps/mavlink/orb_listener.c
@@ -731,8 +731,8 @@ uorb_receive_start(void)
pthread_attr_t uorb_attr;
pthread_attr_init(&uorb_attr);
- /* Set stack size, needs more than 8000 bytes */
- pthread_attr_setstacksize(&uorb_attr, 4096);
+ /* Set stack size, needs less than 2k */
+ pthread_attr_setstacksize(&uorb_attr, 2048);
pthread_t thread;
pthread_create(&thread, &uorb_attr, uorb_receive_thread, NULL);
diff --git a/apps/mavlink/orb_topics.h b/apps/mavlink/orb_topics.h
index 1b371e5cd..61e664401 100644
--- a/apps/mavlink/orb_topics.h
+++ b/apps/mavlink/orb_topics.h
@@ -54,6 +54,7 @@
#include <uORB/topics/vehicle_attitude_setpoint.h>
#include <uORB/topics/optical_flow.h>
#include <uORB/topics/actuator_outputs.h>
+#include <uORB/topics/actuator_controls_effective.h>
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/manual_control_setpoint.h>
#include <uORB/topics/debug_key_value.h>