Skip to main content
Version: 1.5.0

MRS System's UAV-ROS API

The UAV can be given commands via the following managers and nodes.

ControlManager

The ControlManager takes care of executing the trackers and controllers and it maintains one of each as an active one. The controllers handle a feedback loop for stabilization and control of the UAV. The trackers are the reference generators for the controllers. High-level navigation (or a user) does not interact with the controllers/trackers directly. The managers provide most of the interface*.

The flow of information

The ControManager is subscribed to a source of UAV State, and it hands it to the trackers and controllers. With each update of the UAV State, the currently active tracker produces a new reference, and the currently active controller generates a new control output. The controllers and trackers can be switched in mid-flight to accommodate for different mission scenarios. Users supply the desired references to the ControlManager, which forwards the references to the currently active tracker and controller.

Provided topics

Please refer to control_manager.launch for a complete list of topics. Notable topics:

General topics reporting on the current state of the ControlManager:

topicdescriptiontopic type
control_manager/diagnosticsstatus of the ControlManagermrs_msgs/ControlManagerDiagnostics
control_manager/tracker_cmdcontrol reference from the active trackermrs_msgs/TrackerCommand
control_manager/mass_estimatetotal estimated massstd_msgs/Float64
control_manager/current_constraintscurrent values of the dynamic constraintsmrs_msgs::DynamicsConstraints
control_manager/headingcurrent headingmrs_msgs::Float64Stamped

Topics dedicated to Rviz vizualization:

topicdescriptiontopic type
control_manager/control_referencecontrol reference from the active trackernav_msgs/Odometry
control_manager/safety_area_markersRviz markers showing the safety areavisualization_msgs::MarkerArray
control_manager/safety_area_coordinatesRviz markers showing the coordinates of the safety areavisualization_msgs::MarkerArray
control_manager/disturbance_markersRviz markers showing the estimated distrubancesvisualization_msgs::MarkerArray
control_manager/trajectory_original/posespose array re-publishing the original set trajectorygeometry_msgs::PoseArray
control_manager/trajectory_original/markersRviz markers re-publishing the original set trajectoryvisualization_msgs::MarkerArray

Selected services for human-to-machine interaction:

Press <tab> after typing in the desired service to auto-complete the default arguments.

Use those services to interact with the drone from the terminal:

servicedescriptionservice typeargs
control_manager/gotofly to given coordinatesmrs_msgs/Vec4[x,y,z,hdg]
control_manager/goto_fcufly to given coordinates in the drone's framemrs_msgs/Vec4[x,y,z,hdg]
control_manager/goto_relativefly to relative coordinates in the world framemrs_msgs/Vec4[x,y,z,hdg]
control_manager/goto_altitudefly to a given height/altitude (the z coordinate)mrs_msgs/Vec1[z]
control_manager/set_headingset the headingmrs_msgs/Vec1[hdg]
control_manager/set_heading_relativeset a relative headingmrs_msgs/Vec1[hdg]

However, these services should not be used from within a program, since they lack the Header. The message header contains the frame of reference name and the timestamp.

Selected services for program-to-machine interaction:

Setting references:

servicedescriptionservice type
control_manager/referencefly to given coordinates in a given framemrs_msgs/ReferenceStampedSrv
control_manager/velocity_referencefly using velocity command (requires MpcTracker)mrs_msgs/VelocityReferenceStampedSrv
control_manager/trajectory_referencefly along a given trajectorymrs_msgs/TrajectoryReferenceSrv

Control of trajectory tracking:

servicedescriptionservice type
control_manager/goto_trajectory_startfly to the first point in the trajectorystd_srvs/Trigger
control_manager/start_trajectory_trackingstart trajectory trackingstd_srvs/Trigger
control_manager/stop_trajectory_trackingstop trajectory trackingstd_srvs/Trigger
control_manager/resume_trajectory_trackingresume previously stopped trajectory trackingstd_srvs/Trigger

Control of trackers and controllers:

servicedescriptionservice type
control_manager/switch_trackerswitch a trackermrs_msgs/String
control_manager/switch_controllerswitch a controllermrs_msgs/String

Safety and higher-level flight control:

