|
225 | 225 | </entry>
|
226 | 226 | </enum>
|
227 | 227 | <enum name="MAV_FRAME">
|
228 |
| - <description>Co-ordinate frames used by MAVLink. Not all frames are supported by all commands, messages, or vehicles. |
| 228 | + <description>Coordinate frames used by MAVLink. Not all frames are supported by all commands, messages, or vehicles. |
229 | 229 |
|
230 | 230 | Global frames use the following naming conventions:
|
231 |
| - - "GLOBAL": Global co-ordinate frame with WGS84 latitude/longitude and altitude positive over mean sea level (MSL) by default. |
| 231 | + - "GLOBAL": Global coordinate frame with WGS84 latitude/longitude and altitude positive over mean sea level (MSL) by default. |
232 | 232 | The following modifiers may be used with "GLOBAL":
|
233 | 233 | - "RELATIVE_ALT": Altitude is relative to the vehicle home position rather than MSL.
|
234 | 234 | - "TERRAIN_ALT": Altitude is relative to ground level rather than MSL.
|
|
273 | 273 | </entry>
|
274 | 274 | <entry value="8" name="MAV_FRAME_BODY_NED">
|
275 | 275 | <deprecated since="2019-08" replaced_by="MAV_FRAME_BODY_FRD"/>
|
276 |
| - <description>Same as MAV_FRAME_LOCAL_NED when used to represent position values. Same as MAV_FRAME_BODY_FRD when used with velocity/accelaration values.</description> |
| 276 | + <description>Same as MAV_FRAME_LOCAL_NED when used to represent position values. Same as MAV_FRAME_BODY_FRD when used with velocity/acceleration values.</description> |
277 | 277 | </entry>
|
278 | 278 | <entry value="9" name="MAV_FRAME_BODY_OFFSET_NED">
|
279 | 279 | <deprecated since="2019-08" replaced_by="MAV_FRAME_BODY_FRD"/>
|
|
3722 | 3722 | <description>Zoom value as proportion of full camera range (a value between 0.0 and 100.0)</description>
|
3723 | 3723 | </entry>
|
3724 | 3724 | <entry value="3" name="ZOOM_TYPE_FOCAL_LENGTH">
|
3725 |
| - <description>Zoom value/variable focal length in milimetres. Note that there is no message to get the valid zoom range of the camera, so this can type can only be used for cameras where the zoom range is known (implying that this cannot reliably be used in a GCS for an arbitrary camera)</description> |
| 3725 | + <description>Zoom value/variable focal length in millimetres. Note that there is no message to get the valid zoom range of the camera, so this can type can only be used for cameras where the zoom range is known (implying that this cannot reliably be used in a GCS for an arbitrary camera)</description> |
3726 | 3726 | </entry>
|
3727 | 3727 | </enum>
|
3728 | 3728 | <enum name="SET_FOCUS_TYPE">
|
|
3761 | 3761 | <description>Parameter failed to set</description>
|
3762 | 3762 | </entry>
|
3763 | 3763 | <entry value="3" name="PARAM_ACK_IN_PROGRESS">
|
3764 |
| - <description>Parameter value received but not yet set/accepted. A subsequent PARAM_ACK_TRANSACTION or PARAM_EXT_ACK with the final result will follow once operation is completed. This is returned immediately for parameters that take longer to set, indicating taht the the parameter was recieved and does not need to be resent.</description> |
| 3764 | + <description>Parameter value received but not yet set/accepted. A subsequent PARAM_ACK_TRANSACTION or PARAM_EXT_ACK with the final result will follow once operation is completed. This is returned immediately for parameters that take longer to set, indicating that the the parameter was received and does not need to be resent.</description> |
3765 | 3765 | </entry>
|
3766 | 3766 | </enum>
|
3767 | 3767 | <enum name="CAMERA_MODE">
|
|
3965 | 3965 | <description>SIM is required for the modem but missing</description>
|
3966 | 3966 | </entry>
|
3967 | 3967 | <entry value="3" name="CELLULAR_NETWORK_FAILED_REASON_SIM_ERROR">
|
3968 |
| - <description>SIM is available, but not usuable for connection</description> |
| 3968 | + <description>SIM is available, but not usable for connection</description> |
3969 | 3969 | </entry>
|
3970 | 3970 | </enum>
|
3971 | 3971 | <enum name="CELLULAR_NETWORK_RADIO_TYPE">
|
|
4595 | 4595 | </description>
|
4596 | 4596 | </entry>
|
4597 | 4597 | <entry value="2" name="NAV_VTOL_LAND_OPTIONS_HOVER_DESCENT">
|
4598 |
| - <description>Land in multicopter mode on reaching the landing co-ordinates (the whole landing is by "hover descent").</description> |
| 4598 | + <description>Land in multicopter mode on reaching the landing coordinates (the whole landing is by "hover descent").</description> |
4599 | 4599 | </entry>
|
4600 | 4600 | </enum>
|
4601 | 4601 | <enum name="MAV_WINCH_STATUS_FLAG" bitmask="true">
|
|
4631 | 4631 | <description>Winch is redelivering the payload. This is a failover state if the line tension goes above a threshold during RETRACTING.</description>
|
4632 | 4632 | </entry>
|
4633 | 4633 | <entry value="1024" name="MAV_WINCH_STATUS_ABANDON_LINE">
|
4634 |
| - <description>Winch is abandoning the line and possibly payload. Winch unspools the entire calculated line length. This is a failover state from REDELIVER if the number of attemps exceeds a threshold.</description> |
| 4634 | + <description>Winch is abandoning the line and possibly payload. Winch unspools the entire calculated line length. This is a failover state from REDELIVER if the number of attempts exceeds a threshold.</description> |
4635 | 4635 | </entry>
|
4636 | 4636 | </enum>
|
4637 | 4637 | <enum name="MAG_CAL_STATUS">
|
|
5225 | 5225 | <field type="uint8_t" name="mission_type" enum="MAV_MISSION_TYPE">Mission type.</field>
|
5226 | 5226 | </message>
|
5227 | 5227 | <message id="48" name="SET_GPS_GLOBAL_ORIGIN">
|
5228 |
| - <description>Sets the GPS co-ordinates of the vehicle local origin (0,0,0) position. Vehicle should emit GPS_GLOBAL_ORIGIN irrespective of whether the origin is changed. This enables transform between the local coordinate frame and the global (GPS) coordinate frame, which may be necessary when (for example) indoor and outdoor settings are connected and the MAV should move from in- to outdoor.</description> |
| 5228 | + <description>Sets the GPS coordinates of the vehicle local origin (0,0,0) position. Vehicle should emit GPS_GLOBAL_ORIGIN irrespective of whether the origin is changed. This enables transform between the local coordinate frame and the global (GPS) coordinate frame, which may be necessary when (for example) indoor and outdoor settings are connected and the MAV should move from in- to outdoor.</description> |
5229 | 5229 | <field type="uint8_t" name="target_system">System ID</field>
|
5230 | 5230 | <field type="int32_t" name="latitude" units="degE7">Latitude (WGS84)</field>
|
5231 | 5231 | <field type="int32_t" name="longitude" units="degE7">Longitude (WGS84)</field>
|
|
5234 | 5234 | <field type="uint64_t" name="time_usec" units="us">Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.</field>
|
5235 | 5235 | </message>
|
5236 | 5236 | <message id="49" name="GPS_GLOBAL_ORIGIN">
|
5237 |
| - <description>Publishes the GPS co-ordinates of the vehicle local origin (0,0,0) position. Emitted whenever a new GPS-Local position mapping is requested or set - e.g. following SET_GPS_GLOBAL_ORIGIN message.</description> |
| 5237 | + <description>Publishes the GPS coordinates of the vehicle local origin (0,0,0) position. Emitted whenever a new GPS-Local position mapping is requested or set - e.g. following SET_GPS_GLOBAL_ORIGIN message.</description> |
5238 | 5238 | <field type="int32_t" name="latitude" units="degE7">Latitude (WGS84)</field>
|
5239 | 5239 | <field type="int32_t" name="longitude" units="degE7">Longitude (WGS84)</field>
|
5240 | 5240 | <field type="int32_t" name="altitude" units="mm">Altitude (MSL). Positive for up.</field>
|
|
5804 | 5804 | </message>
|
5805 | 5805 | <message id="109" name="RADIO_STATUS">
|
5806 | 5806 | <description>Status generated by radio and injected into MAVLink stream.</description>
|
5807 |
| - <field type="uint8_t" name="rssi" invalid="UINT8_MAX">Local (message sender) recieved signal strength indication in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown.</field> |
| 5807 | + <field type="uint8_t" name="rssi" invalid="UINT8_MAX">Local (message sender) received signal strength indication in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown.</field> |
5808 | 5808 | <field type="uint8_t" name="remrssi" invalid="UINT8_MAX">Remote (message receiver) signal strength indication in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown.</field>
|
5809 | 5809 | <field type="uint8_t" name="txbuf" units="%">Remaining free transmitter buffer space.</field>
|
5810 | 5810 | <field type="uint8_t" name="noise" invalid="UINT8_MAX">Local background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], UINT8_MAX: invalid/unknown.</field>
|
|
5831 | 5831 | </message>
|
5832 | 5832 | <message id="113" name="HIL_GPS">
|
5833 | 5833 | <description>The global position, as returned by the Global Positioning System (GPS). This is
|
5834 |
| - NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION_INT for the global position estimate.</description> |
| 5834 | + NOT the global position estimate of the system, but rather a RAW sensor value. See message GLOBAL_POSITION_INT for the global position estimate.</description> |
5835 | 5835 | <field type="uint64_t" name="time_usec" units="us">Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.</field>
|
5836 | 5836 | <field type="uint8_t" name="fix_type">0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.</field>
|
5837 | 5837 | <field type="int32_t" name="lat" units="degE7">Latitude (WGS84)</field>
|
|
7336 | 7336 | <field type="uint8_t[64]" name="data">Frame data</field>
|
7337 | 7337 | </message>
|
7338 | 7338 | <message id="388" name="CAN_FILTER_MODIFY">
|
7339 |
| - <description>Modify the filter of what CAN messages to forward over the mavlink. This can be used to make CAN forwarding work well on low bandwith links. The filtering is applied on bits 8 to 24 of the CAN id (2nd and 3rd bytes) which corresponds to the DroneCAN message ID for DroneCAN. Filters with more than 16 IDs can be constructed by sending multiple CAN_FILTER_MODIFY messages.</description> |
| 7339 | + <description>Modify the filter of what CAN messages to forward over the mavlink. This can be used to make CAN forwarding work well on low bandwidth links. The filtering is applied on bits 8 to 24 of the CAN id (2nd and 3rd bytes) which corresponds to the DroneCAN message ID for DroneCAN. Filters with more than 16 IDs can be constructed by sending multiple CAN_FILTER_MODIFY messages.</description> |
7340 | 7340 | <field type="uint8_t" name="target_system">System ID.</field>
|
7341 | 7341 | <field type="uint8_t" name="target_component">Component ID.</field>
|
7342 | 7342 | <field type="uint8_t" name="bus">bus number</field>
|
|
7459 | 7459 | <field type="uint8_t" name="target_system">System ID (0 for broadcast).</field>
|
7460 | 7460 | <field type="uint8_t" name="target_component">Component ID (0 for broadcast).</field>
|
7461 | 7461 | <field type="uint8_t[20]" name="id_or_mac">Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. </field>
|
7462 |
| - <field type="uint8_t" name="single_message_size" units="bytes">This field must currently always be equal to 25 (bytes), since all encoded OpenDroneID messages are specificed to have this length.</field> |
| 7462 | + <field type="uint8_t" name="single_message_size" units="bytes">This field must currently always be equal to 25 (bytes), since all encoded OpenDroneID messages are specified to have this length.</field> |
7463 | 7463 | <field type="uint8_t" name="msg_pack_size">Number of encoded messages in the pack (not the number of bytes). Allowed range is 1 - 9.</field>
|
7464 | 7464 | <field type="uint8_t[225]" name="messages">Concatenation of encoded OpenDroneID messages. Shall be filled with nulls in the unused portion of the field.</field>
|
7465 | 7465 | </message>
|
|
0 commit comments