forked from Archive/PX4-Autopilot
Hotfix: Throttle scaling in HIL
This commit is contained in:
parent
c720a32380
commit
424923271e
|
@ -513,14 +513,14 @@ l_actuator_outputs(struct listener *l)
|
||||||
} else {
|
} else {
|
||||||
mavlink_msg_hil_controls_send(chan,
|
mavlink_msg_hil_controls_send(chan,
|
||||||
hrt_absolute_time(),
|
hrt_absolute_time(),
|
||||||
(act_outputs.output[0] - 1500.0f) / 600.0f,
|
(act_outputs.output[0] - 1500.0f) / 500.0f,
|
||||||
(act_outputs.output[1] - 1500.0f) / 600.0f,
|
(act_outputs.output[1] - 1500.0f) / 500.0f,
|
||||||
(act_outputs.output[2] - 1500.0f) / 600.0f,
|
(act_outputs.output[2] - 1500.0f) / 500.0f,
|
||||||
(act_outputs.output[3] - 900.0f) / 1200.0f,
|
(act_outputs.output[3] - 1000.0f) / 1000.0f,
|
||||||
(act_outputs.output[4] - 1500.0f) / 600.0f,
|
(act_outputs.output[4] - 1500.0f) / 500.0f,
|
||||||
(act_outputs.output[5] - 1500.0f) / 600.0f,
|
(act_outputs.output[5] - 1500.0f) / 500.0f,
|
||||||
(act_outputs.output[6] - 1500.0f) / 600.0f,
|
(act_outputs.output[6] - 1500.0f) / 500.0f,
|
||||||
(act_outputs.output[7] - 1500.0f) / 600.0f,
|
(act_outputs.output[7] - 1500.0f) / 500.0f,
|
||||||
mavlink_mode,
|
mavlink_mode,
|
||||||
0);
|
0);
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue