corrected hil scaling factors

This commit is contained in:
Thomas Gubler 2012-11-10 20:02:16 +01:00
parent f8291711d3
commit 3e6e7647c9
1 changed files with 9 additions and 9 deletions

View File

@ -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);
}