Skip to content
Martin Molina edited this page May 11, 2021 · 21 revisions

This page describes common ROS topics and messages for interprocess communication used by Aerostack. The goal of this set of topics is to facilitate the interoperability of the ROS nodes in Aerostack.

The content of part of these messages can be visualized with the help of the following tool:

Sensor Measurements

Sensor measurements are values corresponding to direct measurements recorded by sensors.

Topic name ROS message Description
sensor_measurement/camera sensor_msgs/Image Raw image data received from camera (a general camera).
sensor_measurement/camera/front sensor_msgs/Image Raw image data received from front camera.
sensor_measurement/camera/bottom sensor_msgs/Image Raw image data received from the bottom camera.
sensor_measurement/gps sensor_msgs/NavSatFix GPS (Global Positioning System) coordinates
sensor_measurement/magnetometer geometry_msgs/Vector3Stamped Magnetic field measurement
sensor_measurement/imu sensor_msgs/Imu Inertial Measurement Unit data
sensor_measurement/pressure sensor_msgs/FluidPressure Pressure
sensor_measurement/temperature sensor_msgs/Temperature Temperature reading
sensor_measurement/battery_state sensor_msgs/BatteryState Battery state
sensor_measurement/altitude geometry_msgs/PointStamped Altitude respect to the ground (in the message PointStamped, only the z value is used)
sensor_measurement/sea_level_altitude geometry_msgs/PointStamped Sea level altitude

Deprecated topics:

Topic name ROS message Description
sensor_measurement/position geometry_msgs/PointStamped Position measured by sensor (e.g., using RTK)
sensor_measurement/odometry nav_msgs/Odometry Odometry estimated by the platform
sensor_measurement/linear_speed geometry_msgs/TwistStamped Linear speed estimated by odometry (e.g. using visual odometry)
sensor_measurement/rotation_angles geometry_msgs/Vector3Stamped Rotation angles yaw (rad), pitch (rad), roll (rad)

Raw localization from aerial platform

Raw values corresponding to state estimation performed by the aerial platform.

Topic name ROS message Description
raw_localization/position geometry_msgs/PointStamped Position estimated by the aerial platform
raw_localization/odometry nav_msgs/Odometry Odometry estimated by the platform
raw_localization/linear_speed geometry_msgs/TwistStamped Linear speed estimated by odometry (e.g. using visual odometry)
raw_localization/rotation_angles geometry_msgs/Vector3Stamped Rotation angles yaw (rad), pitch (rad), roll (rad)

Ground truth

These values are considered as true reference. They can be used, for example, to compare with measured values and values obtained by estimation algorithms. These values are generated by simulators or by redundant sensors (e.g., Opti Track).

Topic name ROS message Description
ground_truth/pose geometry_msgs/PoseStamped Pose of the robot considered as true
ground_truth/speed geometry_msgs/TwistStamped Speed of the robot considered as true

Self Localization

These values correspond to the robot localization in the environment together with kinematic values (e.g., speed) as they are believed by the robot. These values may be obtained, for example, by fusing sensor measurements with the help of extended Kalman filters (EKF).

Topic name ROS message Description
self_localization/position geometry_msgs/PointStamped Estimated position (x,y,z). This information usually corresponds to position that is not refined using data from IMU
self_localization/pose geometry_msgs/PoseStamped Estimated pose
self_localization/speed geometry_msgs/TwistStamped Estimated speed
self_localization/flight_state aerostack_msgs/flightState Flight state (landed, hovering, ...)

Environment Understanding

These values correspond to characteristics of the environment and its elements as they are believed by the robot.

ROS message Description
aerostack_msgs/DynamicObstacle.msg Pair of messages geometry_msgs/PointStamped.msgs and shape_msgs/SolidPrimitive.msgs
Topic name ROS message Description
environment/costmap nav_msgs/OccupancyGrid Environment map represented as an occupancy grid (as used by Navigation Stack). This is not implemented yet.
environment/path_blocked_by_obstacle std_msgs/Bool This message notifies that the current path cannot be followed because an obstacle has been detected along the path.
environment/social_communication_channel aerostack_msgs/SocialCommunicationStatement.msg Communication channel with all messages sent between different robots.
environment/shared_robot_positions_channel aerostack_msgs/SharedRobotPosition.msg Communication channel with positions (x,y,z) shared by multiple robots.
environment/message_from_robot aerostack_msgs/SocialCommunicationStatement.msg Message sent from another robot to the own robot.
environment/dynamic_obstacles aerostack_msgs/DynamicObstacles.msg Dynamic obstacles in the environment.

