mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-02 05:04:08 +08:00
mavlink: return unsupported frame result when that's the case
This commit is contained in:
parent
3b21f3999f
commit
1d5d96e8f9
@ -5,13 +5,16 @@
|
||||
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
|
||||
uint8 VEHICLE_CMD_RESULT_ACCEPTED = 0 # Command is valid (is supported and has valid parameters), and was executed
|
||||
uint8 VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED = 1 # Command is valid, but cannot be executed at this time
|
||||
uint8 VEHICLE_CMD_RESULT_DENIED = 2 # Command is invalid (is supported but has invalid parameters)
|
||||
uint8 VEHICLE_CMD_RESULT_UNSUPPORTED = 3 # Command is not supported (unknown)
|
||||
uint8 VEHICLE_CMD_RESULT_FAILED = 4 # Command is valid, but execution has failed
|
||||
uint8 VEHICLE_CMD_RESULT_IN_PROGRESS = 5 # Command is valid and is being executed
|
||||
uint8 VEHICLE_CMD_RESULT_CANCELLED = 6 # Command has been cancelled (as a result of receiving a COMMAND_CANCEL message)
|
||||
uint8 VEHICLE_CMD_RESULT_COMMAND_LONG_ONLY = 7 # Command is only accepted when sent as a COMMAND_LONG
|
||||
uint8 VEHICLE_CMD_RESULT_COMMAND_INT_ONLY = 8 # Command is only accepted when sent as a COMMAND_INT
|
||||
uint8 VEHICLE_CMD_RESULT_COMMAND_UNSUPPORTED_MAV_FRAME = 9 # Command is invalid because a frame is required and the specified frame is not supported
|
||||
|
||||
# Arming denied specific cases
|
||||
uint16 ARM_AUTH_DENIED_REASON_GENERIC = 0
|
||||
|
||||
@ -483,7 +483,8 @@ MavlinkReceiver::handle_message_command_int(mavlink_message_t *msg)
|
||||
default:
|
||||
vcmd.frame = vehicle_command_s::FRAME_UNKNOWN;
|
||||
PX4_ERR("invalid frame %" PRIu8 " for command %" PRIu16, cmd_mavlink.frame, cmd_mavlink.command);
|
||||
acknowledge(msg->sysid, msg->compid, cmd_mavlink.command, vehicle_command_ack_s::VEHICLE_CMD_RESULT_DENIED);
|
||||
acknowledge(msg->sysid, msg->compid, cmd_mavlink.command,
|
||||
vehicle_command_ack_s::VEHICLE_CMD_RESULT_COMMAND_UNSUPPORTED_MAV_FRAME);
|
||||
return;
|
||||
}
|
||||
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user