aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2012-11-10 20:03:17 +0100
committerThomas Gubler <thomasgubler@gmail.com>2012-11-10 20:03:17 +0100
commit2b1e199b91641fb3ad097792f5ead98d5148de00 (patch)
tree2131ad45570bdbacd6de288c448407f70d3b9d02
parentbbfd31dd681d0c86d55d8e0dfc2a0315b286928b (diff)
parent3e6e7647c95d160f919c089471b6ed3acac2e51f (diff)
downloadpx4-firmware-2b1e199b91641fb3ad097792f5ead98d5148de00.tar.gz
px4-firmware-2b1e199b91641fb3ad097792f5ead98d5148de00.tar.bz2
px4-firmware-2b1e199b91641fb3ad097792f5ead98d5148de00.zip
Merge branch 'hil_scaling' into fw_control
-rw-r--r--apps/mavlink/orb_listener.c18
1 files changed, 9 insertions, 9 deletions
diff --git a/apps/mavlink/orb_listener.c b/apps/mavlink/orb_listener.c
index f17c78c7a..c49b47051 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);
}