$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 #include <ros/ros.h> 00032 00033 #include <interactive_markers/interactive_marker_server.h> 00034 #include <interactive_markers/menu_handler.h> 00035 00036 #include <tf/transform_broadcaster.h> 00037 #include <tf/tf.h> 00038 00039 #include <math.h> 00040 00041 using namespace visualization_msgs; 00042 00043 00044 // %Tag(vars)% 00045 boost::shared_ptr<interactive_markers::InteractiveMarkerServer> server; 00046 float marker_pos = 0; 00047 interactive_markers::MenuHandler menu_handler; 00048 // %EndTag(vars)% 00049 00050 00051 // %Tag(frameCallback)% 00052 void frameCallback(const ros::TimerEvent&) 00053 { 00054 static uint32_t counter = 0; 00055 00056 static tf::TransformBroadcaster br; 00057 00058 tf::Transform t; 00059 00060 ros::Time time = ros::Time::now(); 00061 00062 t.setOrigin(tf::Vector3(0.0, 0.0, sin(float(counter)/140.0) * 2.0)); 00063 t.setRotation(tf::Quaternion(0.0, 0.0, 0.0, 1.0)); 00064 br.sendTransform(tf::StampedTransform(t, time, "base_link", "moving_frame")); 00065 00066 t.setOrigin(tf::Vector3(0.0, 0.0, 0.0)); 00067 t.setRotation(tf::createQuaternionFromRPY(0.0, float(counter)/140.0, 0.0)); 00068 br.sendTransform(tf::StampedTransform(t, time, "base_link", "rotating_frame")); 00069 00070 ++counter; 00071 } 00072 // %EndTag(frameCallback)% 00073 00074 // %Tag(processFeedback)% 00075 void processFeedback( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback ) 00076 { 00077 std::ostringstream s; 00078 s << "Feedback from marker '" << feedback->marker_name << "' " 00079 << " / control '" << feedback->control_name << "'"; 00080 00081 std::ostringstream mouse_point_ss; 00082 if( feedback->mouse_point_valid ) 00083 { 00084 mouse_point_ss << " at " << feedback->mouse_point.x 00085 << ", " << feedback->mouse_point.y 00086 << ", " << feedback->mouse_point.z 00087 << " in frame " << feedback->header.frame_id; 00088 } 00089 00090 switch ( feedback->event_type ) 00091 { 00092 case visualization_msgs::InteractiveMarkerFeedback::BUTTON_CLICK: 00093 ROS_INFO_STREAM( s.str() << ": button click" << mouse_point_ss.str() << "." ); 00094 break; 00095 00096 case visualization_msgs::InteractiveMarkerFeedback::MENU_SELECT: 00097 ROS_INFO_STREAM( s.str() << ": menu item " << feedback->menu_entry_id << " clicked" << mouse_point_ss.str() << "." ); 00098 break; 00099 00100 case visualization_msgs::InteractiveMarkerFeedback::POSE_UPDATE: 00101 ROS_INFO_STREAM( s.str() << ": pose changed" 00102 << "\nposition = " 00103 << feedback->pose.position.x 00104 << ", " << feedback->pose.position.y 00105 << ", " << feedback->pose.position.z 00106 << "\norientation = " 00107 << feedback->pose.orientation.w 00108 << ", " << feedback->pose.orientation.x 00109 << ", " << feedback->pose.orientation.y 00110 << ", " << feedback->pose.orientation.z 00111 << "\nframe: " << feedback->header.frame_id 00112 << " time: " << feedback->header.stamp.sec << "sec, " 00113 << feedback->header.stamp.nsec << " nsec" ); 00114 break; 00115 00116 case visualization_msgs::InteractiveMarkerFeedback::MOUSE_DOWN: 00117 ROS_INFO_STREAM( s.str() << ": mouse down" << mouse_point_ss.str() << "." ); 00118 break; 00119 00120 case visualization_msgs::InteractiveMarkerFeedback::MOUSE_UP: 00121 ROS_INFO_STREAM( s.str() << ": mouse up" << mouse_point_ss.str() << "." ); 00122 break; 00123 } 00124 00125 server->applyChanges(); 00126 } 00127 // %EndTag(processFeedback)% 00128 00129 // %Tag(alignMarker)% 00130 void alignMarker( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback ) 00131 { 00132 geometry_msgs::Pose pose = feedback->pose; 00133 00134 pose.position.x = round(pose.position.x-0.5)+0.5; 00135 pose.position.y = round(pose.position.y-0.5)+0.5; 00136 00137 ROS_INFO_STREAM( feedback->marker_name << ":" 00138 << " aligning position = " 00139 << feedback->pose.position.x 00140 << ", " << feedback->pose.position.y 00141 << ", " << feedback->pose.position.z 00142 << " to " 00143 << pose.position.x 00144 << ", " << pose.position.y 00145 << ", " << pose.position.z ); 00146 00147 server->setPose( feedback->marker_name, pose ); 00148 server->applyChanges(); 00149 } 00150 // %EndTag(alignMarker)% 00151 00152 double rand( double min, double max ) 00153 { 00154 double t = (double)rand() / (double)RAND_MAX; 00155 return min + t*(max-min); 00156 } 00157 00158 // %Tag(Box)% 00159 Marker makeBox( InteractiveMarker &msg ) 00160 { 00161 Marker marker; 00162 00163 marker.type = Marker::CUBE; 00164 marker.scale.x = msg.scale * 0.45; 00165 marker.scale.y = msg.scale * 0.45; 00166 marker.scale.z = msg.scale * 0.45; 00167 marker.color.r = 0.5; 00168 marker.color.g = 0.5; 00169 marker.color.b = 0.5; 00170 marker.color.a = 1.0; 00171 00172 return marker; 00173 } 00174 00175 InteractiveMarkerControl& makeBoxControl( InteractiveMarker &msg ) 00176 { 00177 InteractiveMarkerControl control; 00178 control.always_visible = true; 00179 control.markers.push_back( makeBox(msg) ); 00180 msg.controls.push_back( control ); 00181 00182 return msg.controls.back(); 00183 } 00184 // %EndTag(Box)% 00185 00186 void saveMarker( InteractiveMarker int_marker ) 00187 { 00188 server->insert(int_marker); 00189 server->setCallback(int_marker.name, &processFeedback); 00190 } 00191 00193 00194 // %Tag(6DOF)% 00195 void make6DofMarker( bool fixed ) 00196 { 00197 InteractiveMarker int_marker; 00198 int_marker.header.frame_id = "/base_link"; 00199 int_marker.pose.position.y = -3.0 * marker_pos++;; 00200 int_marker.scale = 1; 00201 00202 int_marker.name = "simple_6dof"; 00203 int_marker.description = "Simple 6-DOF Control"; 00204 00205 // insert a box 00206 makeBoxControl(int_marker); 00207 00208 InteractiveMarkerControl control; 00209 00210 if ( fixed ) 00211 { 00212 int_marker.name += "_fixed"; 00213 int_marker.description += "\n(fixed orientation)"; 00214 control.orientation_mode = InteractiveMarkerControl::FIXED; 00215 } 00216 00217 control.orientation.w = 1; 00218 control.orientation.x = 1; 00219 control.orientation.y = 0; 00220 control.orientation.z = 0; 00221 control.name = "rotate_x"; 00222 control.interaction_mode = InteractiveMarkerControl::ROTATE_AXIS; 00223 int_marker.controls.push_back(control); 00224 control.name = "move_x"; 00225 control.interaction_mode = InteractiveMarkerControl::MOVE_AXIS; 00226 int_marker.controls.push_back(control); 00227 00228 control.orientation.w = 1; 00229 control.orientation.x = 0; 00230 control.orientation.y = 1; 00231 control.orientation.z = 0; 00232 control.name = "rotate_z"; 00233 control.interaction_mode = InteractiveMarkerControl::ROTATE_AXIS; 00234 int_marker.controls.push_back(control); 00235 control.name = "move_z"; 00236 control.interaction_mode = InteractiveMarkerControl::MOVE_AXIS; 00237 int_marker.controls.push_back(control); 00238 00239 control.orientation.w = 1; 00240 control.orientation.x = 0; 00241 control.orientation.y = 0; 00242 control.orientation.z = 1; 00243 control.name = "rotate_y"; 00244 control.interaction_mode = InteractiveMarkerControl::ROTATE_AXIS; 00245 int_marker.controls.push_back(control); 00246 control.name = "move_y"; 00247 control.interaction_mode = InteractiveMarkerControl::MOVE_AXIS; 00248 int_marker.controls.push_back(control); 00249 00250 server->insert(int_marker); 00251 server->setCallback(int_marker.name, &processFeedback); 00252 } 00253 // %EndTag(6DOF)% 00254 00255 // %Tag(RandomDof)% 00256 void makeRandomDofMarker( ) 00257 { 00258 InteractiveMarker int_marker; 00259 int_marker.header.frame_id = "/base_link"; 00260 int_marker.pose.position.y = -3.0 * marker_pos++;; 00261 int_marker.scale = 1; 00262 00263 int_marker.name = "6dof_random_axes"; 00264 int_marker.description = "6-DOF\n(Arbitrary Axes)"; 00265 00266 makeBoxControl(int_marker); 00267 00268 InteractiveMarkerControl control; 00269 00270 for ( int i=0; i<3; i++ ) 00271 { 00272 control.orientation.w = rand(-1,1); 00273 control.orientation.x = rand(-1,1); 00274 control.orientation.y = rand(-1,1); 00275 control.orientation.z = rand(-1,1); 00276 control.interaction_mode = InteractiveMarkerControl::ROTATE_AXIS; 00277 int_marker.controls.push_back(control); 00278 control.interaction_mode = InteractiveMarkerControl::MOVE_AXIS; 00279 int_marker.controls.push_back(control); 00280 } 00281 00282 server->insert(int_marker); 00283 server->setCallback(int_marker.name, &processFeedback); 00284 } 00285 // %EndTag(RandomDof)% 00286 00287 00288 // %Tag(ViewFacing)% 00289 void makeViewFacingMarker( ) 00290 { 00291 InteractiveMarker int_marker; 00292 int_marker.header.frame_id = "/base_link"; 00293 int_marker.pose.position.y = -3.0 * marker_pos++;; 00294 int_marker.scale = 1; 00295 00296 int_marker.name = "view_facing"; 00297 int_marker.description = "View Facing 6-DOF"; 00298 00299 InteractiveMarkerControl control; 00300 00301 // make a control that rotates around the view axis 00302 control.orientation_mode = InteractiveMarkerControl::VIEW_FACING; 00303 control.interaction_mode = InteractiveMarkerControl::ROTATE_AXIS; 00304 control.orientation.w = 1; 00305 control.name = "rotate"; 00306 00307 int_marker.controls.push_back(control); 00308 00309 // create a box in the center which should not be view facing, 00310 // but move in the camera plane. 00311 control.orientation_mode = InteractiveMarkerControl::VIEW_FACING; 00312 control.interaction_mode = InteractiveMarkerControl::MOVE_PLANE; 00313 control.independent_marker_orientation = true; 00314 control.name = "move"; 00315 00316 control.markers.push_back( makeBox(int_marker) ); 00317 control.always_visible = true; 00318 00319 int_marker.controls.push_back(control); 00320 00321 server->insert(int_marker); 00322 server->setCallback(int_marker.name, &processFeedback); 00323 } 00324 // %EndTag(ViewFacing)% 00325 00326 00327 // %Tag(Quadrocopter)% 00328 void makeQuadrocopterMarker( ) 00329 { 00330 InteractiveMarker int_marker; 00331 int_marker.header.frame_id = "/base_link"; 00332 int_marker.pose.position.y = -3.0 * marker_pos++;; 00333 int_marker.scale = 1; 00334 00335 int_marker.name = "quadrocopter"; 00336 int_marker.description = "Quadrocopter"; 00337 00338 makeBoxControl(int_marker); 00339 00340 InteractiveMarkerControl control; 00341 00342 control.orientation.w = 1; 00343 control.orientation.x = 0; 00344 control.orientation.y = 1; 00345 control.orientation.z = 0; 00346 control.interaction_mode = InteractiveMarkerControl::MOVE_ROTATE; 00347 int_marker.controls.push_back(control); 00348 control.interaction_mode = InteractiveMarkerControl::MOVE_AXIS; 00349 int_marker.controls.push_back(control); 00350 00351 server->insert(int_marker); 00352 server->setCallback(int_marker.name, &processFeedback); 00353 } 00354 // %EndTag(Quadrocopter)% 00355 00356 // %Tag(ChessPiece)% 00357 void makeChessPieceMarker( ) 00358 { 00359 InteractiveMarker int_marker; 00360 int_marker.header.frame_id = "/base_link"; 00361 int_marker.pose.position.y = -3.0 * marker_pos++;; 00362 int_marker.scale = 1; 00363 00364 int_marker.name = "chess_piece"; 00365 int_marker.description = "Chess Piece\n(2D Move + Alignment)"; 00366 00367 InteractiveMarkerControl control; 00368 00369 control.orientation.w = 1; 00370 control.orientation.x = 0; 00371 control.orientation.y = 1; 00372 control.orientation.z = 0; 00373 control.interaction_mode = InteractiveMarkerControl::MOVE_PLANE; 00374 int_marker.controls.push_back(control); 00375 00376 // make a box which also moves in the plane 00377 control.markers.push_back( makeBox(int_marker) ); 00378 control.always_visible = true; 00379 int_marker.controls.push_back(control); 00380 00381 // we want to use our special callback function 00382 server->insert(int_marker); 00383 server->setCallback(int_marker.name, &processFeedback); 00384 00385 // set different callback for POSE_UPDATE feedback 00386 server->setCallback(int_marker.name, &alignMarker, visualization_msgs::InteractiveMarkerFeedback::POSE_UPDATE ); 00387 } 00388 // %EndTag(ChessPiece)% 00389 00390 // %Tag(PanTilt)% 00391 void makePanTiltMarker( ) 00392 { 00393 InteractiveMarker int_marker; 00394 int_marker.header.frame_id = "/base_link"; 00395 int_marker.pose.position.y = -3.0 * marker_pos++;; 00396 int_marker.scale = 1; 00397 00398 int_marker.name = "pan_tilt"; 00399 int_marker.description = "Pan / Tilt"; 00400 00401 makeBoxControl(int_marker); 00402 00403 InteractiveMarkerControl control; 00404 00405 control.orientation.w = 1; 00406 control.orientation.x = 0; 00407 control.orientation.y = 1; 00408 control.orientation.z = 0; 00409 control.interaction_mode = InteractiveMarkerControl::ROTATE_AXIS; 00410 control.orientation_mode = InteractiveMarkerControl::FIXED; 00411 int_marker.controls.push_back(control); 00412 00413 control.orientation.w = 1; 00414 control.orientation.x = 0; 00415 control.orientation.y = 0; 00416 control.orientation.z = 1; 00417 control.interaction_mode = InteractiveMarkerControl::ROTATE_AXIS; 00418 control.orientation_mode = InteractiveMarkerControl::INHERIT; 00419 int_marker.controls.push_back(control); 00420 00421 server->insert(int_marker); 00422 server->setCallback(int_marker.name, &processFeedback); 00423 } 00424 // %EndTag(PanTilt)% 00425 00426 // %Tag(Menu)% 00427 void makeMenuMarker() 00428 { 00429 InteractiveMarker int_marker; 00430 int_marker.header.frame_id = "/base_link"; 00431 int_marker.pose.position.y = -3.0 * marker_pos++;; 00432 int_marker.scale = 1; 00433 00434 int_marker.name = "context_menu"; 00435 int_marker.description = "Context Menu\n(Right Click)"; 00436 00437 InteractiveMarkerControl control; 00438 00439 // make one control using default visuals 00440 control.interaction_mode = InteractiveMarkerControl::MENU; 00441 control.description="Options"; 00442 control.name = "menu_only_control"; 00443 int_marker.controls.push_back(control); 00444 00445 // make one control showing a box 00446 Marker marker = makeBox( int_marker ); 00447 control.markers.push_back( marker ); 00448 control.always_visible = true; 00449 int_marker.controls.push_back(control); 00450 00451 server->insert(int_marker); 00452 server->setCallback(int_marker.name, &processFeedback); 00453 menu_handler.apply( *server, int_marker.name ); 00454 } 00455 // %EndTag(Menu)% 00456 00457 // %Tag(Moving)% 00458 void makeMovingMarker() 00459 { 00460 InteractiveMarker int_marker; 00461 int_marker.header.frame_id = "/moving_frame"; 00462 int_marker.pose.position.y = -3.0 * marker_pos++;; 00463 int_marker.scale = 1; 00464 00465 int_marker.name = "moving"; 00466 int_marker.description = "Marker Attached to a\nMoving Frame"; 00467 00468 InteractiveMarkerControl control; 00469 00470 control.orientation.w = 1; 00471 control.orientation.x = 1; 00472 control.orientation.y = 0; 00473 control.orientation.z = 0; 00474 control.interaction_mode = InteractiveMarkerControl::ROTATE_AXIS; 00475 int_marker.controls.push_back(control); 00476 00477 control.interaction_mode = InteractiveMarkerControl::MOVE_PLANE; 00478 control.always_visible = true; 00479 control.markers.push_back( makeBox(int_marker) ); 00480 int_marker.controls.push_back(control); 00481 00482 server->insert(int_marker); 00483 server->setCallback(int_marker.name, &processFeedback); 00484 } 00485 // %EndTag(Moving)% 00486 00487 // %Tag(main)% 00488 int main(int argc, char** argv) 00489 { 00490 ros::init(argc, argv, "basic_controls"); 00491 ros::NodeHandle n; 00492 00493 // create a timer to update the published transforms 00494 ros::Timer frame_timer = n.createTimer(ros::Duration(0.01), frameCallback); 00495 00496 server.reset( new interactive_markers::InteractiveMarkerServer("basic_controls","",false) ); 00497 00498 ros::Duration(0.1).sleep(); 00499 00500 menu_handler.insert( "First Entry", &processFeedback ); 00501 menu_handler.insert( "Second Entry", &processFeedback ); 00502 interactive_markers::MenuHandler::EntryHandle sub_menu_handle = menu_handler.insert( "Submenu" ); 00503 menu_handler.insert( sub_menu_handle, "First Entry", &processFeedback ); 00504 menu_handler.insert( sub_menu_handle, "Second Entry", &processFeedback ); 00505 00506 make6DofMarker( false ); 00507 make6DofMarker( true ); 00508 makeRandomDofMarker( ); 00509 makeViewFacingMarker( ); 00510 makeQuadrocopterMarker( ); 00511 makeChessPieceMarker( ); 00512 makePanTiltMarker( ); 00513 makeMenuMarker( ); 00514 makeMovingMarker( ); 00515 00516 server->applyChanges(); 00517 00518 ros::spin(); 00519 00520 server.reset(); 00521 } 00522 // %EndTag(main)%