Skip to content

VehicleCommandAck (UORB message)

Vehicle Command Ackonwledgement uORB message. Used for acknowledging the vehicle command being received. Follows the MAVLink COMMAND_ACK message definition.

TOPICS: vehicle_command_ack

Fields

NameTypeUnit [Frame]Range/EnumDescription
timestampuint64time since system start (microseconds)
commanduint32Command that is being acknowledged
resultuint8Command result
result_param1uint8Also used as progress[%], it can be set with the reason why the command was denied, or the progress percentage when result is MAV_RESULT_IN_PROGRESS
result_param2int32Additional parameter of the result, example: which parameter of MAV_CMD_NAV_WAYPOINT caused it to be denied.
target_systemuint8
target_componentuint16Target component / mode executor
from_externalboolIndicates if the command came from an external source

Constants

NameTypeValueDescription
MESSAGE_VERSIONuint320
VEHICLE_CMD_RESULT_ACCEPTEDuint80Command ACCEPTED and EXECUTED
VEHICLE_CMD_RESULT_TEMPORARILY_REJECTEDuint81Command TEMPORARY REJECTED/DENIED
VEHICLE_CMD_RESULT_DENIEDuint82Command PERMANENTLY DENIED
VEHICLE_CMD_RESULT_UNSUPPORTEDuint83Command UNKNOWN/UNSUPPORTED
VEHICLE_CMD_RESULT_FAILEDuint84Command executed, but failed
VEHICLE_CMD_RESULT_IN_PROGRESSuint85Command being executed
VEHICLE_CMD_RESULT_CANCELLEDuint86Command Canceled
ARM_AUTH_DENIED_REASON_GENERICuint160
ARM_AUTH_DENIED_REASON_NONEuint161
ARM_AUTH_DENIED_REASON_INVALID_WAYPOINTuint162
ARM_AUTH_DENIED_REASON_TIMEOUTuint163
ARM_AUTH_DENIED_REASON_AIRSPACE_IN_USEuint164
ARM_AUTH_DENIED_REASON_BAD_WEATHERuint165
ORB_QUEUE_LENGTHuint88

Source Message

Source file (GitHub)

Click here to see original file
c
# Vehicle Command Ackonwledgement uORB message.
# Used for acknowledging the vehicle command being received.
# Follows the MAVLink COMMAND_ACK message definition

uint32 MESSAGE_VERSION = 0

uint64 timestamp		# time since system start (microseconds)

# Result cases. This follows the MAVLink MAV_RESULT enum definition
uint8 VEHICLE_CMD_RESULT_ACCEPTED = 0			# Command ACCEPTED and EXECUTED |
uint8 VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED = 1	# Command TEMPORARY REJECTED/DENIED |
uint8 VEHICLE_CMD_RESULT_DENIED = 2			# Command PERMANENTLY DENIED |
uint8 VEHICLE_CMD_RESULT_UNSUPPORTED = 3		# Command UNKNOWN/UNSUPPORTED |
uint8 VEHICLE_CMD_RESULT_FAILED = 4			# Command executed, but failed |
uint8 VEHICLE_CMD_RESULT_IN_PROGRESS = 5		# Command being executed |
uint8 VEHICLE_CMD_RESULT_CANCELLED = 6			# Command Canceled

# Arming denied specific cases
uint16 ARM_AUTH_DENIED_REASON_GENERIC = 0
uint16 ARM_AUTH_DENIED_REASON_NONE = 1
uint16 ARM_AUTH_DENIED_REASON_INVALID_WAYPOINT = 2
uint16 ARM_AUTH_DENIED_REASON_TIMEOUT = 3
uint16 ARM_AUTH_DENIED_REASON_AIRSPACE_IN_USE = 4
uint16 ARM_AUTH_DENIED_REASON_BAD_WEATHER = 5

uint8 ORB_QUEUE_LENGTH = 8

uint32 command						# Command that is being acknowledged
uint8 result						# Command result
uint8 result_param1					# Also used as progress[%], it can be set with the reason why the command was denied, or the progress percentage when result is MAV_RESULT_IN_PROGRESS
int32 result_param2					# Additional parameter of the result, example: which parameter of MAV_CMD_NAV_WAYPOINT caused it to be denied.
uint8 target_system
uint16 target_component 				# Target component / mode executor

bool from_external					# Indicates if the command came from an external source