Motion References

These messages are motion values to be considered as goals by quadrotor controllers.

ROS message Description
aerostack_msgs/MotionControlMode.msg Control mode of quadrotor PID controller
Topic name ROS message Description
motion_reference/pose geometry_msgs/PoseStamped.msg Pose reference for the controller. The following values from the message are used <x, y, z, yaw> (the values for <pitch, roll> are discarded)
motion_reference/speed geometry_msgs/TwistStamped.msg Speed reference for the controller. The following values from the message are used <d_x, d_y, d_z, d_yaw> (the values for <d_pitch, d_roll> are discarded)
motion_reference/path nav_msgs/Path.msg Reference path to be tracked by the quadrotor. The path is defined as a list of points. Each point is defined with a pose <x, y, z, yaw> (the values for <pitch, roll> are discarded)
motion_reference/trajectory trajectory_msgs/MultiDOFJointTrajectory Desired trajectory reference with points, velocities and accelerations.
motion_reference/remaining_path nav_msgs/Path.msg Remaining points of the path being followed by the multirotor. This list of points is updated each time a point is reached. When the remaining path is updated with an empty list of points, the reference path has been completed by the multirotor. Each point is defined with a pose <x, y, z, yaw> (the values for <pitch, roll> are discarded)
motion_reference/assumed_control_mode aerostack_msgs/MotionControlMode.msg Current control mode of the flight motion controller
motion_reference/assumed_pose geometry_msgs/PoseStamped.msg Pose reference assumed by the controller. For example, the controller can generate a variable pose to follow a particular trajectory.
motion_reference/assumed_speed geometry_msgs/TwistStamped.msg Speed reference assumed by the controller. For example, the controller can generate a variable speed to follow a particular trajectory.
Service Name ROS service type Description
set_control_mode aerostack_msgs/SetControlMode Sets control mode of the PID controller.

Actuator Commands

Actuator commands are messages that are accepted by the actuators of the robotic platform.

Topic name ROS message Description
actuator_command/motor_speed mav_msgs/Actuators.msg Motor speeds of multirotor.
actuator_command/thrust mavros_msgs/Thrust Message Actuator command for the multirotor specifying thrust (N: Newtons).
actuator_command/pose geometry_msgs/PoseStamped Actuator command for the multirotor specifying x, y, z, roll, pitch and yaw.
actuator_command/speed geometry_msgs/TwistStamped.msg Actuator command for the multirotor specifying dx, dy, dz, roll rate, pitch rate and yaw rate.
actuator_command/gimbal_speed geometry_msgs/TwistStamped.msg Actuator command for the camera gimbal.
actuator_command/flight_action aerostack_msgs/FlightActionCommand.msg Flight command specifying a qualitative action of the robot (take off, hover or land). This command can be interpreted by some aerial platforms (e.g. Parrot drones) but it is ignored by others.
actuator_command/odometry_actuation [aerostack_msgs/OdometryActuation.msg] Actuation command specifying an action on the odometry (e.g., reset or stop).

Deprecated:

Topic name ROS message Description
actuator_command/roll_pitch_yaw_rate_thrust mav_msgs/RollPitchYawrateThrust.msg Actuator command for the multirotor specifying roll (rad), pitch (rad), yaw rate (rad/s) and thrust (N: Newtons).
actuator_command/roll_pitch geometry_msgs/PoseStamped.msg Actuator command for the multirotor specifying roll and pitch (the rest of values for <x, y, z, yaw> are discarded)
actuator_command/altitude_rate_yaw_rate geometry_msgs/TwistStamped.msg Actuator command for the multirotor specifying rates for altitude (d_z) and yaw (d_yaw) (the rest of values for <d_x, d_y, d_yaw, d_pitch, d_roll> are discarded)
Clone this wiki locally