aboutsummaryrefslogtreecommitdiff
path: root/apps/fixedwing_att_control/fixedwing_att_control_rate.c
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2012-11-25 13:55:28 +0100
committerLorenz Meier <lm@inf.ethz.ch>2012-11-25 13:55:28 +0100
commitfaa672f8bb257ec0ee357ad55da3195b79aeb54b (patch)
treed20ffd7f403aab274652b016af49554128a472d1 /apps/fixedwing_att_control/fixedwing_att_control_rate.c
parentdc72d467d4abe3d18bbf02091eb4eaddb4f491d2 (diff)
downloadpx4-firmware-faa672f8bb257ec0ee357ad55da3195b79aeb54b.tar.gz
px4-firmware-faa672f8bb257ec0ee357ad55da3195b79aeb54b.tar.bz2
px4-firmware-faa672f8bb257ec0ee357ad55da3195b79aeb54b.zip
mode switching for all platforms, additional fixed wing modes
Diffstat (limited to 'apps/fixedwing_att_control/fixedwing_att_control_rate.c')
-rw-r--r--apps/fixedwing_att_control/fixedwing_att_control_rate.c8
1 files changed, 5 insertions, 3 deletions
diff --git a/apps/fixedwing_att_control/fixedwing_att_control_rate.c b/apps/fixedwing_att_control/fixedwing_att_control_rate.c
index b81d50168..f46761922 100644
--- a/apps/fixedwing_att_control/fixedwing_att_control_rate.c
+++ b/apps/fixedwing_att_control/fixedwing_att_control_rate.c
@@ -1,7 +1,7 @@
/****************************************************************************
*
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * Author: Thomas Gubler <thomasgubler@student.ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -34,6 +34,8 @@
/**
* @file fixedwing_att_control_rate.c
* Implementation of a fixed wing attitude controller.
+ *
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
*/
#include <fixedwing_att_control_rate.h>
@@ -171,8 +173,8 @@ int fixedwing_att_control_rates(const struct vehicle_rates_setpoint_s *rate_sp,
actuators->control[0] = pid_calculate(&roll_rate_controller, rate_sp->roll, rates[0], 0, deltaT);
- actuators->control[1] = pid_calculate(&pitch_rate_controller, rate_sp->pitch, rates[1], 0, deltaT); //TODO: (-) sign comes from the elevator (positive --> deflection downwards), this has to be moved to the mixer...
- actuators->control[2] = 0;//pid_calculate(&yaw_rate_controller, rate_sp->yaw, rates[2], 0, deltaT); //XXX TODO disabled for now
+ actuators->control[1] = pid_calculate(&pitch_rate_controller, rate_sp->pitch, rates[1], 0, deltaT);
+ actuators->control[2] = 0.0f;//pid_calculate(&yaw_rate_controller, rate_sp->yaw, rates[2], 0, deltaT); //XXX TODO disabled for now
counter++;