aboutsummaryrefslogtreecommitdiff
path: root/apps
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2012-11-27 17:27:52 +0100
committerLorenz Meier <lm@inf.ethz.ch>2012-11-27 17:27:52 +0100
commit98283e16b0da59d19c54e6cb8f55924c258e1cb3 (patch)
tree91b5dc95bb6009661e18aa4ddc752270444e5fe8 /apps
parent67fbe415dc85c5eaf07714289fef1bf1d9c7dda4 (diff)
parentcaf0fefa32b5441f1093de460cbc77f6d3aa2f92 (diff)
downloadpx4-firmware-98283e16b0da59d19c54e6cb8f55924c258e1cb3.tar.gz
px4-firmware-98283e16b0da59d19c54e6cb8f55924c258e1cb3.tar.bz2
px4-firmware-98283e16b0da59d19c54e6cb8f55924c258e1cb3.zip
Merged
Diffstat (limited to 'apps')
-rw-r--r--apps/mavlink/mavlink.c2
-rw-r--r--apps/mavlink/mavlink_receiver.c2
-rw-r--r--apps/mavlink/orb_listener.c4
-rw-r--r--apps/mavlink/orb_topics.h1
-rw-r--r--apps/sensors/sensors.cpp2
-rw-r--r--apps/uORB/topics/actuator_controls_effective.h2
6 files changed, 8 insertions, 5 deletions
diff --git a/apps/mavlink/mavlink.c b/apps/mavlink/mavlink.c
index a94591424..77034914f 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 1801ddc9b..fb59d07a1 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;
diff --git a/apps/mavlink/orb_listener.c b/apps/mavlink/orb_listener.c
index 254100b2e..b0aa401fc 100644
--- a/apps/mavlink/orb_listener.c
+++ b/apps/mavlink/orb_listener.c
@@ -754,8 +754,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 0eb2fabfd..4650c4991 100644
--- a/apps/mavlink/orb_topics.h
+++ b/apps/mavlink/orb_topics.h
@@ -56,6 +56,7 @@
#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>
#include <drivers/drv_rc_input.h>
diff --git a/apps/sensors/sensors.cpp b/apps/sensors/sensors.cpp
index fd71780cc..71feb377b 100644
--- a/apps/sensors/sensors.cpp
+++ b/apps/sensors/sensors.cpp
@@ -1188,7 +1188,7 @@ Sensors::start()
_sensors_task = task_spawn("sensors_task",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
- 6000, /* XXX may be excesssive */
+ 2048,
(main_t)&Sensors::task_main_trampoline,
nullptr);
diff --git a/apps/uORB/topics/actuator_controls_effective.h b/apps/uORB/topics/actuator_controls_effective.h
index 83f082c8a..40278c56c 100644
--- a/apps/uORB/topics/actuator_controls_effective.h
+++ b/apps/uORB/topics/actuator_controls_effective.h
@@ -55,7 +55,7 @@
struct actuator_controls_effective_s {
uint64_t timestamp;
- float control_effective[NUM_ACTUATOR_CONTROLS];
+ float control_effective[NUM_ACTUATOR_CONTROLS_EFFECTIVE];
};
/* actuator control sets; this list can be expanded as more controllers emerge */