aboutsummaryrefslogtreecommitdiff
path: root/apps/mavlink/orb_listener.c
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2012-11-10 19:04:04 +0100
committerLorenz Meier <lm@inf.ethz.ch>2012-11-10 19:04:04 +0100
commit6adab3b31930074ad9336ac596c1b4c2d6a4bd74 (patch)
tree26a039e62718ac09d1551426acf8664496a1af28 /apps/mavlink/orb_listener.c
parent92fe049f6524b88861e7f3ef4f6c2344095f39ea (diff)
downloadpx4-firmware-6adab3b31930074ad9336ac596c1b4c2d6a4bd74.tar.gz
px4-firmware-6adab3b31930074ad9336ac596c1b4c2d6a4bd74.tar.bz2
px4-firmware-6adab3b31930074ad9336ac596c1b4c2d6a4bd74.zip
Hack to detect the number of control inputs
Diffstat (limited to 'apps/mavlink/orb_listener.c')
-rw-r--r--apps/mavlink/orb_listener.c18
1 files changed, 16 insertions, 2 deletions
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,