aboutsummaryrefslogtreecommitdiff
path: root/apps/mavlink/orb_listener.c
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2012-11-10 19:06:58 +0100
committerLorenz Meier <lm@inf.ethz.ch>2012-11-10 19:06:58 +0100
commitfb022f40e50e34c5e37356247fc98bc3a5c88f4d (patch)
tree05d418df3a35047dd475b77f3d4e88b32b5ffc43 /apps/mavlink/orb_listener.c
parent6adab3b31930074ad9336ac596c1b4c2d6a4bd74 (diff)
downloadpx4-firmware-fb022f40e50e34c5e37356247fc98bc3a5c88f4d.tar.gz
px4-firmware-fb022f40e50e34c5e37356247fc98bc3a5c88f4d.tar.bz2
px4-firmware-fb022f40e50e34c5e37356247fc98bc3a5c88f4d.zip
Fixed zero offset in HIL
Diffstat (limited to 'apps/mavlink/orb_listener.c')
-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 e214f435e..f7bc32935 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] - 1000.0f) / 1000.0f;
- throttle = (act_outputs.output[3] - 1000.0f) / 1000.0f;
+ rudder = (act_outputs.output[2] - 1500.0f) / 1000.0f;
+ throttle = (act_outputs.output[3] - 1500.0f) / 1000.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) / 1000.0f;
}
/* HIL message as per MAVLink spec */
mavlink_msg_hil_controls_send(chan,
hrt_absolute_time(),
- (act_outputs.output[0] - 1000.0f) / 1000.0f,
- (act_outputs.output[1] - 1000.0f) / 1000.0f,
+ (act_outputs.output[0] - 1500.0f) / 1000.0f,
+ (act_outputs.output[1] - 1500.0f) / 1000.0f,
rudder,
throttle,
- (act_outputs.output[4] - 1000.0f) / 1000.0f,
- (act_outputs.output[5] - 1000.0f) / 1000.0f,
- (act_outputs.output[6] - 1000.0f) / 1000.0f,
- (act_outputs.output[7] - 1000.0f) / 1000.0f,
+ (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,
mavlink_mode,
0);
}