Skip to content

GimbalManagerInformation (UORB message)

TOPICS: gimbal_managerinformation

Fields

NameTypeUnit [Frame]Range/EnumDescription
timestampuint64time since system start (microseconds)
cap_flagsuint32
gimbal_device_iduint8
roll_minfloat32rad
roll_maxfloat32rad
pitch_minfloat32rad
pitch_maxfloat32rad
yaw_minfloat32rad
yaw_maxfloat32rad

Constants

NameTypeValueDescription
GIMBAL_MANAGER_CAP_FLAGS_HAS_RETRACTuint321
GIMBAL_MANAGER_CAP_FLAGS_HAS_NEUTRALuint322
GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_AXISuint324
GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_FOLLOWuint328
GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_LOCKuint3216
GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_AXISuint3232
GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_FOLLOWuint3264
GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_LOCKuint32128
GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_AXISuint32256
GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_FOLLOWuint32512
GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_LOCKuint321024
GIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_INFINITE_YAWuint322048
GIMBAL_MANAGER_CAP_FLAGS_CAN_POINT_LOCATION_LOCALuint3265536
GIMBAL_MANAGER_CAP_FLAGS_CAN_POINT_LOCATION_GLOBALuint32131072

Source Message

Source file (GitHub)

Click here to see original file
c
uint64 timestamp						# time since system start (microseconds)

uint32 cap_flags

uint32 GIMBAL_MANAGER_CAP_FLAGS_HAS_RETRACT = 1
uint32 GIMBAL_MANAGER_CAP_FLAGS_HAS_NEUTRAL = 2
uint32 GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_AXIS = 4
uint32 GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_FOLLOW = 8
uint32 GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_LOCK = 16
uint32 GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_AXIS = 32
uint32 GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_FOLLOW = 64
uint32 GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_LOCK = 128
uint32 GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_AXIS = 256
uint32 GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_FOLLOW = 512
uint32 GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_LOCK = 1024
uint32 GIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_INFINITE_YAW = 2048
uint32 GIMBAL_MANAGER_CAP_FLAGS_CAN_POINT_LOCATION_LOCAL = 65536
uint32 GIMBAL_MANAGER_CAP_FLAGS_CAN_POINT_LOCATION_GLOBAL = 131072

uint8 gimbal_device_id

float32 roll_min # [rad]
float32 roll_max # [rad]

float32 pitch_min # [rad]
float32 pitch_max # [rad]

float32 yaw_min # [rad]
float32 yaw_max # [rad]