00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 #include <jsk_interactive_marker/interactive_marker_helpers.h>
00034 
00035 #include <tf/tf.h>
00036 
00037 
00038 namespace im_helpers {
00039 
00040 geometry_msgs::Pose createPoseMsg(const tf::Transform &transform)
00041 {
00042   geometry_msgs::Pose pose;
00043   tf::Vector3 pos = transform.getOrigin();
00044   tf::Quaternion rot = transform.getRotation();
00045   pose.position.x = pos[0];
00046   pose.position.y = pos[1];
00047   pose.position.z = pos[2];
00048   pose.orientation.x = rot.getX();
00049   pose.orientation.y = rot.getY();
00050   pose.orientation.z = rot.getZ();
00051   pose.orientation.w = rot.getW();
00052   return pose;
00053 }
00054   
00055 visualization_msgs::InteractiveMarker makeEmptyMarker( const char *frame_id )
00056 {
00057   visualization_msgs::InteractiveMarker int_marker;
00058   int_marker.header.frame_id = frame_id;
00059   int_marker.scale = 1;
00060 
00061   return int_marker;
00062 }
00063 
00064 visualization_msgs::Marker makeBox( float scale )
00065 {
00066   visualization_msgs::Marker marker;
00067 
00068   marker.type = visualization_msgs::Marker::CUBE;
00069   marker.scale.x = scale;
00070   marker.scale.y = scale;
00071   marker.scale.z = scale;
00072   marker.color.r = 1.0;
00073   marker.color.g = 1.0;
00074   marker.color.b = 1.0;
00075   marker.color.a = 1.0;
00076 
00077   return marker;
00078 }
00079 
00080 visualization_msgs::Marker makeSphere( float scale )
00081 {
00082   visualization_msgs::Marker marker;
00083 
00084   marker.type = visualization_msgs::Marker::SPHERE;
00085   marker.scale.x = scale;
00086   marker.scale.y = scale;
00087   marker.scale.z = scale;
00088   marker.color.r = 1.0;
00089   marker.color.g = 1.0;
00090   marker.color.b = 1.0;
00091   marker.color.a = 1.0;
00092 
00093   return marker;
00094 }
00095 
00096 void add3Dof2DControl( visualization_msgs::InteractiveMarker &msg, bool fixed)
00097 {
00098   visualization_msgs::InteractiveMarkerControl control;
00099 
00100   if(fixed)
00101     control.orientation_mode = visualization_msgs::InteractiveMarkerControl::FIXED;
00102 
00103   control.orientation.w = 1;
00104   control.orientation.x = 1;
00105   control.orientation.y = 0;
00106   control.orientation.z = 0;
00107   
00108   
00109   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
00110   msg.controls.push_back(control);
00111 
00112   control.orientation.w = 1;
00113   control.orientation.x = 0;
00114   control.orientation.y = 1;
00115   control.orientation.z = 0;
00116   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
00117   msg.controls.push_back(control);
00118   
00119   
00120 
00121   control.orientation.w = 1;
00122   control.orientation.x = 0;
00123   control.orientation.y = 0;
00124   control.orientation.z = 1;
00125   
00126   
00127   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
00128   msg.controls.push_back(control);
00129 
00130 }
00131 
00132 void add6DofControl( visualization_msgs::InteractiveMarker &msg, bool fixed)
00133 {
00134   visualization_msgs::InteractiveMarkerControl control;
00135 
00136   if(fixed)
00137     control.orientation_mode = visualization_msgs::InteractiveMarkerControl::FIXED;
00138 
00139   control.orientation.w = 1;
00140   control.orientation.x = 1;
00141   control.orientation.y = 0;
00142   control.orientation.z = 0;
00143   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
00144   msg.controls.push_back(control);
00145   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
00146   msg.controls.push_back(control);
00147 
00148   control.orientation.w = 1;
00149   control.orientation.x = 0;
00150   control.orientation.y = 1;
00151   control.orientation.z = 0;
00152   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
00153   msg.controls.push_back(control);
00154   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
00155   msg.controls.push_back(control);
00156 
00157   control.orientation.w = 1;
00158   control.orientation.x = 0;
00159   control.orientation.y = 0;
00160   control.orientation.z = 1;
00161   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
00162   msg.controls.push_back(control);
00163   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
00164   msg.controls.push_back(control);
00165 }
00166 
00167   void addVisible6DofControl( visualization_msgs::InteractiveMarker &msg, bool fixed, bool visible)
00168   {
00169   visualization_msgs::InteractiveMarkerControl control;
00170   
00171   if(visible)
00172     control.always_visible = true;
00173 
00174   if(fixed)
00175     control.orientation_mode = visualization_msgs::InteractiveMarkerControl::FIXED;
00176 
00177   control.orientation.w = 1;
00178   control.orientation.x = 1;
00179   control.orientation.y = 0;
00180   control.orientation.z = 0;
00181   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
00182   msg.controls.push_back(control);
00183   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
00184   msg.controls.push_back(control);
00185 
00186   control.orientation.w = 1;
00187   control.orientation.x = 0;
00188   control.orientation.y = 1;
00189   control.orientation.z = 0;
00190   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
00191   msg.controls.push_back(control);
00192   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
00193   msg.controls.push_back(control);
00194 
00195   control.orientation.w = 1;
00196   control.orientation.x = 0;
00197   control.orientation.y = 0;
00198   control.orientation.z = 1;
00199   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
00200   msg.controls.push_back(control);
00201   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
00202   msg.controls.push_back(control);
00203 }
00204 
00205 
00206 visualization_msgs::InteractiveMarkerControl& makeBoxControl( visualization_msgs::InteractiveMarker &msg )
00207 {
00208   visualization_msgs::InteractiveMarkerControl control;
00209   control.always_visible = true;
00210   control.markers.push_back( makeBox(msg.scale) );
00211   msg.controls.push_back( control );
00212 
00213   return msg.controls.back();
00214 }
00215 
00216 visualization_msgs::InteractiveMarkerControl& makeSphereControl( visualization_msgs::InteractiveMarker &msg )
00217 {
00218   visualization_msgs::InteractiveMarkerControl control;
00219   control.always_visible = true;
00220   control.markers.push_back( makeSphere(msg.scale) );
00221   msg.controls.push_back( control );
00222 
00223   return msg.controls.back();
00224 }
00225 
00226 visualization_msgs::MenuEntry makeMenuEntry(const char *title)
00227 {
00228   visualization_msgs::MenuEntry m;
00229   m.title = title;
00230   m.command = title;
00231   return m;
00232 }
00233 
00234 visualization_msgs::MenuEntry makeMenuEntry(const char *title, const char *command, int type  )
00235 {
00236   visualization_msgs::MenuEntry m;
00237   m.title = title;
00238   m.command = command;
00239   m.command_type = type;
00240   return m;
00241 }
00242 
00243 visualization_msgs::InteractiveMarker makePostureMarker( const char *name, const geometry_msgs::PoseStamped &stamped,
00244                                                          float scale, bool fixed, bool view_facing )
00245 {
00246   visualization_msgs::InteractiveMarker int_marker;
00247   int_marker.header =  stamped.header;
00248   int_marker.name = name;
00249   int_marker.scale = scale;
00250   int_marker.pose = stamped.pose;
00251 
00252   visualization_msgs::InteractiveMarkerControl control;
00253   control.orientation.w = 1;
00254   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
00255   int_marker.controls.push_back(control);
00256 
00257   return int_marker;
00258 }
00259 
00260 visualization_msgs::InteractiveMarker makeHeadGoalMarker( const char *name, const geometry_msgs::PoseStamped &stamped,
00261                                                           float scale)
00262 {
00263   visualization_msgs::InteractiveMarker int_marker;
00264   int_marker.header =  stamped.header;
00265   int_marker.name = name;
00266   int_marker.scale = scale;
00267   int_marker.pose = stamped.pose;
00268 
00269   visualization_msgs::InteractiveMarkerControl control;
00270   control.orientation_mode = visualization_msgs::InteractiveMarkerControl::VIEW_FACING;
00271   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_PLANE;
00272   control.orientation.w = 1;
00273   control.markers.push_back( makeSphere(scale*0.7) );
00274   int_marker.controls.push_back(control);
00275   control.markers.clear();
00276 
00277   add6DofControl(int_marker);
00278 
00279   return int_marker;
00280 }
00281 
00282 visualization_msgs::InteractiveMarker makeMeshMarker( const std::string &name, const std::string &mesh_resource,
00283                                                       const geometry_msgs::PoseStamped &stamped, float scale, const std_msgs::ColorRGBA &color, bool use_color )
00284 {
00285   visualization_msgs::InteractiveMarker int_marker;
00286   int_marker.header =  stamped.header;
00287   int_marker.pose = stamped.pose;
00288   int_marker.name = name;
00289   int_marker.scale = scale;
00290 
00291   visualization_msgs::Marker mesh;
00292   if (use_color) mesh.color = color;
00293   mesh.mesh_resource = mesh_resource;
00294   mesh.mesh_use_embedded_materials = !use_color;
00295   mesh.type = visualization_msgs::Marker::MESH_RESOURCE;
00296   mesh.scale.x = scale;
00297   mesh.scale.y = scale;
00298   mesh.scale.z = scale;
00299 
00300   visualization_msgs::InteractiveMarkerControl control;
00301   control.markers.push_back( mesh );
00302   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
00303   int_marker.controls.push_back( control );
00304 
00305   return int_marker;
00306 }
00307 
00308 visualization_msgs::InteractiveMarker makeMeshMarker( const std::string &name, const std::string &mesh_resource,
00309                                                       const geometry_msgs::PoseStamped &stamped, float scale)
00310 {
00311   std_msgs::ColorRGBA color;
00312   return makeMeshMarker( name, mesh_resource, stamped, scale, color, false);
00313 }
00314 
00315 visualization_msgs::InteractiveMarker makeMeshMarker( const std::string &name, const std::string &mesh_resource,
00316                                                       const geometry_msgs::PoseStamped &stamped, float scale, const std_msgs::ColorRGBA &color)
00317 {
00318   return makeMeshMarker( name, mesh_resource, stamped, scale, color, true);
00319 }
00320 
00321 visualization_msgs::InteractiveMarker makeButtonBox( const char *name, const geometry_msgs::PoseStamped &stamped, float scale, bool fixed, bool view_facing )
00322 {
00323   visualization_msgs::InteractiveMarker int_marker;
00324   int_marker.header =  stamped.header;
00325   int_marker.name = name;
00326   int_marker.scale = scale;
00327   int_marker.pose = stamped.pose;
00328   
00329 
00330   visualization_msgs::InteractiveMarkerControl &control = makeBoxControl(int_marker);
00331   
00332   control.always_visible = false;
00333   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
00334 
00335   return int_marker;
00336 }
00337 
00338 visualization_msgs::InteractiveMarker makeButtonSphere( const char *name, const geometry_msgs::PoseStamped &stamped,
00339                                                         float scale, bool fixed, bool view_facing)
00340 {
00341   std_msgs::ColorRGBA color;
00342   return makeButtonSphere(name, stamped, scale, fixed, view_facing, color);
00343 }
00344 
00345 visualization_msgs::InteractiveMarker makeButtonSphere( const char *name, const geometry_msgs::PoseStamped &stamped,
00346                                                         float scale, bool fixed, bool view_facing,
00347                                                         std_msgs::ColorRGBA color)
00348 {
00349   visualization_msgs::InteractiveMarker int_marker;
00350   int_marker.header =  stamped.header;
00351   int_marker.name = name;
00352   int_marker.scale = scale;
00353   int_marker.pose = stamped.pose;
00354   
00355 
00356   visualization_msgs::InteractiveMarkerControl &control = makeSphereControl(int_marker);
00357   
00358   control.always_visible = false;
00359   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
00360   control.markers.back().color = color;
00361 
00362   return int_marker;
00363 }
00364 
00365 visualization_msgs::InteractiveMarker makeListControl( const char *name, const geometry_msgs::PoseStamped &stamped, int num, int total, float scale)
00366 {
00367 
00368   visualization_msgs::InteractiveMarker int_marker;
00369   int_marker.header =  stamped.header;
00370   int_marker.name = name;
00371   int_marker.scale = scale;
00372   int_marker.pose = stamped.pose;
00373 
00374   visualization_msgs::InteractiveMarkerControl control;
00375 
00376 
00377   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
00378   std::stringstream ss;
00379   ss << "pose(" << num << "/" << total << ")";
00380   interactive_markers::makeViewFacingButton(int_marker, control, ss.str());
00381 
00382 
00383 
00384 
00385 
00386 
00387 
00388 
00389 
00390 
00391 
00392 
00393 
00394 
00395 
00396 
00397 
00398 
00399 
00400   int_marker.controls.push_back(control);
00401 
00402   return int_marker;
00403 
00404 
00405 
00406 
00407 
00408 
00409 
00410 
00411 
00412 
00413 
00414 
00415 
00416 
00417 
00418 }
00419 
00420 visualization_msgs::InteractiveMarker make6DofMarker( const char *name, const geometry_msgs::PoseStamped &stamped, float scale, bool fixed, bool view_facing )
00421 {
00422   visualization_msgs::InteractiveMarker int_marker;
00423   int_marker.header =  stamped.header;
00424   int_marker.name = name;
00425   int_marker.scale = scale;
00426   int_marker.pose = stamped.pose;
00427 
00428   if ( view_facing )
00429   {
00430     visualization_msgs::InteractiveMarkerControl control;
00431     control.orientation_mode = visualization_msgs::InteractiveMarkerControl::VIEW_FACING;
00432     
00433     control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
00434     control.orientation.w = 1;
00435     int_marker.controls.push_back(control);
00436 
00437     control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_PLANE;
00438     control.markers.push_back( makeSphere(scale*0.5) );
00439     int_marker.controls.push_back(control);
00440   }
00441   else
00442   {
00443     add6DofControl(int_marker, fixed);
00444   }
00445 
00446   return int_marker;
00447 }
00448 
00449 visualization_msgs::InteractiveMarker makePlanarMarker( const char *name, const geometry_msgs::PoseStamped &stamped, float scale, bool fixed )
00450 {
00451   visualization_msgs::InteractiveMarker int_marker;
00452   int_marker.header =  stamped.header;
00453   int_marker.name = name;
00454   int_marker.scale = scale;
00455   int_marker.pose = stamped.pose;
00456 
00457   visualization_msgs::InteractiveMarkerControl control;
00458   control.orientation_mode = fixed ? (uint8_t)visualization_msgs::InteractiveMarkerControl::FIXED : (uint8_t)visualization_msgs::InteractiveMarkerControl::INHERIT;
00459   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_ROTATE;
00460   control.orientation.w = 1;
00461   control.orientation.x = 0;
00462   control.orientation.y = 1;
00463   control.orientation.z = 0;
00464   int_marker.controls.push_back(control);
00465 
00466   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_PLANE;
00467   interactive_markers::makeArrow( int_marker, control, 0 );
00468   control.markers.back().pose.orientation.w = 0;
00469   control.markers.back().pose.orientation.x = 0;
00470   control.markers.back().pose.orientation.y = 1;
00471   control.markers.back().pose.orientation.z = 0;
00472   control.markers.back().color.r = 0.0;
00473   control.markers.back().color.g = 1.0;
00474   control.markers.back().color.b = 0.0;
00475   int_marker.controls.push_back(control);
00476 
00477   return int_marker;
00478 }
00479 
00480 visualization_msgs::InteractiveMarker makeElevatorMarker( const char *name, const geometry_msgs::PoseStamped &stamped, float scale, bool fixed)
00481 {
00482   visualization_msgs::InteractiveMarker int_marker;
00483   int_marker.header =  stamped.header;
00484   int_marker.name = name;
00485   int_marker.scale = scale;
00486   int_marker.pose = stamped.pose;
00487 
00488   visualization_msgs::InteractiveMarkerControl control;
00489 
00490   if(fixed)
00491     control.orientation_mode = visualization_msgs::InteractiveMarkerControl::FIXED;
00492 
00493   control.orientation.w = 1;
00494   control.orientation.x = 0;
00495   control.orientation.y = -1;
00496   control.orientation.z = 0;
00497   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
00498 
00499   interactive_markers::makeArrow( int_marker, control, 0.3 );
00500   control.markers.back().color.r = 0.0;
00501   control.markers.back().color.g = 1.0;
00502   control.markers.back().color.b = 0.0;
00503   control.name = "up";
00504   int_marker.controls.push_back(control);
00505 
00506   control.markers.clear();
00507   interactive_markers::makeArrow( int_marker, control, -0.3 );
00508   control.markers.back().color.r = 1.0;
00509   control.markers.back().color.g = 0.0;
00510   control.markers.back().color.b = 0.0;
00511   control.name = "down";
00512   int_marker.controls.push_back(control);
00513 
00514   return int_marker;
00515 }
00516 
00517 visualization_msgs::InteractiveMarker makeProjectorMarker( const char *name, const geometry_msgs::PoseStamped &stamped, float scale)
00518 {
00519   visualization_msgs::InteractiveMarker int_marker;
00520   int_marker.header =  stamped.header;
00521   int_marker.name = name;
00522   int_marker.scale = scale;
00523   int_marker.pose = stamped.pose;
00524 
00525   visualization_msgs::InteractiveMarkerControl control;
00526   control.orientation.w = 1;
00527   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
00528   visualization_msgs::Marker marker;
00529   marker.type = visualization_msgs::Marker::CYLINDER;
00530   marker.scale.x = 0.03;
00531   marker.scale.y = 0.03;
00532   marker.scale.z = 0.04;
00533   marker.color.r = 1.0;
00534   marker.color.a = 0.8;
00535   control.markers.push_back(marker);
00536   int_marker.controls.push_back(control);
00537 
00538   return int_marker;
00539 }
00540 
00541 
00542 visualization_msgs::InteractiveMarker makeBaseMarker( const char *name, const geometry_msgs::PoseStamped &stamped, float scale, bool fixed)
00543 {
00544   visualization_msgs::InteractiveMarker int_marker;
00545   int_marker.header =  stamped.header;
00546   int_marker.name = name;
00547   int_marker.scale = scale;
00548   int_marker.pose = stamped.pose;
00549 
00550   visualization_msgs::InteractiveMarkerControl control;
00551 
00552   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
00553   control.orientation.w = 1;
00554   control.orientation.y = -1;
00555   int_marker.controls.push_back(control);
00556 
00557 
00558   if(fixed)
00559     control.orientation_mode = visualization_msgs::InteractiveMarkerControl::FIXED;
00560 
00561   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
00562   control.orientation.w = 1;
00563   control.orientation.y = 0;
00564 
00565   control.markers.clear();
00566   interactive_markers::makeArrow( int_marker, control, 0.9 );
00567   control.markers.back().color.r = 1.0;
00568   control.markers.back().color.g = 0.0;
00569   control.markers.back().color.b = 0.0;
00570   control.name = "forward";
00571   int_marker.controls.push_back(control);
00572 
00573   control.markers.clear();
00574   interactive_markers::makeArrow( int_marker, control, -0.9 );
00575   control.markers.back().color.r = 1.0;
00576   control.markers.back().color.g = 0.0;
00577   control.markers.back().color.b = 0.0;
00578   control.name = "back";
00579   int_marker.controls.push_back(control);
00580 
00581   control.orientation.z = 1;
00582   control.markers.clear();
00583   interactive_markers::makeArrow( int_marker, control, 0.9 );
00584   control.markers.back().color.r = 1.0;
00585   control.markers.back().color.g = 0.0;
00586   control.markers.back().color.b = 0.0;
00587   control.name = "left";
00588   int_marker.controls.push_back(control);
00589 
00590   control.markers.clear();
00591   interactive_markers::makeArrow( int_marker, control, -0.9 );
00592   control.markers.back().color.r = 1.0;
00593   control.markers.back().color.g = 0.0;
00594   control.markers.back().color.b = 0.0;
00595   control.name = "right";
00596   int_marker.controls.push_back(control);
00597 
00598   control.markers.clear();
00599   tf::quaternionTFToMsg( tf::Quaternion(tf::Vector3(0,0,1), 135*M_PI/180.0), control.orientation);
00600   interactive_markers::makeArrow( int_marker, control, 1.0 );
00601   control.markers.back().pose.position.x = 0.7;
00602   control.markers.back().color.r = 1.0;
00603   control.markers.back().color.g = 1.0;
00604   control.markers.back().color.b = 0.0;
00605   control.name = "rotate left";
00606   int_marker.controls.push_back(control);
00607 
00608   control.markers.clear();
00609   tf::quaternionTFToMsg( tf::Quaternion(tf::Vector3(0,0,1), -135*M_PI/180.0), control.orientation);
00610   interactive_markers::makeArrow( int_marker, control, 1.0 );
00611   control.markers.back().pose.position.x = 0.7;
00612   control.markers.back().color.r = 1.0;
00613   control.markers.back().color.g = 1.0;
00614   control.markers.back().color.b = 0.0;
00615   control.name = "rotate right";
00616   int_marker.controls.push_back(control);
00617   return int_marker;
00618 }
00619 
00620 visualization_msgs::InteractiveMarker makeGripperMarker( const char *name, const geometry_msgs::PoseStamped &stamped,
00621                                                          float scale, float angle, bool view_facing)
00622 {
00623   std_msgs::ColorRGBA color;
00624   return makeGripperMarker( name, stamped, scale, angle, view_facing, color, false);
00625 }
00626 
00627 visualization_msgs::InteractiveMarker makeGripperMarker( const char *name, const geometry_msgs::PoseStamped &stamped,
00628                                                          float scale, float angle, bool view_facing, std_msgs::ColorRGBA color )
00629 {
00630   return makeGripperMarker( name, stamped, scale, angle, view_facing, color, true);
00631 }
00632 
00633 
00634 visualization_msgs::InteractiveMarker makeGripperMarker( const char *name, const geometry_msgs::PoseStamped &stamped,
00635                                                          float scale, float angle, bool view_facing, std_msgs::ColorRGBA color, bool use_color )
00636 {
00637   visualization_msgs::InteractiveMarker int_marker;
00638   int_marker.header =  stamped.header;
00639   int_marker.name = name;
00640   int_marker.scale = 1.0; 
00641   int_marker.pose = stamped.pose;
00642 
00643 
00644 
00645   visualization_msgs::InteractiveMarkerControl control;
00646 
00647   visualization_msgs::Marker mesh;
00648   mesh.mesh_use_embedded_materials = !use_color;
00649   mesh.type = visualization_msgs::Marker::MESH_RESOURCE;
00650   mesh.scale.x = scale;
00651   mesh.scale.y = scale;
00652   mesh.scale.z = scale;
00653   mesh.color = color;
00654 
00655   tf::Transform T1, T2;
00656   tf::Transform T_proximal, T_distal;
00657 
00658   T1.setOrigin(tf::Vector3(0.07691, 0.01, 0));
00659   T1.setRotation(tf::Quaternion(tf::Vector3(0,0,1),  angle));
00660   T2.setOrigin(tf::Vector3(0.09137, 0.00495, 0));
00661   T2.setRotation(tf::Quaternion(tf::Vector3(0,0,1), -angle));
00662   T_proximal = T1;
00663   T_distal = T1 * T2;
00664 
00665   mesh.mesh_resource = "package://pr2_description/meshes/gripper_v0/gripper_palm.dae";
00666   mesh.pose.orientation.w = 1;
00667   control.markers.push_back( mesh );
00668   mesh.mesh_resource = "package://pr2_description/meshes/gripper_v0/l_finger.dae";
00669   mesh.pose = createPoseMsg(T_proximal);
00670   control.markers.push_back( mesh );
00671   mesh.mesh_resource = "package://pr2_description/meshes/gripper_v0/l_finger_tip.dae";
00672   mesh.pose = createPoseMsg(T_distal);
00673   control.markers.push_back( mesh );
00674 
00675   T1.setOrigin(tf::Vector3(0.07691, -0.01, 0));
00676   T1.setRotation(tf::Quaternion(tf::Vector3(1,0,0), M_PI)*tf::Quaternion(tf::Vector3(0,0,1),  angle));
00677   T2.setOrigin(tf::Vector3(0.09137, 0.00495, 0));
00678   T2.setRotation(tf::Quaternion(tf::Vector3(0,0,1), -angle));
00679   T_proximal = T1;
00680   T_distal = T1 * T2;
00681 
00682   mesh.mesh_resource = "package://pr2_description/meshes/gripper_v0/l_finger.dae";
00683   mesh.pose = createPoseMsg(T_proximal);
00684   control.markers.push_back( mesh );
00685   mesh.mesh_resource = "package://pr2_description/meshes/gripper_v0/l_finger_tip.dae";
00686   mesh.pose = createPoseMsg(T_distal);
00687   control.markers.push_back( mesh );
00688 
00689   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
00690   control.always_visible = true;
00691   int_marker.controls.push_back( control );
00692 
00693   return int_marker;
00694 }
00695 
00696 
00697 visualization_msgs::InteractiveMarker makeGraspMarker( const char * name, const geometry_msgs::PoseStamped &stamped, float scale, PoseState pose_state)
00698 {
00699   visualization_msgs::InteractiveMarker int_marker;
00700   int_marker.header =  stamped.header;
00701   int_marker.header.stamp = ros::Time(0);
00702   int_marker.name = name;
00703   int_marker.scale = scale;
00704   int_marker.pose = stamped.pose;
00705 
00706   visualization_msgs::InteractiveMarkerControl control;
00707   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
00708   control.orientation.w = 1;
00709   visualization_msgs::Marker marker;
00710   marker.type = visualization_msgs::Marker::ARROW;
00711   
00712   
00713   marker.scale.x = 0.025*scale;
00714   marker.scale.y = 0.0025*scale;
00715   marker.scale.z = 0.0025*scale;
00716   marker.color.r = 1.0;
00717   marker.color.a = 1.0;
00718   control.markers.push_back(marker);
00719   marker.type = visualization_msgs::Marker::CUBE;
00720   marker.scale.x = 0.015*scale;
00721   marker.scale.y = 0.04*scale;
00722   marker.scale.z = 0.015*scale;
00723   switch (pose_state)
00724   {
00725   case UNTESTED:
00726     marker.color.g = 0.5;
00727     marker.color.b = 0.5;
00728     marker.color.r = 0.5;
00729     break;
00730   case VALID:
00731     marker.color.g = 1.0;
00732     marker.color.r = 0.0;
00733     break;
00734   case INVALID:
00735     marker.color.g = 0.0;
00736     marker.color.r = 1.0;
00737     break;
00738   }
00739   control.markers.push_back(marker);
00740 
00741 
00742 
00743 
00744 
00745 
00746   int_marker.controls.push_back(control);
00747 
00748   return int_marker;
00749 }
00750 
00751 
00752 visualization_msgs::InteractiveMarker makePosedMultiMeshMarker( const char * name, const geometry_msgs::PoseStamped &stamped,
00753                                                                 const std::vector< geometry_msgs::PoseStamped> &mesh_poses,
00754                                                                 const std::vector<std::string> &mesh_paths, const float &scale,
00755                                                                 const bool button_only)
00756 {
00757     
00758     visualization_msgs::InteractiveMarker int_marker;
00759     int_marker.header =  stamped.header;
00760     int_marker.name = name;
00761     int_marker.scale = scale;
00762     int_marker.pose = stamped.pose;
00763 
00764     bool fixed = false;
00765     visualization_msgs::InteractiveMarkerControl control;
00766     if( !button_only )
00767     {
00768         control.orientation_mode = fixed ? (uint8_t)visualization_msgs::InteractiveMarkerControl::FIXED : (uint8_t)visualization_msgs::InteractiveMarkerControl::INHERIT;
00769         control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
00770         control.orientation.w = 1;
00771         control.orientation.x = 0;
00772         control.orientation.y = 1;
00773         control.orientation.z = 0;
00774         int_marker.controls.push_back(control);
00775     }
00776 
00777     control.markers.clear();
00778     if (button_only) {
00779       control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
00780     }
00781     else {
00782       control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_PLANE;
00783     }
00784     control.always_visible = true;
00785     for(size_t i = 0; i < mesh_poses.size(); i++)
00786     {
00787         visualization_msgs::Marker mesh;
00788         mesh.color = std_msgs::ColorRGBA();
00789         mesh.mesh_resource = mesh_paths[i];
00790         mesh.mesh_use_embedded_materials = true;
00791         mesh.type = visualization_msgs::Marker::MESH_RESOURCE;
00792         mesh.scale.x = mesh.scale.y = mesh.scale.z = scale;
00793         mesh.pose = mesh_poses[i].pose;
00794         control.markers.push_back( mesh );
00795     }
00796     int_marker.controls.push_back( control );
00797 
00798     return int_marker;
00799 
00800 }
00801 
00802 visualization_msgs::InteractiveMarker makeFollowerMultiMeshMarker( const char * name, const geometry_msgs::PoseStamped &stamped,
00803                                                                    const std::vector<std::string> &mesh_frames,
00804                                                                    const std::vector<std::string> &mesh_paths,
00805                                                                    const float &scale)
00806 {
00807     visualization_msgs::InteractiveMarker int_marker;
00808     int_marker.header =  stamped.header;
00809     int_marker.name = name;
00810     int_marker.scale = scale;
00811     int_marker.pose = stamped.pose;
00812 
00813     if(mesh_frames.size() != mesh_paths.size())
00814     {
00815       ROS_ERROR("The number of mesh frames and mesh paths is not equal!");
00816       return int_marker;
00817     }
00818 
00819     visualization_msgs::InteractiveMarkerControl control;
00820 
00821     control.markers.clear();
00822     control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
00823     control.always_visible = true;
00824     for(size_t i = 0; i < mesh_frames.size(); i++)
00825     {
00826         visualization_msgs::Marker mesh;
00827         mesh.color = std_msgs::ColorRGBA();
00828         mesh.mesh_resource = mesh_paths[i];
00829         mesh.mesh_use_embedded_materials = true;
00830         mesh.type = visualization_msgs::Marker::MESH_RESOURCE;
00831         mesh.scale.x = mesh.scale.y = mesh.scale.z = scale;
00832         mesh.pose.orientation.w = 1;
00833         mesh.header.frame_id = mesh_frames[i];
00834         control.markers.push_back( mesh );
00835         mesh.frame_locked = true;
00836     }
00837     int_marker.controls.push_back( control );
00838 
00839     return int_marker;
00840 }
00841 
00842 }