Move Vehicle Command Result Enum defs to Vehicle Command Ack (#19729)

- As it is always only used for the vehicle command ack message
- It was a duplicate, hence making it error prone for maintainment
- The uORB message comments were updated to make the relationship with
the MAVLink message / enum definitions clear
This commit is contained in:
Junwoo Hwang 2022-07-07 16:15:11 +02:00 committed by GitHub
parent af4038aa7e
commit 32ae00fd44
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
23 changed files with 212 additions and 209 deletions

View File

@ -1,4 +1,7 @@
uint64 timestamp # time since system start (microseconds)
# Vehicle Command uORB message. Used for commanding a mission / action / etc.
# Follows the MAVLink COMMAND_INT / COMMAND_LONG definition
uint64 timestamp # time since system start (microseconds)
uint16 VEHICLE_CMD_CUSTOM_0 = 0 # test command
uint16 VEHICLE_CMD_CUSTOM_1 = 1 # test command
@ -11,7 +14,7 @@ uint16 VEHICLE_CMD_NAV_RETURN_TO_LAUNCH = 20 # Return to launch location |Empty
uint16 VEHICLE_CMD_NAV_LAND = 21 # Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude|
uint16 VEHICLE_CMD_NAV_TAKEOFF = 22 # Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude|
uint16 VEHICLE_CMD_NAV_PRECLAND = 23 # Attempt a precision landing
uint16 VEHICLE_CMD_DO_ORBIT = 34 # Start orbiting on the circumference of a circle defined by the parameters. |Radius [m] |Velocity [m/s] |Yaw behaviour |Empty |Latitude/X |Longitude/Y |Altitude/Z |
uint16 VEHICLE_CMD_DO_ORBIT = 34 # Start orbiting on the circumference of a circle defined by the parameters. |Radius [m] |Velocity [m/s] |Yaw behaviour |Empty |Latitude/X |Longitude/Y |Altitude/Z |
uint16 VEHICLE_CMD_NAV_ROI = 80 # Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of interest mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z|
uint16 VEHICLE_CMD_NAV_PATHPLANNING = 81 # Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal|
uint16 VEHICLE_CMD_NAV_VTOL_TAKEOFF = 84 # Takeoff from ground / hand and transition to fixed wing |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude|
@ -24,7 +27,7 @@ uint16 VEHICLE_CMD_CONDITION_DELAY = 112 # Delay mission state machine. |Delay
uint16 VEHICLE_CMD_CONDITION_CHANGE_ALT = 113 # Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude|
uint16 VEHICLE_CMD_CONDITION_DISTANCE = 114 # Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_CONDITION_YAW = 115 # Reach a certain target angle. |target angle: [0-360], 0 is north| speed during yaw change:[deg per second]| direction: negative: counter clockwise, positive: clockwise [-1,1]| relative offset or absolute angle: [ 1,0]| Empty| Empty| Empty|
uint16 VEHICLE_CMD_CONDITION_LAST = 159 # NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_CONDITION_LAST = 159 # NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_CONDITION_GATE = 4501 # Wait until passing a threshold |2D coord mode: 0: Orthogonal to planned route | Altitude mode: 0: Ignore altitude| Empty| Empty| Lat| Lon| Alt|
uint16 VEHICLE_CMD_DO_SET_MODE = 176 # Set system mode. |Mode, as defined by ENUM MAV_MODE| Empty| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_JUMP = 177 # Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty|
@ -41,11 +44,11 @@ uint16 VEHICLE_CMD_DO_LAND_START = 189 # Mission command to perform a landing.
uint16 VEHICLE_CMD_DO_GO_AROUND = 191 # Mission command to safely abort an autonmous landing. |Altitude (meters)| Empty| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_REPOSITION = 192
uint16 VEHICLE_CMD_DO_PAUSE_CONTINUE = 193
uint16 VEHICLE_CMD_DO_SET_ROI_LOCATION = 195 # Sets the region of interest (ROI) to a location. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Empty| Empty| Empty| Empty| Latitude| Longitude| Altitude|
uint16 VEHICLE_CMD_DO_SET_ROI_WPNEXT_OFFSET = 196 # Sets the region of interest (ROI) to be toward next waypoint, with optional pitch/roll/yaw offset. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Empty| Empty| Empty| Empty| pitch offset from next waypoint| roll offset from next waypoint| yaw offset from next waypoint|
uint16 VEHICLE_CMD_DO_SET_ROI_LOCATION = 195 # Sets the region of interest (ROI) to a location. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Empty| Empty| Empty| Empty| Latitude| Longitude| Altitude|
uint16 VEHICLE_CMD_DO_SET_ROI_WPNEXT_OFFSET = 196 # Sets the region of interest (ROI) to be toward next waypoint, with optional pitch/roll/yaw offset. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Empty| Empty| Empty| Empty| pitch offset from next waypoint| roll offset from next waypoint| yaw offset from next waypoint|
uint16 VEHICLE_CMD_DO_SET_ROI_NONE = 197 # Cancels any previous ROI command returning the vehicle/sensors to default flight characteristics. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Empty| Empty| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_CONTROL_VIDEO = 200 # Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_SET_ROI = 201 # Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of interest mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z|
uint16 VEHICLE_CMD_DO_SET_ROI = 201 # Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of interest mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z|
uint16 VEHICLE_CMD_DO_DIGICAM_CONTROL=203
uint16 VEHICLE_CMD_DO_MOUNT_CONFIGURE=204 # Mission command to configure a camera or antenna mount |Mount operation mode (see MAV_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_MOUNT_CONTROL=205 # Mission command to control a camera or antenna mount |pitch or lat in degrees, depending on mount mode.| roll or lon in degrees depending on mount mode| yaw or alt (in meters) depending on mount mode| reserved| reserved| reserved| MAV_MOUNT_MODE enum value|
@ -54,19 +57,19 @@ uint16 VEHICLE_CMD_DO_FENCE_ENABLE=207 # Mission command to enable the geofenc
uint16 VEHICLE_CMD_DO_PARACHUTE=208 # Mission command to trigger a parachute |action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)| Empty| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_MOTOR_TEST=209 # motor test command |Instance (1, ...)| throttle type| throttle| timeout [s]| Motor count | Test order| Empty|
uint16 VEHICLE_CMD_DO_INVERTED_FLIGHT=210 # Change to/from inverted flight |inverted (0=normal, 1=inverted)| Empty| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_SET_CAM_TRIGG_INTERVAL=214 # Mission command to set TRIG_INTERVAL for this flight |Camera trigger distance (meters)| Shutter integration time (ms)| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_SET_CAM_TRIGG_INTERVAL=214 # Mission command to set TRIG_INTERVAL for this flight |Camera trigger distance (meters)| Shutter integration time (ms)| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_MOUNT_CONTROL_QUAT=220 # Mission command to control a camera or antenna mount, using a quaternion as reference. |q1 - quaternion param #1, w (1 in null-rotation)| q2 - quaternion param #2, x (0 in null-rotation)| q3 - quaternion param #3, y (0 in null-rotation)| q4 - quaternion param #4, z (0 in null-rotation)| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_GUIDED_MASTER=221 # set id of master controller |System ID| Component ID| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_GUIDED_LIMITS=222 # set limits for external control |timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout| absolute altitude min (in meters, AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit| absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit| horizontal move limit (in meters, AMSL) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_LAST = 240 # NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_PREFLIGHT_CALIBRATION = 241 # Trigger calibration. This command will be only accepted if in pre-flight mode. See mavlink spec MAV_CMD_PREFLIGHT_CALIBRATION
uint16 PREFLIGHT_CALIBRATION_TEMPERATURE_CALIBRATION = 3 # param value for VEHICLE_CMD_PREFLIGHT_CALIBRATION to start temperature calibration
uint16 PREFLIGHT_CALIBRATION_TEMPERATURE_CALIBRATION = 3# param value for VEHICLE_CMD_PREFLIGHT_CALIBRATION to start temperature calibration
uint16 VEHICLE_CMD_PREFLIGHT_SET_SENSOR_OFFSETS = 242 # Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units|
uint16 VEHICLE_CMD_PREFLIGHT_UAVCAN = 243 # UAVCAN configuration. If param 1 == 1 actuator mapping and direction assignment should be started
uint16 VEHICLE_CMD_PREFLIGHT_STORAGE = 245 # Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Reserved| Reserved| Empty| Empty| Empty|
uint16 VEHICLE_CMD_PREFLIGHT_REBOOT_SHUTDOWN = 246 # Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty|
uint16 VEHICLE_CMD_OBLIQUE_SURVEY=260 # Mission command to set a Camera Auto Mount Pivoting Oblique Survey for this flight|Camera trigger distance (meters)| Shutter integration time (ms)| Camera minimum trigger interval| Number of positions| Roll| Pitch| Empty|
uint16 VEHICLE_CMD_GIMBAL_DEVICE_INFORMATION = 283 # Command to ask information about a low level gimbal
uint16 VEHICLE_CMD_GIMBAL_DEVICE_INFORMATION = 283 # Command to ask information about a low level gimbal
uint16 VEHICLE_CMD_MISSION_START = 300 # start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)|
uint16 VEHICLE_CMD_ACTUATOR_TEST = 310 # Actuator testing command|value [-1,1]|timeout [s]|Empty|Empty|output function|
@ -74,21 +77,21 @@ uint16 VEHICLE_CMD_CONFIGURE_ACTUATOR = 311 # Actuator configuration command|co
uint16 VEHICLE_CMD_COMPONENT_ARM_DISARM = 400 # Arms / Disarms a component |1 to arm, 0 to disarm
uint16 VEHICLE_CMD_INJECT_FAILURE = 420 # Inject artificial failure for testing purposes
uint16 VEHICLE_CMD_START_RX_PAIR = 500 # Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX|
uint16 VEHICLE_CMD_REQUEST_MESSAGE = 512 # Request to send a single instance of the specified message
uint16 VEHICLE_CMD_SET_CAMERA_MODE = 530 # Set camera capture mode (photo, video, etc.)
uint16 VEHICLE_CMD_SET_CAMERA_ZOOM = 531 # Set camera zoom
uint16 VEHICLE_CMD_REQUEST_MESSAGE = 512 # Request to send a single instance of the specified message
uint16 VEHICLE_CMD_SET_CAMERA_MODE = 530 # Set camera capture mode (photo, video, etc.)
uint16 VEHICLE_CMD_SET_CAMERA_ZOOM = 531 # Set camera zoom
uint16 VEHICLE_CMD_SET_CAMERA_FOCUS = 532
uint16 VEHICLE_CMD_DO_GIMBAL_MANAGER_PITCHYAW = 1000 # Setpoint to be sent to a gimbal manager to set a gimbal pitch and yaw
uint16 VEHICLE_CMD_DO_GIMBAL_MANAGER_CONFIGURE = 1001 # Gimbal configuration to set which sysid/compid is in primary and secondary control
uint16 VEHICLE_CMD_IMAGE_START_CAPTURE = 2000 # Start image capture sequence.
uint16 VEHICLE_CMD_DO_TRIGGER_CONTROL = 2003 # Enable or disable on-board camera triggering system
uint16 VEHICLE_CMD_VIDEO_START_CAPTURE = 2500 # Start a video capture.
uint16 VEHICLE_CMD_VIDEO_STOP_CAPTURE = 2501 # Stop the current video capture.
uint16 VEHICLE_CMD_LOGGING_START = 2510 # start streaming ULog data
uint16 VEHICLE_CMD_DO_GIMBAL_MANAGER_PITCHYAW = 1000 # Setpoint to be sent to a gimbal manager to set a gimbal pitch and yaw
uint16 VEHICLE_CMD_DO_GIMBAL_MANAGER_CONFIGURE = 1001 # Gimbal configuration to set which sysid/compid is in primary and secondary control
uint16 VEHICLE_CMD_IMAGE_START_CAPTURE = 2000 # Start image capture sequence.
uint16 VEHICLE_CMD_DO_TRIGGER_CONTROL = 2003 # Enable or disable on-board camera triggering system
uint16 VEHICLE_CMD_VIDEO_START_CAPTURE = 2500 # Start a video capture.
uint16 VEHICLE_CMD_VIDEO_STOP_CAPTURE = 2501 # Stop the current video capture.
uint16 VEHICLE_CMD_LOGGING_START = 2510 # start streaming ULog data
uint16 VEHICLE_CMD_LOGGING_STOP = 2511 # stop streaming ULog data
uint16 VEHICLE_CMD_CONTROL_HIGH_LATENCY = 2600 # control starting/stopping transmitting data over the high latency link
uint16 VEHICLE_CMD_DO_VTOL_TRANSITION = 3000 # Command VTOL transition
uint16 VEHICLE_CMD_ARM_AUTHORIZATION_REQUEST = 3001 # Request arm authorization
uint16 VEHICLE_CMD_CONTROL_HIGH_LATENCY = 2600 # control starting/stopping transmitting data over the high latency link
uint16 VEHICLE_CMD_DO_VTOL_TRANSITION = 3000 # Command VTOL transition
uint16 VEHICLE_CMD_ARM_AUTHORIZATION_REQUEST = 3001 # Request arm authorization
uint16 VEHICLE_CMD_PAYLOAD_PREPARE_DEPLOY = 30001 # Prepare a payload deployment in the flight plan
uint16 VEHICLE_CMD_PAYLOAD_CONTROL_DEPLOY = 30002 # Control a pre-programmed payload deployment
uint16 VEHICLE_CMD_FIXED_MAG_CAL_YAW = 42006 # Magnetometer calibration based on provided known yaw. This allows for fast calibration using WMM field tables in the vehicle, given only the known yaw of the vehicle. If Latitude and longitude are both zero then use the current vehicle location.
@ -98,33 +101,24 @@ uint16 VEHICLE_CMD_FIXED_MAG_CAL_YAW = 42006 # Magnetometer calibrati
uint32 VEHICLE_CMD_PX4_INTERNAL_START = 65537 # start of PX4 internal only vehicle commands (> UINT16_MAX)
uint32 VEHICLE_CMD_SET_GPS_GLOBAL_ORIGIN = 100000 # Sets the GPS co-ordinates of the vehicle local origin (0,0,0) position. |Empty|Empty|Empty|Empty|Latitude|Longitude|Altitude|
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_ENUM_END = 6 #
uint8 VEHICLE_MOUNT_MODE_RETRACT = 0 # Load and keep safe position (Roll,Pitch,Yaw) from permanent memory and stop stabilization |
uint8 VEHICLE_MOUNT_MODE_NEUTRAL = 1 # Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. |
uint8 VEHICLE_MOUNT_MODE_RETRACT = 0 # Load and keep safe position (Roll,Pitch,Yaw) from permanent memory and stop stabilization |
uint8 VEHICLE_MOUNT_MODE_NEUTRAL = 1 # Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. |
uint8 VEHICLE_MOUNT_MODE_MAVLINK_TARGETING = 2 # Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization |
uint8 VEHICLE_MOUNT_MODE_RC_TARGETING = 3 # Load neutral position and start RC Roll,Pitch,Yaw control with stabilization |
uint8 VEHICLE_MOUNT_MODE_GPS_POINT = 4 # Load neutral position and start to point to Lat,Lon,Alt |
uint8 VEHICLE_MOUNT_MODE_ENUM_END = 5 #
uint8 VEHICLE_MOUNT_MODE_RC_TARGETING = 3 # Load neutral position and start RC Roll,Pitch,Yaw control with stabilization |
uint8 VEHICLE_MOUNT_MODE_GPS_POINT = 4 # Load neutral position and start to point to Lat,Lon,Alt |
uint8 VEHICLE_MOUNT_MODE_ENUM_END = 5 #
uint8 VEHICLE_ROI_NONE = 0 # No region of interest |
uint8 VEHICLE_ROI_WPNEXT = 1 # Point toward next MISSION |
uint8 VEHICLE_ROI_WPINDEX = 2 # Point toward given MISSION |
uint8 VEHICLE_ROI_LOCATION = 3 # Point toward fixed location |
uint8 VEHICLE_ROI_TARGET = 4 # Point toward target
uint8 VEHICLE_ROI_NONE = 0 # No region of interest |
uint8 VEHICLE_ROI_WPNEXT = 1 # Point toward next MISSION |
uint8 VEHICLE_ROI_WPINDEX = 2 # Point toward given MISSION |
uint8 VEHICLE_ROI_LOCATION = 3 # Point toward fixed location |
uint8 VEHICLE_ROI_TARGET = 4 # Point toward target
uint8 VEHICLE_ROI_ENUM_END = 5
uint8 VEHICLE_CAMERA_ZOOM_TYPE_STEP = 0 # Zoom one step increment
uint8 VEHICLE_CAMERA_ZOOM_TYPE_CONTINUOUS = 1 # Continuous zoom up/down until stopped
uint8 VEHICLE_CAMERA_ZOOM_TYPE_RANGE = 2 # Zoom value as proportion of full camera range
uint8 VEHICLE_CAMERA_ZOOM_TYPE_FOCAL_LENGTH = 3 # Zoom to a focal length
uint8 VEHICLE_CAMERA_ZOOM_TYPE_STEP = 0 # Zoom one step increment
uint8 VEHICLE_CAMERA_ZOOM_TYPE_CONTINUOUS = 1 # Continuous zoom up/down until stopped
uint8 VEHICLE_CAMERA_ZOOM_TYPE_RANGE = 2 # Zoom value as proportion of full camera range
uint8 VEHICLE_CAMERA_ZOOM_TYPE_FOCAL_LENGTH = 3 # Zoom to a focal length
uint8 PARACHUTE_ACTION_DISABLE = 0
uint8 PARACHUTE_ACTION_ENABLE = 1

View File

@ -1,11 +1,19 @@
uint64 timestamp # time since system start (microseconds)
uint8 VEHICLE_RESULT_ACCEPTED = 0
uint8 VEHICLE_RESULT_TEMPORARILY_REJECTED = 1
uint8 VEHICLE_RESULT_DENIED = 2
uint8 VEHICLE_RESULT_UNSUPPORTED = 3
uint8 VEHICLE_RESULT_FAILED = 4
uint8 VEHICLE_RESULT_IN_PROGRESS = 5
# Vehicle Command Ackonwledgement uORB message.
# Used for acknowledging the vehicle command being received.
# Follows the MAVLink COMMAND_ACK message definition
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
@ -15,10 +23,11 @@ uint16 ARM_AUTH_DENIED_REASON_BAD_WEATHER = 5
uint8 ORB_QUEUE_LENGTH = 4
uint32 command
uint8 result
bool from_external
uint8 result_param1
int32 result_param2
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
uint8 target_component
bool from_external # Indicates if the command came from an external source

View File

@ -270,7 +270,7 @@ CameraCapture::Run()
command_ack.timestamp = hrt_absolute_time();
command_ack.command = cmd.command;
command_ack.result = (uint8_t)vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
command_ack.result = (uint8_t)vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED;
command_ack.target_system = cmd.source_system;
command_ack.target_component = cmd.source_component;

View File

@ -508,7 +508,7 @@ CameraTrigger::Run()
int poll_interval_usec = 50000;
vehicle_command_s cmd{};
unsigned cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
unsigned cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
bool need_ack = false;
// this flag is set when the polling loop is slowed down to allow the camera to power on
@ -530,7 +530,7 @@ CameraTrigger::Run()
if (now - _last_trigger_timestamp < _min_interval * 1000) {
// triggering too fast, abort
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
} else {
if (commandParamToInt(cmd.param7) == 1) {
@ -543,7 +543,7 @@ CameraTrigger::Run()
_one_shot = true;
}
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED;
}
} else if (cmd.command == vehicle_command_s::VEHICLE_CMD_DO_TRIGGER_CONTROL) {
@ -570,7 +570,7 @@ CameraTrigger::Run()
_trigger_enabled = false;
}
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED;
} else if (cmd.command == vehicle_command_s::VEHICLE_CMD_DO_SET_CAM_TRIGG_DIST) {
PX4_DEBUG("received DO_SET_CAM_TRIGG_DIST");
@ -608,7 +608,7 @@ CameraTrigger::Run()
_one_shot = true;
}
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED;
} else if (cmd.command == vehicle_command_s::VEHICLE_CMD_DO_SET_CAM_TRIGG_INTERVAL) {
PX4_DEBUG("received DO_SET_CAM_TRIGG_INTERVAL");
@ -627,7 +627,7 @@ CameraTrigger::Run()
}
}
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED;
} else if (cmd.command == vehicle_command_s::VEHICLE_CMD_OBLIQUE_SURVEY) {
PX4_INFO("received OBLIQUE_SURVEY");
@ -676,7 +676,7 @@ CameraTrigger::Run()
_CAMPOS_num_poses = 0;
}
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED;
} else {
goto unknown_cmd;

View File

@ -624,7 +624,7 @@ void DShot::handle_vehicle_commands()
command_ack.command = vehicle_command.command;
command_ack.target_system = vehicle_command.source_system;
command_ack.target_component = vehicle_command.source_component;
command_ack.result = vehicle_command_s::VEHICLE_CMD_RESULT_UNSUPPORTED;
command_ack.result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_UNSUPPORTED;
if (index != -1) {
PX4_DEBUG("setting command: index: %i type: %i", index, type);
@ -646,7 +646,7 @@ void DShot::handle_vehicle_commands()
PX4_WARN("unknown command: %i", type);
} else {
command_ack.result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
command_ack.result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED;
_current_command.motor_mask = 1 << index;
_current_command.num_repetitions = 10;
_current_command.save = true;

View File

@ -590,10 +590,10 @@ void PX4IO::Run()
/* publish ACK */
if (dsm_ret == OK) {
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
answer_command(cmd, vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED);
} else {
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_FAILED);
answer_command(cmd, vehicle_command_ack_s::VEHICLE_CMD_RESULT_FAILED);
}
}
}

