From 6adab3b31930074ad9336ac596c1b4c2d6a4bd74 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 10 Nov 2012 19:04:04 +0100 Subject: Hack to detect the number of control inputs --- apps/mavlink/orb_listener.c | 18 ++++++++++++++++-- 1 file changed, 16 insertions(+), 2 deletions(-) (limited to 'apps/mavlink/orb_listener.c') diff --git a/apps/mavlink/orb_listener.c b/apps/mavlink/orb_listener.c index df6b1a475..e214f435e 100644 --- a/apps/mavlink/orb_listener.c +++ b/apps/mavlink/orb_listener.c @@ -441,13 +441,27 @@ l_actuator_outputs(struct listener *l) uint8_t mavlink_mode = 0; get_mavlink_mode_and_state(&mavlink_state, &mavlink_mode); + float rudder, throttle; + + // XXX very ugly, needs rework + if (isfinite(act_outputs.output[3]) + && act_outputs.output[3] > 800 && act_outputs.output[3] < 2200) { + /* throttle is fourth output */ + rudder = (act_outputs.output[2] - 1000.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] - 1000.0f) / 1000.0f; + } + /* HIL message as per MAVLink spec */ mavlink_msg_hil_controls_send(chan, hrt_absolute_time(), (act_outputs.output[0] - 1000.0f) / 1000.0f, (act_outputs.output[1] - 1000.0f) / 1000.0f, - (act_outputs.output[2] - 1000.0f) / 1000.0f, - (act_outputs.output[3] - 1000.0f) / 1000.0f, + rudder, + throttle, (act_outputs.output[4] - 1000.0f) / 1000.0f, (act_outputs.output[5] - 1000.0f) / 1000.0f, (act_outputs.output[6] - 1000.0f) / 1000.0f, -- cgit v1.2.3