mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-13 17:57:35 +08:00
Switch manual_control_setpoint.z scaling from [0,1] to [-1,1]
To be consistent with all other axes of stick input and avoid future rescaling confusion. Note: for the MAVLink message 69 MANUAL_CONTROL it's using the full range according to the message specs now [-1000,1000].
This commit is contained in:
@@ -32,11 +32,11 @@ float32 y # stick position in y direction -1..1
|
||||
# in general a positive value means right or positive roll and
|
||||
# a negative value means left or negative roll
|
||||
|
||||
float32 z # throttle stick position 0..1
|
||||
float32 z # throttle stick position -1..1
|
||||
# in general corresponds to up/down motion or thrust of vehicle,
|
||||
# in general the value corresponds to the demanded throttle by the user,
|
||||
# if the input is used for setting the setpoint of a vertical position
|
||||
# controller any value > 0.5 means up and any value < 0.5 means down
|
||||
# controller any value > 0 means up and any value < 0 means down
|
||||
|
||||
float32 r # yaw stick/twist position, -1..1
|
||||
# in general corresponds to the righthand rotation around the vertical
|
||||
|
||||
Reference in New Issue
Block a user