aboutsummaryrefslogtreecommitdiff
path: root/apps
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2013-03-10 01:00:16 +0100
committerLorenz Meier <lm@inf.ethz.ch>2013-03-10 01:00:16 +0100
commitc720a3238014e347fb84063a3fee2f9c812b3bf8 (patch)
treecff325ee7abf7c85d3b9d50051bad72be5eb4c08 /apps
parent921ef9178d58ff83dcad44d0584b4f71fb2cae6f (diff)
downloadpx4-firmware-c720a3238014e347fb84063a3fee2f9c812b3bf8.tar.gz
px4-firmware-c720a3238014e347fb84063a3fee2f9c812b3bf8.tar.bz2
px4-firmware-c720a3238014e347fb84063a3fee2f9c812b3bf8.zip
Hotfix: Correct channel order in HIL
Diffstat (limited to 'apps')
-rw-r--r--apps/mavlink/orb_listener.c20
1 files changed, 2 insertions, 18 deletions
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,