From 424923271e5b8e802a3c082841eccea450326277 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 11 Mar 2013 21:46:16 +0100 Subject: Hotfix: Throttle scaling in HIL --- apps/mavlink/orb_listener.c | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) (limited to 'apps/mavlink') diff --git a/apps/mavlink/orb_listener.c b/apps/mavlink/orb_listener.c index 58c709aec..7c34fb474 100644 --- a/apps/mavlink/orb_listener.c +++ b/apps/mavlink/orb_listener.c @@ -513,14 +513,14 @@ l_actuator_outputs(struct listener *l) } else { 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, - (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, - (act_outputs.output[7] - 1500.0f) / 600.0f, + (act_outputs.output[0] - 1500.0f) / 500.0f, + (act_outputs.output[1] - 1500.0f) / 500.0f, + (act_outputs.output[2] - 1500.0f) / 500.0f, + (act_outputs.output[3] - 1000.0f) / 1000.0f, + (act_outputs.output[4] - 1500.0f) / 500.0f, + (act_outputs.output[5] - 1500.0f) / 500.0f, + (act_outputs.output[6] - 1500.0f) / 500.0f, + (act_outputs.output[7] - 1500.0f) / 500.0f, mavlink_mode, 0); } -- cgit v1.2.3