mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
mavlink_receiver: refactor manual_control.throttle extraction to exactly match MAVLink output
This commit is contained in:
parent
80ea3a09bb
commit
a048a8e8a0
@ -2093,8 +2093,10 @@ MavlinkReceiver::handle_message_manual_control(mavlink_message_t *msg)
|
||||
|
||||
if (math::isInRange((int)mavlink_manual_control.y, -1000, 1000)) { manual_control_setpoint.roll = mavlink_manual_control.y / 1000.f; }
|
||||
|
||||
// For backwards compatibility at the moment interpret throttle in range [0,1000]
|
||||
if (math::isInRange((int)mavlink_manual_control.z, 0, 1000)) { manual_control_setpoint.throttle = ((mavlink_manual_control.z / 1000.f) * 2.f) - 1.f; }
|
||||
// For backwards compatibility we need to interpret throttle in range [0,1000]
|
||||
// Convert from [0, 1000] to internal range [-1, 1]
|
||||
// (([0, 1000] / 1000 * 2) - 1 = [-1, 1]
|
||||
if (math::isInRange((int)mavlink_manual_control.z, 0, 1000)) { manual_control_setpoint.throttle = (mavlink_manual_control.z / 500.f) - 1.f; }
|
||||
|
||||
if (math::isInRange((int)mavlink_manual_control.r, -1000, 1000)) { manual_control_setpoint.yaw = mavlink_manual_control.r / 1000.f; }
|
||||
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user