commander: implement external modes and mode executors

This commit is contained in:
Beat Küng
2022-11-07 15:57:51 +01:00
parent 58d2badf9f
commit fbbccf6997
32 changed files with 1632 additions and 51 deletions
+34
View File
@@ -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
View File
@@ -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
+5
View File
@@ -49,6 +49,8 @@ set(msg_files
Airspeed.msg
AirspeedValidated.msg
AirspeedWind.msg
ArmingCheckReply.msg
ArmingCheckRequest.msg
AutotuneAttitudeControlStatus.msg
BatteryStatus.msg
ButtonEvent.msg
@@ -161,6 +163,8 @@ set(msg_files
RateCtrlStatus.msg
RcChannels.msg
RcParameterMap.msg
RegisterExtComponentReply.msg
RegisterExtComponentRequest.msg
Rpm.msg
RtlTimeEstimate.msg
SatelliteInfo.msg
@@ -198,6 +202,7 @@ set(msg_files
UavcanParameterValue.msg
UlogStream.msg
UlogStreamAck.msg
UnregisterExtComponent.msg
VehicleAcceleration.msg
VehicleAirData.msg
VehicleAngularAccelerationSetpoint.msg
+14
View File
@@ -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_ros2_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
View File
@@ -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_ROS2_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_ros2_api_version # Set to LATEST_PX4_ROS2_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
+10
View File
@@ -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)
+4 -2
View File
@@ -174,8 +174,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
+1 -1
View File
@@ -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
+5
View File
@@ -15,3 +15,8 @@ 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
+11 -1
View File
@@ -52,7 +52,17 @@ 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)
# Bitmask of detected failures
uint16 failure_detector_status