Skip to content

Commit

Permalink
add mode registration messages
Browse files Browse the repository at this point in the history
  • Loading branch information
bkueng committed Jul 20, 2023
1 parent 67d6426 commit 77d7b97
Show file tree
Hide file tree
Showing 16 changed files with 204 additions and 42 deletions.
34 changes: 34 additions & 0 deletions msg/ArmingCheckReply.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
uint64 timestamp # time since system start (microseconds)

uint8 request_id
uint8 registration_id

uint8 HEALTH_COMPONENT_INDEX_NONE = 0
uint8 HEALTH_COMPONENT_INDEX_AVOIDANCE = 19

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_mission
bool mode_req_home_position
bool mode_req_prevent_arming
bool mode_req_manual_control


uint8 ORB_QUEUE_LENGTH = 4

7 changes: 7 additions & 0 deletions msg/ArmingCheckRequest.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
uint64 timestamp # time since system start (microseconds)

# broadcast message to request all registered arming checks to be reported

uint8 request_id


19 changes: 19 additions & 0 deletions msg/ConfigOverrides.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
# Configurable overrides by (external) modes or mode executors
uint64 timestamp # time since system start (microseconds)

bool disable_auto_disarm # Prevent the drone from automatically disarming after landing (if configured)

bool defer_failsafes # Defer all failsafes that can be deferred (until the flag is cleared)
int16 defer_failsafes_timeout_s # Maximum time a failsafe can be deferred. 0 = system default, -1 = no timeout


int8 SOURCE_TYPE_MODE = 0
int8 SOURCE_TYPE_MODE_EXECUTOR = 1
int8 source_type

uint8 source_id # ID depending on source_type

uint8 ORB_QUEUE_LENGTH = 4

# TOPICS config_overrides config_overrides_request

11 changes: 11 additions & 0 deletions msg/MessageFormatRequest.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
uint64 timestamp # time since system start (microseconds)

# Request to PX4 to get the hash of a message, to check for message
# compatibility

uint16 LATEST_PROTOCOL_VERSION = 1 # Current version of this protocol. Increase this whenever the MessageFormatRequest or MessageFormatResponse changes.

uint16 protocol_version # Must be set to LATEST_PROTOCOL_VERSION. Do not change this field, it must be the first field after the timestamp

char[50] topic_name # E.g. /fmu/in/vehicle_command

11 changes: 11 additions & 0 deletions msg/MessageFormatResponse.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
uint64 timestamp # time since system start (microseconds)

# Response from PX4 with the format of a message

uint16 protocol_version # Must be set to LATEST_PROTOCOL_VERSION. Do not change this field, it must be the first field after the timestamp

char[50] topic_name # E.g. /fmu/in/vehicle_command

bool success
uint32 message_hash # hash over all message fields

14 changes: 14 additions & 0 deletions msg/RegisterExtComponentReply.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
uint64 timestamp # time since system start (microseconds)

uint64 request_id # ID from the request
char[25] name # name from the request

uint16 px4_sdk_api_version

bool success
int8 arming_check_id # arming check registration ID (-1 if invalid)
int8 mode_id # assigned mode ID (-1 if invalid)
int8 mode_executor_id # assigned mode executor ID (-1 if invalid)

uint8 ORB_QUEUE_LENGTH = 2

21 changes: 21 additions & 0 deletions msg/RegisterExtComponentRequest.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
# Request to register an external component
uint64 timestamp # time since system start (microseconds)

uint64 request_id # ID, set this to a random value
char[25] name # either the requested mode name, or component name

uint16 LATEST_PX4_SDK_API_VERSION = 1 # API version compatibility. Increase this on a breaking semantic change. Changes to any message field are detected separately and do not require an API version change.

uint16 px4_sdk_api_version # Set to LATEST_PX4_SDK_API_VERSION

# Components to be registered
bool register_arming_check
bool register_mode # registering a mode also requires arming_check to be set
bool register_mode_executor # registering an executor also requires a mode to be registered (which is the owned mode by the executor)

bool enable_replace_internal_mode # set to true if an internal mode should be replaced
uint8 replace_internal_mode # vehicle_status::NAVIGATION_STATE_*
bool activate_mode_immediately # switch to the registered mode (can only be set in combination with an executor)


uint8 ORB_QUEUE_LENGTH = 2
8 changes: 4 additions & 4 deletions msg/SensorGps.msg
Original file line number Diff line number Diff line change
Expand Up @@ -5,10 +5,10 @@ uint64 timestamp_sample

uint32 device_id # unique device ID for the sensor that does not change between power cycles

