Browse Source

Add takeoff commands / flags

sbg
Lorenz Meier 9 years ago
parent
commit
7d59213a01
  1. 6
      msg/vehicle_status.msg

6
msg/vehicle_status.msg

@ -9,7 +9,8 @@ uint8 MAIN_STATE_ACRO = 6 @@ -9,7 +9,8 @@ uint8 MAIN_STATE_ACRO = 6
uint8 MAIN_STATE_OFFBOARD = 7
uint8 MAIN_STATE_STAB = 8
uint8 MAIN_STATE_RATTITUDE = 9
uint8 MAIN_STATE_MAX = 10
uint8 MAIN_STATE_AUTO_TAKEOFF = 10
uint8 MAIN_STATE_MAX = 11
# If you change the order, add or remove arming_state_t states make sure to update the arrays
# in state_machine_helper.cpp as well.
@ -43,7 +44,8 @@ uint8 NAVIGATION_STATE_TERMINATION = 13 # Termination mode @@ -43,7 +44,8 @@ uint8 NAVIGATION_STATE_TERMINATION = 13 # Termination mode
uint8 NAVIGATION_STATE_OFFBOARD = 14
uint8 NAVIGATION_STATE_STAB = 15 # Stabilized mode
uint8 NAVIGATION_STATE_RATTITUDE = 16 # Rattitude (aka "flip") mode
uint8 NAVIGATION_STATE_MAX = 17
uint8 NAVIGATION_STATE_AUTO_TAKEOFF = 17 # Takeoff
uint8 NAVIGATION_STATE_MAX = 18
# VEHICLE_MODE_FLAG, same as MAV_MODE_FLAG of MAVLink 1.0 protocol
uint8 VEHICLE_MODE_FLAG_SAFETY_ARMED = 128

Loading…
Cancel
Save