|
1063 | 1063 | <description>Erase all mission data stored on the vehicle (both persistent and volatile storage)</description>
|
1064 | 1064 | </entry>
|
1065 | 1065 | </enum>
|
| 1066 | + <enum name="REBOOT_SHUTDOWN_CONDITIONS"> |
| 1067 | + <description>Specifies the conditions under which the MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN command should be accepted.</description> |
| 1068 | + <entry value="0" name="REBOOT_SHUTDOWN_CONDITIONS_SAFETY_INTERLOCKED"> |
| 1069 | + <description>Reboot/Shutdown only if allowed by safety checks, such as being landed.</description> |
| 1070 | + </entry> |
| 1071 | + <entry value="20190226" name="REBOOT_SHUTDOWN_CONDITIONS_FORCE"> |
| 1072 | + <description>Force reboot/shutdown of the autopilot/component regardless of system state.</description> |
| 1073 | + </entry> |
| 1074 | + </enum> |
1066 | 1075 | <!-- The MAV_CMD enum entries describe either: -->
|
1067 | 1076 | <!-- * the data payload of mission items (as used in the MISSION_ITEM_INT message) -->
|
1068 | 1077 | <!-- * the data payload of mavlink commands (as used in the COMMAND_INT and COMMAND_LONG messages) -->
|
|
1564 | 1573 | <param index="1" label="Speed" units="m/s" minValue="-1">Ground speed, less than 0 (-1) for default</param>
|
1565 | 1574 | <param index="2" label="Bitmask" enum="MAV_DO_REPOSITION_FLAGS">Bitmask of option flags.</param>
|
1566 | 1575 | <param index="3" label="Radius" units="m">Loiter radius for planes. Positive values only, direction is controlled by Yaw value. A value of zero or NaN is ignored. </param>
|
1567 |
| - <param index="4" label="Yaw" units="deg">Yaw heading. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.). For planes indicates loiter direction (0: clockwise, 1: counter clockwise)</param> |
| 1576 | + <param index="4" label="Yaw" units="rad">Yaw heading. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.). For planes indicates loiter direction (0: clockwise, 1: counter clockwise)</param> |
1568 | 1577 | <param index="5" label="Latitude">Latitude</param>
|
1569 | 1578 | <param index="6" label="Longitude">Longitude</param>
|
1570 | 1579 | <param index="7" label="Altitude" units="m">Altitude</param>
|
|
1908 | 1917 | <param index="3" label="Component action" minValue="0" maxValue="3" increment="1">0: Do nothing for component, 1: Reboot component, 2: Shutdown component, 3: Reboot component and keep it in the bootloader until upgraded</param>
|
1909 | 1918 | <param index="4" label="Component ID" minValue="0" maxValue="255" increment="1">MAVLink Component ID targeted in param3 (0 for all components).</param>
|
1910 | 1919 | <param index="5">Reserved (set to 0)</param>
|
1911 |
| - <param index="6">Reserved (set to 0)</param> |
| 1920 | + <param index="6" label="Conditions" enum="REBOOT_SHUTDOWN_CONDITIONS">Conditions under which reboot/shutdown is allowed.</param> |
1912 | 1921 | <param index="7">WIP: ID (e.g. camera ID -1 for all IDs)</param>
|
1913 | 1922 | </entry>
|
1914 | 1923 | <!-- id "247" reserved for MAV_CMD_DO_UPGRADE in development.xml -->
|
|
3908 | 3917 | <description>Zoom one step increment (-1 for wide, 1 for tele)</description>
|
3909 | 3918 | </entry>
|
3910 | 3919 | <entry value="1" name="ZOOM_TYPE_CONTINUOUS">
|
3911 |
| - <description>Continuous zoom up/down until stopped (-1 for wide, 1 for tele, 0 to stop zooming)</description> |
| 3920 | + <description>Continuous normalized zoom in/out rate until stopped. Range -1..1, negative: wide, positive: narrow/tele, 0 to stop zooming. Other values should be clipped to the range.</description> |
3912 | 3921 | </entry>
|
3913 | 3922 | <entry value="2" name="ZOOM_TYPE_RANGE">
|
3914 | 3923 | <description>Zoom value as proportion of full camera range (a percentage value between 0.0 and 100.0)</description>
|
|
3926 | 3935 | <description>Focus one step increment (-1 for focusing in, 1 for focusing out towards infinity).</description>
|
3927 | 3936 | </entry>
|
3928 | 3937 | <entry value="1" name="FOCUS_TYPE_CONTINUOUS">
|
3929 |
| - <description>Continuous focus up/down until stopped (-1 for focusing in, 1 for focusing out towards infinity, 0 to stop focusing)</description> |
| 3938 | + <description>Continuous normalized focus in/out rate until stopped. Range -1..1, negative: in, positive: out towards infinity, 0 to stop focusing. Other values should be clipped to the range.</description> |
3930 | 3939 | </entry>
|
3931 | 3940 | <entry value="2" name="FOCUS_TYPE_RANGE">
|
3932 | 3941 | <description>Focus value as proportion of full camera focus range (a value between 0.0 and 100.0)</description>
|
|
5275 | 5284 | <field type="uint32_t" name="onboard_control_sensors_health_extended" enum="MAV_SYS_STATUS_SENSOR_EXTENDED" print_format="0x%04x">Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy.</field>
|
5276 | 5285 | </message>
|
5277 | 5286 | <message id="2" name="SYSTEM_TIME">
|
5278 |
| - <description>The system time is the time of the master clock, typically the computer clock of the main onboard computer.</description> |
| 5287 | + <description>The system time is the time of the master clock. |
| 5288 | + This can be emitted by flight controllers, onboard computers, or other components in the MAVLink network. |
| 5289 | + Components that are using a less reliable time source, such as a battery-backed real time clock, can choose to match their system clock to that of a SYSTEM_TYPE that indicates a more recent time. |
| 5290 | + This allows more broadly accurate date stamping of logs, and so on. |
| 5291 | + If precise time synchronization is needed then use TIMESYNC instead.</description> |
5279 | 5292 | <field type="uint64_t" name="time_unix_usec" units="us">Timestamp (UNIX epoch time).</field>
|
5280 | 5293 | <field type="uint32_t" name="time_boot_ms" units="ms">Timestamp (time since system boot).</field>
|
5281 | 5294 | </message>
|
|
5599 | 5612 | <description>
|
5600 | 5613 | Message that announces the sequence number of the current target mission item (that the system will fly towards/execute when the mission is running).
|
5601 | 5614 | This message should be streamed all the time (nominally at 1Hz).
|
5602 |
| - This message should be emitted following a call to MAV_CMD_DO_SET_MISSION_CURRENT or SET_MISSION_CURRENT. |
| 5615 | + This message should be emitted following a call to MAV_CMD_DO_SET_MISSION_CURRENT or MISSION_SET_CURRENT. |
5603 | 5616 | </description>
|
5604 | 5617 | <field type="uint16_t" name="seq">Sequence</field>
|
5605 | 5618 | <extensions/>
|
|
0 commit comments