You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
uint32MESSAGE_VERSION=0uint64timestamp# time since system start (microseconds)
uint64timestamp_sample# the timestamp of the raw data (microseconds)
boolvaliduint8SOURCE_UNKNOWN=0uint8SOURCE_RC=1# radio control (input_rc)
uint8SOURCE_MAVLINK_0=2# mavlink instance 0
uint8SOURCE_MAVLINK_1=3# mavlink instance 1
uint8SOURCE_MAVLINK_2=4# mavlink instance 2
uint8SOURCE_MAVLINK_3=5# mavlink instance 3
uint8SOURCE_MAVLINK_4=6# mavlink instance 4
uint8SOURCE_MAVLINK_5=7# mavlink instance 5
uint8data_source# Any of the channels may not be available and be set to NaN
# to indicate that it does not contain valid data.
# 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:
float32roll# move right, positive roll rotation, right side down
float32pitch# move forward, negative pitch rotation, nose down
float32yaw# positive yaw rotation, clockwise when seen top down
float32throttle# move up, positive thrust, -1 is minimum available 0% or -100% +1 is 100% thrust
float32flaps# position of flaps switch/knob/lever [-1, 1]
float32aux1float32aux2float32aux3float32aux4float32aux5float32aux6boolsticks_movinguint16buttons# From uint16 buttons field of Mavlink manual_control message
# TOPICS manual_control_setpoint manual_control_input
# DEPRECATED: float32 x
# DEPRECATED: float32 y
# DEPRECATED: float32 z
# DEPRECATED: float32 r