|
1932 | 1932 | <param index="6" label="Pitch Angle" units="deg" minValue="-180" maxValue="180" default="0">Fixed pitch angle that the camera will hold in oblique mode if the mount is actuated in the pitch axis.</param>
|
1933 | 1933 | <param index="7">Empty</param>
|
1934 | 1934 | </entry>
|
| 1935 | + <entry value="262" name="MAV_CMD_DO_SET_STANDARD_MODE" hasLocation="false" isDestination="false"> |
| 1936 | + <description>Enable the specified standard MAVLink mode. |
| 1937 | + If the specified mode is not supported, the vehicle should ACK with MAV_RESULT_FAILED. |
| 1938 | + See https://mavlink.io/en/services/standard_modes.html |
| 1939 | + </description> |
| 1940 | + <param index="1" label="Standard Mode" enum="MAV_STANDARD_MODE">The mode to set.</param> |
| 1941 | + <param index="2" reserved="true" default="0"/> |
| 1942 | + <param index="3" reserved="true" default="0"/> |
| 1943 | + <param index="4" reserved="true" default="0"/> |
| 1944 | + <param index="5" reserved="true" default="0"/> |
| 1945 | + <param index="6" reserved="true" default="0"/> |
| 1946 | + <param index="7" reserved="true" default="NaN"/> |
| 1947 | + </entry> |
1935 | 1948 | <entry value="300" name="MAV_CMD_MISSION_START" hasLocation="false" isDestination="false">
|
1936 | 1949 | <description>start running a mission</description>
|
1937 | 1950 | <param index="1" label="First Item" minValue="0" increment="1">first_item: the first mission item to run</param>
|
|
5137 | 5150 | <description>Illuminator thermistor failure.</description>
|
5138 | 5151 | </entry>
|
5139 | 5152 | </enum>
|
| 5153 | + <enum name="MAV_STANDARD_MODE"> |
| 5154 | + <description>Standard modes with a well understood meaning across flight stacks and vehicle types. |
| 5155 | + For example, most flight stack have the concept of a "return" or "RTL" mode that takes a vehicle to safety, even though the precise mechanics of this mode may differ. |
| 5156 | + The modes supported by a flight stack can be queried using AVAILABLE_MODES and set using MAV_CMD_DO_SET_STANDARD_MODE. |
| 5157 | + The current mode is streamed in CURRENT_MODE. |
| 5158 | + See https://mavlink.io/en/services/standard_modes.html |
| 5159 | + </description> |
| 5160 | + <entry value="0" name="MAV_STANDARD_MODE_NON_STANDARD"> |
| 5161 | + <description>Non standard mode. |
| 5162 | + This may be used when reporting the mode if the current flight mode is not a standard mode. |
| 5163 | + </description> |
| 5164 | + </entry> |
| 5165 | + <entry value="1" name="MAV_STANDARD_MODE_POSITION_HOLD"> |
| 5166 | + <description>Position mode (manual). |
| 5167 | + Position-controlled and stabilized manual mode. |
| 5168 | + When sticks are released vehicles return to their level-flight orientation and hold both position and altitude against wind and external forces. |
| 5169 | + This mode can only be set by vehicles that can hold a fixed position. |
| 5170 | + Multicopter (MC) vehicles actively brake and hold both position and altitude against wind and external forces. |
| 5171 | + Hybrid MC/FW ("VTOL") vehicles first transition to multicopter mode (if needed) but otherwise behave in the same way as MC vehicles. |
| 5172 | + Fixed-wing (FW) vehicles must not support this mode. |
| 5173 | + Other vehicle types must not support this mode (this may be revisited through the PR process). |
| 5174 | + </description> |
| 5175 | + </entry> |
| 5176 | + <entry value="2" name="MAV_STANDARD_MODE_ORBIT"> |
| 5177 | + <description>Orbit (manual). |
| 5178 | + Position-controlled and stabilized manual mode. |
| 5179 | + The vehicle circles around a fixed setpoint in the horizontal plane at a particular radius, altitude, and direction. |
| 5180 | + Flight stacks may further allow manual control over the setpoint position, radius, direction, speed, and/or altitude of the circle, but this is not mandated. |
| 5181 | + Flight stacks may support the [MAV_CMD_DO_ORBIT](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_ORBIT) for changing the orbit parameters. |
| 5182 | + MC and FW vehicles may support this mode. |
| 5183 | + Hybrid MC/FW ("VTOL") vehicles may support this mode in MC/FW or both modes; if the mode is not supported by the current configuration the vehicle should transition to the supported configuration. |
| 5184 | + Other vehicle types must not support this mode (this may be revisited through the PR process). |
| 5185 | + </description> |
| 5186 | + </entry> |
| 5187 | + <entry value="3" name="MAV_STANDARD_MODE_CRUISE"> |
| 5188 | + <description>Cruise mode (manual). |
| 5189 | + Position-controlled and stabilized manual mode. |
| 5190 | + When sticks are released vehicles return to their level-flight orientation and hold their original track against wind and external forces. |
| 5191 | + Fixed-wing (FW) vehicles level orientation and maintain current track and altitude against wind and external forces. |
| 5192 | + Hybrid MC/FW ("VTOL") vehicles first transition to FW mode (if needed) but otherwise behave in the same way as MC vehicles. |
| 5193 | + Multicopter (MC) vehicles must not support this mode. |
| 5194 | + Other vehicle types must not support this mode (this may be revisited through the PR process). |
| 5195 | + </description> |
| 5196 | + </entry> |
| 5197 | + <entry value="4" name="MAV_STANDARD_MODE_ALTITUDE_HOLD"> |
| 5198 | + <description>Altitude hold (manual). |
| 5199 | + Altitude-controlled and stabilized manual mode. |
| 5200 | + When sticks are released vehicles return to their level-flight orientation and hold their altitude. |
| 5201 | + MC vehicles continue with existing momentum and may move with wind (or other external forces). |
| 5202 | + FW vehicles continue with current heading, but may be moved off-track by wind. |
| 5203 | + Hybrid MC/FW ("VTOL") vehicles behave according to their current configuration/mode (FW or MC). |
| 5204 | + Other vehicle types must not support this mode (this may be revisited through the PR process). |
| 5205 | + </description> |
| 5206 | + </entry> |
| 5207 | + <entry value="5" name="MAV_STANDARD_MODE_SAFE_RECOVERY"> |
| 5208 | + <description>Safe recovery mode (auto). |
| 5209 | + Automatic mode that takes vehicle to a predefined safe location via a safe flight path, and may also automatically land the vehicle. |
| 5210 | + This mode is more commonly referred to as RTL and/or or Smart RTL. |
| 5211 | + The precise return location, flight path, and landing behaviour depend on vehicle configuration and type. |
| 5212 | + For example, the vehicle might return to the home/launch location, a rally point, or the start of a mission landing, it might follow a direct path, mission path, or breadcrumb path, and land using a mission landing pattern or some other kind of descent. |
| 5213 | + </description> |
| 5214 | + </entry> |
| 5215 | + <entry value="6" name="MAV_STANDARD_MODE_MISSION"> |
| 5216 | + <description>Mission mode (automatic). |
| 5217 | + Automatic mode that executes MAVLink missions. |
| 5218 | + Missions are executed from the current waypoint as soon as the mode is enabled. |
| 5219 | + </description> |
| 5220 | + </entry> |
| 5221 | + <entry value="7" name="MAV_STANDARD_MODE_LAND"> |
| 5222 | + <description>Land mode (auto). |
| 5223 | + Automatic mode that lands the vehicle at the current location. |
| 5224 | + The precise landing behaviour depends on vehicle configuration and type. |
| 5225 | + </description> |
| 5226 | + </entry> |
| 5227 | + <entry value="8" name="MAV_STANDARD_MODE_TAKEOFF"> |
| 5228 | + <description>Takeoff mode (auto). |
| 5229 | + Automatic takeoff mode. |
| 5230 | + The precise takeoff behaviour depends on vehicle configuration and type. |
| 5231 | + </description> |
| 5232 | + </entry> |
| 5233 | + </enum> |
5140 | 5234 | <enum name="HIL_ACTUATOR_CONTROLS_FLAGS" bitmask="true">
|
5141 | 5235 | <description>Flags used in HIL_ACTUATOR_CONTROLS message.</description>
|
5142 | 5236 | <entry value="1" name="HIL_ACTUATOR_CONTROLS_FLAGS_LOCKSTEP">
|
5143 | 5237 | <description>Simulation is using lockstep</description>
|
5144 | 5238 | </entry>
|
5145 | 5239 | </enum>
|
| 5240 | + <enum name="MAV_MODE_PROPERTY" bitmask="true"> |
| 5241 | + <description>Mode properties. |
| 5242 | + </description> |
| 5243 | + <entry value="1" name="MAV_MODE_PROPERTY_ADVANCED"> |
| 5244 | + <description>If set, this mode is an advanced mode. |
| 5245 | + For example a rate-controlled manual mode might be advanced, whereas a position-controlled manual mode is not. |
| 5246 | + A GCS can optionally use this flag to configure the UI for its intended users. |
| 5247 | + </description> |
| 5248 | + </entry> |
| 5249 | + <entry value="2" name="MAV_MODE_PROPERTY_NOT_USER_SELECTABLE"> |
| 5250 | + <description>If set, this mode should not be added to the list of selectable modes. |
| 5251 | + The mode might still be selected by the FC directly (for example as part of a failsafe). |
| 5252 | + </description> |
| 5253 | + </entry> |
| 5254 | + </enum> |
5146 | 5255 | </enums>
|
5147 | 5256 | <messages>
|
5148 | 5257 | <message id="1" name="SYS_STATUS">
|
|
7800 | 7909 | <field type="uint16_t" name="sequence_oldest_available">Oldest Sequence number that is still available after the sequence set in REQUEST_EVENT.</field>
|
7801 | 7910 | <field type="uint8_t" name="reason" enum="MAV_EVENT_ERROR_REASON">Error reason.</field>
|
7802 | 7911 | </message>
|
| 7912 | + <message id="435" name="AVAILABLE_MODES"> |
| 7913 | + <description>Information about a flight mode. |
| 7914 | + |
| 7915 | + The message can be enumerated to get information for all modes, or requested for a particular mode, using MAV_CMD_REQUEST_MESSAGE. |
| 7916 | + Specify 0 in param2 to request that the message is emitted for all available modes or the specific index for just one mode. |
| 7917 | + The modes must be available/settable for the current vehicle/frame type. |
| 7918 | + Each mode should only be emitted once (even if it is both standard and custom). |
| 7919 | + Note that the current mode should be emitted in CURRENT_MODE, and that if the mode list can change then AVAILABLE_MODES_MONITOR must be emitted on first change and subsequently streamed. |
| 7920 | + See https://mavlink.io/en/services/standard_modes.html |
| 7921 | + </description> |
| 7922 | + <field type="uint8_t" name="number_modes">The total number of available modes for the current vehicle type.</field> |
| 7923 | + <field type="uint8_t" name="mode_index">The current mode index within number_modes, indexed from 1. The index is not guaranteed to be persistent, and may change between reboots or if the set of modes change.</field> |
| 7924 | + <field type="uint8_t" name="standard_mode" enum="MAV_STANDARD_MODE">Standard mode.</field> |
| 7925 | + <field type="uint32_t" name="custom_mode">A bitfield for use for autopilot-specific flags</field> |
| 7926 | + <field type="uint32_t" name="properties" enum="MAV_MODE_PROPERTY">Mode properties.</field> |
| 7927 | + <field type="char[35]" name="mode_name">Name of custom mode, with null termination character. Should be omitted for standard modes.</field> |
| 7928 | + </message> |
| 7929 | + <message id="436" name="CURRENT_MODE"> |
| 7930 | + <description>Get the current mode. |
| 7931 | + This should be emitted on any mode change, and broadcast at low rate (nominally 0.5 Hz). |
| 7932 | + It may be requested using MAV_CMD_REQUEST_MESSAGE. |
| 7933 | + See https://mavlink.io/en/services/standard_modes.html |
| 7934 | + </description> |
| 7935 | + <field type="uint8_t" name="standard_mode" enum="MAV_STANDARD_MODE">Standard mode.</field> |
| 7936 | + <field type="uint32_t" name="custom_mode">A bitfield for use for autopilot-specific flags</field> |
| 7937 | + <field type="uint32_t" name="intended_custom_mode" invalid="0">The custom_mode of the mode that was last commanded by the user (for example, with MAV_CMD_DO_SET_STANDARD_MODE, MAV_CMD_DO_SET_MODE or via RC). This should usually be the same as custom_mode. It will be different if the vehicle is unable to enter the intended mode, or has left that mode due to a failsafe condition. 0 indicates the intended custom mode is unknown/not supplied</field> |
| 7938 | + </message> |
| 7939 | + <message id="437" name="AVAILABLE_MODES_MONITOR"> |
| 7940 | + <description>A change to the sequence number indicates that the set of AVAILABLE_MODES has changed. |
| 7941 | + A receiver must re-request all available modes whenever the sequence number changes. |
| 7942 | + This is only emitted after the first change and should then be broadcast at low rate (nominally 0.3 Hz) and on change. |
| 7943 | + See https://mavlink.io/en/services/standard_modes.html |
| 7944 | + </description> |
| 7945 | + <field type="uint8_t" name="seq">Sequence number. The value iterates sequentially whenever AVAILABLE_MODES changes (e.g. support for a new mode is added/removed dynamically).</field> |
| 7946 | + </message> |
7803 | 7947 | <message id="440" name="ILLUMINATOR_STATUS">
|
7804 | 7948 | <description>Illuminator status</description>
|
7805 | 7949 | <field type="uint32_t" name="uptime_ms" units="ms">Time since the start-up of the illuminator in ms</field>
|
|
0 commit comments