float64 latitude_deg # Latitude in degrees, allows centimeter level RTK precision
float64 longitude_deg # Longitude in degrees, allows centimeter level RTK precision
float64 altitude_msl_m # Altitude above MSL, meters
float64 altitude_ellipsoid_m # Altitude above Ellipsoid, meters
int32 lat # Latitude in 1E-7 degrees
int32 lon # Longitude in 1E-7 degrees
int32 alt # Altitude in 1E-3 meters above MSL, (millimetres)
int32 alt_ellipsoid # Altitude in 1E-3 meters bove Ellipsoid, (millimetres)

float32 s_variance_m_s # GPS speed accuracy estimate, (metres/sec)
float32 c_variance_rad # GPS course accuracy estimate, (radians)
Expand Down
34 changes: 0 additions & 34 deletions msg/SensorUwb.msg

This file was deleted.

10 changes: 10 additions & 0 deletions msg/UnregisterExtComponent.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
uint64 timestamp # time since system start (microseconds)

char[25] name # either the mode name, or component name

int8 arming_check_id # arming check registration ID (-1 if not registered)
int8 mode_id # assigned mode ID (-1 if not registered)
int8 mode_executor_id # assigned mode executor ID (-1 if not registered)



15 changes: 15 additions & 0 deletions msg/UwbDistance.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
# UWB distance contains the distance information measured by an ultra-wideband positioning system,
# such as Pozyx or NXP Rddrone.

uint64 timestamp # time since system start (microseconds)
uint32 time_uwb_ms # Time of UWB device in ms
uint32 counter # Number of Ranges since last Start of Ranging
uint32 sessionid # UWB SessionID
uint32 time_offset # Time between Ranging Rounds in ms
uint16 status # status feedback #

uint16[12] anchor_distance # distance in cm to each UWB Anchor (UWB Device which takes part in Ranging)
bool[12] nlos # Visual line of sight yes/no
float32[12] aoafirst # Angle of arrival of first incoming RX msg

float32[3] position # Position of the Landing point in relation to the Drone (x,y,z in Meters NED)
25 changes: 25 additions & 0 deletions msg/UwbGrid.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
# UWB report message contains the grid information measured by an ultra-wideband positioning system,
# such as Pozyx or NXP Rddrone.

uint64 timestamp # time since system start (microseconds)
uint16 initator_time # time to synchronize clocks (microseconds)
uint8 num_anchors # Number of anchors

float64[4] target_gps # GPS position of target of the UWB system (Lat / Lon / Alt / Yaw Offset to true North)

# Grid position information
# Position in x,y,z in (x,y,z in centimeters NED)
# staring with POI and Anchor 0 up to Anchor 11
int16[3] target_pos # Point of Interest, mostly landing Target x,y,z
int16[3] anchor_pos_0
int16[3] anchor_pos_1
int16[3] anchor_pos_2
int16[3] anchor_pos_3
int16[3] anchor_pos_4
int16[3] anchor_pos_5
int16[3] anchor_pos_6
int16[3] anchor_pos_7
int16[3] anchor_pos_8
int16[3] anchor_pos_9
int16[3] anchor_pos_10
int16[3] anchor_pos_11
8 changes: 6 additions & 2 deletions msg/VehicleCommand.msg
Original file line number Diff line number Diff line change
Expand Up @@ -70,6 +70,7 @@ uint16 VEHICLE_CMD_PREFLIGHT_UAVCAN = 243 # UAVCAN configuration. If param 1 ==
uint16 VEHICLE_CMD_PREFLIGHT_STORAGE = 245 # Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Reserved| Reserved| Empty| Empty| Empty|
uint16 VEHICLE_CMD_PREFLIGHT_REBOOT_SHUTDOWN = 246 # Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty|
uint16 VEHICLE_CMD_OBLIQUE_SURVEY=260 # Mission command to set a Camera Auto Mount Pivoting Oblique Survey for this flight|Camera trigger distance (meters)| Shutter integration time (ms)| Camera minimum trigger interval| Number of positions| Roll| Pitch| Empty|
uint16 VEHICLE_CMD_DO_SET_STANDARD_MODE=262 # Enable the specified standard MAVLink mode |MAV_STANDARD_MODE|
uint16 VEHICLE_CMD_GIMBAL_DEVICE_INFORMATION = 283 # Command to ask information about a low level gimbal

uint16 VEHICLE_CMD_MISSION_START = 300 # start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)|
Expand Down Expand Up @@ -102,6 +103,7 @@ uint16 VEHICLE_CMD_DO_WINCH = 42600 # Command to operate winch.
# PX4 vehicle commands (beyond 16 bit mavlink commands)
uint32 VEHICLE_CMD_PX4_INTERNAL_START = 65537 # start of PX4 internal only vehicle commands (> UINT16_MAX)
uint32 VEHICLE_CMD_SET_GPS_GLOBAL_ORIGIN = 100000 # Sets the GPS coordinates of the vehicle local origin (0,0,0) position. |Empty|Empty|Empty|Empty|Latitude|Longitude|Altitude|
uint32 VEHICLE_CMD_SET_NAV_STATE = 100001 # Change mode by specifying nav_state directly. |nav_state|Empty|Empty|Empty|Empty|Empty|Empty|

