diff options
author | Lorenz Meier <lm@inf.ethz.ch> | 2012-12-19 11:34:51 +0100 |
---|---|---|
committer | Lorenz Meier <lm@inf.ethz.ch> | 2012-12-19 11:34:51 +0100 |
commit | bc3b66043f57adebdef3980f3a113d2d5362416a (patch) | |
tree | f4e79be24be286b286d555a9b02d2f94a9cb4a3d /apps/mavlink | |
parent | f41e5728fc132a7cd2764f166e36ca4d2f5909ea (diff) | |
download | px4-firmware-bc3b66043f57adebdef3980f3a113d2d5362416a.tar.gz px4-firmware-bc3b66043f57adebdef3980f3a113d2d5362416a.tar.bz2 px4-firmware-bc3b66043f57adebdef3980f3a113d2d5362416a.zip |
Cleaned up HIL on FMU / IO combo
Diffstat (limited to 'apps/mavlink')
-rw-r--r-- | apps/mavlink/orb_listener.c | 19 |
1 files changed, 2 insertions, 17 deletions
diff --git a/apps/mavlink/orb_listener.c b/apps/mavlink/orb_listener.c index b0aa401fc..e763e642a 100644 --- a/apps/mavlink/orb_listener.c +++ b/apps/mavlink/orb_listener.c @@ -506,28 +506,13 @@ l_actuator_outputs(struct listener *l) mavlink_mode, 0); } else { - float rudder, throttle; - - /* SCALING: PWM min: 900, PWM max: 2100, center: 1500 */ - - // 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] - 1500.0f) / 600.0f; - throttle = (((act_outputs.output[3] - 900.0f) / 600.0f) / 2.0f); - } else { - /* only three outputs, put throttle on position 4 / index 3 */ - rudder = 0; - throttle = (((act_outputs.output[2] - 900.0f) / 600.0f) / 2.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, + 0.0f/*(act_outputs.output[2] - 1500.0f) / 600.0f*/, + (act_outputs.output[2] - 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, |