mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
* Add vitepress tree * Update existing workflows so they dont trigger on changes in the docs path * Add nojekyll, package.json, LICENCE etc * Add crowdin docs upload/download scripts * Add docs flaw checker workflows * Used docs prefix for docs workflows * Crowdin obvious fixes * ci: docs move to self hosted runner runs on a beefy server for faster builds Signed-off-by: Ramon Roche <mrpollo@gmail.com> * ci: don't run build action for docs or ci changes Signed-off-by: Ramon Roche <mrpollo@gmail.com> * ci: update runners Signed-off-by: Ramon Roche <mrpollo@gmail.com> * Add docs/en * Add docs assets and scripts * Fix up editlinks to point to PX4 sources * Download just the translations that are supported * Add translation sources for zh, uk, ko * Update latest tranlsation and uorb graphs * update vitepress to latest --------- Signed-off-by: Ramon Roche <mrpollo@gmail.com> Co-authored-by: Ramon Roche <mrpollo@gmail.com>
47 lines
2.0 KiB
Markdown
47 lines
2.0 KiB
Markdown
# VehicleCommandAck (UORB message)
|
|
|
|
Vehicle Command Ackonwledgement uORB message.
|
|
Used for acknowledging the vehicle command being received.
|
|
Follows the MAVLink COMMAND_ACK message definition
|
|
|
|
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleCommandAck.msg)
|
|
|
|
```c
|
|
# Vehicle Command Ackonwledgement uORB message.
|
|
# Used for acknowledging the vehicle command being received.
|
|
# Follows the MAVLink COMMAND_ACK message definition
|
|
|
|
uint32 MESSAGE_VERSION = 0
|
|
|
|
uint64 timestamp # time since system start (microseconds)
|
|
|
|
# Result cases. This follows the MAVLink MAV_RESULT enum definition
|
|
uint8 VEHICLE_CMD_RESULT_ACCEPTED = 0 # Command ACCEPTED and EXECUTED |
|
|
uint8 VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED = 1 # Command TEMPORARY REJECTED/DENIED |
|
|
uint8 VEHICLE_CMD_RESULT_DENIED = 2 # Command PERMANENTLY DENIED |
|
|
uint8 VEHICLE_CMD_RESULT_UNSUPPORTED = 3 # Command UNKNOWN/UNSUPPORTED |
|
|
uint8 VEHICLE_CMD_RESULT_FAILED = 4 # Command executed, but failed |
|
|
uint8 VEHICLE_CMD_RESULT_IN_PROGRESS = 5 # Command being executed |
|
|
uint8 VEHICLE_CMD_RESULT_CANCELLED = 6 # Command Canceled
|
|
|
|
# Arming denied specific cases
|
|
uint16 ARM_AUTH_DENIED_REASON_GENERIC = 0
|
|
uint16 ARM_AUTH_DENIED_REASON_NONE = 1
|
|
uint16 ARM_AUTH_DENIED_REASON_INVALID_WAYPOINT = 2
|
|
uint16 ARM_AUTH_DENIED_REASON_TIMEOUT = 3
|
|
uint16 ARM_AUTH_DENIED_REASON_AIRSPACE_IN_USE = 4
|
|
uint16 ARM_AUTH_DENIED_REASON_BAD_WEATHER = 5
|
|
|
|
uint8 ORB_QUEUE_LENGTH = 4
|
|
|
|
uint32 command # Command that is being acknowledged
|
|
uint8 result # Command result
|
|
uint8 result_param1 # Also used as progress[%], it can be set with the reason why the command was denied, or the progress percentage when result is MAV_RESULT_IN_PROGRESS
|
|
int32 result_param2 # Additional parameter of the result, example: which parameter of MAV_CMD_NAV_WAYPOINT caused it to be denied.
|
|
uint8 target_system
|
|
uint16 target_component # Target component / mode executor
|
|
|
|
bool from_external # Indicates if the command came from an external source
|
|
|
|
```
|