mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-13 18:37:34 +08:00
manual_control_setpoint: change stick axes naming
In review it was requested to have a different name for manual_control_setpoint.z because of the adjusted range. I started to investigate what naming is most intuitive and found that most people recognize the stick axes as roll, pitch, yaw, throttle. It comes at no surprise because other autopilots and APIs seem to share this convention. While changing the code I realized that even within the code base the axes are usually assigned to a variable with that name or have comments next to the assignment clarifying the axes using these names.
This commit is contained in:
@@ -16,31 +16,15 @@ uint8 data_source
|
||||
|
||||
# Any of the channels may not be available and be set to NaN
|
||||
# to indicate that it does not contain valid data.
|
||||
# The variable names follow the definition of the
|
||||
# MANUAL_CONTROL mavlink message.
|
||||
# The default range is from -1 to 1 (mavlink message -1000 to 1000)
|
||||
# The range for the z variable is defined from 0 to 1. (The z field of
|
||||
# the MANUAL_CONTROL mavlink message is defined from -1000 to 1000)
|
||||
|
||||
float32 x # stick position in x direction -1..1
|
||||
# in general corresponds to forward/back motion or pitch of vehicle,
|
||||
# in general a positive value means forward or negative pitch and
|
||||
# a negative value means backward or positive pitch
|
||||
|
||||
float32 y # stick position in y direction -1..1
|
||||
# in general corresponds to right/left motion or roll of vehicle,
|
||||
# in general a positive value means right or positive roll and
|
||||
# a negative value means left or negative roll
|
||||
|
||||
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 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
|
||||
# (downwards) axis of the vehicle
|
||||
# Stick positions [-1,1]
|
||||
# on a common RC mode 1/2/3/4 remote/joystick the stick deflection: -1 is down/left, 1 is up/right
|
||||
# Note: QGC sends throttle/z in range [0,1000] - [0,1]. The MAVLink input conversion [0,1] to [-1,1] is at the moment kept backwards compatible.
|
||||
# Positive values are generally used for:
|
||||
float32 roll # move right, positive roll rotation, right side down
|
||||
float32 pitch # move forward, negative pitch rotation, nose down
|
||||
float32 yaw # positive yaw rotation, clockwise when seen top down
|
||||
float32 throttle # move up, positive thrust, -1 is minimum available 0% or -100% +1 is 100% thrust
|
||||
|
||||
float32 flaps # flap position
|
||||
|
||||
@@ -54,3 +38,7 @@ float32 aux6
|
||||
bool sticks_moving
|
||||
|
||||
# TOPICS manual_control_setpoint manual_control_input
|
||||
# DEPRECATED: float32 x
|
||||
# DEPRECATED: float32 y
|
||||
# DEPRECATED: float32 z
|
||||
# DEPRECATED: float32 r
|
||||
|
||||
Reference in New Issue
Block a user