$search
00001 /* 00002 * Copyright (c) 2011, Willow Garage, Inc. 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of the Willow Garage, Inc. nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 */ 00029 00030 00031 // %Tag(fullSource)% 00032 #include <math.h> 00033 00034 #include <ros/ros.h> 00035 00036 #include <interactive_markers/interactive_marker_server.h> 00037 00038 namespace vm = visualization_msgs; 00039 00040 void processFeedback( const vm::InteractiveMarkerFeedbackConstPtr &feedback ) 00041 { 00042 uint8_t type = feedback->event_type; 00043 00044 if( type == vm::InteractiveMarkerFeedback::BUTTON_CLICK || 00045 type == vm::InteractiveMarkerFeedback::MOUSE_DOWN || 00046 type == vm::InteractiveMarkerFeedback::MOUSE_UP ) 00047 { 00048 const char* type_str = (type == vm::InteractiveMarkerFeedback::BUTTON_CLICK ? "button click" : 00049 (type == vm::InteractiveMarkerFeedback::MOUSE_DOWN ? "mouse down" : "mouse up")); 00050 00051 if( feedback->mouse_point_valid ) 00052 { 00053 ROS_INFO( "%s at %f, %f, %f in frame %s", 00054 type_str, 00055 feedback->mouse_point.x, feedback->mouse_point.y, feedback->mouse_point.z, 00056 feedback->header.frame_id.c_str() ); 00057 } 00058 else 00059 { 00060 ROS_INFO( "%s", type_str ); 00061 } 00062 } 00063 else if( type == vm::InteractiveMarkerFeedback::POSE_UPDATE ) 00064 { 00065 ROS_INFO_STREAM( feedback->marker_name << " is now at " 00066 << feedback->pose.position.x << ", " << feedback->pose.position.y 00067 << ", " << feedback->pose.position.z ); 00068 } 00069 } 00070 00071 void makePoints( std::vector<geometry_msgs::Point>& points_out, int num_points ) 00072 { 00073 double radius = 3; 00074 points_out.resize(num_points); 00075 for( int i = 0; i < num_points; i++ ) 00076 { 00077 double angle = (i / (double) num_points * 50 * M_PI); 00078 double height = (i / (double) num_points * 10); 00079 points_out[i].x = radius * cos( angle ); 00080 points_out[i].y = radius * sin( angle ); 00081 points_out[i].z = height; 00082 } 00083 } 00084 00085 vm::InteractiveMarker makeMarker( std::string name, std::string description, int32_t type, float x, int num_points = 10000, float scale = 0.1f ) 00086 { 00087 // create an interactive marker for our server 00088 vm::InteractiveMarker int_marker; 00089 int_marker.header.frame_id = "/base_link"; 00090 int_marker.name = name; 00091 int_marker.description = description; 00092 00093 // create a point cloud marker 00094 vm::Marker points_marker; 00095 points_marker.type = type; 00096 points_marker.scale.x = scale; 00097 points_marker.scale.y = scale; 00098 points_marker.scale.z = scale; 00099 points_marker.color.r = 0.5; 00100 points_marker.color.g = 0.5; 00101 points_marker.color.b = 0.5; 00102 points_marker.color.a = 1.0; 00103 makePoints( points_marker.points, num_points ); 00104 00105 // create a control which contains the point cloud which acts like a button. 00106 vm::InteractiveMarkerControl points_control; 00107 points_control.always_visible = true; 00108 points_control.interaction_mode = vm::InteractiveMarkerControl::BUTTON; 00109 points_control.markers.push_back( points_marker ); 00110 00111 // add the control to the interactive marker 00112 int_marker.controls.push_back( points_control ); 00113 00114 // create a control which will move the box 00115 // this control does not contain any markers, 00116 // which will cause RViz to insert two arrows 00117 vm::InteractiveMarkerControl rotate_control; 00118 rotate_control.name = "move_x"; 00119 rotate_control.interaction_mode = 00120 vm::InteractiveMarkerControl::MOVE_AXIS; 00121 00122 // add the control to the interactive marker 00123 int_marker.controls.push_back(rotate_control); 00124 00125 int_marker.pose.position.x = x; 00126 00127 return int_marker; 00128 } 00129 00130 int main(int argc, char** argv) 00131 { 00132 ros::init(argc, argv, "point_cloud"); 00133 00134 // create an interactive marker server on the topic namespace simple_marker 00135 interactive_markers::InteractiveMarkerServer server("point_cloud"); 00136 00137 server.insert(makeMarker("points", "Points marker", vm::Marker::POINTS, 0), &processFeedback); 00138 // LINE_STRIP and LINE_LIST are not actually selectable, and they won't highlight or detect mouse clicks like the others (yet). 00139 server.insert(makeMarker("line_strip", "Line Strip marker", vm::Marker::LINE_STRIP, 10, 1000), &processFeedback); 00140 server.insert(makeMarker("line_list", "Line List marker", vm::Marker::LINE_LIST, 20), &processFeedback); 00141 server.insert(makeMarker("cube_list", "Cube List marker", vm::Marker::CUBE_LIST, 30), &processFeedback); 00142 server.insert(makeMarker("sphere_list", "Sphere List marker", vm::Marker::SPHERE_LIST, 40), &processFeedback); 00143 server.insert(makeMarker("triangle_list", "Triangle List marker", vm::Marker::TRIANGLE_LIST, 50, 201, 1.0f), &processFeedback); 00144 00145 // 'commit' changes and send to all clients 00146 server.applyChanges(); 00147 00148 // start the ROS main loop 00149 ros::spin(); 00150 } 00151 // %Tag(fullSource)%