Vehicle command for Prearm Safety button (#26079)

* added vehicle command and support to remotely activate/deactivate the safety system (#26078)

* added print_status support for prearm safety status

* updated safety button to map to MAV_CMD_DO_SET_SAFETY_SWITCH_STATE = '5300'

* safety switch cmd: fixed incorrect catch-all and added commanded_state variable for easier reading
This commit is contained in:
Brandon W. Banks
2025-12-15 14:25:32 -06:00
committed by GitHub
parent 8604604a5b
commit 1345b3500a
4 changed files with 59 additions and 0 deletions
+5
View File
@@ -100,6 +100,7 @@ uint16 VEHICLE_CMD_LOGGING_START = 2510 # Start streaming ULog data.
uint16 VEHICLE_CMD_LOGGING_STOP = 2511 # Stop streaming ULog data.
uint16 VEHICLE_CMD_CONTROL_HIGH_LATENCY = 2600 # Control starting/stopping transmitting data over the high latency link.
uint16 VEHICLE_CMD_DO_VTOL_TRANSITION = 3000 # Command VTOL transition.
uint16 VEHICLE_CMD_DO_SET_SAFETY_SWITCH_STATE = 5300 # Command safety on/off. |1 to activate safety, 0 to deactivate safety and allow control surface movements|Unused|Unused|Unused|Unused|Unused|Unused|
uint16 VEHICLE_CMD_ARM_AUTHORIZATION_REQUEST = 3001 # Request arm authorization.
uint16 VEHICLE_CMD_PAYLOAD_PREPARE_DEPLOY = 30001 # Prepare a payload deployment in the flight plan.
uint16 VEHICLE_CMD_PAYLOAD_CONTROL_DEPLOY = 30002 # Control a pre-programmed payload deployment.
@@ -179,6 +180,10 @@ int8 ARMING_ACTION_ARM = 1
uint8 GRIPPER_ACTION_RELEASE = 0
uint8 GRIPPER_ACTION_GRAB = 1
# Used as param1 in DO_SET_SAFETY_SWITCH_STATE command.
uint8 SAFETY_OFF = 0
uint8 SAFETY_ON = 1
uint8 ORB_QUEUE_LENGTH = 8
float32 param1 # Parameter 1, as defined by MAVLink uint16 VEHICLE_CMD enum.