aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--ROMFS/mixers/FMU_AERT.mix4
-rw-r--r--ROMFS/mixers/FMU_AET.mix4
-rw-r--r--ROMFS/mixers/FMU_RET.mix4
-rw-r--r--apps/fixedwing_att_control/fixedwing_att_control_rate.c2
4 files changed, 7 insertions, 7 deletions
diff --git a/ROMFS/mixers/FMU_AERT.mix b/ROMFS/mixers/FMU_AERT.mix
index d7e317e13..75e82bb00 100644
--- a/ROMFS/mixers/FMU_AERT.mix
+++ b/ROMFS/mixers/FMU_AERT.mix
@@ -36,8 +36,8 @@ factors (to reverse the servo movement) and adjust the offset, scaling and
endpoints to suit.
M: 1
-O: 10000 10000 0 -10000 10000
-S: 0 1 10000 10000 0 -10000 10000
+O: 10000 10000 0 -10000 10000
+S: 0 1 -10000 -10000 0 -10000 10000
Rudder mixer
------------
diff --git a/ROMFS/mixers/FMU_AET.mix b/ROMFS/mixers/FMU_AET.mix
index bd7056f7c..20cb88b91 100644
--- a/ROMFS/mixers/FMU_AET.mix
+++ b/ROMFS/mixers/FMU_AET.mix
@@ -39,8 +39,8 @@ factors (to reverse the servo movement) and adjust the offset, scaling and
endpoints to suit.
M: 1
-O: 10000 10000 0 -10000 10000
-S: 0 1 10000 10000 0 -10000 10000
+O: 10000 10000 0 -10000 10000
+S: 0 1 -10000 -10000 0 -10000 10000
Output 2
--------
diff --git a/ROMFS/mixers/FMU_RET.mix b/ROMFS/mixers/FMU_RET.mix
index 156fcb129..95beb8927 100644
--- a/ROMFS/mixers/FMU_RET.mix
+++ b/ROMFS/mixers/FMU_RET.mix
@@ -32,8 +32,8 @@ factors (to reverse the servo movement) and adjust the offset, scaling and
endpoints to suit.
M: 1
-O: 10000 10000 0 -10000 10000
-S: 0 1 10000 10000 0 -10000 10000
+O: 10000 10000 0 -10000 10000
+S: 0 1 -10000 -10000 0 -10000 10000
Output 2
--------
diff --git a/apps/fixedwing_att_control/fixedwing_att_control_rate.c b/apps/fixedwing_att_control/fixedwing_att_control_rate.c
index 567f03784..b81d50168 100644
--- a/apps/fixedwing_att_control/fixedwing_att_control_rate.c
+++ b/apps/fixedwing_att_control/fixedwing_att_control_rate.c
@@ -171,7 +171,7 @@ 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[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
counter++;