Visualization in ROS
Overview
- ROS has several tools for interacting graphically with robotic systems.
- Much of this information has not been documented for ROS 2 but it is substantially similar to ROS 1, therefore these notes often refer to ROS 1 documentation.
Rviz2
rviz2
is used to visualize data in ROS in a 3D environment- In
rviz2
you add Display Types to the display and connect them to information thatrviz2
receives via ROS messages and parameters.- There are many built in Display Types, documented in FEATURES.md
Paths
- Paths allow you to visualize a series of points that have been visited over time
- These are visualized with the Path datatype using nav_msgs/Path messages
Visualization Messages
- The visualization_msgs package contains
messages for displaying visual primitives in
rviz2
using some Display Types in Rviz2
Markers
- Markers are the simplest visualization message
- They let you draw basic shapes at specified locations
- For example, spheres, cubes, cylinders, lines
- Markers are drawn by publishing visualization_msgs/msg/Marker messages.
- By default, the Marker display type listens on the
visualization_marker
topic, but this can be changed in the rviz2 gui or with remapping. - Markers have a
header
field that requires the time. Usingnode.get_clock().now()
for this ensures the Marker will be drawn - Be sure to set the alpha (
.a
) field to be non-zero (e.g. 1) so that the marker is not drawn transparently
- By default, the Marker display type listens on the
- These C++ tutorials mostly apply to python as well since they are simply setting values in the marker message topic
- Some important fields are
header
contains the time at which the marker comes into existence and the frame used to interpret any coordinatesns
andid
are used to identify the marker. For a given namespacens
each marker has an id. If you send a marker message with anid
andns
that already exists, you modify the existing markertype
What the shape of the marker is: =visualization_msgs.Marker.{ARROW | CUBE | SPHERE | CYLINDER …}action
Lets you eithervisualization_msgs.Marker.ADD
,visualization_msgs.Marker.DELETE
, orvisualization_msgs.Marker.DELETEALL
the markerspose
this is the 3D pose of the object, used to set its position and orientation relative toheader.frame_id
scale
used to set the size of the object. By default the markers are 1x1x1 meter.color
RGBA (red, green, blue, alpha) color (0 - 1). A common error is forgetting to set the alpha to a non-zero value, otherwise the marker is completely transparentlifetime
How long to display the marker before it disappears. Set to 0 for it to last forever (well at least as long as Rviz2 remains open!)frame_locked
- Controls behavior of the marker when it's parent frame moves. If this is true then the marker will always be at the same position relative to its parent frame, even if that frame moves after the marker is drawnpoints
andcolors
,text
,mesh_resource
are used for some marker types
- An example of markers is here https://github.com/m-elwin/me495_markers
MarkerArray
- The MarkerArray message consists of an array of Marker messages
- This message type lets you publish multiple markers with a single message
rviz2
has a DisplayType that can subscribe to aMarkerArray
message and visualize all markers in the array- If you are sending many markers, it is more efficient to send them as an array
Static Markers
- Some markers visualize something that does not move and therefore (in an ideal world) would only be published one time
- These markers could all be published in a single MarkerArray message, for example
- However, if
rviz
opens after the markers are published, it will not have received the message and will not display the markers- It is generally difficult and not a good idea to require one node to start before another in ROS
- ROS 1 had a mechanism called a "latching publisher" to help with this issue:
- The latching publisher remembers the last message it published
- When a new subscriber connects, that message is sent to the new subscriber
- For example, if
rviz
launched after the message is published, it would still receive the message due to the latching
- In ROS 2 the Quality of Service (QoS) settings enable emulating the behavior similar to ROS 1
- The publisher on the topic should have it's "Durability" set to
TRANSIENT_LOCAL
- The subscriber (e.g., the Marker Display in
rviz
) should also have it's "Durability" set toTRANSIENT_LOCAL
- When the subscriber connects to the publisher it will receive the last message published
- The main difference from ROS 1 is that both publisher and subscriber must have matching settings: see ros2 Issue on latching
- The publisher on the topic should have it's "Durability" set to
To set the QoS setting for Durability in python:
from rclpy.qos import QoSProfile, QoSDurabilityPolicy # The depth here is what you typically pass in as the 3rd argument to create_publisher qos = QoSProfile(depth=10, durability=QoSDurabilityPolicy.TRANSIENT_LOCAL) create_publisher(Type, "topic_name", qos)
- In
rviz
the Durability policy is selected from a list of options for the marker display widget
InteractiveMarkers
- Interactive Markers lets users manipulate markers inside Rviz2. Your nodes can then respond to the actions of the user.
- To use interactive markers, you create an
InteractiveMarkerServer
- This server creates the necessary publishers and subscribers
- You then provide a callback which gets called whenever the user manipulates the marker in rviz2
- You can call functions to change the marker in rviz2
- To learn interactive markers, you should go through at least the first two of these tutorials:
- An additional example of using interactive markers is here
Plugins
- Using markers enables you to create complex visualizations by building ROS messages
- However, marker messages are quite large and using many of them can become slow
- Fortunately,
rviz2
is modular: each of the built-in DisplayTypes is actually a plugin. - You can write your own plugins in C++ that contain display logic for your own message types
- Plugins can also add panels in
rviz2
(Panels Tutorial) - Plugins can also add tools that change what the mouse does in
rviz2
(Tools Tutorial).
rqt
- Qt is a library for creating graphical user interfaces
- rqt is a ROS package that enables you to create GUIs using ROS nodes
- If you create a widget in
Qt
you can wrap that widget withrqt
and use it as part of the ROS user interface - Essentially,
rqt
widgets can be docked and split in a parent window. These configurations can be saved so that others can reproduce your view - All built-in rqt plugins can be run with
ros2 run
- Type
ros2 run rqt_
then hit tab to see a list of packages. - Some of these tools are so useful and popular they have there own shortcuts on the path
- Type
rqt_
then tab to see these. For example - rqt_graph - seeing how nodes are connected to each other via topics
- rqt_console - reading debugging output from ros nodes
- rqt_logger_level - used to set debugging output level for ROS
rqt_plot
- plotting message values versus time
- Type
- Type
rqt_plot
- rqt_plot is the simplest way to draw real-time time-plots of data from ROS topics
- You can specify what fields of which topics to plot in the gui or
Plot Juggler
- Plot Juggler is an advanced tool for plotting time-series data
- With the plotjuggler-ros package, it is capable of plotting topics in realtime from ROS 2
- Plot Juggler has significantly more capability than
rqt_plot
ros2 run plotjuggler plotjuggler
- Click "Start" on the "ROS 2 Topic Subscriber" window to add ROS 2 topics to plot juggler
- In the window below you can click and drag message fields into the plotting area to plot them
- Select two fields and drag-and-drop with right click will allow you to plot one topic vs another