servicedescriptionservice type
control_manager/ehoveremergency hoverstd_srvs/Trigger
control_manager/elandemergency landingstd_srvs/Trigger
control_manager/failsafeemergency failsafe landingstd_srvs/Trigger
control_manager/failsafe_escalatingemergency escalating failsafestd_srvs/Trigger
control_manager/motorsactivates/deactivates the control output (don't touch this!)std_srvs/SetBool

Transformation services:

servicedescriptionservice type
control_manager/transform_poseuses the mrs_lib::Transformer to transform geometry_msgs::PoseStampedmrs_msgs/TransformPoseSrv
control_manager/transform_vectoruses the mrs_lib::Transformer to transform geometry_msgs::Vector3Stampedmrs_msgs/TransformVector3Srv
control_manager/transform_referenceuses the mrs_lib::Transformer to transform mrs_msgs::ReferenceStampedmrs_msgs/TransformReferenceSrv

UavManager

The UavManager handles higher-level routines such as takeoff and landing. It also carries some non-essential safety routines.

Provided services

servicedescriptionservice type
uav_manager/takeofftake offstd_srvs/Trigger
uav_manager/landlandstd_srvs/Trigger
uav_manager/land_homereturn to the takeoff coordinates and landstd_srvs/Trigger
uav_manager/land_thereland on a particular placemrs_msgs/ReferenceStamped

ConstraintManager

The ConstraintManager handles the definition and switching of dynamics constraints for trackers. The constraints are supplied to all the loaded trackers by the ControlManager. To simplify the system structure, the ConstraintManager was created to load user-defined constraints from parameter files. The ConstraintManager maintains feasible constraints active during the flight based on the currently active estimator and allows users to change them by ROS service.

Provided topics

topicdescriptiontopic type
constraint_manager/diagnosticsstatus of the ConstraintManagermrs_msgs/ConstraintManagerDiagnostics

Provided services

servicedescriptionservice type
constraint_manager/set_constraintsactivate the desired constraintsmrs_msgs/String

GainManager

The GainManager handles the definition and switching of controller gains for the Se3Controller. The Se3Controller should be tuned for a particular UAV model, desired dynamics, and the state estimator used for obtained the UAV State. A proper set of gains needs to be provided based on the flight conditions and odometry source.

Provided topics

topicdescriptiontopic type
gain_manager/diagnosticsstatus of the GainManagermrs_msgs/GainManagerDiagnostics

Provided services

servicedescriptionservice type
gain_manager/set_gainsactivate the desired gainsmrs_msgs/String

Estimation Manager

The EstimationManager handles the fusion of various measurements of the UAV state variables (position, velocity, acceleration, heading, heading rate) and publishes UAV State messages for the ControlManager.

Provided topics

Please refer to estimation_manager.launch for a complete list of topics.

Notable topics:

topicdescriptiontopic type
estimation_manager/uav_stateUAV state msg used for controlmrs_msgs/UavState
estimation_manager/odom_maincurrent UAV state in the Odometry typenav_msgs/Odometry
estimation_manager/height_aglheight above ground levelmrs_msgs::Float64Stamped

Provided services

servicedescriptionservice type
estimation_manager/change_estimatorswitch to a desired estimatormrs_msgs/String

Transform manager

The TransformManager handles the broadcasting of default TFs. Can construct custom configurable TFs from nav_msgs/Odometry topics by adding them to the tf_sources array in custom config. Can republish a nav_msgs/Odometry topic in another frame by adding the frame_id to the republish_in_frames array.

Provided default TFs

TFdescriptionexample usage
fcu_untilted_origin(heading only) fcu frame with removed tilts (z-axis is aligned with the gravity vector)commanding UAV in body frame disregarding tilts
world_originorigin position defined by the world file, ENU orientation, based on UTM estimators (GPS, RTK, etc.), does not exist for non-UTM estimatorscommanding UAV localized by UTM-based estimator in a locally defined coordinate world
local_originorigin pose defined by the initial pose of the UAV (including orientation), exists for all estimatorscommanding UAV w.r.t. initial pose, universal frame that is always available
fixed_originorigin pose defined by the initial estimator, origin does not move after estimator switch, odometry in this frame jumps after estimator switchcommanding UAV w.r.t. initial estimator frame, universal frame that is always available
stable_originorigin pose defined by the initial estimator, origin jumps after estimator switch, odometry in this frame is smooth without jumpsmapping position of detected objects invariant to estimator switching
utm_originorigin position defined by the intersetion of the equator and the zone's central meridian, ENU orientationcommanding UAV in absolute metric coordinates irregardless of the current world file
mapping_origin_tforigin position and heading defined by initialization of a SLAM algorithm, origin tilt around x and y axes optionally defined by custom topicmapping of environment using a SLAM that cannot estimate orientation

Trajectory generation

The mrs_uav_trajectory_generation serves to generate a feasible time-parametrized trajectory from a desired waypoint path.

Provided topics

topicdescriptiontopic type
trajectory_generation/pathdesired path to flymrs_msgs/Path

Provided services

servicedescriptionservice type
trajectory_generation/pathdesired path to flymrs_msgs/PathSrv