mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-02 05:04:08 +08:00
A custom action waypoint is an action defined in a waypoint that is scripted and processed outside the flight controller, usually in a mission computer process. The ability to process that action in the mission computer should be coded by the user, or instead using the MAVSDK custom_action plugin implementation (a full-scale example can be seen in the integration tests directory). The custom action command associated, for now, is the MAV_CMD_WAYPOINT_USER_1 but will eventually be replaced with an appropriate MAV_CMD to the purpose. The modifications in the navigator module allow to block the navigator for an amount of time defined on param3 of the MAV_CMD_WAYPONT_USER_1 mission item. The navigator expects to receive a progress status of the action being process, which in the case of not received, will result on the mission continuing to the next waypoint, and a COMMAND_CANCEL to be broadcasted to cancel that same command. The mission will continue to the next waypoint as soon as an ACCEPTED ACK gets sent from the component processing the custom action.
26 lines
742 B
Plaintext
26 lines
742 B
Plaintext
uint64 timestamp # time since system start (microseconds)
|
|
uint8 VEHICLE_RESULT_ACCEPTED = 0
|
|
uint8 VEHICLE_RESULT_TEMPORARILY_REJECTED = 1
|
|
uint8 VEHICLE_RESULT_DENIED = 2
|
|
uint8 VEHICLE_RESULT_UNSUPPORTED = 3
|
|
uint8 VEHICLE_RESULT_FAILED = 4
|
|
uint8 VEHICLE_RESULT_IN_PROGRESS = 5
|
|
uint8 VEHICLE_RESULT_CANCELLED = 6
|
|
|
|
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
|
|
uint8 result
|
|
bool from_external
|
|
uint8 result_param1
|
|
int32 result_param2
|
|
uint8 target_system
|
|
uint8 target_component
|