aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2012-10-17 10:38:23 +0200
committerLorenz Meier <lm@inf.ethz.ch>2012-10-17 10:38:23 +0200
commit5d3d17d025fa860879b145a99ec80afb7db38edc (patch)
tree3e2e5084612f510160d27cfa4300f7b6b95c19a5
parent32e586d4b7561d1018e29aa59f572c3bac625024 (diff)
downloadpx4-firmware-5d3d17d025fa860879b145a99ec80afb7db38edc.tar.gz
px4-firmware-5d3d17d025fa860879b145a99ec80afb7db38edc.tar.bz2
px4-firmware-5d3d17d025fa860879b145a99ec80afb7db38edc.zip
Increased priority of MAVLink receiver thread
-rw-r--r--apps/mavlink/mavlink.c2
-rw-r--r--apps/mavlink/mavlink_receiver.c5
-rw-r--r--apps/multirotor_att_control/multirotor_attitude_control.c2
3 files changed, 7 insertions, 2 deletions
diff --git a/apps/mavlink/mavlink.c b/apps/mavlink/mavlink.c
index e893ea951..075dc9e3b 100644
--- a/apps/mavlink/mavlink.c
+++ b/apps/mavlink/mavlink.c
@@ -1,4 +1,4 @@
-/****************************************************************************
+ /****************************************************************************
*
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
* Author: @author Lorenz Meier <lm@inf.ethz.ch>
diff --git a/apps/mavlink/mavlink_receiver.c b/apps/mavlink/mavlink_receiver.c
index ad46c3ede..060bff2b4 100644
--- a/apps/mavlink/mavlink_receiver.c
+++ b/apps/mavlink/mavlink_receiver.c
@@ -487,6 +487,11 @@ receive_start(int uart)
{
pthread_attr_t receiveloop_attr;
pthread_attr_init(&receiveloop_attr);
+
+ struct sched_param param;
+ param.sched_priority = SCHED_PRIORITY_MAX - 40;
+ (void)pthread_attr_setschedparam(&receiveloop_attr, &param);
+
pthread_attr_setstacksize(&receiveloop_attr, 2048);
pthread_t thread;
diff --git a/apps/multirotor_att_control/multirotor_attitude_control.c b/apps/multirotor_att_control/multirotor_attitude_control.c
index 00b759d73..33cab5cc9 100644
--- a/apps/multirotor_att_control/multirotor_attitude_control.c
+++ b/apps/multirotor_att_control/multirotor_attitude_control.c
@@ -248,7 +248,7 @@ void multirotor_control_attitude(const struct vehicle_attitude_setpoint_s *att_s
att->roll, att->rollspeed, deltaT)*1/10.0f;
/* control yaw rate */
//float yaw_rate_control = pid_calculate(&yaw_speed_controller, att_sp->yaw_body, att->yawspeed, 0.0f, deltaT)*1/10.0f;
- rates_sp->yaw= deltaT*p.yaw_p*atan2f(sinf(att->yaw-att_sp->yaw_body),cos(att->yaw-att_sp->yaw_body));
+ rates_sp->yaw= deltaT * p.yaw_p * atan2f(sinf(att->yaw - att_sp->yaw_body),cos(att->yaw - att_sp->yaw_body));