/* * Copyright (c) 2010, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above copyright * notice, this list of conditions and the following disclaimer in the * documentation and/or other materials provided with the distribution. * * Neither the name of the Willow Garage, Inc. nor the names of its * contributors may be used to endorse or promote products derived from * this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ // %Tag(FULLTEXT)% #include #include #include int main( int argc, char** argv ) { ros::init(argc, argv, "points_and_lines"); ros::NodeHandle n; ros::Publisher marker_pub = n.advertise("visualization_marker", 10); ros::Rate r(30); float f = 0.0; while (ros::ok()) { // %Tag(MARKER_INIT)% visualization_msgs::Marker points, line_strip, line_list; points.header.frame_id = line_strip.header.frame_id = line_list.header.frame_id = "/my_frame"; points.header.stamp = line_strip.header.stamp = line_list.header.stamp = ros::Time::now(); points.ns = line_strip.ns = line_list.ns = "points_and_lines"; points.action = line_strip.action = line_list.action = visualization_msgs::Marker::ADD; points.pose.orientation.w = line_strip.pose.orientation.w = line_list.pose.orientation.w = 1.0; // %EndTag(MARKER_INIT)% // %Tag(ID)% points.id = 0; line_strip.id = 1; line_list.id = 2; // %EndTag(ID)% // %Tag(TYPE)% points.type = visualization_msgs::Marker::POINTS; line_strip.type = visualization_msgs::Marker::LINE_STRIP; line_list.type = visualization_msgs::Marker::LINE_LIST; // %EndTag(TYPE)% // %Tag(SCALE)% // POINTS markers use x and y scale for width/height respectively points.scale.x = 0.2; points.scale.y = 0.2; // LINE_STRIP/LINE_LIST markers use only the x component of scale, for the line width line_strip.scale.x = 0.1; line_list.scale.x = 0.1; // %EndTag(SCALE)% // %Tag(COLOR)% // Points are green points.color.g = 1.0f; points.color.a = 1.0; // Line strip is blue line_strip.color.b = 1.0; line_strip.color.a = 1.0; // Line list is red line_list.color.r = 1.0; line_list.color.a = 1.0; // %EndTag(COLOR)% // %Tag(HELIX)% // Create the vertices for the points and lines for (uint32_t i = 0; i < 100; ++i) { float y = 5 * sin(f + i / 100.0f * 2 * M_PI); float z = 5 * cos(f + i / 100.0f * 2 * M_PI); geometry_msgs::Point p; p.x = (int32_t)i - 50; p.y = y; p.z = z; points.points.push_back(p); line_strip.points.push_back(p); // The line list needs two points for each line line_list.points.push_back(p); p.z += 1.0; line_list.points.push_back(p); } // %EndTag(HELIX)% marker_pub.publish(points); marker_pub.publish(line_strip); marker_pub.publish(line_list); r.sleep(); f += 0.04; } } // %EndTag(FULLTEXT)%