From f8291711d3daf0e4af12b018f7cc711414e3bf95 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 10 Nov 2012 19:10:57 +0100 Subject: [PATCH] Correct scaling for throttle --- apps/mavlink/orb_listener.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/apps/mavlink/orb_listener.c b/apps/mavlink/orb_listener.c index f7bc32935d..f17c78c7a5 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 */