aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mavlink
diff options
context:
space:
mode:
authorAnton Babushkin <anton.babushkin@me.com>2014-01-30 17:23:10 +0100
committerAnton Babushkin <anton.babushkin@me.com>2014-01-30 17:23:10 +0100
commitf64872b9b305df51bad14c4cbf5519e3e4b95030 (patch)
tree67c3d4d000b262baf97543310dd34e02e2bce15d /src/modules/mavlink
parent13a5b5b4a3d8e487fb836e14185d61c03493ef0a (diff)
parent2f267fbf439d867d47b6772471d0f203036eefa2 (diff)
downloadpx4-firmware-f64872b9b305df51bad14c4cbf5519e3e4b95030.tar.gz
px4-firmware-f64872b9b305df51bad14c4cbf5519e3e4b95030.tar.bz2
px4-firmware-f64872b9b305df51bad14c4cbf5519e3e4b95030.zip
Merge branch 'master' into beta
Diffstat (limited to 'src/modules/mavlink')
-rw-r--r--src/modules/mavlink/mavlink.c2
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp2
-rw-r--r--src/modules/mavlink/orb_listener.c4
3 files changed, 4 insertions, 4 deletions
diff --git a/src/modules/mavlink/mavlink.c b/src/modules/mavlink/mavlink.c
index 4d975066f..9bb92cbf5 100644
--- a/src/modules/mavlink/mavlink.c
+++ b/src/modules/mavlink/mavlink.c
@@ -794,7 +794,7 @@ int mavlink_main(int argc, char *argv[])
mavlink_task = task_spawn_cmd("mavlink",
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
- 2048,
+ 1200,
mavlink_thread_main,
(const char **)argv);
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index a371a499e..f71dd9a3f 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -872,7 +872,7 @@ receive_start(int uart)
param.sched_priority = SCHED_PRIORITY_MAX - 40;
(void)pthread_attr_setschedparam(&receiveloop_attr, &param);
- pthread_attr_setstacksize(&receiveloop_attr, 3000);
+ pthread_attr_setstacksize(&receiveloop_attr, 1816);
pthread_t thread;
pthread_create(&thread, &receiveloop_attr, receive_thread, &uart);
diff --git a/src/modules/mavlink/orb_listener.c b/src/modules/mavlink/orb_listener.c
index 5d071d0be..3acf3e262 100644
--- a/src/modules/mavlink/orb_listener.c
+++ b/src/modules/mavlink/orb_listener.c
@@ -357,7 +357,7 @@ l_input_rc(const struct listener *l)
for (unsigned i = 0; (i * port_width) < rc_raw.channel_count; i++) {
/* Channels are sent in MAVLink main loop at a fixed interval */
mavlink_msg_rc_channels_raw_send(chan,
- rc_raw.timestamp / 1000,
+ rc_raw.timestamp_publication / 1000,
i,
(rc_raw.channel_count > (i * port_width) + 0) ? rc_raw.values[(i * port_width) + 0] : UINT16_MAX,
(rc_raw.channel_count > (i * port_width) + 1) ? rc_raw.values[(i * port_width) + 1] : UINT16_MAX,
@@ -838,7 +838,7 @@ uorb_receive_start(void)
pthread_attr_init(&uorb_attr);
/* Set stack size, needs less than 2k */
- pthread_attr_setstacksize(&uorb_attr, 2048);
+ pthread_attr_setstacksize(&uorb_attr, 1648);
pthread_t thread;
pthread_create(&thread, &uorb_attr, uorb_receive_thread, NULL);