diff --git a/ko/messages/all.md b/ko/messages/all.md index ff49978aa..78321a5a8 100644 --- a/ko/messages/all.md +++ b/ko/messages/all.md @@ -62,8 +62,8 @@ span.warning { | Type | Defined | Included | | -------------------------- | ------- | -------- | | [Messages](#messages) | 0 | 381 | -| [Enums](#enumerated-types) | 0 | 243 | -| [Commands](#mav_commands) | 218 | 0 | +| [Enums](#enumerated-types) | 0 | 244 | +| [Commands](#mav_commands) | 219 | 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 7bbd58aac..3fe0a193f 100644 --- a/ko/messages/common.md +++ b/ko/messages/common.md @@ -1912,22 +1912,22 @@ Version and capability of autopilot software. This should be emitted in response The location of a landing target. See: https://mavlink.io/en/services/landing_target.html -| 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. | -| target_num | `uint8_t` | | | The ID of the target if multiple targets are present | -| frame | `uint8_t` | | [MAV_FRAME](#MAV_FRAME) | Coordinate frame used for following fields. | -| angle_x | `float` | rad | | X-axis angular offset of the target from the center of the image | -| angle_y | `float` | rad | | Y-axis angular offset of the target from the center of the image | -| distance | `float` | m | | Distance to the target from the vehicle | -| size_x | `float` | rad | | Size of target along x-axis | -| size_y | `float` | rad | | Size of target along y-axis | -| x ++ | `float` | m | | X Position of the landing target in [MAV_FRAME](#MAV_FRAME) | -| y ++ | `float` | m | | Y Position of the landing target in [MAV_FRAME](#MAV_FRAME) | -| z ++ | `float` | m | | Z Position of the landing target in [MAV_FRAME](#MAV_FRAME) | -| q ++ | `float[4]` | | | Quaternion of landing target orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0) | -| type ++ | `uint8_t` | | [LANDING_TARGET_TYPE](#LANDING_TARGET_TYPE) | Type of landing target | -| position_valid ++ | `uint8_t` | | default:0 BOOL | Position fields (x, y, z, q, type) contain valid target position information ([BOOL_FALSE](#BOOL_FALSE): invalid values). Values not equal to 0 or 1 are invalid. | +| 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. | +| target_num | `uint8_t` | | | The ID of the target if multiple targets are present | +| frame | `uint8_t` | | [MAV_FRAME](#MAV_FRAME) | Coordinate frame used for following fields. | +| angle_x | `float` | rad | | X-axis angular offset of the target from the center of the image | +| angle_y | `float` | rad | | Y-axis angular offset of the target from the center of the image | +| distance | `float` | m | | Distance to the target from the vehicle | +| size_x | `float` | rad | | Size of target along x-axis | +| size_y | `float` | rad | | Size of target along y-axis | +| x ++ | `float` | m | | X Position of the landing target in [MAV_FRAME](#MAV_FRAME) | +| y ++ | `float` | m | | Y Position of the landing target in [MAV_FRAME](#MAV_FRAME) | +| z ++ | `float` | m | | Z Position of the landing target in [MAV_FRAME](#MAV_FRAME) | +| q ++ | `float[4]` | | | Quaternion of landing target orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0) | +| type ++ | `uint8_t` | | [LANDING_TARGET_TYPE](#LANDING_TARGET_TYPE) | Type of landing target | +| position_valid ++ | `uint8_t` | | default:0 [MAV_BOOL](#MAV_BOOL) | Position fields (x, y, z, q, type) contain valid target position information ([MAV_BOOL_FALSE](#MAV_BOOL_FALSE): invalid values). Values not equal to 0 or 1 are invalid. | ### FENCE_STATUS (162) {#FENCE_STATUS} @@ -2448,7 +2448,7 @@ set to the sequence number of the final message in the range. | relative_alt | `int32_t` | mm | | Altitude above ground | | q | `float[4]` | | | Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0) | | image_index | `int32_t` | | | Zero based index of this image (i.e. a new image will have index [CAMERA_CAPTURE_STATUS](#CAMERA_CAPTURE_STATUS).image count -1) | -| capture_result | `int8_t` | | BOOL | Image was captured successfully ([BOOL_TRUE](#BOOL_TRUE)). Values not equal to 0 or 1 are invalid. | +| capture_result | `int8_t` | | [MAV_BOOL](#MAV_BOOL) | Image was captured successfully ([MAV_BOOL_TRUE](#MAV_BOOL_TRUE)). Values not equal to 0 or 1 are invalid. | | file_url | `char[205]` | | | URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface. | ### FLIGHT_INFORMATION (264) {#FLIGHT_INFORMATION} @@ -5858,14 +5858,14 @@ See https://mavlink.io/en/services/standard_modes.html | -------------------------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------- | | 1 | [HIL_ACTUATOR_CONTROLS_FLAGS_LOCKSTEP](#HIL_ACTUATOR_CONTROLS_FLAGS_LOCKSTEP) | Simulation is using lockstep | -### BOOL — \[from: [standard](../messages/standard.md#BOOL)\] {#BOOL} +### MAV_BOOL — \[from: [standard](../messages/standard.md#MAV_BOOL)\] {#MAV_BOOL} (Bitmask) Enum used to indicate true or false (also: success or failure, enabled or disabled, active or inactive). -| Value | Name | Description | -| ------------------------ | ---------------------------------------------- | ---------------------- | -| 0 | [BOOL_FALSE](#BOOL_FALSE) | False. | -| 1 | [BOOL_TRUE](#BOOL_TRUE) | True. | +| Value | Name | Description | +| ---------------------------- | --------------------------------------------------------------------------- | ---------------------- | +| 0 | [MAV_BOOL_FALSE](#MAV_BOOL_FALSE) | False. | +| 1 | [MAV_BOOL_TRUE](#MAV_BOOL_TRUE) | True. | ### MAV_AUTOPILOT — \[from: [minimal](../messages/minimal.md#MAV_AUTOPILOT)\] {#MAV_AUTOPILOT} @@ -6182,29 +6182,29 @@ Loiter around this waypoint an unlimited amount of time Loiter around this waypoint for X turns -| Param (Label) | Description | Values | Units | -| --------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------- | ----- | -| 1 (Turns) | Number of turns. | min: 0 | | -| 2 (Heading Required) | Leave loiter circle only when track heads towards the next waypoint (BOOL_FALSE: Leave when turns complete). Values not equal to 0 or 1 are invalid. | BOOL | | -| 3 (Radius) | Loiter radius around waypoint for forward-only moving vehicles (not multicopters). If positive loiter clockwise, else counter-clockwise | | m | -| 4 (Xtrack Location) | Loiter circle exit location and/or path to next waypoint ("xtrack") for forward-only moving vehicles (not multicopters). 0 for the vehicle to converge towards the center xtrack when it leaves the loiter (the line between the centers of the current and next waypoint), 1 to converge to the direct line between the location that the vehicle exits the loiter radius and the next waypoint. Otherwise the angle (in degrees) between the tangent of the loiter circle and the center xtrack at which the vehicle must leave the loiter (and converge to the center xtrack). NaN to use the current system default xtrack behaviour. | | | -| 5 (Latitude) | Latitude | | | -| 6 (Longitude) | Longitude | | | -| 7 (Altitude) | Altitude | | m | +| Param (Label) | Description | Values | Units | +| --------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------ | ----- | +| 1 (Turns) | Number of turns. | min: 0 | | +| 2 (Heading Required) | Leave loiter circle only when track heads towards the next waypoint (MAV_BOOL_FALSE: Leave when turns complete). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | | +| 3 (Radius) | Loiter radius around waypoint for forward-only moving vehicles (not multicopters). If positive loiter clockwise, else counter-clockwise | | m | +| 4 (Xtrack Location) | Loiter circle exit location and/or path to next waypoint ("xtrack") for forward-only moving vehicles (not multicopters). 0 for the vehicle to converge towards the center xtrack when it leaves the loiter (the line between the centers of the current and next waypoint), 1 to converge to the direct line between the location that the vehicle exits the loiter radius and the next waypoint. Otherwise the angle (in degrees) between the tangent of the loiter circle and the center xtrack at which the vehicle must leave the loiter (and converge to the center xtrack). NaN to use the current system default xtrack behaviour. | | | +| 5 (Latitude) | Latitude | | | +| 6 (Longitude) | Longitude | | | +| 7 (Altitude) | Altitude | | m | ### MAV_CMD_NAV_LOITER_TIME (19) {#MAV_CMD_NAV_LOITER_TIME} Loiter at the specified latitude, longitude and altitude for a certain amount of time. Multicopter vehicles stop at the point (within a vehicle-specific acceptance radius). Forward-only moving vehicles (e.g. fixed-wing) circle the point with the specified radius/direction. If the Heading Required parameter (2) is non-zero forward moving aircraft will only leave the loiter circle once heading towards the next waypoint. -| Param (Label) | Description | Values | Units | -| --------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------- | ----- | -| 1 (Time) | Loiter time (only starts once Lat, Lon and Alt is reached). | min: 0 | s | -| 2 (Heading Required) | Leave loiter circle only when track heading towards the next waypoint (BOOL_FALSE: Leave on time expiry). Values not equal to 0 or 1 are invalid. | BOOL | | -| 3 (Radius) | Loiter radius around waypoint for forward-only moving vehicles (not multicopters). If positive loiter clockwise, else counter-clockwise. | | m | -| 4 (Xtrack Location) | Loiter circle exit location and/or path to next waypoint ("xtrack") for forward-only moving vehicles (not multicopters). 0 for the vehicle to converge towards the center xtrack when it leaves the loiter (the line between the centers of the current and next waypoint), 1 to converge to the direct line between the location that the vehicle exits the loiter radius and the next waypoint. Otherwise the angle (in degrees) between the tangent of the loiter circle and the center xtrack at which the vehicle must leave the loiter (and converge to the center xtrack). NaN to use the current system default xtrack behaviour. | | | -| 5 (Latitude) | Latitude | | | -| 6 (Longitude) | Longitude | | | -| 7 (Altitude) | Altitude | | m | +| Param (Label) | Description | Values | Units | +| --------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------ | ----- | +| 1 (Time) | Loiter time (only starts once Lat, Lon and Alt is reached). | min: 0 | s | +| 2 (Heading Required) | Leave loiter circle only when track heading towards the next waypoint (MAV_BOOL_FALSE: Leave on time expiry). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | | +| 3 (Radius) | Loiter radius around waypoint for forward-only moving vehicles (not multicopters). If positive loiter clockwise, else counter-clockwise. | | m | +| 4 (Xtrack Location) | Loiter circle exit location and/or path to next waypoint ("xtrack") for forward-only moving vehicles (not multicopters). 0 for the vehicle to converge towards the center xtrack when it leaves the loiter (the line between the centers of the current and next waypoint), 1 to converge to the direct line between the location that the vehicle exits the loiter radius and the next waypoint. Otherwise the angle (in degrees) between the tangent of the loiter circle and the center xtrack at which the vehicle must leave the loiter (and converge to the center xtrack). NaN to use the current system default xtrack behaviour. | | | +| 5 (Latitude) | Latitude | | | +| 6 (Longitude) | Longitude | | | +| 7 (Altitude) | Altitude | | m | ### MAV_CMD_NAV_RETURN_TO_LAUNCH (20) {#MAV_CMD_NAV_RETURN_TO_LAUNCH} @@ -6310,7 +6310,7 @@ Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, then loiter | Param (Label) | Description | Values | Units | | --------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------- | ----- | -| 1 (Heading Required) | Leave loiter circle only when track heading towards the next waypoint (BOOL_FALSE: Leave when altitude reached). Values not equal to 0 or 1 are invalid. | BOOL | | +| 1 (Heading Required) | Leave loiter circle only when track heading towards the next waypoint (MAV_BOOL_FALSE: Leave when altitude reached). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | | | 2 (Radius) | Loiter radius around waypoint for forward-only moving vehicles (not multicopters). If positive loiter clockwise, negative counter-clockwise, 0 means no change to standard loiter. | | m | | 3 | Empty | | | | 4 (Xtrack Location) | Loiter circle exit location and/or path to next waypoint ("xtrack") for forward-only moving vehicles (not multicopters). 0 for the vehicle to converge towards the center xtrack when it leaves the loiter (the line between the centers of the current and next waypoint), 1 to converge to the direct line between the location that the vehicle exits the loiter radius and the next waypoint. Otherwise the angle (in degrees) between the tangent of the loiter circle and the center xtrack at which the vehicle must leave the loiter (and converge to the center xtrack). NaN to use the current system default xtrack behaviour. | min: 0 max: 1 inc: 1 | | @@ -6438,15 +6438,15 @@ Land using VTOL mode Hand control over to an external controller -| Param (Label) | Description | Values | -| -------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------ | -| 1 (Enable) | Guided mode on (BOOL_FALSE: Off). Values not equal to 0 or 1 are invalid. | BOOL | -| 2 | Empty | | -| 3 | Empty | | -| 4 | Empty | | -| 5 | Empty | | -| 6 | Empty | | -| 7 | Empty | | +| Param (Label) | Description | Values | +| -------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | ------------------------------------------ | +| 1 (Enable) | Guided mode on (MAV_BOOL_FALSE: Off). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | +| 2 | Empty | | +| 3 | Empty | | +| 4 | Empty | | +| 5 | Empty | | +| 6 | Empty | | +| 7 | Empty | | ### MAV_CMD_NAV_DELAY (93) {#MAV_CMD_NAV_DELAY} @@ -6541,7 +6541,7 @@ Reach a certain target angle. | 1 (Angle) | target angle [0-360]. Absolute angles: 0 is north. Relative angle: 0 is initial yaw. Direction set by param3. | min: 0 max: 360 | deg | | 2 (Angular Speed) | angular speed | min: 0 | deg/s | | 3 (Direction) | direction: -1: counter clockwise, 0: shortest direction, 1: clockwise | min: -1 max: 1 inc: 1 | | -| 4 (Relative) | Relative offset (BOOL_FALSE: absolute angle). Values not equal to 0 or 1 are invalid. | BOOL | | +| 4 (Relative) | Relative offset (MAV_BOOL_FALSE: absolute angle). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | | | 5 | Empty | | | | 6 | Empty | | | | 7 | Empty | | | @@ -6611,7 +6611,7 @@ Note: the current home position may be emitted in a [HOME_POSITION](#HOME_POSITI | Param (Label) | Description | Values | Units | | ---------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -------------------------------------------------- | ----- | -| 1 (Use Current) | Use current location (BOOL_FALSE: use specified location). Values not equal to 0 or 1 are invalid. | BOOL | | +| 1 (Use Current) | Use current location (MAV_BOOL_FALSE: use specified location). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | | | 2 (Roll) | Roll angle (of surface). Range: -180..180 degrees. NAN or 0 means value not set. 0.01 indicates zero roll. | min: -180 max: 180 | deg | | 3 (Pitch) | Pitch angle (of surface). Range: -90..90 degrees. NAN or 0 means value not set. 0.01 means zero pitch. | min: -90 max: 90 | deg | | 4 (Yaw) | Yaw angle. NaN to use default heading. Range: -180..180 degrees. | min: -180 max: 180 | deg | @@ -6833,29 +6833,29 @@ Reposition the vehicle to a specific WGS84 global position. This command is inte If in a GPS controlled position mode, hold the current position or continue. -| Param (Label) | Description | Values | -| -------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------ | -| 1 (Continue) | Continue mission (BOOL_TRUE), Pause current mission or reposition command, hold current position (BOOL_FALSE). Values not equal to 0 or 1 are invalid. A VTOL capable vehicle should enter hover mode (multicopter and VTOL planes). A plane should loiter with the default loiter radius. | BOOL | -| 2 | Reserved | | -| 3 | Reserved | | -| 4 | Reserved | | -| 5 | Reserved | | -| 6 | Reserved | | -| 7 | Reserved | | +| Param (Label) | Description | Values | +| -------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------ | +| 1 (Continue) | Continue mission (MAV_BOOL_TRUE), Pause current mission or reposition command, hold current position (MAV_BOOL_FALSE). Values not equal to 0 or 1 are invalid. A VTOL capable vehicle should enter hover mode (multicopter and VTOL planes). A plane should loiter with the default loiter radius. | [MAV_BOOL](#MAV_BOOL) | +| 2 | Reserved | | +| 3 | Reserved | | +| 4 | Reserved | | +| 5 | Reserved | | +| 6 | Reserved | | +| 7 | Reserved | | ### MAV_CMD_DO_SET_REVERSE (194) {#MAV_CMD_DO_SET_REVERSE} Set moving direction to forward or reverse. -| Param (Label) | Description | Values | -| -------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------ | -| 1 (Reverse) | Reverse direction (BOOL_FALSE: Forward direction). Values not equal to 0 or 1 are invalid. | BOOL | -| 2 | Empty | | -| 3 | Empty | | -| 4 | Empty | | -| 5 | Empty | | -| 6 | Empty | | -| 7 | Empty | | +| Param (Label) | Description | Values | +| -------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------ | +| 1 (Reverse) | Reverse direction (MAV_BOOL_FALSE: Forward direction). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | +| 2 | Empty | | +| 3 | Empty | | +| 4 | Empty | | +| 5 | Empty | | +| 6 | Empty | | +| 7 | Empty | | ### MAV_CMD_DO_SET_ROI_LOCATION (195) {#MAV_CMD_DO_SET_ROI_LOCATION} @@ -6972,15 +6972,15 @@ Control digital camera. This is a fallback message for systems that have not yet Mission command to configure a camera or antenna mount -| Param (Label) | Description | Values | -| --------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------- | -| 1 (Mode) | Mount operation mode | [MAV_MOUNT_MODE](#MAV_MOUNT_MODE) | -| 2 (Stabilize Roll) | Stabilize roll (BOOL_TRUE). Values not equal to 0 or 1 are invalid. | BOOL | -| 3 (Stabilize Pitch) | Stabilize pitch (BOOL_TRUE). Values not equal to 0 or 1 are invalid. | BOOL | -| 4 (Stabilize Yaw) | Stabilize yaw (BOOL_TRUE). Values not equal to 0 or 1 are invalid. | BOOL | -| 5 (Roll Input Mode) | Roll input (0 = angle body frame, 1 = angular rate, 2 = angle absolute frame) | | -| 6 (Pitch Input Mode) | Pitch input (0 = angle body frame, 1 = angular rate, 2 = angle absolute frame) | | -| 7 (Yaw Input Mode) | Yaw input (0 = angle body frame, 1 = angular rate, 2 = angle absolute frame) | | +| Param (Label) | Description | Values | +| --------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------- | +| 1 (Mode) | Mount operation mode | [MAV_MOUNT_MODE](#MAV_MOUNT_MODE) | +| 2 (Stabilize Roll) | Stabilize roll (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | +| 3 (Stabilize Pitch) | Stabilize pitch (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | +| 4 (Stabilize Yaw) | Stabilize yaw (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | +| 5 (Roll Input Mode) | Roll input (0 = angle body frame, 1 = angular rate, 2 = angle absolute frame) | | +| 6 (Pitch Input Mode) | Pitch input (0 = angle body frame, 1 = angular rate, 2 = angle absolute frame) | | +| 7 (Yaw Input Mode) | Yaw input (0 = angle body frame, 1 = angular rate, 2 = angle absolute frame) | | ### MAV_CMD_DO_MOUNT_CONTROL (205) — [DEP] {#MAV_CMD_DO_MOUNT_CONTROL} @@ -7006,7 +7006,7 @@ Mission command to set camera trigger distance for this flight. The camera is tr | --------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------- | ----- | | 1 (Distance) | Camera trigger distance. 0 to stop triggering. | min: 0 | m | | 2 (Shutter) | Camera shutter integration time. -1 or 0 to ignore | min: -1 inc: 1 | ms | -| 3 (Trigger) | Trigger camera once, immediately (BOOL_TRUE). Values not equal to 0 or 1 are invalid. | BOOL | | +| 3 (Trigger) | Trigger camera once, immediately (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | | | 4 (Target Camera ID) | Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission. | min: 0 max: 255 inc: 1 | | | 5 | Empty | | | | 6 | Empty | | | @@ -7062,15 +7062,15 @@ Command to perform motor test. Change to/from inverted flight. -| Param (Label) | Description | Values | -| -------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------ | -| 1 (Inverted) | Inverted flight (BOOL_False: normal flight). Values not equal to 0 or 1 are invalid. | BOOL | -| 2 | Empty | | -| 3 | Empty | | -| 4 | Empty | | -| 5 | Empty | | -| 6 | Empty | | -| 7 | Empty | | +| Param (Label) | Description | Values | +| -------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------ | +| 1 (Inverted) | Inverted flight (MAV_BOOL_False: normal flight). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | +| 2 | Empty | | +| 3 | Empty | | +| 4 | Empty | | +| 5 | Empty | | +| 6 | Empty | | +| 7 | Empty | | ### MAV_CMD_DO_GRIPPER (211) {#MAV_CMD_DO_GRIPPER} @@ -7092,7 +7092,7 @@ Enable/disable autotune. | Param (Label) | Description | Values | | -------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------------- | -| 1 (Enable) | Enable autotune (BOOL_FALSE: disable autotune). Values not equal to 0 or 1 are invalid. | BOOL | +| 1 (Enable) | Enable autotune (MAV_BOOL_FALSE: disable autotune). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | | 2 (Axis) | Specify axes for which autotuning is enabled/disabled. 0 indicates the field is unused (for compatibility 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. | | @@ -7104,15 +7104,15 @@ Enable/disable autotune. Sets a desired vehicle turn angle and speed change. -| Param (Label) | Description | Values | Units | -| -------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------ | ----- | -| 1 (Yaw) | Yaw angle to adjust steering by. | | deg | -| 2 (Speed) | Speed. | | m/s | -| 3 (Angle) | Relative final angle (BOOL_FALSE: Absolute angle). Values not equal to 0 or 1 are invalid. | BOOL | | -| 4 | Empty | | | -| 5 | Empty | | | -| 6 | Empty | | | -| 7 | Empty | | | +| Param (Label) | Description | Values | Units | +| -------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------ | ----- | +| 1 (Yaw) | Yaw angle to adjust steering by. | | deg | +| 2 (Speed) | Speed. | | m/s | +| 3 (Angle) | Relative final angle (MAV_BOOL_FALSE: Absolute angle). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | | +| 4 | Empty | | | +| 5 | Empty | | | +| 6 | Empty | | | +| 7 | Empty | | | ### MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL (214) {#MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL} @@ -7176,15 +7176,15 @@ Set limits for external control Control vehicle engine. This is interpreted by the vehicles engine controller to change the target engine state. It is intended for vehicles with internal combustion engines -| Param (Label) | Description | Values | Units | -| ----------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------- | ----- | -| 1 (Start Engine) | Start engine (BOOL_False: Stop engine). Values not equal to 0 or 1 are invalid. | BOOL | | -| 2 (Cold Start) | Cold start engine (BOOL_FALSE: Warm start). Values not equal to 0 or 1 are invalid. Controls use of choke where applicable | BOOL | | -| 3 (Height Delay) | Height delay. This is for commanding engine start only after the vehicle has gained the specified height. Used in VTOL vehicles during takeoff to start engine after the aircraft is off the ground. Zero for no delay. | min: 0 | m | -| 4 | Empty | | | -| 5 | Empty | | | -| 6 | Empty | | | -| 7 | Empty | | | +| Param (Label) | Description | Values | Units | +| ----------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------ | ----- | +| 1 (Start Engine) | Start engine (MAV_BOOL_False: Stop engine). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | | +| 2 (Cold Start) | Cold start engine (MAV_BOOL_FALSE: Warm start). Values not equal to 0 or 1 are invalid. Controls use of choke where applicable | [MAV_BOOL](#MAV_BOOL) | | +| 3 (Height Delay) | Height delay. This is for commanding engine start only after the vehicle has gained the specified height. Used in VTOL vehicles during takeoff to start engine after the aircraft is off the ground. Zero for no delay. | min: 0 | m | +| 4 | Empty | | | +| 5 | Empty | | | +| 6 | Empty | | | +| 7 | Empty | | | ### MAV_CMD_DO_SET_MISSION_CURRENT (224) {#MAV_CMD_DO_SET_MISSION_CURRENT} @@ -7202,15 +7202,15 @@ Resetting also explicitly changes a mission state of [MISSION_STATE_COMPLETE](#M The command will ACK with [MAV_RESULT_FAILED](#MAV_RESULT_FAILED) if the sequence number is out of range (including if there is no mission item). -| Param (Label) | Description | Values | -| ------------------------------------ | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------- | -| 1 (Number) | Mission sequence value to set. -1 for the current mission item (use to reset mission without changing current mission item). | min: -1 inc: 1 | -| 2 (Reset Mission) | Reset mission (BOOL_TRUE). Values not equal to 0 or 1 are invalid. Resets jump counters to initial values and changes mission state "completed" to be "active" or "paused". | BOOL | -| 3 | Empty | | -| 4 | Empty | | -| 5 | Empty | | -| 6 | Empty | | -| 7 | Empty | | +| Param (Label) | Description | Values | +| ------------------------------------ | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------- | +| 1 (Number) | Mission sequence value to set. -1 for the current mission item (use to reset mission without changing current mission item). | min: -1 inc: 1 | +| 2 (Reset Mission) | Reset mission (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid. Resets jump counters to initial values and changes mission state "completed" to be "active" or "paused". | [MAV_BOOL](#MAV_BOOL) | +| 3 | Empty | | +| 4 | Empty | | +| 5 | Empty | | +| 6 | Empty | | +| 7 | Empty | | ### MAV_CMD_DO_LAST (240) {#MAV_CMD_DO_LAST} @@ -7233,8 +7233,8 @@ Trigger calibration. This command will be only accepted if in pre-flight mode. E | Param (Label) | Description | Values | | ------------------------------------------ | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------- | | 1 (Gyro Temperature) | 1: gyro calibration, 3: gyro temperature calibration | min: 0 max: 3 inc: 1 | -| 2 (Magnetometer) | Magnetometer calibration. Values not equal to 0 or 1 are invalid. | BOOL | -| 3 (Ground Pressure) | Ground pressure calibration. Values not equal to 0 or 1 are invalid. | BOOL | +| 2 (Magnetometer) | Magnetometer calibration. Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | +| 3 (Ground Pressure) | Ground pressure calibration. Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | | 4 (Remote Control) | 1: radio RC calibration, 2: RC trim calibration | min: 0 max: 1 inc: 1 | | 5 (Accelerometer) | 1: accelerometer calibration, 2: board level calibration, 3: accelerometer temperature calibration, 4: simple accelerometer calibration | min: 0 max: 4 inc: 1 | | 6 (Compmot or Airspeed) | 1: APM: compass/motor interference calibration (PX4: airspeed calibration, deprecated), 2: airspeed calibration | min: 0 max: 2 inc: 1 | @@ -7384,7 +7384,7 @@ Arms / Disarms a component | Param (Label) | Description | Values | | -------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------------- | -| 1 (Arm) | Arm (BOOL_FALSE: disarm). Values not equal to 0 or 1 are invalid. | BOOL | +| 1 (Arm) | Arm (MAV_BOOL_FALSE: disarm). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | | 2 (Force) | 0: arm-disarm unless prevented by safety checks (i.e. when landed), 21196: force arming/disarming (e.g. allow arming to override preflight checks and disarming in flight) | min: 0 max: 21196 inc: 21196 | ### MAV_CMD_RUN_PREARM_CHECKS (401) {#MAV_CMD_RUN_PREARM_CHECKS} @@ -7403,9 +7403,9 @@ The command should return [MAV_RESULT_TEMPORARILY_REJECTED](#MAV_RESULT_TEMPORAR Turns illuminators ON/OFF. An illuminator is a light source that is used for lighting up dark areas external to the system: e.g. a torch or searchlight (as opposed to a light source for illuminating the system itself, e.g. an indicator light). -| Param (Label) | Description | Values | -| -------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------ | -| 1 (Enable) | Illuminators on/off (BOOL_TRUE: illuminators on). Values not equal to 0 or 1 are invalid. | BOOL | +| Param (Label) | Description | Values | +| -------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------ | +| 1 (Enable) | Illuminators on/off (MAV_BOOL_TRUE: illuminators on). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | ### MAV_CMD_DO_ILLUMINATOR_CONFIGURE (406) {#MAV_CMD_DO_ILLUMINATOR_CONFIGURE} @@ -7500,10 +7500,10 @@ Request the target system(s) emit a single instance of a specified message (i.e. Request MAVLink protocol version compatibility. All receivers should ACK the command and then emit their capabilities in an [PROTOCOL_VERSION](#PROTOCOL_VERSION) message -| Param (Label) | Description | Values | -| -------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------ | -| 1 (Protocol) | Request supported protocol versions by all nodes on the network (BOOL_TRUE). Values not equal to 0 or 1 are invalid. | BOOL | -| 2 | Reserved (all remaining params) | | +| Param (Label) | Description | Values | +| -------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------ | +| 1 (Protocol) | Request supported protocol versions by all nodes on the network (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | +| 2 | Reserved (all remaining params) | | ### MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES (520) — [DEP] {#MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES} @@ -7511,10 +7511,10 @@ Request MAVLink protocol version compatibility. All receivers should ACK the com Request autopilot capabilities. The receiver should ACK the command and then emit its capabilities in an [AUTOPILOT_VERSION](#AUTOPILOT_VERSION) message -| Param (Label) | Description | Values | -| -------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------ | ------ | -| 1 (Version) | Request autopilot version (BOOL_TRUE). Values not equal to 0 or 1 are invalid. | BOOL | -| 2 | Reserved (all remaining params) | | +| Param (Label) | Description | Values | +| -------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------ | +| 1 (Version) | Request autopilot version (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | +| 2 | Reserved (all remaining params) | | ### MAV_CMD_REQUEST_CAMERA_INFORMATION (521) — [DEP] {#MAV_CMD_REQUEST_CAMERA_INFORMATION} @@ -7522,10 +7522,10 @@ Request autopilot capabilities. The receiver should ACK the command and then emi Request camera information ([CAMERA_INFORMATION](#CAMERA_INFORMATION)). -| Param (Label) | Description | Values | -| ----------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------- | ------ | -| 1 (Capabilities) | Request camera capabilities (BOOL_TRUE). Values not equal to 0 or 1 are invalid. | BOOL | -| 2 | Reserved (all remaining params) | | +| Param (Label) | Description | Values | +| ----------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------ | +| 1 (Capabilities) | Request camera capabilities (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | +| 2 | Reserved (all remaining params) | | ### MAV_CMD_REQUEST_CAMERA_SETTINGS (522) — [DEP] {#MAV_CMD_REQUEST_CAMERA_SETTINGS} @@ -7533,10 +7533,10 @@ Request camera information ([CAMERA_INFORMATION](#CAMERA_INFORMATION)). Request camera settings ([CAMERA_SETTINGS](#CAMERA_SETTINGS)). -| Param (Label) | Description | Values | -| -------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------- | ------ | -| 1 (Settings) | Request camera settings (BOOL_TRUE). Values not equal to 0 or 1 are invalid. | BOOL | -| 2 | Reserved (all remaining params) | | +| Param (Label) | Description | Values | +| -------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------ | +| 1 (Settings) | Request camera settings (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | +| 2 | Reserved (all remaining params) | | ### MAV_CMD_REQUEST_STORAGE_INFORMATION (525) — [DEP] {#MAV_CMD_REQUEST_STORAGE_INFORMATION} @@ -7544,11 +7544,11 @@ Request camera settings ([CAMERA_SETTINGS](#CAMERA_SETTINGS)). Request storage information ([STORAGE_INFORMATION](#STORAGE_INFORMATION)). Use the command's target_component to target a specific component's storage. -| Param (Label) | Description | Values | -| ---------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------- | -| 1 (Storage ID) | Storage ID (0 for all, 1 for first, 2 for second, etc.) | min: 0 inc: 1 | -| 2 (Information) | Request storage information (BOOL_TRUE). Values not equal to 0 or 1 are invalid. | BOOL | -| 3 | Reserved (all remaining params) | | +| Param (Label) | Description | Values | +| ---------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------- | +| 1 (Storage ID) | Storage ID (0 for all, 1 for first, 2 for second, etc.) | min: 0 inc: 1 | +| 2 (Information) | Request storage information (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | +| 3 | Reserved (all remaining params) | | ### MAV_CMD_STORAGE_FORMAT (526) {#MAV_CMD_STORAGE_FORMAT} @@ -7557,8 +7557,8 @@ Format a storage medium. Once format is complete, a [STORAGE_INFORMATION](#STORA | Param (Label) | Description | Values | | -------------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------- | | 1 (Storage ID) | Storage ID (1 for first, 2 for second, etc.) | min: 0 inc: 1 | -| 2 (Format) | Format storage (and reset image log). Values not equal to 0 or 1 are invalid. | BOOL | -| 3 (Reset Image Log) | Reset Image Log (without formatting storage medium). This will reset CAMERA_CAPTURE_STATUS.image_count and CAMERA_IMAGE_CAPTURED.image_index. Values not equal to 0 or 1 are invalid. | BOOL | +| 2 (Format) | Format storage (and reset image log). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | +| 3 (Reset Image Log) | Reset Image Log (without formatting storage medium). This will reset CAMERA_CAPTURE_STATUS.image_count and CAMERA_IMAGE_CAPTURED.image_index. Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | | 4 | Reserved (all remaining params) | | ### MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS (527) — [DEP] {#MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS} @@ -7567,10 +7567,10 @@ Format a storage medium. Once format is complete, a [STORAGE_INFORMATION](#STORA Request camera capture status ([CAMERA_CAPTURE_STATUS](#CAMERA_CAPTURE_STATUS)) -| Param (Label) | Description | Values | -| ------------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------- | ------ | -| 1 (Capture Status) | Request camera capture status (BOOL_TRUE). Values not equal to 0 or 1 are invalid. | BOOL | -| 2 | Reserved (all remaining params) | | +| Param (Label) | Description | Values | +| ------------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------ | +| 1 (Capture Status) | Request camera capture status (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | +| 2 | Reserved (all remaining params) | | ### MAV_CMD_REQUEST_FLIGHT_INFORMATION (528) — [DEP] {#MAV_CMD_REQUEST_FLIGHT_INFORMATION} @@ -7578,10 +7578,10 @@ Request camera capture status ([CAMERA_CAPTURE_STATUS](#CAMERA_CAPTURE_STATUS)) Request flight information ([FLIGHT_INFORMATION](#FLIGHT_INFORMATION)) -| Param (Label) | Description | Values | -| ----------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------- | ------ | -| 1 (Flight Information) | Request flight information (BOOL_TRUE). Values not equal to 0 or 1 are invalid. | BOOL | -| 2 | Reserved (all remaining params) | | +| Param (Label) | Description | Values | +| ----------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------ | +| 1 (Flight Information) | Request flight information (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | +| 2 | Reserved (all remaining params) | | ### MAV_CMD_RESET_CAMERA_SETTINGS (529) {#MAV_CMD_RESET_CAMERA_SETTINGS} @@ -7589,7 +7589,7 @@ Reset all camera settings to Factory Default | Param (Label) | Description | Values | | --------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------- | -| 1 (Reset) | Reset all settings (BOOL_TRUE). Values not equal to 0 or 1 are invalid. | BOOL | +| 1 (Reset) | Reset all settings (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | | 2 (Target Camera ID) | Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission. | min: 0 max: 255 inc: 1 | ### MAV_CMD_SET_CAMERA_MODE (530) {#MAV_CMD_SET_CAMERA_MODE} @@ -7912,15 +7912,15 @@ Request to stop streaming log data over MAVLink Request to start/stop transmitting over the high latency telemetry -| Param (Label) | Description | Values | -| -------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------ | -| 1 (Enable) | Start transmission over high latency telemetry (BOOL_FALSE: stop transmission). Values not equal to 0 or 1 are invalid. | BOOL | -| 2 | Empty | | -| 3 | Empty | | -| 4 | Empty | | -| 5 | Empty | | -| 6 | Empty | | -| 7 | Empty | | +| Param (Label) | Description | Values | +| -------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------ | +| 1 (Enable) | Start transmission over high latency telemetry (MAV_BOOL_FALSE: stop transmission). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | +| 2 | Empty | | +| 3 | Empty | | +| 4 | Empty | | +| 5 | Empty | | +| 6 | Empty | | +| 7 | Empty | | ### MAV_CMD_PANORAMA_CREATE (2800) {#MAV_CMD_PANORAMA_CREATE} @@ -7979,15 +7979,15 @@ This command sets submode circle when vehicle is in guided mode. Vehicle flies a Delay mission state machine until gate has been reached. -| Param (Label) | Description | Values | Units | -| ---------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------- | ----- | -| 1 (Geometry) | Geometry: 0: orthogonal to path between previous and next waypoint. | min: 0 inc: 1 | | -| 2 (UseAltitude) | Use altitude (BOOL_FALSE: ignore altitude). Values not equal to 0 or 1 are invalid. | BOOL | | -| 3 | Empty | | | -| 4 | Empty | | | -| 5 (Latitude) | Latitude | | | -| 6 (Longitude) | Longitude | | | -| 7 (Altitude) | Altitude | | m | +| Param (Label) | Description | Values | Units | +| ---------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------- | ----- | +| 1 (Geometry) | Geometry: 0: orthogonal to path between previous and next waypoint. | min: 0 inc: 1 | | +| 2 (UseAltitude) | Use altitude (MAV_BOOL_FALSE: ignore altitude). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | | +| 3 | Empty | | | +| 4 | Empty | | | +| 5 (Latitude) | Latitude | | | +| 6 (Longitude) | Longitude | | | +| 7 (Altitude) | Altitude | | m | ### MAV_CMD_NAV_FENCE_RETURN_POINT (5000) {#MAV_CMD_NAV_FENCE_RETURN_POINT} diff --git a/ko/messages/development.md b/ko/messages/development.md index ca4e3a0b9..802136f8a 100644 --- a/ko/messages/development.md +++ b/ko/messages/development.md @@ -38,8 +38,8 @@ span.warning { | Type | Defined | Included | | -------------------------- | ------- | -------- | | [Messages](#messages) | 12 | 229 | -| [Enums](#enumerated-types) | 11 | 148 | -| [Commands](#mav_commands) | 172 | 0 | +| [Enums](#enumerated-types) | 12 | 148 | +| [Commands](#mav_commands) | 173 | 0 | The following sections list all entities in the dialect (both included and defined in this file). @@ -413,6 +413,19 @@ State of RAIM processing. | 2 | [GPS_RAIM_STATE_OK](#GPS_RAIM_STATE_OK) | RAIM integrity check was successful. | | 3 | [GPS_RAIM_STATE_FAILED](#GPS_RAIM_STATE_FAILED) | RAIM integrity check failed. | +### ACTUATOR_TEST_GROUP — [WIP] {#ACTUATOR_TEST_GROUP} + +**WORK IN PROGRESS**: Do not use in stable production environments (it may change). + +Actuator groups to test in [MAV_CMD_ACTUATOR_GROUP_TEST](#MAV_CMD_ACTUATOR_GROUP_TEST). + +| Value | Name | Description | +| ------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------------------- | +| 0 | [ACTUATOR_TEST_GROUP_ROLL_TORQUE](#ACTUATOR_TEST_GROUP_ROLL_TORQUE) | Actuators that contribute to roll torque. | +| 1 | [ACTUATOR_TEST_GROUP_PITCH_TORQUE](#ACTUATOR_TEST_GROUP_PITCH_TORQUE) | Actuators that contribute to pitch torque. | +| 2 | [ACTUATOR_TEST_GROUP_YAW_TORQUE](#ACTUATOR_TEST_GROUP_YAW_TORQUE) | Actuators that contribute to yaw torque. | +| 3 | [ACTUATOR_TEST_GROUP_COLLECTIVE_TILT](#ACTUATOR_TEST_GROUP_COLLECTIVE_TILT) | Actuators that affect collective tilt. | + ## Commands (MAV_CMD) {#mav_commands} ### MAV_CMD_DO_FIGURE_EIGHT (35) — [WIP] {#MAV_CMD_DO_FIGURE_EIGHT} @@ -456,6 +469,22 @@ Command protocol information: https://mavlink.io/en/services/command.html. | 6 | Reserved | | | 7 | WIP: upgrade progress report rate (can be used for more granular control). | | +### MAV_CMD_ACTUATOR_GROUP_TEST (309) — [WIP] {#MAV_CMD_ACTUATOR_GROUP_TEST} + +**WORK IN PROGRESS**: Do not use in stable production environments (it may change). + +Command to test groups of related actuators together. + +This might include groups such as the actuators that contribute to roll, pitch, or yaw torque, actuators that contribute to thrust in x, y, z axis, tilt mechanisms, flaps and spoilers, and so on. +This is similar to [MAV_CMD_ACTUATOR_TEST](#MAV_CMD_ACTUATOR_TEST), except that multiple actuators may be affected. +Different groups may also affect the same actuators (as in the case of controls that affect torque in different axes). +Autopilots must NACK this command with [MAV_RESULT_TEMPORARILY_REJECTED](#MAV_RESULT_TEMPORARILY_REJECTED) while armed. + +| Param (Label) | Description | Values | +| -------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | ------------------------------------------------------------------------------------- | +| 1 (Group) | Actuator group to check, such as actuators related to roll torque. | [ACTUATOR_TEST_GROUP](#ACTUATOR_TEST_GROUP) | +| 2 (Value) | Value to set. This is a normalized value across the full range of the tested group [-1,1]. | min: -1 max: 1 | + ### MAV_CMD_DO_SET_SYS_CMP_ID (610) — [WIP] {#MAV_CMD_DO_SET_SYS_CMP_ID} **WORK IN PROGRESS**: Do not use in stable production environments (it may change). diff --git a/ko/messages/standard.md b/ko/messages/standard.md index 37cb8b038..171549c9c 100644 --- a/ko/messages/standard.md +++ b/ko/messages/standard.md @@ -45,12 +45,12 @@ The following sections list all entities in the dialect (both included and defin ## Enumerated Types -### BOOL {#BOOL} +### MAV_BOOL {#MAV_BOOL} (Bitmask) Enum used to indicate true or false (also: success or failure, enabled or disabled, active or inactive). -| Value | Name | Description | -| ------------------------ | ---------------------------------------------- | ---------------------- | -| 0 | [BOOL_FALSE](#BOOL_FALSE) | False. | -| 1 | [BOOL_TRUE](#BOOL_TRUE) | True. | +| Value | Name | Description | +| ---------------------------- | --------------------------------------------------------------------------- | ---------------------- | +| 0 | [MAV_BOOL_FALSE](#MAV_BOOL_FALSE) | False. | +| 1 | [MAV_BOOL_TRUE](#MAV_BOOL_TRUE) | True. | diff --git a/zh/messages/all.md b/zh/messages/all.md index 71e968ae7..c10642776 100644 --- a/zh/messages/all.md +++ b/zh/messages/all.md @@ -62,8 +62,8 @@ span.warning { | Type | Defined | Included | | -------------------------- | ------- | -------- | | [Messages](#messages) | 0 | 381 | -| [Enums](#enumerated-types) | 0 | 243 | -| [Commands](#mav_commands) | 218 | 0 | +| [Enums](#enumerated-types) | 0 | 244 | +| [Commands](#mav_commands) | 219 | 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 37cb64d57..9407f3fe2 100644 --- a/zh/messages/common.md +++ b/zh/messages/common.md @@ -1912,22 +1912,22 @@ Version and capability of autopilot software. This should be emitted in response The location of a landing target. See: https://mavlink.io/en/services/landing_target.html -| 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. | -| target_num | `uint8_t` | | | The ID of the target if multiple targets are present | -| frame | `uint8_t` | | [MAV_FRAME](#MAV_FRAME) | Coordinate frame used for following fields. | -| angle_x | `float` | rad | | X-axis angular offset of the target from the center of the image | -| angle_y | `float` | rad | | Y-axis angular offset of the target from the center of the image | -| distance | `float` | m | | Distance to the target from the vehicle | -| size_x | `float` | rad | | Size of target along x-axis | -| size_y | `float` | rad | | Size of target along y-axis | -| x ++ | `float` | m | | X Position of the landing target in [MAV_FRAME](#MAV_FRAME) | -| y ++ | `float` | m | | Y Position of the landing target in [MAV_FRAME](#MAV_FRAME) | -| z ++ | `float` | m | | Z Position of the landing target in [MAV_FRAME](#MAV_FRAME) | -| q ++ | `float[4]` | | | Quaternion of landing target orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0) | -| type ++ | `uint8_t` | | [LANDING_TARGET_TYPE](#LANDING_TARGET_TYPE) | Type of landing target | -| position_valid ++ | `uint8_t` | | default:0 BOOL | Position fields (x, y, z, q, type) contain valid target position information ([BOOL_FALSE](#BOOL_FALSE): invalid values). Values not equal to 0 or 1 are invalid. | +| 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. | +| target_num | `uint8_t` | | | The ID of the target if multiple targets are present | +| frame | `uint8_t` | | [MAV_FRAME](#MAV_FRAME) | Coordinate frame used for following fields. | +| angle_x | `float` | rad | | X-axis angular offset of the target from the center of the image | +| angle_y | `float` | rad | | Y-axis angular offset of the target from the center of the image | +| distance | `float` | m | | Distance to the target from the vehicle | +| size_x | `float` | rad | | Size of target along x-axis | +| size_y | `float` | rad | | Size of target along y-axis | +| x ++ | `float` | m | | X Position of the landing target in [MAV_FRAME](#MAV_FRAME) | +| y ++ | `float` | m | | Y Position of the landing target in [MAV_FRAME](#MAV_FRAME) | +| z ++ | `float` | m | | Z Position of the landing target in [MAV_FRAME](#MAV_FRAME) | +| q ++ | `float[4]` | | | Quaternion of landing target orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0) | +| type ++ | `uint8_t` | | [LANDING_TARGET_TYPE](#LANDING_TARGET_TYPE) | Type of landing target | +| position_valid ++ | `uint8_t` | | default:0 [MAV_BOOL](#MAV_BOOL) | Position fields (x, y, z, q, type) contain valid target position information ([MAV_BOOL_FALSE](#MAV_BOOL_FALSE): invalid values). Values not equal to 0 or 1 are invalid. | ### FENCE_STATUS (162) {#FENCE_STATUS} @@ -2448,7 +2448,7 @@ set to the sequence number of the final message in the range. | relative_alt | `int32_t` | 毫米 | | Altitude above ground | | q | `float[4]` | | | Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0) | | image_index | `int32_t` | | | Zero based index of this image (i.e. a new image will have index [CAMERA_CAPTURE_STATUS](#CAMERA_CAPTURE_STATUS).image count -1) | -| capture_result | `int8_t` | | BOOL | Image was captured successfully ([BOOL_TRUE](#BOOL_TRUE)). Values not equal to 0 or 1 are invalid. | +| capture_result | `int8_t` | | [MAV_BOOL](#MAV_BOOL) | Image was captured successfully ([MAV_BOOL_TRUE](#MAV_BOOL_TRUE)). Values not equal to 0 or 1 are invalid. | | file_url | `char[205]` | | | URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface. | ### FLIGHT_INFORMATION (264) {#FLIGHT_INFORMATION} @@ -5858,14 +5858,14 @@ See https://mavlink.io/en/services/standard_modes.html | -------------------------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------- | | 1 | [HIL_ACTUATOR_CONTROLS_FLAGS_LOCKSTEP](#HIL_ACTUATOR_CONTROLS_FLAGS_LOCKSTEP) | Simulation is using lockstep | -### BOOL — \[from: [standard](../messages/standard.md#BOOL)\] {#BOOL} +### MAV_BOOL — \[from: [standard](../messages/standard.md#MAV_BOOL)\] {#MAV_BOOL} (Bitmask) Enum used to indicate true or false (also: success or failure, enabled or disabled, active or inactive). -| 值 | Name | 描述 | -| ------------------------ | ---------------------------------------------- | ---------------------- | -| 0 | [BOOL_FALSE](#BOOL_FALSE) | False. | -| 1 | [BOOL_TRUE](#BOOL_TRUE) | True. | +| 值 | Name | 描述 | +| ---------------------------- | --------------------------------------------------------------------------- | ---------------------- | +| 0 | [MAV_BOOL_FALSE](#MAV_BOOL_FALSE) | False. | +| 1 | [MAV_BOOL_TRUE](#MAV_BOOL_TRUE) | True. | ### MAV_AUTOPILOT — \[from: [minimal](../messages/minimal.md#MAV_AUTOPILOT)\] {#MAV_AUTOPILOT} @@ -6182,29 +6182,29 @@ Loiter around this waypoint an unlimited amount of time Loiter around this waypoint for X turns -| Param (Label) | 描述 | 值 | Units | -| --------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------- | ----- | -| 1 (Turns) | Number of turns. | min: 0 | | -| 2 (Heading Required) | Leave loiter circle only when track heads towards the next waypoint (BOOL_FALSE: Leave when turns complete). Values not equal to 0 or 1 are invalid. | BOOL | | -| 3 (Radius) | Loiter radius around waypoint for forward-only moving vehicles (not multicopters). If positive loiter clockwise, else counter-clockwise | | m | -| 4 (Xtrack Location) | Loiter circle exit location and/or path to next waypoint ("xtrack") for forward-only moving vehicles (not multicopters). 0 for the vehicle to converge towards the center xtrack when it leaves the loiter (the line between the centers of the current and next waypoint), 1 to converge to the direct line between the location that the vehicle exits the loiter radius and the next waypoint. Otherwise the angle (in degrees) between the tangent of the loiter circle and the center xtrack at which the vehicle must leave the loiter (and converge to the center xtrack). NaN to use the current system default xtrack behaviour. | | | -| 5 (Latitude) | Latitude | | | -| 6 (Longitude) | Longitude | | | -| 7 (Altitude) | Altitude | | m | +| Param (Label) | 描述 | 值 | Units | +| --------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------ | ----- | +| 1 (Turns) | Number of turns. | min: 0 | | +| 2 (Heading Required) | Leave loiter circle only when track heads towards the next waypoint (MAV_BOOL_FALSE: Leave when turns complete). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | | +| 3 (Radius) | Loiter radius around waypoint for forward-only moving vehicles (not multicopters). If positive loiter clockwise, else counter-clockwise | | m | +| 4 (Xtrack Location) | Loiter circle exit location and/or path to next waypoint ("xtrack") for forward-only moving vehicles (not multicopters). 0 for the vehicle to converge towards the center xtrack when it leaves the loiter (the line between the centers of the current and next waypoint), 1 to converge to the direct line between the location that the vehicle exits the loiter radius and the next waypoint. Otherwise the angle (in degrees) between the tangent of the loiter circle and the center xtrack at which the vehicle must leave the loiter (and converge to the center xtrack). NaN to use the current system default xtrack behaviour. | | | +| 5 (Latitude) | Latitude | | | +| 6 (Longitude) | Longitude | | | +| 7 (Altitude) | Altitude | | m | ### MAV_CMD_NAV_LOITER_TIME (19) {#MAV_CMD_NAV_LOITER_TIME} Loiter at the specified latitude, longitude and altitude for a certain amount of time. Multicopter vehicles stop at the point (within a vehicle-specific acceptance radius). Forward-only moving vehicles (e.g. fixed-wing) circle the point with the specified radius/direction. If the Heading Required parameter (2) is non-zero forward moving aircraft will only leave the loiter circle once heading towards the next waypoint. -| Param (Label) | 描述 | 值 | Units | -| --------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------- | ----- | -| 1 (Time) | Loiter time (only starts once Lat, Lon and Alt is reached). | min: 0 | s | -| 2 (Heading Required) | Leave loiter circle only when track heading towards the next waypoint (BOOL_FALSE: Leave on time expiry). Values not equal to 0 or 1 are invalid. | BOOL | | -| 3 (Radius) | Loiter radius around waypoint for forward-only moving vehicles (not multicopters). If positive loiter clockwise, else counter-clockwise. | | m | -| 4 (Xtrack Location) | Loiter circle exit location and/or path to next waypoint ("xtrack") for forward-only moving vehicles (not multicopters). 0 for the vehicle to converge towards the center xtrack when it leaves the loiter (the line between the centers of the current and next waypoint), 1 to converge to the direct line between the location that the vehicle exits the loiter radius and the next waypoint. Otherwise the angle (in degrees) between the tangent of the loiter circle and the center xtrack at which the vehicle must leave the loiter (and converge to the center xtrack). NaN to use the current system default xtrack behaviour. | | | -| 5 (Latitude) | Latitude | | | -| 6 (Longitude) | Longitude | | | -| 7 (Altitude) | Altitude | | m | +| Param (Label) | 描述 | 值 | Units | +| --------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------ | ----- | +| 1 (Time) | Loiter time (only starts once Lat, Lon and Alt is reached). | min: 0 | s | +| 2 (Heading Required) | Leave loiter circle only when track heading towards the next waypoint (MAV_BOOL_FALSE: Leave on time expiry). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | | +| 3 (Radius) | Loiter radius around waypoint for forward-only moving vehicles (not multicopters). If positive loiter clockwise, else counter-clockwise. | | m | +| 4 (Xtrack Location) | Loiter circle exit location and/or path to next waypoint ("xtrack") for forward-only moving vehicles (not multicopters). 0 for the vehicle to converge towards the center xtrack when it leaves the loiter (the line between the centers of the current and next waypoint), 1 to converge to the direct line between the location that the vehicle exits the loiter radius and the next waypoint. Otherwise the angle (in degrees) between the tangent of the loiter circle and the center xtrack at which the vehicle must leave the loiter (and converge to the center xtrack). NaN to use the current system default xtrack behaviour. | | | +| 5 (Latitude) | Latitude | | | +| 6 (Longitude) | Longitude | | | +| 7 (Altitude) | Altitude | | m | ### MAV_CMD_NAV_RETURN_TO_LAUNCH (20) {#MAV_CMD_NAV_RETURN_TO_LAUNCH} @@ -6310,7 +6310,7 @@ Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, then loiter | Param (Label) | 描述 | 值 | Units | | --------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------- | ----- | -| 1 (Heading Required) | Leave loiter circle only when track heading towards the next waypoint (BOOL_FALSE: Leave when altitude reached). Values not equal to 0 or 1 are invalid. | BOOL | | +| 1 (Heading Required) | Leave loiter circle only when track heading towards the next waypoint (MAV_BOOL_FALSE: Leave when altitude reached). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | | | 2 (Radius) | Loiter radius around waypoint for forward-only moving vehicles (not multicopters). If positive loiter clockwise, negative counter-clockwise, 0 means no change to standard loiter. | | m | | 3 | Empty | | | | 4 (Xtrack Location) | Loiter circle exit location and/or path to next waypoint ("xtrack") for forward-only moving vehicles (not multicopters). 0 for the vehicle to converge towards the center xtrack when it leaves the loiter (the line between the centers of the current and next waypoint), 1 to converge to the direct line between the location that the vehicle exits the loiter radius and the next waypoint. Otherwise the angle (in degrees) between the tangent of the loiter circle and the center xtrack at which the vehicle must leave the loiter (and converge to the center xtrack). NaN to use the current system default xtrack behaviour. | min: 0 max: 1 inc: 1 | | @@ -6438,15 +6438,15 @@ Land using VTOL mode Hand control over to an external controller -| Param (Label) | 描述 | 值 | -| -------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---- | -| 1 (Enable) | Guided mode on (BOOL_FALSE: Off). Values not equal to 0 or 1 are invalid. | BOOL | -| 2 | Empty | | -| 3 | Empty | | -| 4 | Empty | | -| 5 | Empty | | -| 6 | Empty | | -| 7 | Empty | | +| Param (Label) | 描述 | 值 | +| -------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | ------------------------------------------ | +| 1 (Enable) | Guided mode on (MAV_BOOL_FALSE: Off). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | +| 2 | Empty | | +| 3 | Empty | | +| 4 | Empty | | +| 5 | Empty | | +| 6 | Empty | | +| 7 | Empty | | ### MAV_CMD_NAV_DELAY (93) {#MAV_CMD_NAV_DELAY} @@ -6541,7 +6541,7 @@ Reach a certain target angle. | 1 (Angle) | target angle [0-360]. Absolute angles: 0 is north. Relative angle: 0 is initial yaw. Direction set by param3. | min: 0 max: 360 | 度 | | 2 (Angular Speed) | angular speed | min: 0 | deg/s | | 3 (Direction) | direction: -1: counter clockwise, 0: shortest direction, 1: clockwise | min: -1 max: 1 inc: 1 | | -| 4 (Relative) | Relative offset (BOOL_FALSE: absolute angle). Values not equal to 0 or 1 are invalid. | BOOL | | +| 4 (Relative) | Relative offset (MAV_BOOL_FALSE: absolute angle). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | | | 5 | Empty | | | | 6 | Empty | | | | 7 | Empty | | | @@ -6611,7 +6611,7 @@ Note: the current home position may be emitted in a [HOME_POSITION](#HOME_POSITI | Param (Label) | 描述 | 值 | Units | | ---------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -------------------------------------------------- | ----- | -| 1 (Use Current) | Use current location (BOOL_FALSE: use specified location). Values not equal to 0 or 1 are invalid. | BOOL | | +| 1 (Use Current) | Use current location (MAV_BOOL_FALSE: use specified location). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | | | 2 (Roll) | Roll angle (of surface). Range: -180..180 degrees. NAN or 0 means value not set. 0.01 indicates zero roll. | min: -180 max: 180 | 度 | | 3 (Pitch) | Pitch angle (of surface). Range: -90..90 degrees. NAN or 0 means value not set. 0.01 means zero pitch. | min: -90 max: 90 | 度 | | 4 (Yaw) | Yaw angle. NaN to use default heading. Range: -180..180 degrees. | min: -180 max: 180 | 度 | @@ -6833,29 +6833,29 @@ Reposition the vehicle to a specific WGS84 global position. This command is inte If in a GPS controlled position mode, hold the current position or continue. -| Param (Label) | 描述 | 值 | -| -------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---- | -| 1 (Continue) | Continue mission (BOOL_TRUE), Pause current mission or reposition command, hold current position (BOOL_FALSE). Values not equal to 0 or 1 are invalid. A VTOL capable vehicle should enter hover mode (multicopter and VTOL planes). A plane should loiter with the default loiter radius. | BOOL | -| 2 | Reserved | | -| 3 | Reserved | | -| 4 | Reserved | | -| 5 | Reserved | | -| 6 | Reserved | | -| 7 | Reserved | | +| Param (Label) | 描述 | 值 | +| -------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------ | +| 1 (Continue) | Continue mission (MAV_BOOL_TRUE), Pause current mission or reposition command, hold current position (MAV_BOOL_FALSE). Values not equal to 0 or 1 are invalid. A VTOL capable vehicle should enter hover mode (multicopter and VTOL planes). A plane should loiter with the default loiter radius. | [MAV_BOOL](#MAV_BOOL) | +| 2 | Reserved | | +| 3 | Reserved | | +| 4 | Reserved | | +| 5 | Reserved | | +| 6 | Reserved | | +| 7 | Reserved | | ### MAV_CMD_DO_SET_REVERSE (194) {#MAV_CMD_DO_SET_REVERSE} Set moving direction to forward or reverse. -| Param (Label) | 描述 | 值 | -| -------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---- | -| 1 (Reverse) | Reverse direction (BOOL_FALSE: Forward direction). Values not equal to 0 or 1 are invalid. | BOOL | -| 2 | Empty | | -| 3 | Empty | | -| 4 | Empty | | -| 5 | Empty | | -| 6 | Empty | | -| 7 | Empty | | +| Param (Label) | 描述 | 值 | +| -------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------ | +| 1 (Reverse) | Reverse direction (MAV_BOOL_FALSE: Forward direction). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | +| 2 | Empty | | +| 3 | Empty | | +| 4 | Empty | | +| 5 | Empty | | +| 6 | Empty | | +| 7 | Empty | | ### MAV_CMD_DO_SET_ROI_LOCATION (195) {#MAV_CMD_DO_SET_ROI_LOCATION} @@ -6972,15 +6972,15 @@ Control digital camera. This is a fallback message for systems that have not yet Mission command to configure a camera or antenna mount -| Param (Label) | 描述 | 值 | -| --------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------- | -| 1 (Mode) | Mount operation mode | [MAV_MOUNT_MODE](#MAV_MOUNT_MODE) | -| 2 (Stabilize Roll) | Stabilize roll (BOOL_TRUE). Values not equal to 0 or 1 are invalid. | BOOL | -| 3 (Stabilize Pitch) | Stabilize pitch (BOOL_TRUE). Values not equal to 0 or 1 are invalid. | BOOL | -| 4 (Stabilize Yaw) | Stabilize yaw (BOOL_TRUE). Values not equal to 0 or 1 are invalid. | BOOL | -| 5 (Roll Input Mode) | Roll input (0 = angle body frame, 1 = angular rate, 2 = angle absolute frame) | | -| 6 (Pitch Input Mode) | Pitch input (0 = angle body frame, 1 = angular rate, 2 = angle absolute frame) | | -| 7 (Yaw Input Mode) | Yaw input (0 = angle body frame, 1 = angular rate, 2 = angle absolute frame) | | +| Param (Label) | 描述 | 值 | +| --------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------- | +| 1 (Mode) | Mount operation mode | [MAV_MOUNT_MODE](#MAV_MOUNT_MODE) | +| 2 (Stabilize Roll) | Stabilize roll (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | +| 3 (Stabilize Pitch) | Stabilize pitch (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | +| 4 (Stabilize Yaw) | Stabilize yaw (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | +| 5 (Roll Input Mode) | Roll input (0 = angle body frame, 1 = angular rate, 2 = angle absolute frame) | | +| 6 (Pitch Input Mode) | Pitch input (0 = angle body frame, 1 = angular rate, 2 = angle absolute frame) | | +| 7 (Yaw Input Mode) | Yaw input (0 = angle body frame, 1 = angular rate, 2 = angle absolute frame) | | ### MAV_CMD_DO_MOUNT_CONTROL (205) — [DEP] {#MAV_CMD_DO_MOUNT_CONTROL} @@ -7006,7 +7006,7 @@ Mission command to set camera trigger distance for this flight. The camera is tr | --------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------- | ----- | | 1 (Distance) | Camera trigger distance. 0 to stop triggering. | min: 0 | m | | 2 (Shutter) | Camera shutter integration time. -1 or 0 to ignore | min: -1 inc: 1 | ms | -| 3 (Trigger) | Trigger camera once, immediately (BOOL_TRUE). Values not equal to 0 or 1 are invalid. | BOOL | | +| 3 (Trigger) | Trigger camera once, immediately (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | | | 4 (Target Camera ID) | Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission. | min: 0 max: 255 inc: 1 | | | 5 | Empty | | | | 6 | Empty | | | @@ -7062,15 +7062,15 @@ Command to perform motor test. Change to/from inverted flight. -| Param (Label) | 描述 | 值 | -| -------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---- | -| 1 (Inverted) | Inverted flight (BOOL_False: normal flight). Values not equal to 0 or 1 are invalid. | BOOL | -| 2 | Empty | | -| 3 | Empty | | -| 4 | Empty | | -| 5 | Empty | | -| 6 | Empty | | -| 7 | Empty | | +| Param (Label) | 描述 | 值 | +| -------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------ | +| 1 (Inverted) | Inverted flight (MAV_BOOL_False: normal flight). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | +| 2 | Empty | | +| 3 | Empty | | +| 4 | Empty | | +| 5 | Empty | | +| 6 | Empty | | +| 7 | Empty | | ### MAV_CMD_DO_GRIPPER (211) {#MAV_CMD_DO_GRIPPER} @@ -7092,7 +7092,7 @@ Enable/disable autotune. | Param (Label) | 描述 | 值 | | -------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------------- | -| 1 (Enable) | Enable autotune (BOOL_FALSE: disable autotune). Values not equal to 0 or 1 are invalid. | BOOL | +| 1 (Enable) | Enable autotune (MAV_BOOL_FALSE: disable autotune). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | | 2 (Axis) | Specify axes for which autotuning is enabled/disabled. 0 indicates the field is unused (for compatibility 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. | | @@ -7104,15 +7104,15 @@ Enable/disable autotune. Sets a desired vehicle turn angle and speed change. -| Param (Label) | 描述 | 值 | Units | -| -------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---- | ----- | -| 1 (Yaw) | Yaw angle to adjust steering by. | | 度 | -| 2 (Speed) | Speed. | | m/s | -| 3 (Angle) | Relative final angle (BOOL_FALSE: Absolute angle). Values not equal to 0 or 1 are invalid. | BOOL | | -| 4 | Empty | | | -| 5 | Empty | | | -| 6 | Empty | | | -| 7 | Empty | | | +| Param (Label) | 描述 | 值 | Units | +| -------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------ | ----- | +| 1 (Yaw) | Yaw angle to adjust steering by. | | 度 | +| 2 (Speed) | Speed. | | m/s | +| 3 (Angle) | Relative final angle (MAV_BOOL_FALSE: Absolute angle). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | | +| 4 | Empty | | | +| 5 | Empty | | | +| 6 | Empty | | | +| 7 | Empty | | | ### MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL (214) {#MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL} @@ -7176,15 +7176,15 @@ Set limits for external control Control vehicle engine. This is interpreted by the vehicles engine controller to change the target engine state. It is intended for vehicles with internal combustion engines -| Param (Label) | 描述 | 值 | Units | -| ----------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------- | ----- | -| 1 (Start Engine) | Start engine (BOOL_False: Stop engine). Values not equal to 0 or 1 are invalid. | BOOL | | -| 2 (Cold Start) | Cold start engine (BOOL_FALSE: Warm start). Values not equal to 0 or 1 are invalid. Controls use of choke where applicable | BOOL | | -| 3 (Height Delay) | Height delay. This is for commanding engine start only after the vehicle has gained the specified height. Used in VTOL vehicles during takeoff to start engine after the aircraft is off the ground. Zero for no delay. | min: 0 | m | -| 4 | Empty | | | -| 5 | Empty | | | -| 6 | Empty | | | -| 7 | Empty | | | +| Param (Label) | 描述 | 值 | Units | +| ----------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------ | ----- | +| 1 (Start Engine) | Start engine (MAV_BOOL_False: Stop engine). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | | +| 2 (Cold Start) | Cold start engine (MAV_BOOL_FALSE: Warm start). Values not equal to 0 or 1 are invalid. Controls use of choke where applicable | [MAV_BOOL](#MAV_BOOL) | | +| 3 (Height Delay) | Height delay. This is for commanding engine start only after the vehicle has gained the specified height. Used in VTOL vehicles during takeoff to start engine after the aircraft is off the ground. Zero for no delay. | min: 0 | m | +| 4 | Empty | | | +| 5 | Empty | | | +| 6 | Empty | | | +| 7 | Empty | | | ### MAV_CMD_DO_SET_MISSION_CURRENT (224) {#MAV_CMD_DO_SET_MISSION_CURRENT} @@ -7202,15 +7202,15 @@ Resetting also explicitly changes a mission state of [MISSION_STATE_COMPLETE](#M The command will ACK with [MAV_RESULT_FAILED](#MAV_RESULT_FAILED) if the sequence number is out of range (including if there is no mission item). -| Param (Label) | 描述 | 值 | -| ------------------------------------ | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------- | -| 1 (Number) | Mission sequence value to set. -1 for the current mission item (use to reset mission without changing current mission item). | min: -1 inc: 1 | -| 2 (Reset Mission) | Reset mission (BOOL_TRUE). Values not equal to 0 or 1 are invalid. Resets jump counters to initial values and changes mission state "completed" to be "active" or "paused". | BOOL | -| 3 | Empty | | -| 4 | Empty | | -| 5 | Empty | | -| 6 | Empty | | -| 7 | Empty | | +| Param (Label) | 描述 | 值 | +| ------------------------------------ | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------- | +| 1 (Number) | Mission sequence value to set. -1 for the current mission item (use to reset mission without changing current mission item). | min: -1 inc: 1 | +| 2 (Reset Mission) | Reset mission (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid. Resets jump counters to initial values and changes mission state "completed" to be "active" or "paused". | [MAV_BOOL](#MAV_BOOL) | +| 3 | Empty | | +| 4 | Empty | | +| 5 | Empty | | +| 6 | Empty | | +| 7 | Empty | | ### MAV_CMD_DO_LAST (240) {#MAV_CMD_DO_LAST} @@ -7233,8 +7233,8 @@ Trigger calibration. 只有在飞行前模式下才会接受此命令。 Except | Param (Label) | 描述 | 值 | | ------------------------------------------ | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------- | | 1 (Gyro Temperature) | 1: gyro calibration, 3: gyro temperature calibration | min: 0 max: 3 inc: 1 | -| 2 (Magnetometer) | Magnetometer calibration. Values not equal to 0 or 1 are invalid. | BOOL | -| 3 (Ground Pressure) | Ground pressure calibration. Values not equal to 0 or 1 are invalid. | BOOL | +| 2 (Magnetometer) | Magnetometer calibration. Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | +| 3 (Ground Pressure) | Ground pressure calibration. Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | | 4 (Remote Control) | 1: radio RC calibration, 2: RC trim calibration | min: 0 max: 1 inc: 1 | | 5 (Accelerometer) | 1: accelerometer calibration, 2: board level calibration, 3: accelerometer temperature calibration, 4: simple accelerometer calibration | min: 0 max: 4 inc: 1 | | 6 (Compmot or Airspeed) | 1: APM: compass/motor interference calibration (PX4: airspeed calibration, deprecated), 2: airspeed calibration | min: 0 max: 2 inc: 1 | @@ -7384,7 +7384,7 @@ Arms / Disarms a component | Param (Label) | 描述 | 值 | | -------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------------- | -| 1 (Arm) | Arm (BOOL_FALSE: disarm). Values not equal to 0 or 1 are invalid. | BOOL | +| 1 (Arm) | Arm (MAV_BOOL_FALSE: disarm). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | | 2 (Force) | 0: arm-disarm unless prevented by safety checks (i.e. when landed), 21196: force arming/disarming (e.g. allow arming to override preflight checks and disarming in flight) | min: 0 max: 21196 inc: 21196 | ### MAV_CMD_RUN_PREARM_CHECKS (401) {#MAV_CMD_RUN_PREARM_CHECKS} @@ -7403,9 +7403,9 @@ The command should return [MAV_RESULT_TEMPORARILY_REJECTED](#MAV_RESULT_TEMPORAR Turns illuminators ON/OFF. An illuminator is a light source that is used for lighting up dark areas external to the system: e.g. a torch or searchlight (as opposed to a light source for illuminating the system itself, e.g. an indicator light). -| Param (Label) | 描述 | 值 | -| -------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---- | -| 1 (Enable) | Illuminators on/off (BOOL_TRUE: illuminators on). Values not equal to 0 or 1 are invalid. | BOOL | +| Param (Label) | 描述 | 值 | +| -------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------ | +| 1 (Enable) | Illuminators on/off (MAV_BOOL_TRUE: illuminators on). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | ### MAV_CMD_DO_ILLUMINATOR_CONFIGURE (406) {#MAV_CMD_DO_ILLUMINATOR_CONFIGURE} @@ -7500,10 +7500,10 @@ Request the target system(s) emit a single instance of a specified message (i.e. Request MAVLink protocol version compatibility. All receivers should ACK the command and then emit their capabilities in an [PROTOCOL_VERSION](#PROTOCOL_VERSION) message -| Param (Label) | 描述 | 值 | -| -------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---- | -| 1 (Protocol) | Request supported protocol versions by all nodes on the network (BOOL_TRUE). Values not equal to 0 or 1 are invalid. | BOOL | -| 2 | Reserved (all remaining params) | | +| Param (Label) | 描述 | 值 | +| -------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------ | +| 1 (Protocol) | Request supported protocol versions by all nodes on the network (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | +| 2 | Reserved (all remaining params) | | ### MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES (520) — [DEP] {#MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES} @@ -7511,10 +7511,10 @@ Request MAVLink protocol version compatibility. All receivers should ACK the com Request autopilot capabilities. The receiver should ACK the command and then emit its capabilities in an [AUTOPILOT_VERSION](#AUTOPILOT_VERSION) message -| Param (Label) | 描述 | 值 | -| -------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------ | ---- | -| 1 (Version) | Request autopilot version (BOOL_TRUE). Values not equal to 0 or 1 are invalid. | BOOL | -| 2 | Reserved (all remaining params) | | +| Param (Label) | 描述 | 值 | +| -------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------ | +| 1 (Version) | Request autopilot version (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | +| 2 | Reserved (all remaining params) | | ### MAV_CMD_REQUEST_CAMERA_INFORMATION (521) — [DEP] {#MAV_CMD_REQUEST_CAMERA_INFORMATION} @@ -7522,10 +7522,10 @@ Request autopilot capabilities. The receiver should ACK the command and then emi Request camera information ([CAMERA_INFORMATION](#CAMERA_INFORMATION)). -| Param (Label) | 描述 | 值 | -| ----------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------- | ---- | -| 1 (Capabilities) | Request camera capabilities (BOOL_TRUE). Values not equal to 0 or 1 are invalid. | BOOL | -| 2 | Reserved (all remaining params) | | +| Param (Label) | 描述 | 值 | +| ----------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------ | +| 1 (Capabilities) | Request camera capabilities (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | +| 2 | Reserved (all remaining params) | | ### MAV_CMD_REQUEST_CAMERA_SETTINGS (522) — [DEP] {#MAV_CMD_REQUEST_CAMERA_SETTINGS} @@ -7533,10 +7533,10 @@ Request camera information ([CAMERA_INFORMATION](#CAMERA_INFORMATION)). Request camera settings ([CAMERA_SETTINGS](#CAMERA_SETTINGS)). -| Param (Label) | 描述 | 值 | -| -------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------- | ---- | -| 1 (Settings) | Request camera settings (BOOL_TRUE). Values not equal to 0 or 1 are invalid. | BOOL | -| 2 | Reserved (all remaining params) | | +| Param (Label) | 描述 | 值 | +| -------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------ | +| 1 (Settings) | Request camera settings (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | +| 2 | Reserved (all remaining params) | | ### MAV_CMD_REQUEST_STORAGE_INFORMATION (525) — [DEP] {#MAV_CMD_REQUEST_STORAGE_INFORMATION} @@ -7544,11 +7544,11 @@ Request camera settings ([CAMERA_SETTINGS](#CAMERA_SETTINGS)). Request storage information ([STORAGE_INFORMATION](#STORAGE_INFORMATION)). Use the command's target_component to target a specific component's storage. -| Param (Label) | 描述 | 值 | -| ---------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------- | -| 1 (Storage ID) | Storage ID (0 for all, 1 for first, 2 for second, etc.) | min: 0 inc: 1 | -| 2 (Information) | Request storage information (BOOL_TRUE). Values not equal to 0 or 1 are invalid. | BOOL | -| 3 | Reserved (all remaining params) | | +| Param (Label) | 描述 | 值 | +| ---------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------- | +| 1 (Storage ID) | Storage ID (0 for all, 1 for first, 2 for second, etc.) | min: 0 inc: 1 | +| 2 (Information) | Request storage information (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | +| 3 | Reserved (all remaining params) | | ### MAV_CMD_STORAGE_FORMAT (526) {#MAV_CMD_STORAGE_FORMAT} @@ -7557,8 +7557,8 @@ Format a storage medium. Once format is complete, a [STORAGE_INFORMATION](#STORA | Param (Label) | 描述 | 值 | | -------------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------- | | 1 (Storage ID) | Storage ID (1 for first, 2 for second, etc.) | min: 0 inc: 1 | -| 2 (Format) | Format storage (and reset image log). Values not equal to 0 or 1 are invalid. | BOOL | -| 3 (Reset Image Log) | Reset Image Log (without formatting storage medium). This will reset CAMERA_CAPTURE_STATUS.image_count and CAMERA_IMAGE_CAPTURED.image_index. Values not equal to 0 or 1 are invalid. | BOOL | +| 2 (Format) | Format storage (and reset image log). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | +| 3 (Reset Image Log) | Reset Image Log (without formatting storage medium). This will reset CAMERA_CAPTURE_STATUS.image_count and CAMERA_IMAGE_CAPTURED.image_index. Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | | 4 | Reserved (all remaining params) | | ### MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS (527) — [DEP] {#MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS} @@ -7567,10 +7567,10 @@ Format a storage medium. Once format is complete, a [STORAGE_INFORMATION](#STORA Request camera capture status ([CAMERA_CAPTURE_STATUS](#CAMERA_CAPTURE_STATUS)) -| Param (Label) | 描述 | 值 | -| ------------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------- | ---- | -| 1 (Capture Status) | Request camera capture status (BOOL_TRUE). Values not equal to 0 or 1 are invalid. | BOOL | -| 2 | Reserved (all remaining params) | | +| Param (Label) | 描述 | 值 | +| ------------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------ | +| 1 (Capture Status) | Request camera capture status (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | +| 2 | Reserved (all remaining params) | | ### MAV_CMD_REQUEST_FLIGHT_INFORMATION (528) — [DEP] {#MAV_CMD_REQUEST_FLIGHT_INFORMATION} @@ -7578,10 +7578,10 @@ Request camera capture status ([CAMERA_CAPTURE_STATUS](#CAMERA_CAPTURE_STATUS)) Request flight information ([FLIGHT_INFORMATION](#FLIGHT_INFORMATION)) -| Param (Label) | 描述 | 值 | -| ----------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------- | ---- | -| 1 (Flight Information) | Request flight information (BOOL_TRUE). Values not equal to 0 or 1 are invalid. | BOOL | -| 2 | Reserved (all remaining params) | | +| Param (Label) | 描述 | 值 | +| ----------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------ | +| 1 (Flight Information) | Request flight information (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | +| 2 | Reserved (all remaining params) | | ### MAV_CMD_RESET_CAMERA_SETTINGS (529) {#MAV_CMD_RESET_CAMERA_SETTINGS} @@ -7589,7 +7589,7 @@ Reset all camera settings to Factory Default | Param (Label) | 描述 | 值 | | --------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------- | -| 1 (Reset) | Reset all settings (BOOL_TRUE). Values not equal to 0 or 1 are invalid. | BOOL | +| 1 (Reset) | Reset all settings (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | | 2 (Target Camera ID) | Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission. | min: 0 max: 255 inc: 1 | ### MAV_CMD_SET_CAMERA_MODE (530) {#MAV_CMD_SET_CAMERA_MODE} @@ -7912,15 +7912,15 @@ Request to stop streaming log data over MAVLink Request to start/stop transmitting over the high latency telemetry -| Param (Label) | 描述 | 值 | -| -------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---- | -| 1 (Enable) | Start transmission over high latency telemetry (BOOL_FALSE: stop transmission). Values not equal to 0 or 1 are invalid. | BOOL | -| 2 | Empty | | -| 3 | Empty | | -| 4 | Empty | | -| 5 | Empty | | -| 6 | Empty | | -| 7 | Empty | | +| Param (Label) | 描述 | 值 | +| -------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------ | +| 1 (Enable) | Start transmission over high latency telemetry (MAV_BOOL_FALSE: stop transmission). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | +| 2 | Empty | | +| 3 | Empty | | +| 4 | Empty | | +| 5 | Empty | | +| 6 | Empty | | +| 7 | Empty | | ### MAV_CMD_PANORAMA_CREATE (2800) {#MAV_CMD_PANORAMA_CREATE} @@ -7979,15 +7979,15 @@ This command sets submode circle when vehicle is in guided mode. Vehicle flies a Delay mission state machine until gate has been reached. -| Param (Label) | 描述 | 值 | Units | -| ---------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------- | ----- | -| 1 (Geometry) | Geometry: 0: orthogonal to path between previous and next waypoint. | min: 0 inc: 1 | | -| 2 (UseAltitude) | Use altitude (BOOL_FALSE: ignore altitude). Values not equal to 0 or 1 are invalid. | BOOL | | -| 3 | Empty | | | -| 4 | Empty | | | -| 5 (Latitude) | Latitude | | | -| 6 (Longitude) | Longitude | | | -| 7 (Altitude) | Altitude | | m | +| Param (Label) | 描述 | 值 | Units | +| ---------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------- | ----- | +| 1 (Geometry) | Geometry: 0: orthogonal to path between previous and next waypoint. | min: 0 inc: 1 | | +| 2 (UseAltitude) | Use altitude (MAV_BOOL_FALSE: ignore altitude). Values not equal to 0 or 1 are invalid. | [MAV_BOOL](#MAV_BOOL) | | +| 3 | Empty | | | +| 4 | Empty | | | +| 5 (Latitude) | Latitude | | | +| 6 (Longitude) | Longitude | | | +| 7 (Altitude) | Altitude | | m | ### MAV_CMD_NAV_FENCE_RETURN_POINT (5000) {#MAV_CMD_NAV_FENCE_RETURN_POINT} diff --git a/zh/messages/development.md b/zh/messages/development.md index 01ee124e3..5617e5dce 100644 --- a/zh/messages/development.md +++ b/zh/messages/development.md @@ -38,8 +38,8 @@ span.warning { | Type | Defined | Included | | -------------------------- | ------- | -------- | | [Messages](#messages) | 12 | 229 | -| [Enums](#enumerated-types) | 11 | 148 | -| [Commands](#mav_commands) | 172 | 0 | +| [Enums](#enumerated-types) | 12 | 148 | +| [Commands](#mav_commands) | 173 | 0 | The following sections list all entities in the dialect (both included and defined in this file). @@ -413,6 +413,19 @@ State of RAIM processing. | 2 | [GPS_RAIM_STATE_OK](#GPS_RAIM_STATE_OK) | RAIM integrity check was successful. | | 3 | [GPS_RAIM_STATE_FAILED](#GPS_RAIM_STATE_FAILED) | RAIM integrity check failed. | +### ACTUATOR_TEST_GROUP — [WIP] {#ACTUATOR_TEST_GROUP} + +**WORK IN PROGRESS**: Do not use in stable production environments (it may change). + +Actuator groups to test in [MAV_CMD_ACTUATOR_GROUP_TEST](#MAV_CMD_ACTUATOR_GROUP_TEST). + +| 值 | Name | 描述 | +| ------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------------------- | +| 0 | [ACTUATOR_TEST_GROUP_ROLL_TORQUE](#ACTUATOR_TEST_GROUP_ROLL_TORQUE) | Actuators that contribute to roll torque. | +| 1 | [ACTUATOR_TEST_GROUP_PITCH_TORQUE](#ACTUATOR_TEST_GROUP_PITCH_TORQUE) | Actuators that contribute to pitch torque. | +| 2 | [ACTUATOR_TEST_GROUP_YAW_TORQUE](#ACTUATOR_TEST_GROUP_YAW_TORQUE) | Actuators that contribute to yaw torque. | +| 3 | [ACTUATOR_TEST_GROUP_COLLECTIVE_TILT](#ACTUATOR_TEST_GROUP_COLLECTIVE_TILT) | Actuators that affect collective tilt. | + ## Commands (MAV_CMD) {#mav_commands} ### MAV_CMD_DO_FIGURE_EIGHT (35) — [WIP] {#MAV_CMD_DO_FIGURE_EIGHT} @@ -456,6 +469,22 @@ Command protocol information: https://mavlink.io/en/services/command.html. | 6 | Reserved | | | 7 | WIP: upgrade progress report rate (can be used for more granular control). | | +### MAV_CMD_ACTUATOR_GROUP_TEST (309) — [WIP] {#MAV_CMD_ACTUATOR_GROUP_TEST} + +**WORK IN PROGRESS**: Do not use in stable production environments (it may change). + +Command to test groups of related actuators together. + +This might include groups such as the actuators that contribute to roll, pitch, or yaw torque, actuators that contribute to thrust in x, y, z axis, tilt mechanisms, flaps and spoilers, and so on. +This is similar to [MAV_CMD_ACTUATOR_TEST](#MAV_CMD_ACTUATOR_TEST), except that multiple actuators may be affected. +Different groups may also affect the same actuators (as in the case of controls that affect torque in different axes). +Autopilots must NACK this command with [MAV_RESULT_TEMPORARILY_REJECTED](#MAV_RESULT_TEMPORARILY_REJECTED) while armed. + +| Param (Label) | 描述 | 值 | +| -------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | ------------------------------------------------------------------------------------- | +| 1 (Group) | Actuator group to check, such as actuators related to roll torque. | [ACTUATOR_TEST_GROUP](#ACTUATOR_TEST_GROUP) | +| 2 (Value) | Value to set. This is a normalized value across the full range of the tested group [-1,1]. | min: -1 max: 1 | + ### MAV_CMD_DO_SET_SYS_CMP_ID (610) — [WIP] {#MAV_CMD_DO_SET_SYS_CMP_ID} **WORK IN PROGRESS**: Do not use in stable production environments (it may change). diff --git a/zh/messages/standard.md b/zh/messages/standard.md index 1db4a05cd..5180ad60e 100644 --- a/zh/messages/standard.md +++ b/zh/messages/standard.md @@ -44,12 +44,12 @@ The following sections list all entities in the dialect (both included and defin ## Enumerated Types -### BOOL {#BOOL} +### MAV_BOOL {#MAV_BOOL} (Bitmask) Enum used to indicate true or false (also: success or failure, enabled or disabled, active or inactive). -| 值 | Name | 描述 | -| ------------------------ | ---------------------------------------------- | ---------------------- | -| 0 | [BOOL_FALSE](#BOOL_FALSE) | False. | -| 1 | [BOOL_TRUE](#BOOL_TRUE) | True. | +| 值 | Name | 描述 | +| ---------------------------- | --------------------------------------------------------------------------- | ---------------------- | +| 0 | [MAV_BOOL_FALSE](#MAV_BOOL_FALSE) | False. | +| 1 | [MAV_BOOL_TRUE](#MAV_BOOL_TRUE) | True. |