forked from Archive/PX4-Autopilot
Increased priority of MAVLink receiver thread
This commit is contained in:
parent
32e586d4b7
commit
5d3d17d025
|
@ -1,4 +1,4 @@
|
|||
/****************************************************************************
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* Author: @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
|
|
|
@ -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, ¶m);
|
||||
|
||||
pthread_attr_setstacksize(&receiveloop_attr, 2048);
|
||||
|
||||
pthread_t thread;
|
||||
|
|
|
@ -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));
|
||||
|
||||
|
||||
|
||||
|
|
Loading…
Reference in New Issue