From 0e6d087b78c45d83429c79ec85ee1fd966ecb650 Mon Sep 17 00:00:00 2001 From: Vladimir Ermakov Date: Sun, 3 Mar 2024 09:56:31 +0100 Subject: [PATCH] re-generate with cogall.sh --- mavros_extras/mavros_plugins.xml | 2 +- mavros_msgs/msg/CommandCode.msg | 8 ++++---- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/mavros_extras/mavros_plugins.xml b/mavros_extras/mavros_plugins.xml index 66216012a..a0a7032b8 100644 --- a/mavros_extras/mavros_plugins.xml +++ b/mavros_extras/mavros_plugins.xml @@ -233,4 +233,4 @@ This plugin allows computing and publishing wheel odometry coming from FCU wheel Can use either wheel's RPM or WHEEL_DISTANCE messages (the latter gives better accuracy). - + diff --git a/mavros_msgs/msg/CommandCode.msg b/mavros_msgs/msg/CommandCode.msg index 4ba3d661b..00fd7da5c 100644 --- a/mavros_msgs/msg/CommandCode.msg +++ b/mavros_msgs/msg/CommandCode.msg @@ -38,7 +38,7 @@ uint16 DO_FOLLOW = 32 # Begin following a target uint16 DO_FOLLOW_REPOSITION = 33 # Reposition the MAV after a follow target command has been sent uint16 DO_SET_MODE = 176 # Set system mode. uint16 DO_JUMP = 177 # Jump to the desired command in the mission list. Repeat this action only the specified number of times -uint16 DO_CHANGE_SPEED = 178 # Change speed and/or throttle set points. +uint16 DO_CHANGE_SPEED = 178 # Change speed and/or throttle set points uint16 DO_SET_HOME = 179 # Changes the home location either to the current location or a specified location. uint16 DO_SET_PARAMETER = 180 # Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. uint16 DO_SET_RELAY = 181 # Set a relay to a condition. @@ -93,8 +93,8 @@ uint16 GET_HOME_POSITION = 410 # Request the home position f uint16 GET_MESSAGE_INTERVAL = 510 # Request the interval between messages for a particular MAVLink message ID. The receiver should ACK the command and then emit its response in a MESSAGE_INTERVAL message. # MAV_CMD_IMAGE -uint16 IMAGE_START_CAPTURE = 2000 # Start image capture sequence. Sends CAMERA_IMAGE_CAPTURED after each capture. Use NaN for reserved values. -uint16 IMAGE_STOP_CAPTURE = 2001 # Stop image capture sequence Use NaN for reserved values. +uint16 IMAGE_START_CAPTURE = 2000 # Start image capture sequence. CAMERA_IMAGE_CAPTURED must be emitted after each capture. Param1 (id) may be used to specify the target camera: 0: all cameras, 1 to 6: autopilot-connected cameras, 7-255: MAVLink camera component ID. It is needed in order to target specific cameras connected to the autopilot, or specific sensors in a multi-sensor camera (neither of which have a distinct MAVLink component ID). It is also needed to specify the target camera in missions. When used in a mission, an autopilot should execute the MAV_CMD for a specified local camera (param1 = 1-6), or resend it as a command if it is intended for a MAVLink camera (param1 = 7 - 255), setting the command's target_component as the param1 value (and setting param1 in the command to zero). If the param1 is 0 the autopilot should do both. When sent in a command the target MAVLink address is set using target_component. If addressed specifically to an autopilot: param1 should be used in the same way as it is for missions (though command should NACK with MAV_RESULT_DENIED if a specified local camera does not exist). If addressed to a MAVLink camera, param 1 can be used to address all cameras (0), or to separately address 1 to 7 individual sensors. Other values should be NACKed with MAV_RESULT_DENIED. If the command is broadcast (target_component is 0) then param 1 should be set to 0 (any other value should be NACKED with MAV_RESULT_DENIED). An autopilot would trigger any local cameras and forward the command to all channels. +uint16 IMAGE_STOP_CAPTURE = 2001 # Stop image capture sequence. Param1 (id) may be used to specify the target camera: 0: all cameras, 1 to 6: autopilot-connected cameras, 7-255: MAVLink camera component ID. It is needed in order to target specific cameras connected to the autopilot, or specific sensors in a multi-sensor camera (neither of which have a distinct MAVLink component ID). It is also needed to specify the target camera in missions. When used in a mission, an autopilot should execute the MAV_CMD for a specified local camera (param1 = 1-6), or resend it as a command if it is intended for a MAVLink camera (param1 = 7 - 255), setting the command's target_component as the param1 value (and setting param1 in the command to zero). If the param1 is 0 the autopilot should do both. When sent in a command the target MAVLink address is set using target_component. If addressed specifically to an autopilot: param1 should be used in the same way as it is for missions (though command should NACK with MAV_RESULT_DENIED if a specified local camera does not exist). If addressed to a MAVLink camera, param1 can be used to address all cameras (0), or to separately address 1 to 7 individual sensors. Other values should be NACKed with MAV_RESULT_DENIED. If the command is broadcast (target_component is 0) then param 1 should be set to 0 (any other value should be NACKED with MAV_RESULT_DENIED). An autopilot would trigger any local cameras and forward the command to all channels. # MAV_CMD_JUMP uint16 JUMP_TAG = 600 # Tagged jump target. Can be jumped to with MAV_CMD_DO_JUMP_TAG. @@ -197,4 +197,4 @@ uint16 VIDEO_STOP_CAPTURE = 2501 # Stop the current video capt uint16 VIDEO_START_STREAMING = 2502 # Start video streaming uint16 VIDEO_STOP_STREAMING = 2503 # Stop the given video stream -# [[[end]]] (checksum: cb312f449893c76af4bf35424ccff882) +# [[[end]]] (checksum: 73ee94ac661c9fcb61528a6668f71d94)