diff --git a/apps/mavlink/orb_listener.c b/apps/mavlink/orb_listener.c index f17c78c7a5..c49b470512 100644 --- a/apps/mavlink/orb_listener.c +++ b/apps/mavlink/orb_listener.c @@ -447,25 +447,25 @@ l_actuator_outputs(struct listener *l) 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) / 1000.0f; - throttle = (act_outputs.output[3] - 1000.0f) / 1000.0f; + rudder = (act_outputs.output[2] - 1500.0f) / 600.0f; + throttle = (((act_outputs.output[3] - 1500.0f) / 600.0f) + 1.0f) / 2.0f; } else { /* only three outputs, put throttle on position 4 / index 3 */ rudder = 0; - throttle = (act_outputs.output[2] - 1000.0f) / 1000.0f; + throttle = (((act_outputs.output[2] - 1500.0f) / 600.0f) + 1.0f) / 2.0f; } /* HIL message as per MAVLink spec */ mavlink_msg_hil_controls_send(chan, hrt_absolute_time(), - (act_outputs.output[0] - 1500.0f) / 1000.0f, - (act_outputs.output[1] - 1500.0f) / 1000.0f, + (act_outputs.output[0] - 1500.0f) / 600.0f, + (act_outputs.output[1] - 1500.0f) / 600.0f, rudder, throttle, - (act_outputs.output[4] - 1500.0f) / 1000.0f, - (act_outputs.output[5] - 1500.0f) / 1000.0f, - (act_outputs.output[6] - 1500.0f) / 1000.0f, - (act_outputs.output[7] - 1500.0f) / 1000.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, + (act_outputs.output[7] - 1500.0f) / 600.0f, mavlink_mode, 0); }