aboutsummaryrefslogtreecommitdiff
path: root/apps/mavlink/orb_listener.c
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2012-11-10 19:10:57 +0100
committerLorenz Meier <lm@inf.ethz.ch>2012-11-10 19:10:57 +0100
commitf8291711d3daf0e4af12b018f7cc711414e3bf95 (patch)
tree6b5a3b4ead14e0484c03ff3c08fd19efd15a5793 /apps/mavlink/orb_listener.c
parentfb022f40e50e34c5e37356247fc98bc3a5c88f4d (diff)
downloadpx4-firmware-f8291711d3daf0e4af12b018f7cc711414e3bf95.tar.gz
px4-firmware-f8291711d3daf0e4af12b018f7cc711414e3bf95.tar.bz2
px4-firmware-f8291711d3daf0e4af12b018f7cc711414e3bf95.zip
Correct scaling for throttle
Diffstat (limited to 'apps/mavlink/orb_listener.c')
-rw-r--r--apps/mavlink/orb_listener.c4
1 files changed, 2 insertions, 2 deletions
diff --git a/apps/mavlink/orb_listener.c b/apps/mavlink/orb_listener.c
index f7bc32935..f17c78c7a 100644
--- a/apps/mavlink/orb_listener.c
+++ b/apps/mavlink/orb_listener.c
@@ -448,11 +448,11 @@ l_actuator_outputs(struct listener *l)
&& act_outputs.output[3] > 800 && act_outputs.output[3] < 2200) {
/* throttle is fourth output */
rudder = (act_outputs.output[2] - 1500.0f) / 1000.0f;
- throttle = (act_outputs.output[3] - 1500.0f) / 1000.0f;
+ throttle = (act_outputs.output[3] - 1000.0f) / 1000.0f;
} else {
/* only three outputs, put throttle on position 4 / index 3 */
rudder = 0;
- throttle = (act_outputs.output[2] - 1500.0f) / 1000.0f;
+ throttle = (act_outputs.output[2] - 1000.0f) / 1000.0f;
}
/* HIL message as per MAVLink spec */