Note: This tutorial assumes that you have completed the previous tutorials: Markers: Basic Shapes. |
Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags. |
Markers: Points and Lines (C++)
Description: Teaches how to use the visualization_msgs/Marker message to send points and lines to rviz.Tutorial Level: BEGINNER
Next Tutorial: Interactive Markers: Getting Started
Contents
Intro
In the Markers: Basic Shapes you learned how to send simple shapes to rviz using visualization markers. You can send more than just simple shapes though, and this tutorial will introduce you to the POINTS, LINE_STRIP and LINE_LIST marker types. For a full list of types, see the Marker Display page.
Using Points, Line Strips, and Line Lists
The POINTS, LINE_STRIP and LINE_LIST markers all use the points member of the visualization_msgs/Marker message. The POINTS type places a point at each point added. The LINE_STRIP type uses each point as a vertex in a connected set of lines, where point 0 is connected to point 1, 1 to 2, 2 to 3, etc. The LINE_LIST type creates unconnected lines out of each pair of points, i.e. point 0 to 1, 2 to 3, etc.
Anyway, let's get to the code:
The Code
30 #include <ros/ros.h>
31 #include <visualization_msgs/Marker.h>
32
33 #include <cmath>
34
35 int main( int argc, char** argv )
36 {
37 ros::init(argc, argv, "points_and_lines");
38 ros::NodeHandle n;
39 ros::Publisher marker_pub = n.advertise<visualization_msgs::Marker>("visualization_marker", 10);
40
41 ros::Rate r(30);
42
43 float f = 0.0;
44 while (ros::ok())
45 {
46
47 visualization_msgs::Marker points, line_strip, line_list;
48 points.header.frame_id = line_strip.header.frame_id = line_list.header.frame_id = "/my_frame";
49 points.header.stamp = line_strip.header.stamp = line_list.header.stamp = ros::Time::now();
50 points.ns = line_strip.ns = line_list.ns = "points_and_lines";
51 points.action = line_strip.action = line_list.action = visualization_msgs::Marker::ADD;
52 points.pose.orientation.w = line_strip.pose.orientation.w = line_list.pose.orientation.w = 1.0;
53
54
55
56 points.id = 0;
57 line_strip.id = 1;
58 line_list.id = 2;
59
60
61
62 points.type = visualization_msgs::Marker::POINTS;
63 line_strip.type = visualization_msgs::Marker::LINE_STRIP;
64 line_list.type = visualization_msgs::Marker::LINE_LIST;
65
66
67
68 // POINTS markers use x and y scale for width/height respectively
69 points.scale.x = 0.2;
70 points.scale.y = 0.2;
71
72 // LINE_STRIP/LINE_LIST markers use only the x component of scale, for the line width
73 line_strip.scale.x = 0.1;
74 line_list.scale.x = 0.1;
75
76
77
78 // Points are green
79 points.color.g = 1.0f;
80 points.color.a = 1.0;
81
82 // Line strip is blue
83 line_strip.color.b = 1.0;
84 line_strip.color.a = 1.0;
85
86 // Line list is red
87 line_list.color.r = 1.0;
88 line_list.color.a = 1.0;
89
90
91
92 // Create the vertices for the points and lines
93 for (uint32_t i = 0; i < 100; ++i)
94 {
95 float y = 5 * sin(f + i / 100.0f * 2 * M_PI);
96 float z = 5 * cos(f + i / 100.0f * 2 * M_PI);
97
98 geometry_msgs::Point p;
99 p.x = (int32_t)i - 50;
100 p.y = y;
101 p.z = z;
102
103 points.points.push_back(p);
104 line_strip.points.push_back(p);
105
106 // The line list needs two points for each line
107 line_list.points.push_back(p);
108 p.z += 1.0;
109 line_list.points.push_back(p);
110 }
111
112
113 marker_pub.publish(points);
114 marker_pub.publish(line_strip);
115 marker_pub.publish(line_list);
116
117 r.sleep();
118
119 f += 0.04;
120 }
121 }
The Code Explained
Now let's break down the code, skipping things that were explained in the previous tutorial. The overall effect created is a rotating helix with lines sticking upwards from each vertex.
47 visualization_msgs::Marker points, line_strip, line_list;
48 points.header.frame_id = line_strip.header.frame_id = line_list.header.frame_id = "/my_frame";
49 points.header.stamp = line_strip.header.stamp = line_list.header.stamp = ros::Time::now();
50 points.ns = line_strip.ns = line_list.ns = "points_and_lines";
51 points.action = line_strip.action = line_list.action = visualization_msgs::Marker::ADD;
52 points.pose.orientation.w = line_strip.pose.orientation.w = line_list.pose.orientation.w = 1.0;
Here we create three visualization_msgs/Marker messages and initialize all of their shared data. We take advantage of the fact that message members default to 0 and only set the w member of the pose.
We assign three different ids to the three markers. The use of the points_and_lines namespace ensures they won't collide with other broadcasters.
Here we set the marker types to POINTS, LINE_STRIP and LINE_LIST.
The scale member means different things for these marker types. The POINTS marker uses the x and y members for width and height respectively, while the LINE_STRIP and LINE_LIST markers only use the x component, which defines the line width. Scale values are in meters.
Here we set the points to green, the line strip to blue, and the line list to red.
92 // Create the vertices for the points and lines
93 for (uint32_t i = 0; i < 100; ++i)
94 {
95 float y = 5 * sin(f + i / 100.0f * 2 * M_PI);
96 float z = 5 * cos(f + i / 100.0f * 2 * M_PI);
97
98 geometry_msgs::Point p;
99 p.x = (int32_t)i - 50;
100 p.y = y;
101 p.z = z;
102
103 points.points.push_back(p);
104 line_strip.points.push_back(p);
105
106 // The line list needs two points for each line
107 line_list.points.push_back(p);
108 p.z += 1.0;
109 line_list.points.push_back(p);
110 }
We use sine and cosine to generate a helix. The POINTS and LINE_STRIP markers both require only a point for each vertex, while the LINE_LIST marker requires 2.
Viewing the Markers
Set up rviz the same way you did in the last tutorial, which is as follows:
Edit the CMakeLists.txt file in your using_markers package, and add to the bottom:
rosbuild_add_executable(points_and_lines src/points_and_lines.cpp)
Then,
$ rosmake using_markers
add_executable(points_and_lines src/points_and_lines.cpp) target_link_libraries(points_and_lines ${catkin_LIBRARIES})
Then,
$ catkin_make
Then,
$ rosrun rviz rviz & $ rosrun using_markers points_and_lines
You should see a rotating helix that looks something like this:
Next Steps
The Marker Display page has a list of all the markers and options supported by rviz. Try out some of the other markers!