View File

@ -334,7 +334,7 @@ void RCInput::Run()
// Check for a pairing command
if (vcmd.command == vehicle_command_s::VEHICLE_CMD_START_RX_PAIR) {
uint8_t cmd_ret = vehicle_command_s::VEHICLE_CMD_RESULT_UNSUPPORTED;
uint8_t cmd_ret = vehicle_command_ack_s::VEHICLE_CMD_RESULT_UNSUPPORTED;
#if defined(SPEKTRUM_POWER)
if (!_rc_scan_locked && !_armed) {
@ -356,11 +356,11 @@ void RCInput::Run()
bind_spektrum(dsm_bind_pulses);
cmd_ret = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
cmd_ret = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED;
}
} else {
cmd_ret = vehicle_command_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
cmd_ret = vehicle_command_ack_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
}
#endif // SPEKTRUM_POWER

View File

@ -866,7 +866,7 @@ UavcanNode::Run()
vehicle_command_s cmd{};
_vcmd_sub.copy(&cmd);
uint8_t cmd_ack_result = vehicle_command_ack_s::VEHICLE_RESULT_ACCEPTED;
uint8_t cmd_ack_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED;
if (cmd.command == vehicle_command_s::VEHICLE_CMD_PREFLIGHT_STORAGE) {
acknowledge = true;

View File

@ -110,10 +110,10 @@ static uint8_t _auth_method_arm_req_check()
break;
case ARM_AUTH_MISSION_APPROVED:
return vehicle_command_ack_s::VEHICLE_RESULT_ACCEPTED;
return vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED;
default:
return vehicle_command_ack_s::VEHICLE_RESULT_DENIED;
return vehicle_command_ack_s::VEHICLE_CMD_RESULT_DENIED;
}
/* handling ARM_AUTH_IDLE */
@ -148,7 +148,7 @@ static uint8_t _auth_method_arm_req_check()
}
return state == ARM_AUTH_MISSION_APPROVED ?
vehicle_command_ack_s::VEHICLE_RESULT_ACCEPTED : vehicle_command_ack_s::VEHICLE_RESULT_DENIED;
vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED : vehicle_command_ack_s::VEHICLE_CMD_RESULT_DENIED;
}
static uint8_t _auth_method_two_arm_check()
@ -159,14 +159,14 @@ static uint8_t _auth_method_two_arm_check()
break;
case ARM_AUTH_MISSION_APPROVED:
return vehicle_command_ack_s::VEHICLE_RESULT_ACCEPTED;
return vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED;
case ARM_AUTH_WAITING_AUTH:
case ARM_AUTH_WAITING_AUTH_WITH_ACK:
return vehicle_command_ack_s::VEHICLE_RESULT_TEMPORARILY_REJECTED;
return vehicle_command_ack_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
default:
return vehicle_command_ack_s::VEHICLE_RESULT_DENIED;
return vehicle_command_ack_s::VEHICLE_CMD_RESULT_DENIED;
}
/* handling ARM_AUTH_IDLE */
@ -179,7 +179,7 @@ static uint8_t _auth_method_two_arm_check()
mavlink_log_info(mavlink_log_pub, "Arm auth: Requesting authorization...");
return vehicle_command_ack_s::VEHICLE_RESULT_TEMPORARILY_REJECTED;
return vehicle_command_ack_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
}
uint8_t arm_auth_check()
@ -188,7 +188,7 @@ uint8_t arm_auth_check()
return arm_check_method[_param_com_arm_auth_method]();
}
return vehicle_command_ack_s::VEHICLE_RESULT_DENIED;
return vehicle_command_ack_s::VEHICLE_CMD_RESULT_DENIED;
}
void arm_auth_update(hrt_abstime now, bool param_update)
@ -232,11 +232,11 @@ void arm_auth_update(hrt_abstime now, bool param_update)
&& command_ack.target_system == *system_id
&& command_ack.timestamp > auth_req_time) {
switch (command_ack.result) {
case vehicle_command_ack_s::VEHICLE_RESULT_IN_PROGRESS:
case vehicle_command_ack_s::VEHICLE_CMD_RESULT_IN_PROGRESS:
state = ARM_AUTH_WAITING_AUTH_WITH_ACK;
break;
case vehicle_command_ack_s::VEHICLE_RESULT_ACCEPTED:
case vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED:
mavlink_log_info(mavlink_log_pub,
"Arm auth: Authorized for the next %" PRId32 " seconds",
command_ack.result_param2);
@ -244,12 +244,12 @@ void arm_auth_update(hrt_abstime now, bool param_update)
auth_timeout = command_ack.timestamp + (command_ack.result_param2 * 1000000);
return;
case vehicle_command_ack_s::VEHICLE_RESULT_TEMPORARILY_REJECTED:
case vehicle_command_ack_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED:
mavlink_log_critical(mavlink_log_pub, "Arm auth: Temporarily rejected");
state = ARM_AUTH_IDLE;
return;
case vehicle_command_ack_s::VEHICLE_RESULT_DENIED:
case vehicle_command_ack_s::VEHICLE_CMD_RESULT_DENIED:
default:
switch (command_ack.result_param1) {
case vehicle_command_ack_s::ARM_AUTH_DENIED_REASON_NONE:

View File

@ -240,7 +240,7 @@ bool PreFlightCheck::preArmCheck(orb_advert_t *mavlink_log_pub, const vehicle_st
// check last, and only if everything else has passed
// skip arm authorization check until actual arming attempt
if (arm_authorization_configured && prearm_ok && is_arm_attempt) {
if (arm_auth_check() != vehicle_command_ack_s::VEHICLE_RESULT_ACCEPTED) {
if (arm_auth_check() != vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED) {
// feedback provided in arm_auth_check
prearm_ok = false;
}

View File

@ -872,7 +872,7 @@ Commander::handle_command(const vehicle_command_s &cmd)
}
/* result of the command */
unsigned cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_UNSUPPORTED;
unsigned cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_UNSUPPORTED;
/* request to set different system mode */
switch (cmd.command) {
@ -889,10 +889,10 @@ Commander::handle_command(const vehicle_command_s &cmd)
_vehicle_status_flags, _commander_state);
if ((main_ret != TRANSITION_DENIED)) {
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED;
} else {
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
mavlink_log_critical(&_mavlink_log_pub, "Reposition command rejected\t");
/* EVENT
* @description Check for a valid position estimate
@ -903,7 +903,7 @@ Commander::handle_command(const vehicle_command_s &cmd)
}
} else {
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED;
}
}
break;
@ -1004,10 +1004,10 @@ Commander::handle_command(const vehicle_command_s &cmd)
}
if (main_ret != TRANSITION_DENIED) {
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED;
} else {
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
}
}
break;
@ -1051,10 +1051,10 @@ Commander::handle_command(const vehicle_command_s &cmd)
}
if (arming_res == TRANSITION_DENIED) {
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
} else {
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED;
/* update home position on arming if at least 500 ms from commander start spent to avoid setting home on in-air restart */
if ((arming_action == vehicle_command_s::ARMING_ACTION_ARM) && (arming_res == TRANSITION_CHANGED)
@ -1095,7 +1095,7 @@ Commander::handle_command(const vehicle_command_s &cmd)
PX4_WARN("disabling failsafe and lockdown");
}
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED;
}
break;
@ -1106,10 +1106,10 @@ Commander::handle_command(const vehicle_command_s &cmd)
if (use_current) {
/* use current position */
if (set_home_position()) {
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED;
} else {
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
}
} else {
@ -1142,20 +1142,20 @@ Commander::handle_command(const vehicle_command_s &cmd)
/* mark home position as set */
_vehicle_status_flags.home_position_valid = _home_position_pub.update(home);
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED;
} else {
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
}
} else {
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_DENIED;
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_DENIED;
}
}
} else {
// COM_HOME_EN disabled
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_DENIED;
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_DENIED;
}
}
break;
@ -1167,7 +1167,7 @@ Commander::handle_command(const vehicle_command_s &cmd)
_commander_state)) {
mavlink_log_info(&_mavlink_log_pub, "Returning to launch\t");
events::send(events::ID("commander_rtl"), events::Log::Info, "Returning to launch");
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED;
} else {
mavlink_log_critical(&_mavlink_log_pub, "Return to launch denied\t");
@ -1176,7 +1176,7 @@ Commander::handle_command(const vehicle_command_s &cmd)
*/
events::send(events::ID("commander_rtl_denied"), {events::Log::Critical, events::LogInternal::Info},
"Return to launch denied");
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
}
}
break;
@ -1186,10 +1186,10 @@ Commander::handle_command(const vehicle_command_s &cmd)
if (TRANSITION_CHANGED == main_state_transition(_vehicle_status, commander_state_s::MAIN_STATE_AUTO_TAKEOFF,
_vehicle_status_flags,
_commander_state)) {
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED;
} else if (_commander_state.main_state == commander_state_s::MAIN_STATE_AUTO_TAKEOFF) {
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED;
} else {
mavlink_log_critical(&_mavlink_log_pub, "Takeoff denied! Please disarm and retry\t");
@ -1198,7 +1198,7 @@ Commander::handle_command(const vehicle_command_s &cmd)
*/
events::send(events::ID("commander_takeoff_denied"), {events::Log::Critical, events::LogInternal::Info},
"Takeoff denied! Please disarm and retry");
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
}
}
break;
@ -1209,14 +1209,14 @@ Commander::handle_command(const vehicle_command_s &cmd)
if (TRANSITION_CHANGED == main_state_transition(_vehicle_status, commander_state_s::MAIN_STATE_AUTO_VTOL_TAKEOFF,
_vehicle_status_flags,
_commander_state)) {
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED;
} else if (_commander_state.main_state == commander_state_s::MAIN_STATE_AUTO_VTOL_TAKEOFF) {
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED;
} else {
mavlink_log_critical(&_mavlink_log_pub, "VTOL Takeoff denied! Please disarm and retry");
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
}
break;
@ -1228,7 +1228,7 @@ Commander::handle_command(const vehicle_command_s &cmd)
mavlink_log_info(&_mavlink_log_pub, "Landing at current position\t");
events::send(events::ID("commander_landing_current_pos"), events::Log::Info,
"Landing at current position");
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED;
} else {
mavlink_log_critical(&_mavlink_log_pub, "Landing denied! Please land manually\t");
@ -1237,7 +1237,7 @@ Commander::handle_command(const vehicle_command_s &cmd)
*/
events::send(events::ID("commander_landing_current_pos_denied"), {events::Log::Critical, events::LogInternal::Info},
"Landing denied! Please land manually");
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
}
}
break;
@ -1249,7 +1249,7 @@ Commander::handle_command(const vehicle_command_s &cmd)
mavlink_log_info(&_mavlink_log_pub, "Precision landing\t");
events::send(events::ID("commander_landing_prec_land"), events::Log::Info,
"Landing using precision landing");
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED;
} else {
mavlink_log_critical(&_mavlink_log_pub, "Precision landing denied! Please land manually\t");
@ -1258,14 +1258,14 @@ Commander::handle_command(const vehicle_command_s &cmd)
*/
events::send(events::ID("commander_landing_prec_land_denied"), {events::Log::Critical, events::LogInternal::Info},
"Precision landing denied! Please land manually");
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
}
}
break;
case vehicle_command_s::VEHICLE_CMD_MISSION_START: {
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_DENIED;
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_DENIED;
// check if current mission and first item are valid
if (_vehicle_status_flags.auto_mission_available) {
@ -1279,10 +1279,10 @@ Commander::handle_command(const vehicle_command_s &cmd)
_commander_state))
&& (TRANSITION_DENIED != arm(arm_disarm_reason_t::mission_start))) {
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED;
} else {
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
mavlink_log_critical(&_mavlink_log_pub, "Mission start denied\t");
/* EVENT
* @description Check for a valid position estimate
@ -1303,7 +1303,7 @@ Commander::handle_command(const vehicle_command_s &cmd)
case vehicle_command_s::VEHICLE_CMD_CONTROL_HIGH_LATENCY: {
// if no high latency telemetry exists send a failed acknowledge
if (_high_latency_datalink_heartbeat > _boot_timestamp) {
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_FAILED;
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_FAILED;
mavlink_log_critical(&_mavlink_log_pub, "Control high latency failed! Telemetry unavailable\t");
events::send(events::ID("commander_ctrl_high_latency_failed"), {events::Log::Critical, events::LogInternal::Info},
"Control high latency failed! Telemetry unavailable");
@ -1330,10 +1330,10 @@ Commander::handle_command(const vehicle_command_s &cmd)
}
if ((main_ret != TRANSITION_DENIED)) {
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED;
} else {
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
mavlink_log_critical(&_mavlink_log_pub, "Orbit command rejected");
}
@ -1353,13 +1353,13 @@ Commander::handle_command(const vehicle_command_s &cmd)
if (param1 == 0) {
// 0: Do nothing for autopilot
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
answer_command(cmd, vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED);
#if defined(CONFIG_BOARDCTL_RESET)
} else if ((param1 == 1) && shutdown_if_allowed() && (px4_reboot_request(false, 400_ms) == 0)) {
// 1: Reboot autopilot
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
answer_command(cmd, vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED);
while (1) { px4_usleep(1); }
@ -1369,7 +1369,7 @@ Commander::handle_command(const vehicle_command_s &cmd)
} else if ((param1 == 2) && shutdown_if_allowed() && (px4_shutdown_request(400_ms) == 0)) {
// 2: Shutdown autopilot
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
answer_command(cmd, vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED);
while (1) { px4_usleep(1); }
@ -1379,14 +1379,14 @@ Commander::handle_command(const vehicle_command_s &cmd)
} else if ((param1 == 3) && shutdown_if_allowed() && (px4_reboot_request(true, 400_ms) == 0)) {
// 3: Reboot autopilot and keep it in the bootloader until upgraded.
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
answer_command(cmd, vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED);
while (1) { px4_usleep(1); }
#endif // CONFIG_BOARDCTL_RESET
} else {
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_DENIED);
answer_command(cmd, vehicle_command_ack_s::VEHICLE_CMD_RESULT_DENIED);
}
}
@ -1397,7 +1397,7 @@ Commander::handle_command(const vehicle_command_s &cmd)
if (_arm_state_machine.isArmed() || _arm_state_machine.isShutdown() || _worker_thread.isBusy()) {
// reject if armed or shutting down
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED);
answer_command(cmd, vehicle_command_ack_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED);
} else {
@ -1409,14 +1409,14 @@ Commander::handle_command(const vehicle_command_s &cmd)
(cmd.from_external ? arm_disarm_reason_t::command_external : arm_disarm_reason_t::command_internal))
) {
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_DENIED);
answer_command(cmd, vehicle_command_ack_s::VEHICLE_CMD_RESULT_DENIED);
break;
}
if ((int)(cmd.param1) == 1) {
/* gyro calibration */
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
answer_command(cmd, vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED);
_vehicle_status_flags.calibration_enabled = true;
_worker_thread.startTask(WorkerThread::Request::GyroCalibration);
@ -1428,19 +1428,19 @@ Commander::handle_command(const vehicle_command_s &cmd)
} else if ((int)(cmd.param2) == 1) {
/* magnetometer calibration */
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
answer_command(cmd, vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED);
_vehicle_status_flags.calibration_enabled = true;
_worker_thread.startTask(WorkerThread::Request::MagCalibration);
} else if ((int)(cmd.param3) == 1) {
/* baro calibration */
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
answer_command(cmd, vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED);
_vehicle_status_flags.calibration_enabled = true;
_worker_thread.startTask(WorkerThread::Request::BaroCalibration);
} else if ((int)(cmd.param4) == 1) {
/* RC calibration */
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
answer_command(cmd, vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED);
/* disable RC control input completely */
_vehicle_status_flags.rc_calibration_in_progress = true;
mavlink_log_info(&_mavlink_log_pub, "Calibration: Disabling RC input\t");
@ -1449,39 +1449,38 @@ Commander::handle_command(const vehicle_command_s &cmd)
} else if ((int)(cmd.param4) == 2) {
/* RC trim calibration */
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
answer_command(cmd, vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED);
_vehicle_status_flags.calibration_enabled = true;
_worker_thread.startTask(WorkerThread::Request::RCTrimCalibration);
} else if ((int)(cmd.param5) == 1) {
/* accelerometer calibration */
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
answer_command(cmd, vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED);
_vehicle_status_flags.calibration_enabled = true;
_worker_thread.startTask(WorkerThread::Request::AccelCalibration);
} else if ((int)(cmd.param5) == 2) {
// board offset calibration
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
answer_command(cmd, vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED);
_vehicle_status_flags.calibration_enabled = true;
answer_command(cmd, vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED);
_vehicle_status_flags.calibration_enabled = true;
_worker_thread.startTask(WorkerThread::Request::LevelCalibration);
} else if ((int)(cmd.param5) == 4) {
// accelerometer quick calibration
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
answer_command(cmd, vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED);
_vehicle_status_flags.calibration_enabled = true;
_worker_thread.startTask(WorkerThread::Request::AccelCalibrationQuick);
} else if ((int)(cmd.param6) == 1 || (int)(cmd.param6) == 2) {
// TODO: param6 == 1 is deprecated, but we still accept it for a while (feb 2017)
/* airspeed calibration */
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
answer_command(cmd, vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED);
_vehicle_status_flags.calibration_enabled = true;
_worker_thread.startTask(WorkerThread::Request::AirspeedCalibration);
} else if ((int)(cmd.param7) == 1) {
/* do esc calibration */
if (check_battery_disconnected(&_mavlink_log_pub)) {
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
answer_command(cmd, vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED);
if (_safety.isButtonAvailable() && !_safety.isSafetyOff()) {
mavlink_log_critical(&_mavlink_log_pub, "ESC calibration denied! Press safety button first\t");
@ -1495,7 +1494,7 @@ Commander::handle_command(const vehicle_command_s &cmd)
}
} else {
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_DENIED);
answer_command(cmd, vehicle_command_ack_s::VEHICLE_CMD_RESULT_DENIED);
}
} else if ((int)(cmd.param4) == 0) {
@ -1508,10 +1507,10 @@ Commander::handle_command(const vehicle_command_s &cmd)
"Calibration: Restoring RC input");
}
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
answer_command(cmd, vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED);
} else {
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_UNSUPPORTED);
answer_command(cmd, vehicle_command_ack_s::VEHICLE_CMD_RESULT_UNSUPPORTED);
}
}
@ -1523,10 +1522,10 @@ Commander::handle_command(const vehicle_command_s &cmd)
if (_arm_state_machine.isArmed() || _arm_state_machine.isShutdown() || _worker_thread.isBusy()) {
// reject if armed or shutting down
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED);
answer_command(cmd, vehicle_command_ack_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED);
} else {
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
answer_command(cmd, vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED);
// parameter 1: Heading (degrees)
// parameter 3: Latitude (degrees)
// parameter 4: Longitude (degrees)
@ -1558,28 +1557,28 @@ Commander::handle_command(const vehicle_command_s &cmd)
if (_arm_state_machine.isArmed() || _arm_state_machine.isShutdown() || _worker_thread.isBusy()) {
// reject if armed or shutting down
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED);
answer_command(cmd, vehicle_command_ack_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED);
} else {
if (((int)(cmd.param1)) == 0) {
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
answer_command(cmd, vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED);
_worker_thread.startTask(WorkerThread::Request::ParamLoadDefault);
} else if (((int)(cmd.param1)) == 1) {
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
answer_command(cmd, vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED);
_worker_thread.startTask(WorkerThread::Request::ParamSaveDefault);
} else if (((int)(cmd.param1)) == 2) {
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
answer_command(cmd, vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED);
_worker_thread.startTask(WorkerThread::Request::ParamResetAllConfig);
} else if (((int)(cmd.param1)) == 3) {
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
answer_command(cmd, vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED);
_worker_thread.startTask(WorkerThread::Request::ParamResetSensorFactory);
} else if (((int)(cmd.param1)) == 4) {
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
answer_command(cmd, vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED);
_worker_thread.startTask(WorkerThread::Request::ParamResetAll);
}
}
@ -1631,11 +1630,11 @@ Commander::handle_command(const vehicle_command_s &cmd)
default:
/* Warn about unsupported commands, this makes sense because only commands
* to this component ID (or all) are passed by mavlink. */
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_UNSUPPORTED);
answer_command(cmd, vehicle_command_ack_s::VEHICLE_CMD_RESULT_UNSUPPORTED);
break;
}
if (cmd_result != vehicle_command_s::VEHICLE_CMD_RESULT_UNSUPPORTED) {
if (cmd_result != vehicle_command_ack_s::VEHICLE_CMD_RESULT_UNSUPPORTED) {
/* already warned about unsupported commands in "default" case */
answer_command(cmd, cmd_result);
}
@ -1647,11 +1646,11 @@ unsigned
Commander::handle_command_motor_test(const vehicle_command_s &cmd)
{
if (_arm_state_machine.isArmed() || (_safety.isButtonAvailable() && !_safety.isSafetyOff())) {
return vehicle_command_s::VEHICLE_CMD_RESULT_DENIED;
return vehicle_command_ack_s::VEHICLE_CMD_RESULT_DENIED;
}
if (_param_com_mot_test_en.get() != 1) {
return vehicle_command_s::VEHICLE_CMD_RESULT_DENIED;
return vehicle_command_ack_s::VEHICLE_CMD_RESULT_DENIED;
}
test_motor_s test_motor{};
@ -1661,13 +1660,13 @@ Commander::handle_command_motor_test(const vehicle_command_s &cmd)
int throttle_type = (int)(cmd.param2 + 0.5f);
if (throttle_type != 0) { // 0: MOTOR_TEST_THROTTLE_PERCENT
return vehicle_command_s::VEHICLE_CMD_RESULT_UNSUPPORTED;
return vehicle_command_ack_s::VEHICLE_CMD_RESULT_UNSUPPORTED;
}
int motor_count = (int)(cmd.param5 + 0.5);
if (motor_count > 1) {
return vehicle_command_s::VEHICLE_CMD_RESULT_UNSUPPORTED;
return vehicle_command_ack_s::VEHICLE_CMD_RESULT_UNSUPPORTED;
}
test_motor.action = test_motor_s::ACTION_RUN;
@ -1688,18 +1687,18 @@ Commander::handle_command_motor_test(const vehicle_command_s &cmd)
test_motor.driver_instance = 0; // the mavlink command does not allow to specify the instance, so set to 0 for now
_test_motor_pub.publish(test_motor);
return vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
return vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED;
}
unsigned
Commander::handle_command_actuator_test(const vehicle_command_s &cmd)
{
if (_arm_state_machine.isArmed() || (_safety.isButtonAvailable() && !_safety.isSafetyOff())) {
return vehicle_command_s::VEHICLE_CMD_RESULT_DENIED;
return vehicle_command_ack_s::VEHICLE_CMD_RESULT_DENIED;
}
if (_param_com_mot_test_en.get() != 1) {
return vehicle_command_s::VEHICLE_CMD_RESULT_DENIED;
return vehicle_command_ack_s::VEHICLE_CMD_RESULT_DENIED;
}
actuator_test_s actuator_test{};
@ -1719,7 +1718,7 @@ Commander::handle_command_actuator_test(const vehicle_command_s &cmd)
actuator_test.function = actuator_test.function - first_servo_function + actuator_test_s::FUNCTION_SERVO1;
} else {
return vehicle_command_s::VEHICLE_CMD_RESULT_UNSUPPORTED;
return vehicle_command_ack_s::VEHICLE_CMD_RESULT_UNSUPPORTED;
}
} else {
@ -1744,7 +1743,7 @@ Commander::handle_command_actuator_test(const vehicle_command_s &cmd)
}
_actuator_test_pub.publish(actuator_test);
return vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
return vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED;
}
void Commander::executeActionRequest(const action_request_s &action_request)
@ -3498,22 +3497,22 @@ Commander::print_reject_mode(uint8_t main_state)
void Commander::answer_command(const vehicle_command_s &cmd, uint8_t result)
{
switch (result) {
case vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED:
case vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED:
break;
case vehicle_command_s::VEHICLE_CMD_RESULT_DENIED:
case vehicle_command_ack_s::VEHICLE_CMD_RESULT_DENIED:
tune_negative(true);
break;
case vehicle_command_s::VEHICLE_CMD_RESULT_FAILED:
case vehicle_command_ack_s::VEHICLE_CMD_RESULT_FAILED:
tune_negative(true);
break;
case vehicle_command_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED:
case vehicle_command_ack_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED:
tune_negative(true);
break;
case vehicle_command_s::VEHICLE_CMD_RESULT_UNSUPPORTED:
case vehicle_command_ack_s::VEHICLE_CMD_RESULT_UNSUPPORTED:
tune_negative(true);
break;

View File

@ -339,13 +339,13 @@ bool calibrate_cancel_check(orb_advert_t *mavlink_log_pub, const hrt_abstime &ca
(int)cmd.param5 == 0 &&
(int)cmd.param6 == 0) {
command_ack.result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
command_ack.result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED;
mavlink_log_critical(mavlink_log_pub, CAL_QGC_CANCELLED_MSG);
tune_positive(true);
ret = true;
} else {
command_ack.result = vehicle_command_s::VEHICLE_CMD_RESULT_DENIED;
command_ack.result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_DENIED;
mavlink_log_critical(mavlink_log_pub, "command denied during calibration: %" PRIu32 "\t", cmd.command);
events::send<uint32_t>(events::ID("commander_cal_cmd_denied"), {events::Log::Error, events::LogInternal::Info},
"Command denied during calibration: {1}", cmd.command);

View File

@ -124,8 +124,8 @@ void FailureInjector::update()
ack.command = vehicle_command.command;
ack.from_external = false;
ack.result = supported ?
vehicle_command_ack_s::VEHICLE_RESULT_ACCEPTED :
vehicle_command_ack_s::VEHICLE_RESULT_UNSUPPORTED;
vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED :
vehicle_command_ack_s::VEHICLE_CMD_RESULT_UNSUPPORTED;
ack.timestamp = hrt_absolute_time();
_command_ack_pub.publish(ack);
}

View File

@ -390,15 +390,15 @@ void FlightModeManager::handleCommand()
&& _vehicle_status_sub.get().vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING) {
// switch to the commanded task
bool switch_succeeded = (switchTask(desired_task) == FlightTaskError::NoError);
uint8_t cmd_result = vehicle_command_ack_s::VEHICLE_RESULT_FAILED;
uint8_t cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_FAILED;
// if we are in/switched to the desired task
if (switch_succeeded) {
cmd_result = vehicle_command_ack_s::VEHICLE_RESULT_ACCEPTED;
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED;
// if the task is running apply parameters to it and see if it rejects
if (isAnyTaskActive() && !_current_task.task->applyCommandParameters(command)) {
cmd_result = vehicle_command_ack_s::VEHICLE_RESULT_DENIED;
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_DENIED;
// if we just switched and parameters are not accepted, go to failsafe
if (switch_succeeded) {

View File

@ -360,7 +360,7 @@ void InputMavlinkCmdMount::_ack_vehicle_command(const vehicle_command_s &cmd)
vehicle_command_ack.timestamp = hrt_absolute_time();
vehicle_command_ack.command = cmd.command;
vehicle_command_ack.result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
vehicle_command_ack.result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED;
vehicle_command_ack.target_system = cmd.source_system;
vehicle_command_ack.target_component = cmd.source_component;
@ -729,7 +729,7 @@ InputMavlinkGimbalV2::_process_command(ControlData &control_data, const vehicle_
break;
}
_ack_vehicle_command(vehicle_command, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
_ack_vehicle_command(vehicle_command, vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED);
return update_result;
} else if (vehicle_command.command == vehicle_command_s::VEHICLE_CMD_DO_MOUNT_CONFIGURE) {
@ -763,7 +763,7 @@ InputMavlinkGimbalV2::_process_command(ControlData &control_data, const vehicle_
}
}
_ack_vehicle_command(vehicle_command, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
_ack_vehicle_command(vehicle_command, vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED);
return UpdateResult::UpdatedActive;
} else if (vehicle_command.command ==
@ -828,7 +828,7 @@ InputMavlinkGimbalV2::_process_command(ControlData &control_data, const vehicle_
}
}();
_ack_vehicle_command(vehicle_command, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
_ack_vehicle_command(vehicle_command, vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED);
if (new_sysid_primary_control != control_data.sysid_primary_control ||
new_compid_primary_control != control_data.compid_primary_control) {
@ -861,7 +861,7 @@ InputMavlinkGimbalV2::_process_command(ControlData &control_data, const vehicle_
_set_control_data_from_set_attitude(control_data, flags, q, angular_velocity);
_ack_vehicle_command(vehicle_command,
vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED);
return UpdateResult::UpdatedActive;
@ -871,7 +871,7 @@ InputMavlinkGimbalV2::_process_command(ControlData &control_data, const vehicle_
vehicle_command.source_component,
control_data.sysid_primary_control, control_data.compid_primary_control);
_ack_vehicle_command(vehicle_command,
vehicle_command_s::VEHICLE_CMD_RESULT_DENIED);
vehicle_command_ack_s::VEHICLE_CMD_RESULT_DENIED);
return UpdateResult::UpdatedNotActive;
}

View File

@ -1160,23 +1160,23 @@ void Logger::handle_vehicle_command_update()
if (command.command == vehicle_command_s::VEHICLE_CMD_LOGGING_START) {
if ((int)(command.param1 + 0.5f) != 0) {
ack_vehicle_command(&command, vehicle_command_s::VEHICLE_CMD_RESULT_UNSUPPORTED);
ack_vehicle_command(&command, vehicle_command_ack_s::VEHICLE_CMD_RESULT_UNSUPPORTED);
} else if (can_start_mavlink_log()) {
ack_vehicle_command(&command, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
ack_vehicle_command(&command, vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED);
start_log_mavlink();
} else {
ack_vehicle_command(&command, vehicle_command_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED);
ack_vehicle_command(&command, vehicle_command_ack_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED);
}
} else if (command.command == vehicle_command_s::VEHICLE_CMD_LOGGING_STOP) {
if (_writer.is_started(LogType::Full, LogWriter::BackendMavlink)) {
ack_vehicle_command(&command, vehicle_command_s::VEHICLE_CMD_RESULT_IN_PROGRESS);
ack_vehicle_command(&command, vehicle_command_ack_s::VEHICLE_CMD_RESULT_IN_PROGRESS);
stop_log_mavlink();
}
ack_vehicle_command(&command, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
ack_vehicle_command(&command, vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED);
}
}
}

View File

@ -2339,7 +2339,7 @@ Mavlink::task_main(int argc, char *argv[])
// send positive command ack
vehicle_command_ack_s command_ack{};
command_ack.command = vehicle_cmd.command;
command_ack.result = vehicle_command_ack_s::VEHICLE_RESULT_ACCEPTED;
command_ack.result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED;
command_ack.from_external = !vehicle_cmd.from_external;
command_ack.target_system = vehicle_cmd.source_system;
command_ack.target_component = vehicle_cmd.source_component;
@ -2386,7 +2386,7 @@ Mavlink::task_main(int argc, char *argv[])
cmd_logging_start_acknowledgement = true;
} else if (command_ack.command == vehicle_command_s::VEHICLE_CMD_LOGGING_STOP
&& command_ack.result == vehicle_command_ack_s::VEHICLE_RESULT_ACCEPTED) {
&& command_ack.result == vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED) {
cmd_logging_stop_acknowledgement = true;
}
}

View File

@ -394,7 +394,7 @@ MavlinkReceiver::handle_message_command_long(mavlink_message_t *msg)
// This looks suspicously like INT32_MAX was sent in a COMMAND_LONG instead of
// a COMMAND_INT.
PX4_ERR("param5/param6 invalid of command %" PRIu16, cmd_mavlink.command);
acknowledge(msg->sysid, msg->compid, cmd_mavlink.command, vehicle_command_ack_s::VEHICLE_RESULT_DENIED);
acknowledge(msg->sysid, msg->compid, cmd_mavlink.command, vehicle_command_ack_s::VEHICLE_CMD_RESULT_DENIED);
return;
}
@ -430,7 +430,7 @@ MavlinkReceiver::handle_message_command_int(mavlink_message_t *msg)
if (cmd_mavlink.x == 0x7ff80000 && cmd_mavlink.y == 0x7ff80000) {
// This looks like NAN was by accident sent as int.
PX4_ERR("x/y invalid of command %" PRIu16, cmd_mavlink.command);
acknowledge(msg->sysid, msg->compid, cmd_mavlink.command, vehicle_command_ack_s::VEHICLE_RESULT_DENIED);
acknowledge(msg->sysid, msg->compid, cmd_mavlink.command, vehicle_command_ack_s::VEHICLE_CMD_RESULT_DENIED);
return;
}
@ -468,14 +468,14 @@ void MavlinkReceiver::handle_message_command_both(mavlink_message_t *msg, const
{
bool target_ok = evaluate_target_ok(cmd_mavlink.command, cmd_mavlink.target_system, cmd_mavlink.target_component);
bool send_ack = true;
uint8_t result = vehicle_command_ack_s::VEHICLE_RESULT_ACCEPTED;
uint8_t result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED;
uint8_t progress = 0; // TODO: should be 255, 0 for backwards compatibility
if (!target_ok) {
// Reject alien commands only if there is no forwarding or we've never seen target component before
if (!_mavlink->get_forwarding_on()
|| !_mavlink->component_was_seen(cmd_mavlink.target_system, cmd_mavlink.target_component, _mavlink)) {
acknowledge(msg->sysid, msg->compid, cmd_mavlink.command, vehicle_command_ack_s::VEHICLE_RESULT_FAILED);
acknowledge(msg->sysid, msg->compid, cmd_mavlink.command, vehicle_command_ack_s::VEHICLE_CMD_RESULT_FAILED);
}
return;
@ -500,7 +500,7 @@ void MavlinkReceiver::handle_message_command_both(mavlink_message_t *msg, const
} else if (cmd_mavlink.command == MAV_CMD_SET_MESSAGE_INTERVAL) {
if (set_message_interval((int)roundf(cmd_mavlink.param1), cmd_mavlink.param2, cmd_mavlink.param3)) {
result = vehicle_command_ack_s::VEHICLE_RESULT_FAILED;
result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_FAILED;
}
} else if (cmd_mavlink.command == MAV_CMD_GET_MESSAGE_INTERVAL) {
@ -541,7 +541,7 @@ void MavlinkReceiver::handle_message_command_both(mavlink_message_t *msg, const
send_ack = false;
} else {
result = vehicle_command_ack_s::VEHICLE_RESULT_DENIED;
result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_DENIED;
send_ack = true;
}
@ -627,7 +627,7 @@ void MavlinkReceiver::handle_message_command_both(mavlink_message_t *msg, const
if (has_module) {
// most are in progress
result = vehicle_command_ack_s::VEHICLE_RESULT_IN_PROGRESS;
result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_IN_PROGRESS;
switch (status.state) {
case autotune_attitude_control_status_s::STATE_IDLE:
@ -669,17 +669,17 @@ void MavlinkReceiver::handle_message_command_both(mavlink_message_t *msg, const
case autotune_attitude_control_status_s::STATE_COMPLETE:
progress = 100;
// ack it properly with an ACCEPTED once we're done
result = vehicle_command_ack_s::VEHICLE_RESULT_ACCEPTED;
result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED;
break;
case autotune_attitude_control_status_s::STATE_FAIL:
progress = 0;
result = vehicle_command_ack_s::VEHICLE_RESULT_FAILED;
result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_FAILED;
break;
}
} else {
result = vehicle_command_ack_s::VEHICLE_RESULT_UNSUPPORTED;
result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_UNSUPPORTED;
}
send_ack = true;
@ -698,7 +698,7 @@ void MavlinkReceiver::handle_message_command_both(mavlink_message_t *msg, const
// on a radio link
if (_mavlink->get_data_rate() < 5000) {
send_ack = true;
result = vehicle_command_ack_s::VEHICLE_RESULT_DENIED;
result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_DENIED;
_mavlink->send_statustext_critical("Not enough bandwidth to enable log streaming\t");
events::send<uint32_t>(events::ID("mavlink_log_not_enough_bw"), events::Log::Error,
"Not enough bandwidth to enable log streaming ({1} \\< 5000)", _mavlink->get_data_rate());
@ -753,7 +753,8 @@ uint8_t MavlinkReceiver::handle_request_message_command(uint16_t message_id, flo
}
}
return (message_sent ? vehicle_command_ack_s::VEHICLE_RESULT_ACCEPTED : vehicle_command_ack_s::VEHICLE_RESULT_DENIED);
return (message_sent ? vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED :
vehicle_command_ack_s::VEHICLE_CMD_RESULT_DENIED);
}

View File

@ -230,7 +230,7 @@ void Navigator::run()
// DO_GO_AROUND is currently handled by the position controller (unacknowledged)
// TODO: move DO_GO_AROUND handling to navigator
publish_vehicle_command_ack(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
publish_vehicle_command_ack(cmd, vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED);
} else if (cmd.command == vehicle_command_s::VEHICLE_CMD_DO_REPOSITION
&& _vstatus.arming_state == vehicle_status_s::ARMING_STATE_ARMED) {
@ -463,7 +463,7 @@ void Navigator::run()
PX4_WARN("planned mission landing not available");
}
publish_vehicle_command_ack(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
publish_vehicle_command_ack(cmd, vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED);
} else if (cmd.command == vehicle_command_s::VEHICLE_CMD_MISSION_START) {
if (_mission_result.valid && PX4_ISFINITE(cmd.param1) && (cmd.param1 >= 0)) {
@ -492,7 +492,7 @@ void Navigator::run()
}
// TODO: handle responses for supported DO_CHANGE_SPEED options?
publish_vehicle_command_ack(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
publish_vehicle_command_ack(cmd, vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED);
} else if (cmd.command == vehicle_command_s::VEHICLE_CMD_DO_SET_ROI
|| cmd.command == vehicle_command_s::VEHICLE_CMD_NAV_ROI
@ -534,7 +534,7 @@ void Navigator::run()
_vehicle_roi_pub.publish(_vroi);
publish_vehicle_command_ack(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
publish_vehicle_command_ack(cmd, vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED);
} else if (cmd.command == vehicle_command_s::VEHICLE_CMD_DO_VTOL_TRANSITION
&& get_vstatus()->nav_state != vehicle_status_s::NAVIGATION_STATE_AUTO_VTOL_TAKEOFF) {

View File

@ -1339,8 +1339,8 @@ void Simulator::check_failure_injections()
ack.command = vehicle_command.command;
ack.from_external = false;
ack.result = supported ?
vehicle_command_ack_s::VEHICLE_RESULT_ACCEPTED :
vehicle_command_ack_s::VEHICLE_RESULT_UNSUPPORTED;
vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED :
vehicle_command_ack_s::VEHICLE_CMD_RESULT_UNSUPPORTED;
ack.timestamp = hrt_absolute_time();
_command_ack_pub.publish(ack);
}

View File

@ -226,10 +226,10 @@ void TemperatureCompensationModule::Run()
vehicle_command_ack_s command_ack{};
if (ret == 0) {
command_ack.result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
command_ack.result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED;
} else {
command_ack.result = vehicle_command_s::VEHICLE_CMD_RESULT_FAILED;
command_ack.result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_FAILED;
}
command_ack.timestamp = hrt_absolute_time();

View File

@ -135,7 +135,7 @@ void VtolAttitudeControl::vehicle_cmd_poll()
vehicle_status_s vehicle_status{};
_vehicle_status_sub.copy(&vehicle_status);
uint8_t result = vehicle_command_ack_s::VEHICLE_RESULT_ACCEPTED;
uint8_t result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED;
const int transition_command_param1 = int(vehicle_command.param1 + 0.5f);
@ -146,7 +146,7 @@ void VtolAttitudeControl::vehicle_cmd_poll()
|| vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_RTL
|| vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_ORBIT)) {
result = vehicle_command_ack_s::VEHICLE_RESULT_TEMPORARILY_REJECTED;
result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
} else {
_transition_command = transition_command_param1;

View File

@ -139,7 +139,7 @@ int inject_failure(const FailureUnit& unit, const FailureType& type, uint8_t ins
while (hrt_elapsed_time(&command.timestamp) < 1_s) {
if (command_ack_sub.update(&ack)) {
if (ack.command == command.command) {
if (ack.result != vehicle_command_ack_s::VEHICLE_RESULT_ACCEPTED) {
if (ack.result != vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED) {
PX4_ERR("Result: %d", ack.result);
return 1;