Note: This tutorial assumes you are comfortable with using roscpp, and have gone through the ROS Tutorials.

Markers: Sending Basic Shapes (C++)

Description: Shows how to use visualization_msgs/Marker messages to send basic shapes (cube, sphere, cylinder, arrow) to rviz.

Tutorial Level: BEGINNER

Next Tutorial: Markers: Points and Lines

Intro

Unlike other displays, the Marker Display lets you visualize data in rviz without rviz knowing anything about interpreting that data. Instead, primitive objects are sent to the display through visualization_msgs/Marker messages, which let you show things like arrows, boxes, spheres and lines.

This tutorial will show you how to send the four basic shapes (boxes, spheres, cylinders, and arrows). We'll create a program that sends out a new marker every second, replacing the last one with a different shape.

Create a Scratch Package

Before getting started, let's create a scratch package to called using_markers, somewhere in your package path:

roscreate-pkg using_markers roscpp visualization_msgs

Sending Markers

The Code

Paste the following into src/basic_shapes.cpp:

https://code.ros.org/svn/ros-pkg/stacks/visualization_tutorials/trunk/visualization_marker_tutorials/src/basic_shapes.cpp

  31 
  32 #include <ros/ros.h>
  33 #include <visualization_msgs/Marker.h>
  34 
  35 
  36 int main( int argc, char** argv )
  37 {
  38   ros::init(argc, argv, "basic_shapes");
  39   ros::NodeHandle n;
  40   ros::Rate r(1);
  41   ros::Publisher marker_pub = n.advertise<visualization_msgs::Marker>("visualization_marker", 1);
  42 
  43   // Set our initial shape type to be a cube
  44 
  45   uint32_t shape = visualization_msgs::Marker::CUBE;
  46 
  47 
  48   while (ros::ok())
  49   {
  50     visualization_msgs::Marker marker;
  51     // Set the frame ID and timestamp.  See the TF tutorials for information on these.
  52     marker.header.frame_id = "/my_frame";
  53     marker.header.stamp = ros::Time::now();
  54 
  55     // Set the namespace and id for this marker.  This serves to create a unique ID
  56     // Any marker sent with the same namespace and id will overwrite the old one
  57 
  58     marker.ns = "basic_shapes";
  59     marker.id = 0;
  60 
  61     // Set the marker type.  Initially this is CUBE, and cycles between that and SPHERE, ARROW, and CYLINDER
  62 
  63     marker.type = shape;
  64 
  65     // Set the marker action.  Options are ADD and DELETE
  66 
  67     marker.action = visualization_msgs::Marker::ADD;
  68 
  69     // Set the pose of the marker.  This is a full 6DOF pose relative to the frame/time specified in the header
  70 
  71     marker.pose.position.x = 0;
  72     marker.pose.position.y = 0;
  73     marker.pose.position.z = 0;
  74     marker.pose.orientation.x = 0.0;
  75     marker.pose.orientation.y = 0.0;
  76     marker.pose.orientation.z = 0.0;
  77     marker.pose.orientation.w = 1.0;
  78 
  79     // Set the scale of the marker -- 1x1x1 here means 1m on a side
  80 
  81     marker.scale.x = 1.0;
  82     marker.scale.y = 1.0;
  83     marker.scale.z = 1.0;
  84 
  85     // Set the color -- be sure to set alpha to something non-zero!
  86 
  87     marker.color.r = 0.0f;
  88     marker.color.g = 1.0f;
  89     marker.color.b = 0.0f;
  90     marker.color.a = 1.0;
  91 
  92 
  93     marker.lifetime = ros::Duration();
  94 
  95     // Publish the marker
  96 
  97     marker_pub.publish(marker);
  98 
  99     // Cycle between different shapes
 100 
 101     switch (shape)
 102     {
 103     case visualization_msgs::Marker::CUBE:
 104       shape = visualization_msgs::Marker::SPHERE;
 105       break;
 106     case visualization_msgs::Marker::SPHERE:
 107       shape = visualization_msgs::Marker::ARROW;
 108       break;
 109     case visualization_msgs::Marker::ARROW:
 110       shape = visualization_msgs::Marker::CYLINDER;
 111       break;
 112     case visualization_msgs::Marker::CYLINDER:
 113       shape = visualization_msgs::Marker::CUBE;
 114       break;
 115     }
 116 
 117 
 118     r.sleep();
 119   }
 120 
 121 }

Now edit the CMakeLists.txt file in your using_markers package, and add:

rosbuild_add_executable(basic_shapes src/basic_shapes.cpp)

to the bottom.

The Code Explained

Ok, let's break down the code piece by piece:

  32 #include <ros/ros.h>
  33 #include <visualization_msgs/Marker.h>

