diff options
author | Thomas Gubler <thomasgubler@gmail.com> | 2012-11-10 19:14:50 +0100 |
---|---|---|
committer | Thomas Gubler <thomasgubler@gmail.com> | 2012-11-10 19:14:50 +0100 |
commit | bbfd31dd681d0c86d55d8e0dfc2a0315b286928b (patch) | |
tree | bdc3e028b74169ec1208537409c97331b72425bd /apps | |
parent | 596224883bc1f74a3c297d384b8b69884dbd5858 (diff) | |
parent | f8291711d3daf0e4af12b018f7cc711414e3bf95 (diff) | |
download | px4-firmware-bbfd31dd681d0c86d55d8e0dfc2a0315b286928b.tar.gz px4-firmware-bbfd31dd681d0c86d55d8e0dfc2a0315b286928b.tar.bz2 px4-firmware-bbfd31dd681d0c86d55d8e0dfc2a0315b286928b.zip |
Merge branch 'master' of https://github.com/PX4/Firmware into fw_control
Diffstat (limited to 'apps')
-rw-r--r-- | apps/mavlink/orb_listener.c | 4 |
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 */ |