Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Sync with upstream master | Thu Sep 28 17:01:46 UTC 2023 #232

Merged
merged 3 commits into from
Oct 12, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 0 additions & 4 deletions message_definitions/v1.0/ardupilotmega.xml
Original file line number Diff line number Diff line change
Expand Up @@ -23,10 +23,6 @@
<entry value="0" name="HEADING_TYPE_COURSE_OVER_GROUND"/>
<entry value="1" name="HEADING_TYPE_HEADING"/>
</enum>
<enum name="SPEED_TYPE">
<entry value="0" name="SPEED_TYPE_AIRSPEED"/>
<entry value="1" name="SPEED_TYPE_GROUNDSPEED"/>
</enum>
<!-- ardupilot specific MAV_CMD_* commands -->
<enum name="MAV_CMD">
<!-- 200 to 214 used by common.xml -->
Expand Down
53 changes: 47 additions & 6 deletions message_definitions/v1.0/common.xml
Original file line number Diff line number Diff line change
Expand Up @@ -1399,8 +1399,8 @@
<param index="7">Empty</param>
</entry>
<entry value="178" name="MAV_CMD_DO_CHANGE_SPEED" hasLocation="false" isDestination="false">
<description>Change speed and/or throttle set points. The value persists until it is overridden or there is a mode change.</description>
<param index="1" label="Speed Type" minValue="0" maxValue="3" increment="1">Speed type (0=Airspeed, 1=Ground Speed, 2=Climb Speed, 3=Descent Speed)</param>
<description>Change speed and/or throttle set points. The value persists until it is overridden or there is a mode change</description>
<param index="1" label="Speed Type" enum="SPEED_TYPE">Speed type of value set in param2 (such as airspeed, ground speed, and so on)</param>
<param index="2" label="Speed" units="m/s" minValue="-2">Speed (-1 indicates no change, -2 indicates return to default vehicle speed)</param>
<param index="3" label="Throttle" units="%" minValue="-2">Throttle (-1 indicates no change, -2 indicates return to default vehicle throttle value)</param>
<param index="4" reserved="true" default="0"/>
Expand Down Expand Up @@ -2117,8 +2117,21 @@
<param index="7" label="Gimbal device ID">Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).</param>
</entry>
<entry value="2000" name="MAV_CMD_IMAGE_START_CAPTURE" hasLocation="false" isDestination="false">
<description>Start image capture sequence. Sends CAMERA_IMAGE_CAPTURED after each capture. Use NaN for reserved values.</description>
<param index="1">Reserved (Set to 0)</param>
<description>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.
</description>
<param index="1" label="id" minValue="0" maxValue="255" increment="1">Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras that don't have a distinct component id (such as autopilot-attached cameras). 0: all cameras. This is used to specifically target autopilot-connected cameras or individual sensors in a multi-sensor MAVLink camera. It is also used to target specific cameras when the MAV_CMD is used in a mission</param>
<param index="2" label="Interval" units="s" minValue="0">Desired elapsed time between two consecutive pictures (in seconds). Minimum values depend on hardware (typically greater than 2 seconds).</param>
<param index="3" label="Total Images" minValue="0" increment="1">Total number of images to capture. 0 to capture forever/until MAV_CMD_IMAGE_STOP_CAPTURE.</param>
<param index="4" label="Sequence Number" minValue="1" increment="1">Capture sequence number starting from 1. This is only valid for single-capture (param3 == 1), otherwise set to 0. Increment the capture ID for each capture command to prevent double captures when a command is re-transmitted.</param>
Expand All @@ -2127,8 +2140,21 @@
<param index="7" reserved="true" default="NaN"/>
</entry>
<entry value="2001" name="MAV_CMD_IMAGE_STOP_CAPTURE" hasLocation="false" isDestination="false">
<description>Stop image capture sequence Use NaN for reserved values.</description>
<param index="1">Reserved (Set to 0)</param>
<description>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.
</description>
<param index="1" label="id" minValue="0" maxValue="255" increment="1">Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras that don't have a distinct component id (such as autopilot-attached cameras). 0: all cameras. This is used to specifically target autopilot-connected cameras or individual sensors in a multi-sensor MAVLink camera. It is also used to target specific cameras when the MAV_CMD is used in a mission</param>
<param index="2" reserved="true" default="NaN"/>
<param index="3" reserved="true" default="NaN"/>
<param index="4" reserved="true" default="NaN"/>
Expand Down Expand Up @@ -3433,6 +3459,21 @@
<description>The aircraft should immediately transition into guided. This should not be set for follow me applications</description>
</entry>
</enum>
<enum name="SPEED_TYPE">
<description>Speed setpoint types used in MAV_CMD_DO_CHANGE_SPEED</description>
<entry value="0" name="SPEED_TYPE_AIRSPEED">
<description>Airspeed</description>
</entry>
<entry value="1" name="SPEED_TYPE_GROUNDSPEED">
<description>Groundspeed</description>
</entry>
<entry value="2" name="SPEED_TYPE_CLIMB_SPEED">
<description>Climb speed</description>
</entry>
<entry value="3" name="SPEED_TYPE_DESCENT_SPEED">
<description>Descent speed</description>
</entry>
</enum>
<!-- ESTIMATOR_STATUS_FLAGS - these values should be bit-and with the messages flags field to know if flag has been set -->
<enum name="ESTIMATOR_STATUS_FLAGS" bitmask="true">
<description>Flags in ESTIMATOR_STATUS message</description>
Expand Down
Loading