PX4-Autopilot/msg/versioned/ArmingCheckReply.msg
Roman Bapst b26dd4d3f3
Commander: Introduce global_position_relaxed (#24280)
To separate accuracy requirements for VTOL hover and cruise.

- global_position_relaxed refers to having a valid horizontal velocity aid source 
in the estimator and a set global reference position, but poses no requirements 
on the accuracy of the provided position estimate. 
- Auto flight modes Mission, Loiter and RTL, while in fixed-wing mode, 
only require the relaxed global position going forward
- COM_POS_FS_EPH is thus no longer used on fixed-wing vehicles (resp. VTOL in FW)
- rename failsafe_flags.local_position_accuracy_low to failsafe_flags.position_accuracy_low
---------

Signed-off-by: RomanBapst <bapstroman@gmail.com>
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
Co-authored-by: Silvan <silvan@auterion.com>
2025-05-28 08:16:10 +02:00

36 lines
833 B
Plaintext

uint32 MESSAGE_VERSION = 1
uint64 timestamp # time since system start (microseconds)
uint8 request_id
uint8 registration_id
uint8 HEALTH_COMPONENT_INDEX_NONE = 0
uint8 health_component_index # HEALTH_COMPONENT_INDEX_*
bool health_component_is_present
bool health_component_warning
bool health_component_error
bool can_arm_and_run # whether arming is possible, and if it's a navigation mode, if it can run
uint8 num_events
Event[5] events
# Mode requirements
bool mode_req_angular_velocity
bool mode_req_attitude
bool mode_req_local_alt
bool mode_req_local_position
bool mode_req_local_position_relaxed
bool mode_req_global_position
bool mode_req_global_position_relaxed
bool mode_req_mission
bool mode_req_home_position
bool mode_req_prevent_arming
bool mode_req_manual_control
uint8 ORB_QUEUE_LENGTH = 4