diff --git a/ko/messages/all.md b/ko/messages/all.md index 42cc7a1f9..91dc79ebe 100644 --- a/ko/messages/all.md +++ b/ko/messages/all.md @@ -62,7 +62,7 @@ span.warning { | -------------------------- | ------- | -------- | | [Messages](#messages) | 0 | 372 | | [Enums](#enumerated-types) | 0 | 235 | -| [Commands](#mav_commands) | 217 | 0 | +| [Commands](#mav_commands) | 218 | 0 | The following sections list all entities in the dialect (both included and defined in this file). diff --git a/ko/messages/common.md b/ko/messages/common.md index ed793f439..800a02c49 100644 --- a/ko/messages/common.md +++ b/ko/messages/common.md @@ -582,7 +582,9 @@ Acknowledgment message during waypoint handling. The type field states if this m | mission_type ++ | `uint8_t` | [MAV_MISSION_TYPE](#MAV_MISSION_TYPE) | Mission type. | | opaque_id ++ | `uint32_t` | invalid:0 | Id of new on-vehicle mission, fence, or rally point plan (on upload to vehicle).
The id is calculated and returned by a vehicle when a new plan is uploaded by a GCS.
The only requirement on the id is that it must change when there is any change to the on-vehicle plan type (there is no requirement that the id be globally unique).
0 on download from the vehicle to the GCS (on download the ID is set in [MISSION_COUNT](#MISSION_COUNT)).
0 if plan ids are not supported.
The current on-vehicle plan ids are streamed in `[MISSION_CURRENT](#MISSION_CURRENT)`, allowing a GCS to determine if any part of the plan has changed and needs to be re-uploaded. | -### SET_GPS_GLOBAL_ORIGIN (48) {#SET_GPS_GLOBAL_ORIGIN} +### SET_GPS_GLOBAL_ORIGIN (48) — [DEP] {#SET_GPS_GLOBAL_ORIGIN} + +**DEPRECATED:** Replaced By [MAV_CMD_SET_GLOBAL_ORIGIN](#MAV_CMD_SET_GLOBAL_ORIGIN) (2025-04) Sets the GPS coordinates of the vehicle local origin (0,0,0) position. Vehicle should emit [GPS_GLOBAL_ORIGIN](#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. @@ -1145,12 +1147,12 @@ Sent from simulation to autopilot. The RAW values of the RC channels received. T Sent from autopilot to simulation. Hardware in the loop control outputs. Alternative to [HIL_CONTROLS](#HIL_CONTROLS). -| Field Name | Type | Units | Values | Description | -| ------------------------------ | ----------- | ----- | ------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| time_usec | `uint64_t` | 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. | -| controls | `float[16]` | | | Control outputs -1 .. 1. Channel assignment depends on the simulated hardware. | -| mode | `uint8_t` | | [MAV_MODE_FLAG](#MAV_MODE_FLAG) | System mode. Includes arming state. | -| flags | `uint64_t` | | | Flags as bitfield, 1: indicate simulation using lockstep. | +| Field Name | Type | Units | Values | Description | +| ------------------------------ | ----------- | ----- | -------------------------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| time_usec | `uint64_t` | 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. | +| controls | `float[16]` | | | Control outputs -1 .. 1. Channel assignment depends on the simulated hardware. | +| mode | `uint8_t` | | [MAV_MODE_FLAG](#MAV_MODE_FLAG) | System mode. Includes arming state. | +| flags | `uint64_t` | | [HIL_ACTUATOR_CONTROLS_FLAGS](#HIL_ACTUATOR_CONTROLS_FLAGS) | Flags bitmask. | ### OPTICAL_FLOW (100) {#OPTICAL_FLOW} @@ -1886,20 +1888,20 @@ Battery information. Updates GCS with flight controller battery status. Smart ba Version and capability of autopilot software. This should be emitted in response to a request with [MAV_CMD_REQUEST_MESSAGE](#MAV_CMD_REQUEST_MESSAGE). -| Field Name | Type | Values | Description | -| -------------------------------------------------------------------- | ------------- | --------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| capabilities | `uint64_t` | [MAV_PROTOCOL_CAPABILITY](#MAV_PROTOCOL_CAPABILITY) | Bitmap of capabilities | -| flight_sw_version | `uint32_t` | | Firmware version number | -| middleware_sw_version | `uint32_t` | | Middleware version number | -| os_sw_version | `uint32_t` | | Operating system version number | -| board_version | `uint32_t` | | HW / board version (last 8 bits should be silicon ID, if any). The first 16 bits of this field specify https://github.com/PX4/PX4-Bootloader/blob/master/board_types.txt | -| flight_custom_version | `uint8_t[8]` | | Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. | -| middleware_custom_version | `uint8_t[8]` | | Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. | -| os_custom_version | `uint8_t[8]` | | Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. | -| vendor_id | `uint16_t` | | ID of the board vendor | -| product_id | `uint16_t` | | ID of the product | -| uid | `uint64_t` | | UID if provided by hardware (see uid2) | -| uid2 ++ | `uint8_t[18]` | | UID if provided by hardware (supersedes the uid field. If this is non-zero, use this field, otherwise use uid) | +| Field Name | Type | Values | Description | +| -------------------------------------------------------------------- | ------------- | --------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | +| capabilities | `uint64_t` | [MAV_PROTOCOL_CAPABILITY](#MAV_PROTOCOL_CAPABILITY) | Bitmap of capabilities | +| flight_sw_version | `uint32_t` | | Firmware version number.
The field must be encoded as 4 bytes, where each byte (shown from MSB to LSB) is part of a semantic version: (major) (minor) (patch) ([FIRMWARE_VERSION_TYPE](#FIRMWARE_VERSION_TYPE)). | +| middleware_sw_version | `uint32_t` | | Middleware version number | +| os_sw_version | `uint32_t` | | Operating system version number | +| board_version | `uint32_t` | | HW / board version (last 8 bits should be silicon ID, if any). The first 16 bits of this field specify https://github.com/PX4/PX4-Bootloader/blob/master/board_types.txt | +| flight_custom_version | `uint8_t[8]` | | Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. | +| middleware_custom_version | `uint8_t[8]` | | Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. | +| os_custom_version | `uint8_t[8]` | | Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. | +| vendor_id | `uint16_t` | | ID of the board vendor | +| product_id | `uint16_t` | | ID of the product | +| uid | `uint64_t` | | UID if provided by hardware (see uid2) | +| uid2 ++ | `uint8_t[18]` | | UID if provided by hardware (supersedes the uid field. If this is non-zero, use this field, otherwise use uid) | ### LANDING_TARGET (149) {#LANDING_TARGET} @@ -3883,21 +3885,6 @@ Some deprecated frames do not follow these conventions (e.g. [MAV_FRAME_BODY_NED | 4 | [MAVLINK_DATA_STREAM_IMG_PGM](#MAVLINK_DATA_STREAM_IMG_PGM) | | | 5 | [MAVLINK_DATA_STREAM_IMG_PNG](#MAVLINK_DATA_STREAM_IMG_PNG) | | -### FENCE_ACTION {#FENCE_ACTION} - -Actions following geofence breach. - -| Value | Name | Description | -| ------------------------------------------ | ------------------------------------------------------------------------------------------------------------------------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| 0 | [FENCE_ACTION_NONE](#FENCE_ACTION_NONE) | Disable fenced mode. If used in a plan this would mean the next fence is disabled. | -| 1 | [FENCE_ACTION_GUIDED](#FENCE_ACTION_GUIDED) | Fly to geofence [MAV_CMD_NAV_FENCE_RETURN_POINT](#MAV_CMD_NAV_FENCE_RETURN_POINT) in GUIDED mode. Note: This action is only supported by ArduPlane, and may not be supported in all versions. | -| 2 | [FENCE_ACTION_REPORT](#FENCE_ACTION_REPORT) | Report fence breach, but don't take action | -| 3 | [FENCE_ACTION_GUIDED_THR_PASS](#FENCE_ACTION_GUIDED_THR_PASS) | Fly to geofence [MAV_CMD_NAV_FENCE_RETURN_POINT](#MAV_CMD_NAV_FENCE_RETURN_POINT) with manual throttle control in GUIDED mode. Note: This action is only supported by ArduPlane, and may not be supported in all versions. | -| 4 | [FENCE_ACTION_RTL](#FENCE_ACTION_RTL) | Return/RTL mode. | -| 5 | [FENCE_ACTION_HOLD](#FENCE_ACTION_HOLD) | Hold at current location. | -| 6 | [FENCE_ACTION_TERMINATE](#FENCE_ACTION_TERMINATE) | Termination failsafe. Motors are shut down (some flight stacks may trigger other failsafe actions). | -| 7 | [FENCE_ACTION_LAND](#FENCE_ACTION_LAND) | Land at current location. | - ### FENCE_BREACH {#FENCE_BREACH} | Value | Name | Description | @@ -3919,11 +3906,13 @@ Actions being taken to mitigate/prevent fence breach ### FENCE_TYPE {#FENCE_TYPE} -(Bitmask) +(Bitmask) Fence types to enable or disable when using [MAV_CMD_DO_FENCE_ENABLE](#MAV_CMD_DO_FENCE_ENABLE). + +Note that at least one of these flags must be set in [MAV_CMD_DO_FENCE_ENABLE](#MAV_CMD_DO_FENCE_ENABLE).param2. +If none are set, the flight stack will ignore the field and enable/disable its default set of fences (usually all of them). | Value | Name | Description | | -------------------------------- | -------------------------------------------------------------------------------------------------------- | ---------------------- | -| 0 | [FENCE_TYPE_ALL](#FENCE_TYPE_ALL) | All fence types | | 1 | [FENCE_TYPE_ALT_MAX](#FENCE_TYPE_ALT_MAX) | Maximum altitude fence | | 2 | [FENCE_TYPE_CIRCLE](#FENCE_TYPE_CIRCLE) | Circle fence | | 4 | [FENCE_TYPE_POLYGON](#FENCE_TYPE_POLYGON) | Polygon fence | @@ -4271,14 +4260,15 @@ Actuator output function. Values greater or equal to 1000 are autopilot-specific ### AUTOTUNE_AXIS {#AUTOTUNE_AXIS} -(Bitmask) Enable axes that will be tuned via autotuning. Used in [MAV_CMD_DO_AUTOTUNE_ENABLE](#MAV_CMD_DO_AUTOTUNE_ENABLE). +(Bitmask) Axes that will be autotuned by [MAV_CMD_DO_AUTOTUNE_ENABLE](#MAV_CMD_DO_AUTOTUNE_ENABLE). + +Note that at least one flag must be set in [MAV_CMD_DO_AUTOTUNE_ENABLE](#MAV_CMD_DO_AUTOTUNE_ENABLE).param2: if none are set, the flight stack will tune its default set of axes. -| Value | Name | Description | -| ----------------------------------- | ----------------------------------------------------------------------------------------- | -------------------------------------------------------------------------- | -| 0 | [AUTOTUNE_AXIS_DEFAULT](#AUTOTUNE_AXIS_DEFAULT) | Flight stack tunes axis according to its default settings. | -| 1 | [AUTOTUNE_AXIS_ROLL](#AUTOTUNE_AXIS_ROLL) | Autotune roll axis. | -| 2 | [AUTOTUNE_AXIS_PITCH](#AUTOTUNE_AXIS_PITCH) | Autotune pitch axis. | -| 4 | [AUTOTUNE_AXIS_YAW](#AUTOTUNE_AXIS_YAW) | Autotune yaw axis. | +| Value | Name | Description | +| --------------------------------- | ------------------------------------------------------------------------------------- | ------------------------------------ | +| 1 | [AUTOTUNE_AXIS_ROLL](#AUTOTUNE_AXIS_ROLL) | Autotune roll axis. | +| 2 | [AUTOTUNE_AXIS_PITCH](#AUTOTUNE_AXIS_PITCH) | Autotune pitch axis. | +| 4 | [AUTOTUNE_AXIS_YAW](#AUTOTUNE_AXIS_YAW) | Autotune yaw axis. | ### PREFLIGHT_STORAGE_PARAMETER_ACTION {#PREFLIGHT_STORAGE_PARAMETER_ACTION} @@ -5840,6 +5830,14 @@ See https://mavlink.io/en/services/standard_modes.html | 2 | [MAV_MODE_PROPERTY_NOT_USER_SELECTABLE](#MAV_MODE_PROPERTY_NOT_USER_SELECTABLE) | If set, this mode should not be added to the list of selectable modes.
The mode might still be selected by the FC directly (for example as part of a failsafe). | | 4 | [MAV_MODE_PROPERTY_AUTO_MODE](#MAV_MODE_PROPERTY_AUTO_MODE) | If set, this mode is automatically controlled (it may use but does not require a manual controller).
If unset the mode is a assumed to require user input (be a manual mode). | +### HIL_ACTUATOR_CONTROLS_FLAGS {#HIL_ACTUATOR_CONTROLS_FLAGS} + +(Bitmask) Flags used in [HIL_ACTUATOR_CONTROLS](#HIL_ACTUATOR_CONTROLS) message. + +| Value | Name | Description | +| -------------------------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------- | +| 1 | [HIL_ACTUATOR_CONTROLS_FLAGS_LOCKSTEP](#HIL_ACTUATOR_CONTROLS_FLAGS_LOCKSTEP) | Simulation is using lockstep | + ### MAV_AUTOPILOT — \[from: [minimal](../messages/minimal.md#MAV_AUTOPILOT)\] {#MAV_AUTOPILOT} Micro air vehicle / autopilot classes. This identifies the individual model. @@ -6982,15 +6980,15 @@ The persistence/lifetime of the setting is undefined. Depending on flight stack implementation it may persist until superseded, or it may revert to a system default at the end of a mission. Flight stacks typically reset the setting to system defaults on reboot. -| Param (Label) | Description | Values | -| -------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------- | -| 1 (Enable) | enable? (0=disable, 1=enable, 2=disable_floor_only) | min: 0 max: 2 inc: 1 | -| 2 (Types) | Fence types to enable or disable as a bitmask. A value of 0 indicates that all fences should be enabled or disabled. This parameter is ignored if param 1 has the value 2 | [FENCE_TYPE](#FENCE_TYPE) | -| 3 | Empty | | -| 4 | Empty | | -| 5 | Empty | | -| 6 | Empty | | -| 7 | Empty | | +| Param (Label) | Description | Values | +| -------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------- | +| 1 (Enable) | enable? (0=disable, 1=enable, 2=disable_floor_only) | min: 0 max: 2 inc: 1 | +| 2 (Types) | Fence types to enable or disable as a bitmask. 0: field is unused/all fences should be enabled or disabled (for compatiblity reasons). Parameter is ignored if param1=2. | [FENCE_TYPE](#FENCE_TYPE) | +| 3 | Empty | | +| 4 | Empty | | +| 5 | Empty | | +| 6 | Empty | | +| 7 | Empty | | ### MAV_CMD_DO_PARACHUTE (208) {#MAV_CMD_DO_PARACHUTE} @@ -7052,15 +7050,15 @@ Mission command to operate a gripper. Enable/disable autotune. -| Param (Label) | Description | Values | -| -------------------------------- | --------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------- | -| 1 (Enable) | Enable (1: enable, 0:disable). | min: 0 max: 1 inc: 1 | -| 2 (Axis) | Specify which axis are autotuned. 0 indicates autopilot default settings. | [AUTOTUNE_AXIS](#AUTOTUNE_AXIS) | -| 3 | Empty. | | -| 4 | Empty. | | -| 5 | Empty. | | -| 6 | Empty. | | -| 7 | Empty. | | +| Param (Label) | Description | Values | +| -------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | -------------------------------------------------------------------- | +| 1 (Enable) | Enable (1: enable, 0:disable). | min: 0 max: 1 inc: 1 | +| 2 (Axis) | Specify axes for which autotuning is enabled/disabled. 0 indicates the field is unused (for compatiblity reasons). If 0 the autopilot will follow its default behaviour, which is usually to tune all axes. | [AUTOTUNE_AXIS](#AUTOTUNE_AXIS) | +| 3 | Empty. | | +| 4 | Empty. | | +| 5 | Empty. | | +| 6 | Empty. | | +| 7 | Empty. | | ### MAV_CMD_NAV_SET_YAW_SPEED (213) {#MAV_CMD_NAV_SET_YAW_SPEED} diff --git a/ko/messages/development.md b/ko/messages/development.md index 310bb054d..61815cc7a 100644 --- a/ko/messages/development.md +++ b/ko/messages/development.md @@ -39,7 +39,7 @@ span.warning { | -------------------------- | ------- | -------- | | [Messages](#messages) | 12 | 229 | | [Enums](#enumerated-types) | 11 | 146 | -| [Commands](#mav_commands) | 172 | 0 | +| [Commands](#mav_commands) | 173 | 0 | The following sections list all entities in the dialect (both included and defined in this file). @@ -487,6 +487,27 @@ Recipients must reject command addressed to broadcast system ID. | 3 (Reboot) | Reboot components after ID change. Any non-zero value triggers the reboot. | | | 4 | | | +### MAV_CMD_DO_SET_GLOBAL_ORIGIN (611) — [WIP] {#MAV_CMD_DO_SET_GLOBAL_ORIGIN} + +**WORK IN PROGRESS**: Do not use in stable production environments (it may change). + +Sets the GNSS coordinates of the vehicle local origin (0,0,0) position. + +Vehicle should emit [GPS_GLOBAL_ORIGIN](#GPS_GLOBAL_ORIGIN) irrespective of whether the origin is changed. +This enables transform between the local coordinate frame and the global (GNSS) coordinate frame, which may be necessary when (for example) indoor and outdoor settings are connected and the MAV should move from in- to outdoor. +This command supersedes [SET_GPS_GLOBAL_ORIGIN](#SET_GPS_GLOBAL_ORIGIN). +Should be sent in a [COMMAND_INT](#COMMAND_INT) (Expected frame is [MAV_FRAME_GLOBAL](#MAV_FRAME_GLOBAL), and this should be assumed when sent in [COMMAND_LONG](#COMMAND_LONG)). + +| Param (Label) | Description | Units | +| -------------------------------- | ----------- | ----- | +| 1 | Empty | | +| 2 | Empty | | +| 3 | Empty | | +| 4 | Empty | | +| 5 (Latitude) | Latitude | | +| 6 (Longitude) | Longitude | | +| 7 (Altitude) | Altitude | m | + ### MAV_CMD_ODID_SET_EMERGENCY (12900) — [WIP] {#MAV_CMD_ODID_SET_EMERGENCY} **WORK IN PROGRESS**: Do not use in stable production environments (it may change). diff --git a/ko/messages/ualberta.md b/ko/messages/ualberta.md index 1cae3cb79..aee553676 100644 --- a/ko/messages/ualberta.md +++ b/ko/messages/ualberta.md @@ -116,3 +116,4 @@ Mode currently commanded by pilot | 3 | [PILOT_ROTO](#PILOT_ROTO) | Rotomotion mode | ## Commands (MAV_CMD) {#mav_commands} + diff --git a/zh/messages/all.md b/zh/messages/all.md index 17a836141..5f1317d12 100644 --- a/zh/messages/all.md +++ b/zh/messages/all.md @@ -62,7 +62,7 @@ span.warning { | -------------------------- | ------- | -------- | | [Messages](#messages) | 0 | 372 | | [Enums](#enumerated-types) | 0 | 235 | -| [Commands](#mav_commands) | 217 | 0 | +| [Commands](#mav_commands) | 218 | 0 | The following sections list all entities in the dialect (both included and defined in this file). diff --git a/zh/messages/common.md b/zh/messages/common.md index 84f5898b7..5513943fb 100644 --- a/zh/messages/common.md +++ b/zh/messages/common.md @@ -582,7 +582,9 @@ Acknowledgment message during waypoint handling. The type field states if this m | mission_type ++ | `uint8_t` | [MAV_MISSION_TYPE](#MAV_MISSION_TYPE) | Mission type. | | opaque_id ++ | `uint32_t` | invalid:0 | Id of new on-vehicle mission, fence, or rally point plan (on upload to vehicle).
The id is calculated and returned by a vehicle when a new plan is uploaded by a GCS.
The only requirement on the id is that it must change when there is any change to the on-vehicle plan type (there is no requirement that the id be globally unique).
0 on download from the vehicle to the GCS (on download the ID is set in [MISSION_COUNT](#MISSION_COUNT)).
0 if plan ids are not supported.
The current on-vehicle plan ids are streamed in `[MISSION_CURRENT](#MISSION_CURRENT)`, allowing a GCS to determine if any part of the plan has changed and needs to be re-uploaded. | -### SET_GPS_GLOBAL_ORIGIN (48) {#SET_GPS_GLOBAL_ORIGIN} +### SET_GPS_GLOBAL_ORIGIN (48) — [DEP] {#SET_GPS_GLOBAL_ORIGIN} + +**DEPRECATED:** Replaced By [MAV_CMD_SET_GLOBAL_ORIGIN](#MAV_CMD_SET_GLOBAL_ORIGIN) (2025-04) Sets the GPS coordinates of the vehicle local origin (0,0,0) position. Vehicle should emit [GPS_GLOBAL_ORIGIN](#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. @@ -1145,12 +1147,12 @@ Sent from simulation to autopilot. The RAW values of the RC channels received. T Sent from autopilot to simulation. Hardware in the loop control outputs. Alternative to [HIL_CONTROLS](#HIL_CONTROLS). -| Field Name | Type | Units | 值 | 描述 | -| ------------------------------ | ----------- | ----- | ------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| time_usec | `uint64_t` | 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. | -| controls | `float[16]` | | | Control outputs -1 .. 1. Channel assignment depends on the simulated hardware. | -| 模式 | `uint8_t` | | [MAV_MODE_FLAG](#MAV_MODE_FLAG) | System mode. Includes arming state. | -| flags | `uint64_t` | | | Flags as bitfield, 1: indicate simulation using lockstep. | +| Field Name | Type | Units | 值 | 描述 | +| ------------------------------ | ----------- | ----- | -------------------------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| time_usec | `uint64_t` | 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. | +| controls | `float[16]` | | | Control outputs -1 .. 1. Channel assignment depends on the simulated hardware. | +| 模式 | `uint8_t` | | [MAV_MODE_FLAG](#MAV_MODE_FLAG) | System mode. Includes arming state. | +| flags | `uint64_t` | | [HIL_ACTUATOR_CONTROLS_FLAGS](#HIL_ACTUATOR_CONTROLS_FLAGS) | Flags bitmask. | ### OPTICAL_FLOW (100) {#OPTICAL_FLOW} @@ -1886,20 +1888,20 @@ Battery information. Updates GCS with flight controller battery status. Smart ba Version and capability of autopilot software. This should be emitted in response to a request with [MAV_CMD_REQUEST_MESSAGE](#MAV_CMD_REQUEST_MESSAGE). -| Field Name | Type | 值 | 描述 | -| -------------------------------------------------------------------- | ------------- | --------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| capabilities | `uint64_t` | [MAV_PROTOCOL_CAPABILITY](#MAV_PROTOCOL_CAPABILITY) | Bitmap of capabilities | -| flight_sw_version | `uint32_t` | | Firmware version number | -| middleware_sw_version | `uint32_t` | | Middleware version number | -| os_sw_version | `uint32_t` | | Operating system version number | -| board_version | `uint32_t` | | HW / board version (last 8 bits should be silicon ID, if any). The first 16 bits of this field specify https://github.com/PX4/PX4-Bootloader/blob/master/board_types.txt | -| flight_custom_version | `uint8_t[8]` | | Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. | -| middleware_custom_version | `uint8_t[8]` | | Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. | -| os_custom_version | `uint8_t[8]` | | Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. | -| vendor_id | `uint16_t` | | ID of the board vendor | -| product_id | `uint16_t` | | ID of the product | -| uid | `uint64_t` | | UID if provided by hardware (see uid2) | -| uid2 ++ | `uint8_t[18]` | | UID if provided by hardware (supersedes the uid field. If this is non-zero, use this field, otherwise use uid) | +| Field Name | Type | 值 | 描述 | +| -------------------------------------------------------------------- | ------------- | --------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | +| capabilities | `uint64_t` | [MAV_PROTOCOL_CAPABILITY](#MAV_PROTOCOL_CAPABILITY) | Bitmap of capabilities | +| flight_sw_version | `uint32_t` | | Firmware version number.
The field must be encoded as 4 bytes, where each byte (shown from MSB to LSB) is part of a semantic version: (major) (minor) (patch) ([FIRMWARE_VERSION_TYPE](#FIRMWARE_VERSION_TYPE)). | +| middleware_sw_version | `uint32_t` | | Middleware version number | +| os_sw_version | `uint32_t` | | Operating system version number | +| board_version | `uint32_t` | | HW / board version (last 8 bits should be silicon ID, if any). The first 16 bits of this field specify https://github.com/PX4/PX4-Bootloader/blob/master/board_types.txt | +| flight_custom_version | `uint8_t[8]` | | Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. | +| middleware_custom_version | `uint8_t[8]` | | Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. | +| os_custom_version | `uint8_t[8]` | | Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. | +| vendor_id | `uint16_t` | | ID of the board vendor | +| product_id | `uint16_t` | | ID of the product | +| uid | `uint64_t` | | UID if provided by hardware (see uid2) | +| uid2 ++ | `uint8_t[18]` | | UID if provided by hardware (supersedes the uid field. If this is non-zero, use this field, otherwise use uid) | ### LANDING_TARGET (149) {#LANDING_TARGET} @@ -3883,21 +3885,6 @@ Some deprecated frames do not follow these conventions (e.g. [MAV_FRAME_BODY_NED | 4 | [MAVLINK_DATA_STREAM_IMG_PGM](#MAVLINK_DATA_STREAM_IMG_PGM) | | | 5 | [MAVLINK_DATA_STREAM_IMG_PNG](#MAVLINK_DATA_STREAM_IMG_PNG) | | -### FENCE_ACTION {#FENCE_ACTION} - -Actions following geofence breach. - -| 值 | Name | 描述 | -| ------------------------------------------ | ------------------------------------------------------------------------------------------------------------------------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| 0 | [FENCE_ACTION_NONE](#FENCE_ACTION_NONE) | Disable fenced mode. If used in a plan this would mean the next fence is disabled. | -| 1 | [FENCE_ACTION_GUIDED](#FENCE_ACTION_GUIDED) | Fly to geofence [MAV_CMD_NAV_FENCE_RETURN_POINT](#MAV_CMD_NAV_FENCE_RETURN_POINT) in GUIDED mode. Note: This action is only supported by ArduPlane, and may not be supported in all versions. | -| 2 | [FENCE_ACTION_REPORT](#FENCE_ACTION_REPORT) | Report fence breach, but don't take action | -| 3 | [FENCE_ACTION_GUIDED_THR_PASS](#FENCE_ACTION_GUIDED_THR_PASS) | Fly to geofence [MAV_CMD_NAV_FENCE_RETURN_POINT](#MAV_CMD_NAV_FENCE_RETURN_POINT) with manual throttle control in GUIDED mode. Note: This action is only supported by ArduPlane, and may not be supported in all versions. | -| 4 | [FENCE_ACTION_RTL](#FENCE_ACTION_RTL) | Return/RTL mode. | -| 5 | [FENCE_ACTION_HOLD](#FENCE_ACTION_HOLD) | Hold at current location. | -| 6 | [FENCE_ACTION_TERMINATE](#FENCE_ACTION_TERMINATE) | Termination failsafe. Motors are shut down (some flight stacks may trigger other failsafe actions). | -| 7 | [FENCE_ACTION_LAND](#FENCE_ACTION_LAND) | Land at current location. | - ### FENCE_BREACH {#FENCE_BREACH} | 值 | Name | 描述 | @@ -3919,11 +3906,13 @@ Actions being taken to mitigate/prevent fence breach ### FENCE_TYPE {#FENCE_TYPE} -(Bitmask) +(Bitmask) Fence types to enable or disable when using [MAV_CMD_DO_FENCE_ENABLE](#MAV_CMD_DO_FENCE_ENABLE). + +Note that at least one of these flags must be set in [MAV_CMD_DO_FENCE_ENABLE](#MAV_CMD_DO_FENCE_ENABLE).param2. +If none are set, the flight stack will ignore the field and enable/disable its default set of fences (usually all of them). | 值 | Name | 描述 | | -------------------------------- | -------------------------------------------------------------------------------------------------------- | ---------------------- | -| 0 | [FENCE_TYPE_ALL](#FENCE_TYPE_ALL) | All fence types | | 1 | [FENCE_TYPE_ALT_MAX](#FENCE_TYPE_ALT_MAX) | Maximum altitude fence | | 2 | [FENCE_TYPE_CIRCLE](#FENCE_TYPE_CIRCLE) | Circle fence | | 4 | [FENCE_TYPE_POLYGON](#FENCE_TYPE_POLYGON) | Polygon fence | @@ -4271,14 +4260,15 @@ Actuator output function. Values greater or equal to 1000 are autopilot-specific ### AUTOTUNE_AXIS {#AUTOTUNE_AXIS} -(Bitmask) Enable axes that will be tuned via autotuning. Used in [MAV_CMD_DO_AUTOTUNE_ENABLE](#MAV_CMD_DO_AUTOTUNE_ENABLE). +(Bitmask) Axes that will be autotuned by [MAV_CMD_DO_AUTOTUNE_ENABLE](#MAV_CMD_DO_AUTOTUNE_ENABLE). + +Note that at least one flag must be set in [MAV_CMD_DO_AUTOTUNE_ENABLE](#MAV_CMD_DO_AUTOTUNE_ENABLE).param2: if none are set, the flight stack will tune its default set of axes. -| 值 | Name | 描述 | -| ----------------------------------- | ----------------------------------------------------------------------------------------- | -------------------------------------------------------------------------- | -| 0 | [AUTOTUNE_AXIS_DEFAULT](#AUTOTUNE_AXIS_DEFAULT) | Flight stack tunes axis according to its default settings. | -| 1 | [AUTOTUNE_AXIS_ROLL](#AUTOTUNE_AXIS_ROLL) | Autotune roll axis. | -| 2 | [AUTOTUNE_AXIS_PITCH](#AUTOTUNE_AXIS_PITCH) | Autotune pitch axis. | -| 4 | [AUTOTUNE_AXIS_YAW](#AUTOTUNE_AXIS_YAW) | Autotune yaw axis. | +| 值 | Name | 描述 | +| --------------------------------- | ------------------------------------------------------------------------------------- | ------------------------------------ | +| 1 | [AUTOTUNE_AXIS_ROLL](#AUTOTUNE_AXIS_ROLL) | Autotune roll axis. | +| 2 | [AUTOTUNE_AXIS_PITCH](#AUTOTUNE_AXIS_PITCH) | Autotune pitch axis. | +| 4 | [AUTOTUNE_AXIS_YAW](#AUTOTUNE_AXIS_YAW) | Autotune yaw axis. | ### PREFLIGHT_STORAGE_PARAMETER_ACTION {#PREFLIGHT_STORAGE_PARAMETER_ACTION} @@ -5840,6 +5830,14 @@ See https://mavlink.io/en/services/standard_modes.html | 2 | [MAV_MODE_PROPERTY_NOT_USER_SELECTABLE](#MAV_MODE_PROPERTY_NOT_USER_SELECTABLE) | If set, this mode should not be added to the list of selectable modes.
The mode might still be selected by the FC directly (for example as part of a failsafe). | | 4 | [MAV_MODE_PROPERTY_AUTO_MODE](#MAV_MODE_PROPERTY_AUTO_MODE) | If set, this mode is automatically controlled (it may use but does not require a manual controller).
If unset the mode is a assumed to require user input (be a manual mode). | +### HIL_ACTUATOR_CONTROLS_FLAGS {#HIL_ACTUATOR_CONTROLS_FLAGS} + +(Bitmask) Flags used in [HIL_ACTUATOR_CONTROLS](#HIL_ACTUATOR_CONTROLS) message. + +| 值 | Name | 描述 | +| -------------------------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------- | +| 1 | [HIL_ACTUATOR_CONTROLS_FLAGS_LOCKSTEP](#HIL_ACTUATOR_CONTROLS_FLAGS_LOCKSTEP) | Simulation is using lockstep | + ### MAV_AUTOPILOT — \[from: [minimal](../messages/minimal.md#MAV_AUTOPILOT)\] {#MAV_AUTOPILOT} Micro air vehicle / autopilot classes. 这里标明了每个单个模型。 @@ -6982,15 +6980,15 @@ The persistence/lifetime of the setting is undefined. Depending on flight stack implementation it may persist until superseded, or it may revert to a system default at the end of a mission. Flight stacks typically reset the setting to system defaults on reboot. -| Param (Label) | 描述 | 值 | -| -------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------- | -| 1 (Enable) | enable? (0=disable, 1=enable, 2=disable_floor_only) | min: 0 max: 2 inc: 1 | -| 2 (Types) | Fence types to enable or disable as a bitmask. A value of 0 indicates that all fences should be enabled or disabled. This parameter is ignored if param 1 has the value 2 | [FENCE_TYPE](#FENCE_TYPE) | -| 3 | Empty | | -| 4 | Empty | | -| 5 | Empty | | -| 6 | Empty | | -| 7 | Empty | | +| Param (Label) | 描述 | 值 | +| -------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------- | +| 1 (Enable) | enable? (0=disable, 1=enable, 2=disable_floor_only) | min: 0 max: 2 inc: 1 | +| 2 (Types) | Fence types to enable or disable as a bitmask. 0: field is unused/all fences should be enabled or disabled (for compatiblity reasons). Parameter is ignored if param1=2. | [FENCE_TYPE](#FENCE_TYPE) | +| 3 | Empty | | +| 4 | Empty | | +| 5 | Empty | | +| 6 | Empty | | +| 7 | Empty | | ### MAV_CMD_DO_PARACHUTE (208) {#MAV_CMD_DO_PARACHUTE} @@ -7052,15 +7050,15 @@ Mission command to operate a gripper. Enable/disable autotune. -| Param (Label) | 描述 | 值 | -| -------------------------------- | --------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------- | -| 1 (Enable) | Enable (1: enable, 0:disable). | min: 0 max: 1 inc: 1 | -| 2 (Axis) | Specify which axis are autotuned. 0 indicates autopilot default settings. | [AUTOTUNE_AXIS](#AUTOTUNE_AXIS) | -| 3 | Empty. | | -| 4 | Empty. | | -| 5 | Empty. | | -| 6 | Empty. | | -| 7 | Empty. | | +| Param (Label) | 描述 | 值 | +| -------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | -------------------------------------------------------------------- | +| 1 (Enable) | Enable (1: enable, 0:disable). | min: 0 max: 1 inc: 1 | +| 2 (Axis) | Specify axes for which autotuning is enabled/disabled. 0 indicates the field is unused (for compatiblity reasons). If 0 the autopilot will follow its default behaviour, which is usually to tune all axes. | [AUTOTUNE_AXIS](#AUTOTUNE_AXIS) | +| 3 | Empty. | | +| 4 | Empty. | | +| 5 | Empty. | | +| 6 | Empty. | | +| 7 | Empty. | | ### MAV_CMD_NAV_SET_YAW_SPEED (213) {#MAV_CMD_NAV_SET_YAW_SPEED} diff --git a/zh/messages/development.md b/zh/messages/development.md index 274f4f200..1582f94a6 100644 --- a/zh/messages/development.md +++ b/zh/messages/development.md @@ -39,7 +39,7 @@ span.warning { | -------------------------- | ------- | -------- | | [Messages](#messages) | 12 | 229 | | [Enums](#enumerated-types) | 11 | 146 | -| [Commands](#mav_commands) | 172 | 0 | +| [Commands](#mav_commands) | 173 | 0 | The following sections list all entities in the dialect (both included and defined in this file). @@ -487,6 +487,27 @@ Recipients must reject command addressed to broadcast system ID. | 3 (Reboot) | Reboot components after ID change. Any non-zero value triggers the reboot. | | | 4 | | | +### MAV_CMD_DO_SET_GLOBAL_ORIGIN (611) — [WIP] {#MAV_CMD_DO_SET_GLOBAL_ORIGIN} + +**WORK IN PROGRESS**: Do not use in stable production environments (it may change). + +Sets the GNSS coordinates of the vehicle local origin (0,0,0) position. + +Vehicle should emit [GPS_GLOBAL_ORIGIN](#GPS_GLOBAL_ORIGIN) irrespective of whether the origin is changed. +This enables transform between the local coordinate frame and the global (GNSS) coordinate frame, which may be necessary when (for example) indoor and outdoor settings are connected and the MAV should move from in- to outdoor. +This command supersedes [SET_GPS_GLOBAL_ORIGIN](#SET_GPS_GLOBAL_ORIGIN). +Should be sent in a [COMMAND_INT](#COMMAND_INT) (Expected frame is [MAV_FRAME_GLOBAL](#MAV_FRAME_GLOBAL), and this should be assumed when sent in [COMMAND_LONG](#COMMAND_LONG)). + +| Param (Label) | 描述 | Units | +| -------------------------------- | --------- | ----- | +| 1 | Empty | | +| 2 | Empty | | +| 3 | Empty | | +| 4 | Empty | | +| 5 (Latitude) | Latitude | | +| 6 (Longitude) | Longitude | | +| 7 (Altitude) | Altitude | m | + ### MAV_CMD_ODID_SET_EMERGENCY (12900) — [WIP] {#MAV_CMD_ODID_SET_EMERGENCY} **WORK IN PROGRESS**: Do not use in stable production environments (it may change). diff --git a/zh/messages/ualberta.md b/zh/messages/ualberta.md index bbd75465e..76eb86a11 100644 --- a/zh/messages/ualberta.md +++ b/zh/messages/ualberta.md @@ -116,3 +116,4 @@ Mode currently commanded by pilot | 3 | [PILOT_ROTO](#PILOT_ROTO) | 旋转模式 | ## Commands (MAV_CMD) {#mav_commands} +