uint8 VEHICLE_MOUNT_MODE_RETRACT = 0 # Load and keep safe position (Roll,Pitch,Yaw) from permanent memory and stop stabilization |
uint8 VEHICLE_MOUNT_MODE_NEUTRAL = 1 # Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. |
Expand Down Expand Up @@ -173,8 +175,10 @@ uint32 command # Command ID
uint8 target_system # System which should execute the command
uint8 target_component # Component which should execute the command, 0 for all components
uint8 source_system # System sending the command
uint8 source_component # Component sending the command
uint16 source_component # Component / mode executor sending the command
uint8 confirmation # 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
bool from_external

# TOPICS vehicle_command gimbal_v1_command
uint16 COMPONENT_MODE_EXECUTOR_START = 1000

# TOPICS vehicle_command gimbal_v1_command vehicle_command_mode_executor
2 changes: 1 addition & 1 deletion msg/VehicleCommandAck.msg
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,6 @@ 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
uint8 target_component
uint16 target_component # Target component / mode executor

bool from_external # Indicates if the command came from an external source
6 changes: 6 additions & 0 deletions msg/VehicleControlMode.msg
Original file line number Diff line number Diff line change
Expand Up @@ -14,3 +14,9 @@ bool flag_control_position_enabled # true if position is controlled
bool flag_control_altitude_enabled # true if altitude is controlled
bool flag_control_climb_rate_enabled # true if climb rate is controlled
bool flag_control_termination_enabled # true if flighttermination is enabled
bool flag_control_allocation_enabled # true if control allocation is enabled

# TODO: use dedicated topic for external requests
uint8 source_id # Mode ID (nav_state)

# TOPICS vehicle_control_mode config_control_setpoints
21 changes: 20 additions & 1 deletion msg/VehicleStatus.msg
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,20 @@ uint8 NAVIGATION_STATE_AUTO_FOLLOW_TARGET = 19 # Auto Follow
uint8 NAVIGATION_STATE_AUTO_PRECLAND = 20 # Precision land with landing target
uint8 NAVIGATION_STATE_ORBIT = 21 # Orbit in a circle
uint8 NAVIGATION_STATE_AUTO_VTOL_TAKEOFF = 22 # Takeoff, transition, establish loiter
uint8 NAVIGATION_STATE_MAX = 23
uint8 NAVIGATION_STATE_EXTERNAL1 = 23
uint8 NAVIGATION_STATE_EXTERNAL2 = 24
uint8 NAVIGATION_STATE_EXTERNAL3 = 25
uint8 NAVIGATION_STATE_EXTERNAL4 = 26
uint8 NAVIGATION_STATE_EXTERNAL5 = 27
uint8 NAVIGATION_STATE_EXTERNAL6 = 28
uint8 NAVIGATION_STATE_EXTERNAL7 = 29
uint8 NAVIGATION_STATE_EXTERNAL8 = 30
uint8 NAVIGATION_STATE_MAX = 31

uint8 executor_in_charge # Current mode executor in charge (0=Autopilot)

uint32 valid_nav_states_mask # Bitmask for all valid nav_state values
uint32 can_set_nav_states_mask # Bitmask for all modes that a user can select

# Bitmask of detected failures
uint16 failure_detector_status
Expand All @@ -83,8 +96,13 @@ uint8 VEHICLE_TYPE_FIXED_WING = 2
uint8 VEHICLE_TYPE_ROVER = 3
uint8 VEHICLE_TYPE_AIRSHIP = 4

uint8 FAILSAFE_DEFER_STATE_DISABLED = 0
uint8 FAILSAFE_DEFER_STATE_ENABLED = 1
uint8 FAILSAFE_DEFER_STATE_WOULD_FAILSAFE = 2 # Failsafes deferred, but would trigger a failsafe

bool failsafe # true if system is in failsafe state (e.g.:RTL, Hover, Terminate, ...)
bool failsafe_and_user_took_over # true if system is in failsafe state but the user took over control
uint8 failsafe_defer_state # one of FAILSAFE_DEFER_STATE_*

# Link loss
bool gcs_connection_lost # datalink to GCS lost
Expand Down Expand Up @@ -121,3 +139,4 @@ bool rc_calibration_in_progress
bool calibration_enabled

bool pre_flight_checks_pass # true if all checks necessary to arm pass

0 comments on commit 77d7b97

Please sign in to comment.