From c720a3238014e347fb84063a3fee2f9c812b3bf8 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 10 Mar 2013 01:00:16 +0100 Subject: Hotfix: Correct channel order in HIL --- apps/mavlink/orb_listener.c | 20 ++------------------ 1 file changed, 2 insertions(+), 18 deletions(-) (limited to 'apps/mavlink') diff --git a/apps/mavlink/orb_listener.c b/apps/mavlink/orb_listener.c index 9f85d5801..58c709aec 100644 --- a/apps/mavlink/orb_listener.c +++ b/apps/mavlink/orb_listener.c @@ -511,28 +511,12 @@ l_actuator_outputs(struct listener *l) 0); } else { - - /* - * Catch the case where no rudder is in use and throttle is not - * on output four - */ - float rudder, throttle; - - if (act_outputs.noutputs < 4) { - rudder = 0.0f; - throttle = (act_outputs.output[2] - 900.0f) / 1200.0f; - - } else { - rudder = (act_outputs.output[2] - 1500.0f) / 600.0f; - throttle = (act_outputs.output[3] - 900.0f) / 1200.0f; - } - mavlink_msg_hil_controls_send(chan, hrt_absolute_time(), (act_outputs.output[0] - 1500.0f) / 600.0f, (act_outputs.output[1] - 1500.0f) / 600.0f, - rudder, - throttle, + (act_outputs.output[2] - 1500.0f) / 600.0f, + (act_outputs.output[3] - 900.0f) / 1200.0f, (act_outputs.output[4] - 1500.0f) / 600.0f, (act_outputs.output[5] - 1500.0f) / 600.0f, (act_outputs.output[6] - 1500.0f) / 600.0f, -- cgit v1.2.3