You should have seen the ROS include by now. We also include the visualization_msgs/Marker message definition.

  36 int main( int argc, char** argv )
  37 {
  38   ros::init(argc, argv, "basic_shapes");
  39   ros::NodeHandle n;
  40   ros::Rate r(1);
  41   ros::Publisher marker_pub = n.advertise<visualization_msgs::Marker>("visualization_marker", 1);

This should look familiar. We initialize ROS, and create a ros::Publisher on the visualization_marker topic.

  45   uint32_t shape = visualization_msgs::Marker::CUBE;

Here we create an integer to keep track of what shape we're going to publish. The four types we'll be using here all use the visualization_msgs/Marker message in the same way, so we can simply switch out the shape type to demonstrate the four different shapes.

  48   while (ros::ok())
  49   {
  50     visualization_msgs::Marker marker;
  51     // Set the frame ID and timestamp.  See the TF tutorials for information on these.
  52     marker.header.frame_id = "/my_frame";
  53     marker.header.stamp = ros::Time::now();

This begins the meat of the program. First we create a visualization_msgs/Marker, and begin filling it out. The header here is a roslib/Header, which should be familiar if you've done the tf tutorials. We set the frame_id member to /my_frame as an example. In a running system this should be the frame relative to which you want the marker's pose to be interpreted.

  58     marker.ns = "basic_shapes";
  59     marker.id = 0;

The namespace (ns) and id are used to create a unique name for this marker. If a marker message is received with the same ns and id, the new marker will replace the old one.

  63     marker.type = shape;

This type field is what specifies the kind of marker we're sending. The available types are enumerated in the visualization_msgs/Marker message. Here we set the type to our shape variable, which will change every time through the loop.

  67     marker.action = visualization_msgs::Marker::ADD;

The action field is what specifies what to do with the marker. The options are visualization_msgs::Marker::ADD and visualization_msgs::Marker::DELETE. ADD is something of a misnomer, it really means "create or modify".

  71     marker.pose.position.x = 0;
  72     marker.pose.position.y = 0;
  73     marker.pose.position.z = 0;
  74     marker.pose.orientation.x = 0.0;
  75     marker.pose.orientation.y = 0.0;
  76     marker.pose.orientation.z = 0.0;
  77     marker.pose.orientation.w = 1.0;

Here we set the pose of the marker. The geometry_msgs/Pose message consists of a geometry_msgs/Vector3 to specify the position and a geometry_msgs/Quaternion to specify the orientation. Here we set the position to the origin, and the orientation to the identity orientation (note the 1.0 for w).

  81     marker.scale.x = 1.0;
  82     marker.scale.y = 1.0;
  83     marker.scale.z = 1.0;

Now we specify the scale of the marker. For the basic shapes, a scale of 1 in all directions means 1 meter on a side.

  87     marker.color.r = 0.0f;
  88     marker.color.g = 1.0f;
  89     marker.color.b = 0.0f;
  90     marker.color.a = 1.0;

The color of the marker is specified as a std_msgs/ColorRGBA. Each member should be between 0 and 1. An alpha (a) value of 0 means completely transparent (invisible), and 1 is completely opaque.

  93     marker.lifetime = ros::Duration();

The lifetime field specifies how long this marker should stick around before being automatically deleted. A value of ros::Duration() means never to auto-delete.

If a new marker message is received before the lifetime has been reached, the lifetime will be reset to the value in the new marker message.

  97     marker_pub.publish(marker);

Now we publish the marker.

 101     switch (shape)
 102     {
 103     case visualization_msgs::Marker::CUBE:
 104       shape = visualization_msgs::Marker::SPHERE;
 105       break;
 106     case visualization_msgs::Marker::SPHERE:
 107       shape = visualization_msgs::Marker::ARROW;
 108       break;
 109     case visualization_msgs::Marker::ARROW:
 110       shape = visualization_msgs::Marker::CYLINDER;
 111       break;
 112     case visualization_msgs::Marker::CYLINDER:
 113       shape = visualization_msgs::Marker::CUBE;
 114       break;
 115     }

This code lets us show all four shapes while just publishing the one marker message. Based on the current shape, we set what the next shape to publish will be.

 118     r.sleep();
 119   }

Sleep and loop back to the top.

Building the Code

You should be able to build the code with:

rosmake using_markers basic_shapes

Running the Code

You should be able to run the code with:

rosrun using_markers basic_shapes

Viewing the Markers

Now that you're publishing markers, you need to set rviz up to view them. First, make sure rviz is built:

rosmake rviz

Now, run rviz:

rosrun rviz rviz

If you've never used rviz before, please see the User's Guide to get you started.

The first thing to do, because we don't have any tf transforms setup, is to set both the Fixed and Target Frames to the frame we set the marker to above, /my_frame.

Next add a Markers display. Notice that the default topic specified, visualization_marker, is the same as the one being published.

You should now see a marker at the origin that changes shape every second: Basic Shapes

More Information

For more information on the different types of markers beyond the ones shown here, please see the Markers Display Page

Wiki: rviz/Tutorials/Markers: Basic Shapes (last edited 2010-07-29 21:20:47 by JoshFaust)