px4-firmware/msg/VehicleCommand.msg

185 lines
23 KiB
Plaintext
Raw Normal View History

# 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
uint16 VEHICLE_CMD_CUSTOM_2 = 2 # test command
uint16 VEHICLE_CMD_NAV_WAYPOINT = 16 # Navigate to MISSION. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached)| 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude|
uint16 VEHICLE_CMD_NAV_LOITER_UNLIM = 17 # Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude|
uint16 VEHICLE_CMD_NAV_LOITER_TURNS = 18 # Loiter around this MISSION for X turns |Turns| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude|
uint16 VEHICLE_CMD_NAV_LOITER_TIME = 19 # Loiter around this MISSION for X seconds |Seconds (decimal)| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude|
uint16 VEHICLE_CMD_NAV_RETURN_TO_LAUNCH = 20 # Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| 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_FIGUREEIGHT = 35 # Start flying on the outline of a figure eight defined by the parameters. |Major Radius [m] |Minor Radius [m] |Velocity [m/s] |Orientation |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|
uint16 VEHICLE_CMD_NAV_VTOL_LAND = 85 # Transition to MC and land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude|
uint16 VEHICLE_CMD_NAV_GUIDED_LIMITS = 90 # 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_NAV_GUIDED_MASTER = 91 # set id of master controller |System ID| Component ID| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_NAV_DELAY = 93 # Delay the next navigation command a number of seconds or until a specified time |Delay in seconds (decimal, -1 to enable time-of-day fields)| hour (24h format, UTC, -1 to ignore)| minute (24h format, UTC, -1 to ignore)| second (24h format, UTC)| Empty| Empty| Empty|
uint16 VEHICLE_CMD_NAV_LAST = 95 # NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_CONDITION_DELAY = 112 # Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty|
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_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|
uint16 VEHICLE_CMD_DO_CHANGE_SPEED = 178 # Change speed and/or throttle set points. |Speed type (0=Airspeed, 1=Ground Speed)| Speed (m/s, -1 indicates no change)| Throttle ( Percent, -1 indicates no change)| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_SET_HOME = 179 # Changes the home location either to the current location or a specified location. |Use current (1=use current location, 0=use specified location)| Empty| Empty| Empty| Latitude| Longitude| Altitude|
uint16 VEHICLE_CMD_DO_SET_PARAMETER = 180 # Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. |Parameter number| Parameter value| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_SET_RELAY = 181 # Set a relay to a condition. |Relay number| Setting (1=on, 0=off, others possible depending on system hardware)| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_REPEAT_RELAY = 182 # Cycle a relay on and off for a desired number of cycles with a desired period. |Relay number| Cycle count| Cycle time (seconds, decimal)| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_REPEAT_SERVO = 184 # Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_FLIGHTTERMINATION = 185 # Terminate flight immediately |Flight termination activated if > 0.5| Empty| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_CHANGE_ALTITUDE = 186 # Set the vehicle to Loiter mode and change the altitude to specified value |Altitude| Frame of new altitude | Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_SET_ACTUATOR = 187 # Sets actuators (e.g. servos) to a desired value. |Actuator 1| Actuator 2| Actuator 3| Actuator 4| Actuator 5| Actuator 6| Index|
uint16 VEHICLE_CMD_DO_LAND_START = 189 # Mission command to perform a landing. This is used as a marker in a mission to tell the autopilot where a sequence of mission items that represents a landing starts. It may also be sent via a COMMAND_LONG to trigger a landing, in which case the nearest (geographically) landing sequence in the mission will be used. The Latitude/Longitude is optional, and may be set to 0/0 if not needed. If specified then it will be used to help find the closest landing sequence. |Empty| Empty| Empty| Empty| Latitude| Longitude| Empty|
uint16 VEHICLE_CMD_DO_GO_AROUND = 191 # Mission command to safely abort an autonomous 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|
2018-01-22 15:49:36 -04:00
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_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|
uint16 VEHICLE_CMD_DO_SET_CAM_TRIGG_DIST=206 # Mission command to set TRIG_DIST for this flight |Camera trigger distance (meters)| Shutter integration time (ms)| Empty| Empty| Empty| Empty| Empty|
uint16 VEHICLE_CMD_DO_FENCE_ENABLE=207 # Mission command to enable the geofence |enable? (0=disable, 1=enable)| Empty| Empty| Empty| Empty| Empty| Empty|
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|
Implement Pacakge delivery via Gripper during mission This feature allows user to use a Gripper type pacakge delivery mechanism on a drone to trigger the delivery during a mission via the mission item `DO_GRIPPER`. This is a minimal change that is intended to have simplest pacakge delivery feature on PX4, however the future scope would extend this feature out of Navigator, and rather move towards a federated PX4 (flight-mode flexibility) architecture. But until then, this will serve the purpose. Update Tools/sitl_gazebo submodule to remove sdf file overwrite error - There was an error happening due to .sdf file being overwritten, it was caused by a wrongfully added. sdf file. - This update pulls in the PR commit: https://github.com/Auterion/sitl_gazebo/pull/147 Initial cut on supporing PAYLOAD_PLACE mission item Tidy and comment on navigation.h to clarify mission item definition - Convert vehicle command ack subscription data type to SubscriptionData, to not care about having a dedicated struct for copying the latest data - Tidy and comment on navigation.h to clarify the definition of mission_item_s, which is confusing as it is an intergration of MAVLink Standard into PX4's internal Mission Item structure Rename mission_block's mission item reached function & cleanup navigator - Isolated Handle Vehicle Commands function inside the Navigator - Rename mission_block's mission item reached function to 'reached or completed', as the navigation command can also be an action (e.g. DO_SET_SERVO, which doesn't make sense to refer to as 'reached' when we have successfully done executed the command) Include MAVLink PR commit to include payload_drop message More changes to add payload_drop MAVLink message support - Comitting for testing purposes Add mission item payload_drop to vehicle command payload drop link - Now with a mission item with the nav_cmd set to 'payload drop', the appropriate 'payload drop' vehicle command will be issued Make Payload drop executable via Mission Plan Implement payload_drop module to simulate payload delivery - Simple module that acknowledges the payload drop vehicle command after certain time, to simulate a successful delivery Additional changes - payload drop module not working yet - Need to do more thread stuff to make it work :( Fix Payload Drop enum mismatch in vehicle_command enums - First functional Payload Drop Implementation MVP - Simple Ack & resuming mission from Navigator tested successfully Hold the position while executing payload drop mission item - Still the position hold is not solid, maybe I am missing something in the position setpoint part and all the internal implications of Navigator :( Add DO_WINCH command support Some fixes after rebase on develop branch - Some missed brackets - Some comment edits, etc Add DO_WINCH command support - Still has a problem of flying away from the waypoint while the DO_WINCH is being executed, probably position setpoint related stuff :( Apply braking of the vehicle for DO_WINCH command - Copies the behavior of NAV_CMD_DELAY, which executes a smooth, braking behavior when executing the delay because of the braking condition in `set_mission_items` function - This will not apply to Fixed wings - The payload deploy getting triggered may be too early, as right now as soon as the vehicle approaches the waypoint within the acceptance threshold, the payload gets deployed Add DO_GRIPPER support Implement Gripper actual Hardware triggering support - Currently not working, possibly in the mixer there's a bug - Implemented the publishing of actuator_controls_1 uORB topic - Implemented the test command for the payload_drop module, to test the grpiper functionality - Edited px4board file to include the payload_drop module - Added Holybro X500 V2 airframe file, to enable testing on X500 V2 - Created new Quad X Payload Delivery mixer, which maps the actuator controls 1 topic's data into the MAIN pin 5 output Make Payload Drop Gripper Work - Initialization of the Gripper position to CLOSED on Constructor of the payload_drop module - Setting the OPEN and CLOSED value to the appropriate actuator controls input Set vehicle_command_ack message's timestamp correctly - By not setting the timestamp, the ack commands were not correctly graphed in PlotJuggler! Rename payload drop module to payload deliverer - I think it's a more complex name (harder to type), but more generic Add Gripper class (WIP) Add Gripper class functionalities - Add gripper uORB message - Add gripper state machine Use Gripper class as main interface in payload_deliverer - Utilizes Gripper class functions for doing Gripper functionality Remove mixer based package delivery trigger logic - Remove custom mixer files that mapped actuator controls to outputs statically Additional improvements of the payload_deliverer Fix payload_deliverer module not starting - _task_id wasn't geting set appropriately in task_spawn function, which led to runtime failure Add Gripper Function to mixer_module - Still not showing up as function mapping in QGC, needs fix Add parameters to control gripper behavior - Now user can enable / disable gripper - Also select which type of gripper to use Applying review from nuno Remove timeout fetching from mission item and use gripper's timeout - Previously, it was planned to use a custom DO_GRIPPER and DO_WINCH MAVLink message definitions with information on timeout, but since now we are using original message definition, only relevant timeout information is defined in the payload_deliverer class - This change brings in the timeout parameter to the Navigator, which then sets the timeout in the mission_block class level, which then processes the timeout logic Make payload deployment work for Allmend test :P Support gripper open/close test commands in payload_deliverer Move enum definition for GRIPPER_ACTION to vehicle_command.msg Remove double call for ` ${R}etc/init.d/rc.vehicle_setup` - Was introduced during the rebase - Was causing module already running & uORB topic can't be advertised errors Fix format via `make format` command Modify S500 airframe file to use for control allocation usage - Added Control allocation related parameters as default to not have it reset every time the airframe is selected Implement mission specific payload deploy timeout and more changes Switch payload_deliverer to run on work queue Remove unnecessary files - Airframe changes from enabling control allocation are removed Address review comments - Remove debug messages - Remove unnecessary or verbose comments & code - Properly call parameter_update() function Switch payload_deliverer to scheduled interval work item & refactor - Switch to Schedeuled on Interval Work Item, as previous vehicle command subscription callback based behavior led to vehicle comamnd ack not being sent accordingly (since the Run() wouldn't be called unless there's a new vehicle command), leading to ack command not being sent out - Also, old vehicle commands were getting fetched due to the subscription callback as well, which was removed with this patch - Fix the wrong population of floating point param2 field of vehicle command by int8_t type gripper action by creating dedicated function - Refactor and add comments to increase readability Add gripper::grabbing() method and handle this in parameter update - Previously, the intermediate state 'grabbing' was not considered, and when the parameter update was called after the first initialization of the gripper, the grab() function was being called again, which would produce unnecessary duplicate vehicle command. - Also replaced direct .grab() access to sending vehicle comamnd, which unifies the gripper actuation mechanism through vehicle commands. Navigator: Change SubscriptionData to Subscription to reduce memory usage - Also removed unused vehicle command ack sub PayloadDeliverer: Remove unnecessary changes & Bring back vehicle_command sub cb
2022-06-03 10:14:36 -03:00
uint16 VEHICLE_CMD_DO_GRIPPER = 211 # Command to operate a gripper
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 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
Support for gimbal v2 protocol - add command to request a message - add gimbal attitude message mavlink_receiver handle GIMBAL_MANAGER_SET_ATTITUDE first implementation of new vmount input MavlinkGimbalV2 - setup class - decode gimbal_manager_set_attitude in ControlData add gimbal information message add gimbal manager information and vehicle command ack mavlink messages: add stream for GIMBAL_MANAGER_INFORMATION mavlink_receiver: handle GIMBAL_DEVICE_INFORMATION remove mavlink cmd handling from vmount input MavlinkGimbalV2 complete gimbal manager: - send out fake gimbal_device_information for dummy gimbals - complete ROI handling with nudging small fixes fix typos cleanup - gimbal device information - flags lock - check sanity of string add support for CMD_DO_GIMBAL_MANAGER_ATTITUDE stream GimbalDeviceAttitudeStatus for dummy gimbals - add uROB gimbal_attitude_status - fill status in vmount output_rc for dummy gimbals not able to send the status themselves - stream mavlink GimbalDeviceAttitudeStatus better handle the request for gimbal infomation request clean up bring gimbal information back on vmount init add new gimbal message to mavlink normal stream fix publication of gimbal device information rename gimbal_attitude_status to gimbal_device_attitude_status stream gimbal_manager_status at 5Hz mavlink: send information only on request Sending the information message once on request should now work and we don't need to keep publishing it. mavlink: debug output for now make sure to copy over control data mavlink: add missing copyright header, pragma once mavlink: address review comments mavlink: handle stream not updated Our answer does not just depend on whether the stream was found but whether we actually were able to send out an update. mavlink: remove outdated comment vmount: add option for yaw stabilization only The stabilize flag is used for gimbals which do not have an internal IMU and need the autopilot's attitude in order to do stabilization. These gimbals are probably quite rare by now but it makes sense to keep the functionality given it can e.g. be used by simple servo gimbals for sensors other than highres cameras. The stabilize flag can also be re-used for gimbals which are capable of stabilizing pitch and roll but not absolute yaw (e.g. locked to North). For such gimbals we can now set the param MNT_DO_STAB to 2. We still support configuring which axes are stabilized by the MAVLink command DO_MOUNT_CONFIGURE, however, this is generally not recommended anymore. vmount: fix incorrect check for bit flag mavlink_messages: remove debug message Signed-off-by: Claudio Micheli <claudio@auterion.com> use device id remove debug print gimbal attitude fix mistake clang tidy fix split: - gimbal_attitude -> gimbal_device_set_attitude, gimbal_manager_set_attitude - gimbal_information -> gimbal_device_informatio, gimbal_manager_information add gimbal protocol messages to rtps msg ids support set attitude for gimbal directly speaking mavlink clean up gimbal urob messages vmount: address a few small review comments vmount: split output into v1 and v2 protocol This way we can continue to support the MAVLink v1 protocol. Also, we don't send the old vehicle commands when actually using the new v2 protocol. vmount: config via ctor instead of duplicate param vmount: use loop to poll all topics Otherwise we might give up too soon and miss some data, or run too fast based on commands that have nothing to do with the gimbal. typhoon_h480: use gimbal v2 protocol, use yaw stab Let's by default use the v2 protocol with typhoon_h480 and enable yaw lock mode by stabilizing yaw.
2020-05-12 05:32:16 -03:00
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|
uint16 VEHICLE_CMD_CONFIGURE_ACTUATOR = 311 # Actuator configuration command|configuration|Empty|Empty|Empty|output function|
uint16 VEHICLE_CMD_COMPONENT_ARM_DISARM = 400 # Arms / Disarms a component |1 to arm, 0 to disarm
uint16 VEHICLE_CMD_RUN_PREARM_CHECKS = 401 # Instructs a target system to run pre-arm checks.
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_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_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_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.
Implement Pacakge delivery via Gripper during mission This feature allows user to use a Gripper type pacakge delivery mechanism on a drone to trigger the delivery during a mission via the mission item `DO_GRIPPER`. This is a minimal change that is intended to have simplest pacakge delivery feature on PX4, however the future scope would extend this feature out of Navigator, and rather move towards a federated PX4 (flight-mode flexibility) architecture. But until then, this will serve the purpose. Update Tools/sitl_gazebo submodule to remove sdf file overwrite error - There was an error happening due to .sdf file being overwritten, it was caused by a wrongfully added. sdf file. - This update pulls in the PR commit: https://github.com/Auterion/sitl_gazebo/pull/147 Initial cut on supporing PAYLOAD_PLACE mission item Tidy and comment on navigation.h to clarify mission item definition - Convert vehicle command ack subscription data type to SubscriptionData, to not care about having a dedicated struct for copying the latest data - Tidy and comment on navigation.h to clarify the definition of mission_item_s, which is confusing as it is an intergration of MAVLink Standard into PX4's internal Mission Item structure Rename mission_block's mission item reached function & cleanup navigator - Isolated Handle Vehicle Commands function inside the Navigator - Rename mission_block's mission item reached function to 'reached or completed', as the navigation command can also be an action (e.g. DO_SET_SERVO, which doesn't make sense to refer to as 'reached' when we have successfully done executed the command) Include MAVLink PR commit to include payload_drop message More changes to add payload_drop MAVLink message support - Comitting for testing purposes Add mission item payload_drop to vehicle command payload drop link - Now with a mission item with the nav_cmd set to 'payload drop', the appropriate 'payload drop' vehicle command will be issued Make Payload drop executable via Mission Plan Implement payload_drop module to simulate payload delivery - Simple module that acknowledges the payload drop vehicle command after certain time, to simulate a successful delivery Additional changes - payload drop module not working yet - Need to do more thread stuff to make it work :( Fix Payload Drop enum mismatch in vehicle_command enums - First functional Payload Drop Implementation MVP - Simple Ack & resuming mission from Navigator tested successfully Hold the position while executing payload drop mission item - Still the position hold is not solid, maybe I am missing something in the position setpoint part and all the internal implications of Navigator :( Add DO_WINCH command support Some fixes after rebase on develop branch - Some missed brackets - Some comment edits, etc Add DO_WINCH command support - Still has a problem of flying away from the waypoint while the DO_WINCH is being executed, probably position setpoint related stuff :( Apply braking of the vehicle for DO_WINCH command - Copies the behavior of NAV_CMD_DELAY, which executes a smooth, braking behavior when executing the delay because of the braking condition in `set_mission_items` function - This will not apply to Fixed wings - The payload deploy getting triggered may be too early, as right now as soon as the vehicle approaches the waypoint within the acceptance threshold, the payload gets deployed Add DO_GRIPPER support Implement Gripper actual Hardware triggering support - Currently not working, possibly in the mixer there's a bug - Implemented the publishing of actuator_controls_1 uORB topic - Implemented the test command for the payload_drop module, to test the grpiper functionality - Edited px4board file to include the payload_drop module - Added Holybro X500 V2 airframe file, to enable testing on X500 V2 - Created new Quad X Payload Delivery mixer, which maps the actuator controls 1 topic's data into the MAIN pin 5 output Make Payload Drop Gripper Work - Initialization of the Gripper position to CLOSED on Constructor of the payload_drop module - Setting the OPEN and CLOSED value to the appropriate actuator controls input Set vehicle_command_ack message's timestamp correctly - By not setting the timestamp, the ack commands were not correctly graphed in PlotJuggler! Rename payload drop module to payload deliverer - I think it's a more complex name (harder to type), but more generic Add Gripper class (WIP) Add Gripper class functionalities - Add gripper uORB message - Add gripper state machine Use Gripper class as main interface in payload_deliverer - Utilizes Gripper class functions for doing Gripper functionality Remove mixer based package delivery trigger logic - Remove custom mixer files that mapped actuator controls to outputs statically Additional improvements of the payload_deliverer Fix payload_deliverer module not starting - _task_id wasn't geting set appropriately in task_spawn function, which led to runtime failure Add Gripper Function to mixer_module - Still not showing up as function mapping in QGC, needs fix Add parameters to control gripper behavior - Now user can enable / disable gripper - Also select which type of gripper to use Applying review from nuno Remove timeout fetching from mission item and use gripper's timeout - Previously, it was planned to use a custom DO_GRIPPER and DO_WINCH MAVLink message definitions with information on timeout, but since now we are using original message definition, only relevant timeout information is defined in the payload_deliverer class - This change brings in the timeout parameter to the Navigator, which then sets the timeout in the mission_block class level, which then processes the timeout logic Make payload deployment work for Allmend test :P Support gripper open/close test commands in payload_deliverer Move enum definition for GRIPPER_ACTION to vehicle_command.msg Remove double call for ` ${R}etc/init.d/rc.vehicle_setup` - Was introduced during the rebase - Was causing module already running & uORB topic can't be advertised errors Fix format via `make format` command Modify S500 airframe file to use for control allocation usage - Added Control allocation related parameters as default to not have it reset every time the airframe is selected Implement mission specific payload deploy timeout and more changes Switch payload_deliverer to run on work queue Remove unnecessary files - Airframe changes from enabling control allocation are removed Address review comments - Remove debug messages - Remove unnecessary or verbose comments & code - Properly call parameter_update() function Switch payload_deliverer to scheduled interval work item & refactor - Switch to Schedeuled on Interval Work Item, as previous vehicle command subscription callback based behavior led to vehicle comamnd ack not being sent accordingly (since the Run() wouldn't be called unless there's a new vehicle command), leading to ack command not being sent out - Also, old vehicle commands were getting fetched due to the subscription callback as well, which was removed with this patch - Fix the wrong population of floating point param2 field of vehicle command by int8_t type gripper action by creating dedicated function - Refactor and add comments to increase readability Add gripper::grabbing() method and handle this in parameter update - Previously, the intermediate state 'grabbing' was not considered, and when the parameter update was called after the first initialization of the gripper, the grab() function was being called again, which would produce unnecessary duplicate vehicle command. - Also replaced direct .grab() access to sending vehicle comamnd, which unifies the gripper actuation mechanism through vehicle commands. Navigator: Change SubscriptionData to Subscription to reduce memory usage - Also removed unused vehicle command ack sub PayloadDeliverer: Remove unnecessary changes & Bring back vehicle_command sub cb
2022-06-03 10:14:36 -03:00
uint16 VEHICLE_CMD_DO_WINCH = 42600 # Command to operate winch.
# PX4 vehicle commands (beyond 16 bit mavlink commands)
uint32 VEHICLE_CMD_PX4_INTERNAL_START = 65537 # start of PX4 internal only vehicle commands (> UINT16_MAX)
2022-07-27 01:33:16 -03:00
uint32 VEHICLE_CMD_SET_GPS_GLOBAL_ORIGIN = 100000 # Sets the GPS coordinates of the vehicle local origin (0,0,0) position. |Empty|Empty|Empty|Empty|Latitude|Longitude|Altitude|
uint32 VEHICLE_CMD_SET_NAV_STATE = 100001 # Change mode by specifying nav_state directly. |nav_state|Empty|Empty|Empty|Empty|Empty|Empty|
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_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 PARACHUTE_ACTION_DISABLE = 0
uint8 PARACHUTE_ACTION_ENABLE = 1
uint8 PARACHUTE_ACTION_RELEASE = 2
uint8 FAILURE_UNIT_SENSOR_GYRO = 0
uint8 FAILURE_UNIT_SENSOR_ACCEL = 1
uint8 FAILURE_UNIT_SENSOR_MAG = 2
uint8 FAILURE_UNIT_SENSOR_BARO = 3
uint8 FAILURE_UNIT_SENSOR_GPS = 4
uint8 FAILURE_UNIT_SENSOR_OPTICAL_FLOW = 5
uint8 FAILURE_UNIT_SENSOR_VIO = 6
uint8 FAILURE_UNIT_SENSOR_DISTANCE_SENSOR = 7
uint8 FAILURE_UNIT_SENSOR_AIRSPEED = 8
uint8 FAILURE_UNIT_SYSTEM_BATTERY = 100
uint8 FAILURE_UNIT_SYSTEM_MOTOR = 101
uint8 FAILURE_UNIT_SYSTEM_SERVO = 102
uint8 FAILURE_UNIT_SYSTEM_AVOIDANCE = 103
uint8 FAILURE_UNIT_SYSTEM_RC_SIGNAL = 104
uint8 FAILURE_UNIT_SYSTEM_MAVLINK_SIGNAL = 105
uint8 FAILURE_TYPE_OK = 0
uint8 FAILURE_TYPE_OFF = 1
uint8 FAILURE_TYPE_STUCK = 2
uint8 FAILURE_TYPE_GARBAGE = 3
uint8 FAILURE_TYPE_WRONG = 4
uint8 FAILURE_TYPE_SLOW = 5
uint8 FAILURE_TYPE_DELAYED = 6
uint8 FAILURE_TYPE_INTERMITTENT = 7
# used as param1 in DO_CHANGE_SPEED command
uint8 SPEED_TYPE_AIRSPEED = 0
uint8 SPEED_TYPE_GROUNDSPEED = 1
uint8 SPEED_TYPE_CLIMB_SPEED = 2
uint8 SPEED_TYPE_DESCEND_SPEED = 3
# used as param1 in ARM_DISARM command
int8 ARMING_ACTION_DISARM = 0
int8 ARMING_ACTION_ARM = 1
Implement Pacakge delivery via Gripper during mission This feature allows user to use a Gripper type pacakge delivery mechanism on a drone to trigger the delivery during a mission via the mission item `DO_GRIPPER`. This is a minimal change that is intended to have simplest pacakge delivery feature on PX4, however the future scope would extend this feature out of Navigator, and rather move towards a federated PX4 (flight-mode flexibility) architecture. But until then, this will serve the purpose. Update Tools/sitl_gazebo submodule to remove sdf file overwrite error - There was an error happening due to .sdf file being overwritten, it was caused by a wrongfully added. sdf file. - This update pulls in the PR commit: https://github.com/Auterion/sitl_gazebo/pull/147 Initial cut on supporing PAYLOAD_PLACE mission item Tidy and comment on navigation.h to clarify mission item definition - Convert vehicle command ack subscription data type to SubscriptionData, to not care about having a dedicated struct for copying the latest data - Tidy and comment on navigation.h to clarify the definition of mission_item_s, which is confusing as it is an intergration of MAVLink Standard into PX4's internal Mission Item structure Rename mission_block's mission item reached function & cleanup navigator - Isolated Handle Vehicle Commands function inside the Navigator - Rename mission_block's mission item reached function to 'reached or completed', as the navigation command can also be an action (e.g. DO_SET_SERVO, which doesn't make sense to refer to as 'reached' when we have successfully done executed the command) Include MAVLink PR commit to include payload_drop message More changes to add payload_drop MAVLink message support - Comitting for testing purposes Add mission item payload_drop to vehicle command payload drop link - Now with a mission item with the nav_cmd set to 'payload drop', the appropriate 'payload drop' vehicle command will be issued Make Payload drop executable via Mission Plan Implement payload_drop module to simulate payload delivery - Simple module that acknowledges the payload drop vehicle command after certain time, to simulate a successful delivery Additional changes - payload drop module not working yet - Need to do more thread stuff to make it work :( Fix Payload Drop enum mismatch in vehicle_command enums - First functional Payload Drop Implementation MVP - Simple Ack & resuming mission from Navigator tested successfully Hold the position while executing payload drop mission item - Still the position hold is not solid, maybe I am missing something in the position setpoint part and all the internal implications of Navigator :( Add DO_WINCH command support Some fixes after rebase on develop branch - Some missed brackets - Some comment edits, etc Add DO_WINCH command support - Still has a problem of flying away from the waypoint while the DO_WINCH is being executed, probably position setpoint related stuff :( Apply braking of the vehicle for DO_WINCH command - Copies the behavior of NAV_CMD_DELAY, which executes a smooth, braking behavior when executing the delay because of the braking condition in `set_mission_items` function - This will not apply to Fixed wings - The payload deploy getting triggered may be too early, as right now as soon as the vehicle approaches the waypoint within the acceptance threshold, the payload gets deployed Add DO_GRIPPER support Implement Gripper actual Hardware triggering support - Currently not working, possibly in the mixer there's a bug - Implemented the publishing of actuator_controls_1 uORB topic - Implemented the test command for the payload_drop module, to test the grpiper functionality - Edited px4board file to include the payload_drop module - Added Holybro X500 V2 airframe file, to enable testing on X500 V2 - Created new Quad X Payload Delivery mixer, which maps the actuator controls 1 topic's data into the MAIN pin 5 output Make Payload Drop Gripper Work - Initialization of the Gripper position to CLOSED on Constructor of the payload_drop module - Setting the OPEN and CLOSED value to the appropriate actuator controls input Set vehicle_command_ack message's timestamp correctly - By not setting the timestamp, the ack commands were not correctly graphed in PlotJuggler! Rename payload drop module to payload deliverer - I think it's a more complex name (harder to type), but more generic Add Gripper class (WIP) Add Gripper class functionalities - Add gripper uORB message - Add gripper state machine Use Gripper class as main interface in payload_deliverer - Utilizes Gripper class functions for doing Gripper functionality Remove mixer based package delivery trigger logic - Remove custom mixer files that mapped actuator controls to outputs statically Additional improvements of the payload_deliverer Fix payload_deliverer module not starting - _task_id wasn't geting set appropriately in task_spawn function, which led to runtime failure Add Gripper Function to mixer_module - Still not showing up as function mapping in QGC, needs fix Add parameters to control gripper behavior - Now user can enable / disable gripper - Also select which type of gripper to use Applying review from nuno Remove timeout fetching from mission item and use gripper's timeout - Previously, it was planned to use a custom DO_GRIPPER and DO_WINCH MAVLink message definitions with information on timeout, but since now we are using original message definition, only relevant timeout information is defined in the payload_deliverer class - This change brings in the timeout parameter to the Navigator, which then sets the timeout in the mission_block class level, which then processes the timeout logic Make payload deployment work for Allmend test :P Support gripper open/close test commands in payload_deliverer Move enum definition for GRIPPER_ACTION to vehicle_command.msg Remove double call for ` ${R}etc/init.d/rc.vehicle_setup` - Was introduced during the rebase - Was causing module already running & uORB topic can't be advertised errors Fix format via `make format` command Modify S500 airframe file to use for control allocation usage - Added Control allocation related parameters as default to not have it reset every time the airframe is selected Implement mission specific payload deploy timeout and more changes Switch payload_deliverer to run on work queue Remove unnecessary files - Airframe changes from enabling control allocation are removed Address review comments - Remove debug messages - Remove unnecessary or verbose comments & code - Properly call parameter_update() function Switch payload_deliverer to scheduled interval work item & refactor - Switch to Schedeuled on Interval Work Item, as previous vehicle command subscription callback based behavior led to vehicle comamnd ack not being sent accordingly (since the Run() wouldn't be called unless there's a new vehicle command), leading to ack command not being sent out - Also, old vehicle commands were getting fetched due to the subscription callback as well, which was removed with this patch - Fix the wrong population of floating point param2 field of vehicle command by int8_t type gripper action by creating dedicated function - Refactor and add comments to increase readability Add gripper::grabbing() method and handle this in parameter update - Previously, the intermediate state 'grabbing' was not considered, and when the parameter update was called after the first initialization of the gripper, the grab() function was being called again, which would produce unnecessary duplicate vehicle command. - Also replaced direct .grab() access to sending vehicle comamnd, which unifies the gripper actuation mechanism through vehicle commands. Navigator: Change SubscriptionData to Subscription to reduce memory usage - Also removed unused vehicle command ack sub PayloadDeliverer: Remove unnecessary changes & Bring back vehicle_command sub cb
2022-06-03 10:14:36 -03:00
# param2 in VEHICLE_CMD_DO_GRIPPER
uint8 GRIPPER_ACTION_RELEASE = 0
uint8 GRIPPER_ACTION_GRAB = 1
uint8 ORB_QUEUE_LENGTH = 8
float32 param1 # Parameter 1, as defined by MAVLink uint16 VEHICLE_CMD enum.
float32 param2 # Parameter 2, as defined by MAVLink uint16 VEHICLE_CMD enum.
float32 param3 # Parameter 3, as defined by MAVLink uint16 VEHICLE_CMD enum.
float32 param4 # Parameter 4, as defined by MAVLink uint16 VEHICLE_CMD enum.
float64 param5 # Parameter 5, as defined by MAVLink uint16 VEHICLE_CMD enum.
float64 param6 # Parameter 6, as defined by MAVLink uint16 VEHICLE_CMD enum.
float32 param7 # Parameter 7, as defined by MAVLink uint16 VEHICLE_CMD enum.
uint32 command # Command ID
uint8 target_system # System which should execute the command
uint8 target_component # Component which should execute the command, 0 for all components
uint8 source_system # System sending the command
uint16 source_component # Component / mode executor sending the command
uint8 confirmation # 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
bool from_external
uint16 COMPONENT_MODE_EXECUTOR_START = 1000
# TOPICS vehicle_command gimbal_v1_command vehicle_command_mode_executor