points_and_lines.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2010, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 // %Tag(FULLTEXT)%
31 #include <ros/ros.h>
32 #include <visualization_msgs/Marker.h>
33 
34 #include <cmath>
35 
36 int main( int argc, char** argv )
37 {
38  ros::init(argc, argv, "points_and_lines");
40  ros::Publisher marker_pub = n.advertise<visualization_msgs::Marker>("visualization_marker", 10);
41 
42  ros::Rate r(30);
43 
44  float f = 0.0;
45  while (ros::ok())
46  {
47 // %Tag(MARKER_INIT)%
48  visualization_msgs::Marker points, line_strip, line_list;
49  points.header.frame_id = line_strip.header.frame_id = line_list.header.frame_id = "/my_frame";
50  points.header.stamp = line_strip.header.stamp = line_list.header.stamp = ros::Time::now();
51  points.ns = line_strip.ns = line_list.ns = "points_and_lines";
52  points.action = line_strip.action = line_list.action = visualization_msgs::Marker::ADD;
53  points.pose.orientation.w = line_strip.pose.orientation.w = line_list.pose.orientation.w = 1.0;
54 // %EndTag(MARKER_INIT)%
55 
56 // %Tag(ID)%
57  points.id = 0;
58  line_strip.id = 1;
59  line_list.id = 2;
60 // %EndTag(ID)%
61 
62 // %Tag(TYPE)%
63  points.type = visualization_msgs::Marker::POINTS;
64  line_strip.type = visualization_msgs::Marker::LINE_STRIP;
65  line_list.type = visualization_msgs::Marker::LINE_LIST;
66 // %EndTag(TYPE)%
67 
68 // %Tag(SCALE)%
69  // POINTS markers use x and y scale for width/height respectively
70  points.scale.x = 0.2;
71  points.scale.y = 0.2;
72 
73  // LINE_STRIP/LINE_LIST markers use only the x component of scale, for the line width
74  line_strip.scale.x = 0.1;
75  line_list.scale.x = 0.1;
76 // %EndTag(SCALE)%
77 
78 // %Tag(COLOR)%
79  // Points are green
80  points.color.g = 1.0f;
81  points.color.a = 1.0;
82 
83  // Line strip is blue
84  line_strip.color.b = 1.0;
85  line_strip.color.a = 1.0;
86 
87  // Line list is red
88  line_list.color.r = 1.0;
89  line_list.color.a = 1.0;
90 // %EndTag(COLOR)%
91 
92 // %Tag(HELIX)%
93  // Create the vertices for the points and lines
94  for (uint32_t i = 0; i < 100; ++i)
95  {
96  float y = 5 * sin(f + i / 100.0f * 2 * M_PI);
97  float z = 5 * cos(f + i / 100.0f * 2 * M_PI);
98 
99  geometry_msgs::Point p;
100  p.x = (int32_t)i - 50;
101  p.y = y;
102  p.z = z;
103 
104  points.points.push_back(p);
105  line_strip.points.push_back(p);
106 
107  // The line list needs two points for each line
108  line_list.points.push_back(p);
109  p.z += 1.0;
110  line_list.points.push_back(p);
111  }
112 // %EndTag(HELIX)%
113 
114  marker_pub.publish(points);
115  marker_pub.publish(line_strip);
116  marker_pub.publish(line_list);
117 
118  r.sleep();
119 
120  f += 0.04;
121  }
122 }
123 // %EndTag(FULLTEXT)%
124 
void publish(const boost::shared_ptr< M > &message) const
f
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL bool ok()
int main(int argc, char **argv)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
static Time now()


visualization_marker_tutorials
Author(s): Josh Faust
autogenerated on Sat May 16 2020 03:49:20