42   geometry_msgs::Pose 
pose;
 
   48   pose.orientation.x = 
rot.getX();
 
   49   pose.orientation.y = 
rot.getY();
 
   50   pose.orientation.z = 
rot.getZ();
 
   51   pose.orientation.w = 
rot.getW();
 
   57   visualization_msgs::InteractiveMarker int_marker;
 
   58   int_marker.header.frame_id = 
frame_id;
 
   64 visualization_msgs::Marker 
makeBox( 
float scale )
 
   66   visualization_msgs::Marker 
marker;
 
   68   marker.type = visualization_msgs::Marker::CUBE;
 
   82   visualization_msgs::Marker 
marker;
 
   84   marker.type = visualization_msgs::Marker::SPHERE;
 
   98   visualization_msgs::InteractiveMarkerControl control;
 
  101     control.orientation_mode = visualization_msgs::InteractiveMarkerControl::FIXED;
 
  103   control.orientation.w = 1;
 
  104   control.orientation.x = 1;
 
  105   control.orientation.y = 0;
 
  106   control.orientation.z = 0;
 
  109   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
 
  110   msg.controls.push_back(control);
 
  112   control.orientation.w = 1;
 
  113   control.orientation.x = 0;
 
  114   control.orientation.y = 1;
 
  115   control.orientation.z = 0;
 
  116   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
 
  117   msg.controls.push_back(control);
 
  121   control.orientation.w = 1;
 
  122   control.orientation.x = 0;
 
  123   control.orientation.y = 0;
 
  124   control.orientation.z = 1;
 
  127   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
 
  128   msg.controls.push_back(control);
 
  134   visualization_msgs::InteractiveMarkerControl control;
 
  137     control.orientation_mode = visualization_msgs::InteractiveMarkerControl::FIXED;
 
  139   control.orientation.w = 1;
 
  140   control.orientation.x = 1;
 
  141   control.orientation.y = 0;
 
  142   control.orientation.z = 0;
 
  143   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
 
  144   msg.controls.push_back(control);
 
  145   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
 
  146   msg.controls.push_back(control);
 
  148   control.orientation.w = 1;
 
  149   control.orientation.x = 0;
 
  150   control.orientation.y = 1;
 
  151   control.orientation.z = 0;
 
  152   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
 
  153   msg.controls.push_back(control);
 
  154   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
 
  155   msg.controls.push_back(control);
 
  157   control.orientation.w = 1;
 
  158   control.orientation.x = 0;
 
  159   control.orientation.y = 0;
 
  160   control.orientation.z = 1;
 
  161   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
 
  162   msg.controls.push_back(control);
 
  163   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
 
  164   msg.controls.push_back(control);
 
  169   visualization_msgs::InteractiveMarkerControl control;
 
  172     control.always_visible = 
true;
 
  175     control.orientation_mode = visualization_msgs::InteractiveMarkerControl::FIXED;
 
  177   control.orientation.w = 1;
 
  178   control.orientation.x = 1;
 
  179   control.orientation.y = 0;
 
  180   control.orientation.z = 0;
 
  181   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
 
  182   msg.controls.push_back(control);
 
  183   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
 
  184   msg.controls.push_back(control);
 
  186   control.orientation.w = 1;
 
  187   control.orientation.x = 0;
 
  188   control.orientation.y = 1;
 
  189   control.orientation.z = 0;
 
  190   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
 
  191   msg.controls.push_back(control);
 
  192   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
 
  193   msg.controls.push_back(control);
 
  195   control.orientation.w = 1;
 
  196   control.orientation.x = 0;
 
  197   control.orientation.y = 0;
 
  198   control.orientation.z = 1;
 
  199   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
 
  200   msg.controls.push_back(control);
 
  201   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
 
  202   msg.controls.push_back(control);
 
  206 visualization_msgs::InteractiveMarkerControl& 
makeBoxControl( visualization_msgs::InteractiveMarker &msg )
 
  208   visualization_msgs::InteractiveMarkerControl control;
 
  209   control.always_visible = 
true;
 
  210   control.markers.push_back( 
makeBox(
msg.scale) );
 
  211   msg.controls.push_back( control );
 
  213   return msg.controls.back();
 
  216 visualization_msgs::InteractiveMarkerControl& 
makeSphereControl( visualization_msgs::InteractiveMarker &msg )
 
  218   visualization_msgs::InteractiveMarkerControl control;
 
  219   control.always_visible = 
true;
 
  221   msg.controls.push_back( control );
 
  223   return msg.controls.back();
 
  228   visualization_msgs::MenuEntry m;
 
  234 visualization_msgs::MenuEntry 
makeMenuEntry(
const char *title, 
const char *command, 
int type  )
 
  236   visualization_msgs::MenuEntry m;
 
  239   m.command_type = 
type;
 
  243 visualization_msgs::InteractiveMarker 
makePostureMarker( 
const char *name, 
const geometry_msgs::PoseStamped &stamped,
 
  244                                                          float scale, 
bool fixed, 
bool view_facing )
 
  246   visualization_msgs::InteractiveMarker int_marker;
 
  247   int_marker.header =  stamped.header;
 
  248   int_marker.name = name;
 
  249   int_marker.scale = 
scale;
 
  250   int_marker.pose = stamped.pose;
 
  252   visualization_msgs::InteractiveMarkerControl control;
 
  253   control.orientation.w = 1;
 
  254   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
 
  255   int_marker.controls.push_back(control);
 
  260 visualization_msgs::InteractiveMarker 
makeHeadGoalMarker( 
const char *name, 
const geometry_msgs::PoseStamped &stamped,
 
  263   visualization_msgs::InteractiveMarker int_marker;
 
  264   int_marker.header =  stamped.header;
 
  265   int_marker.name = name;
 
  266   int_marker.scale = 
scale;
 
  267   int_marker.pose = stamped.pose;
 
  269   visualization_msgs::InteractiveMarkerControl control;
 
  270   control.orientation_mode = visualization_msgs::InteractiveMarkerControl::VIEW_FACING;
 
  271   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_PLANE;
 
  272   control.orientation.w = 1;
 
  274   int_marker.controls.push_back(control);
 
  275   control.markers.clear();
 
  282 visualization_msgs::InteractiveMarker 
makeMeshMarker( 
const std::string &name, 
const std::string &mesh_resource,
 
  283                                                       const geometry_msgs::PoseStamped &stamped, 
float scale, 
const std_msgs::ColorRGBA &color, 
bool use_color )
 
  285   visualization_msgs::InteractiveMarker int_marker;
 
  286   int_marker.header =  stamped.header;
 
  287   int_marker.pose = stamped.pose;
 
  288   int_marker.name = name;
 
  289   int_marker.scale = 
scale;
 
  291   visualization_msgs::Marker mesh;
 
  292   if (use_color) mesh.color = color;
 
  294   mesh.mesh_use_embedded_materials = !use_color;
 
  295   mesh.type = visualization_msgs::Marker::MESH_RESOURCE;
 
  296   mesh.scale.x = 
scale;
 
  297   mesh.scale.y = 
scale;
 
  298   mesh.scale.z = 
scale;
 
  300   visualization_msgs::InteractiveMarkerControl control;
 
  301   control.markers.push_back( mesh );
 
  302   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
 
  303   int_marker.controls.push_back( control );
 
  308 visualization_msgs::InteractiveMarker 
makeMeshMarker( 
const std::string &name, 
const std::string &mesh_resource,
 
  309                                                       const geometry_msgs::PoseStamped &stamped, 
float scale)
 
  311   std_msgs::ColorRGBA color;
 
  315 visualization_msgs::InteractiveMarker 
makeMeshMarker( 
const std::string &name, 
const std::string &mesh_resource,
 
  316                                                       const geometry_msgs::PoseStamped &stamped, 
float scale, 
const std_msgs::ColorRGBA &color)
 
  321 visualization_msgs::InteractiveMarker 
makeButtonBox( 
const char *name, 
const geometry_msgs::PoseStamped &stamped, 
float scale, 
bool fixed, 
bool view_facing )
 
  323   visualization_msgs::InteractiveMarker int_marker;
 
  324   int_marker.header =  stamped.header;
 
  325   int_marker.name = name;
 
  326   int_marker.scale = 
scale;
 
  327   int_marker.pose = stamped.pose;
 
  330   visualization_msgs::InteractiveMarkerControl &control = 
makeBoxControl(int_marker);
 
  332   control.always_visible = 
false;
 
  333   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
 
  338 visualization_msgs::InteractiveMarker 
makeButtonSphere( 
const char *name, 
const geometry_msgs::PoseStamped &stamped,
 
  339                                                         float scale, 
bool fixed, 
bool view_facing)
 
  341   std_msgs::ColorRGBA color;
 
  345 visualization_msgs::InteractiveMarker 
makeButtonSphere( 
const char *name, 
const geometry_msgs::PoseStamped &stamped,
 
  346                                                         float scale, 
bool fixed, 
bool view_facing,
 
  347                                                         std_msgs::ColorRGBA color)
 
  349   visualization_msgs::InteractiveMarker int_marker;
 
  350   int_marker.header =  stamped.header;
 
  351   int_marker.name = name;
 
  352   int_marker.scale = 
scale;
 
  353   int_marker.pose = stamped.pose;
 
  356   visualization_msgs::InteractiveMarkerControl &control = 
makeSphereControl(int_marker);
 
  358   control.always_visible = 
false;
 
  359   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
 
  360   control.markers.back().color = color;
 
  365 visualization_msgs::InteractiveMarker 
makeListControl( 
const char *name, 
const geometry_msgs::PoseStamped &stamped, 
int num, 
int total, 
float scale)
 
  368   visualization_msgs::InteractiveMarker int_marker;
 
  369   int_marker.header =  stamped.header;
 
  370   int_marker.name = name;
 
  371   int_marker.scale = 
scale;
 
  372   int_marker.pose = stamped.pose;
 
  374   visualization_msgs::InteractiveMarkerControl control;
 
  377   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
 
  378   std::stringstream ss;
 
  379   ss << 
"pose(" << 
num << 
"/" << total << 
")";
 
  400   int_marker.controls.push_back(control);
 
  420 visualization_msgs::InteractiveMarker 
make6DofMarker( 
const char *name, 
const geometry_msgs::PoseStamped &stamped, 
float scale, 
bool fixed, 
bool view_facing )
 
  422   visualization_msgs::InteractiveMarker int_marker;
 
  423   int_marker.header =  stamped.header;
 
  424   int_marker.name = name;
 
  425   int_marker.scale = 
scale;
 
  426   int_marker.pose = stamped.pose;
 
  430     visualization_msgs::InteractiveMarkerControl control;
 
  431     control.orientation_mode = visualization_msgs::InteractiveMarkerControl::VIEW_FACING;
 
  433     control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
 
  434     control.orientation.w = 1;
 
  435     int_marker.controls.push_back(control);
 
  437     control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_PLANE;
 
  439     int_marker.controls.push_back(control);
 
  449 visualization_msgs::InteractiveMarker 
makePlanarMarker( 
const char *name, 
const geometry_msgs::PoseStamped &stamped, 
float scale, 
bool fixed )
 
  451   visualization_msgs::InteractiveMarker int_marker;
 
  452   int_marker.header =  stamped.header;
 
  453   int_marker.name = name;
 
  454   int_marker.scale = 
scale;
 
  455   int_marker.pose = stamped.pose;
 
  457   visualization_msgs::InteractiveMarkerControl control;
 
  458   control.orientation_mode = fixed ? (uint8_t)visualization_msgs::InteractiveMarkerControl::FIXED : (uint8_t)visualization_msgs::InteractiveMarkerControl::INHERIT;
 
  459   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_ROTATE;
 
  460   control.orientation.w = 1;
 
  461   control.orientation.x = 0;
 
  462   control.orientation.y = 1;
 
  463   control.orientation.z = 0;
 
  464   int_marker.controls.push_back(control);
 
  466   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_PLANE;
 
  468   control.markers.back().pose.orientation.w = 0;
 
  469   control.markers.back().pose.orientation.x = 0;
 
  470   control.markers.back().pose.orientation.y = 1;
 
  471   control.markers.back().pose.orientation.z = 0;
 
  472   control.markers.back().color.r = 0.0;
 
  473   control.markers.back().color.g = 1.0;
 
  474   control.markers.back().color.b = 0.0;
 
  475   int_marker.controls.push_back(control);
 
  480 visualization_msgs::InteractiveMarker 
makeElevatorMarker( 
const char *name, 
const geometry_msgs::PoseStamped &stamped, 
float scale, 
bool fixed)
 
  482   visualization_msgs::InteractiveMarker int_marker;
 
  483   int_marker.header =  stamped.header;
 
  484   int_marker.name = name;
 
  485   int_marker.scale = 
scale;
 
  486   int_marker.pose = stamped.pose;
 
  488   visualization_msgs::InteractiveMarkerControl control;
 
  491     control.orientation_mode = visualization_msgs::InteractiveMarkerControl::FIXED;
 
  493   control.orientation.w = 1;
 
  494   control.orientation.x = 0;
 
  495   control.orientation.y = -1;
 
  496   control.orientation.z = 0;
 
  497   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
 
  500   control.markers.back().color.r = 0.0;
 
  501   control.markers.back().color.g = 1.0;
 
  502   control.markers.back().color.b = 0.0;
 
  504   int_marker.controls.push_back(control);
 
  506   control.markers.clear();
 
  508   control.markers.back().color.r = 1.0;
 
  509   control.markers.back().color.g = 0.0;
 
  510   control.markers.back().color.b = 0.0;
 
  511   control.name = 
"down";
 
  512   int_marker.controls.push_back(control);
 
  517 visualization_msgs::InteractiveMarker 
makeProjectorMarker( 
const char *name, 
const geometry_msgs::PoseStamped &stamped, 
float scale)
 
  519   visualization_msgs::InteractiveMarker int_marker;
 
  520   int_marker.header =  stamped.header;
 
  521   int_marker.name = name;
 
  522   int_marker.scale = 
scale;
 
  523   int_marker.pose = stamped.pose;
 
  525   visualization_msgs::InteractiveMarkerControl control;
 
  526   control.orientation.w = 1;
 
  527   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
 
  528   visualization_msgs::Marker 
marker;
 
  529   marker.type = visualization_msgs::Marker::CYLINDER;
 
  535   control.markers.push_back(
marker);
 
  536   int_marker.controls.push_back(control);
 
  542 visualization_msgs::InteractiveMarker 
makeBaseMarker( 
const char *name, 
const geometry_msgs::PoseStamped &stamped, 
float scale, 
bool fixed)
 
  544   visualization_msgs::InteractiveMarker int_marker;
 
  545   int_marker.header =  stamped.header;
 
  546   int_marker.name = name;
 
  547   int_marker.scale = 
scale;
 
  548   int_marker.pose = stamped.pose;
 
  550   visualization_msgs::InteractiveMarkerControl control;
 
  552   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
 
  553   control.orientation.w = 1;
 
  554   control.orientation.y = -1;
 
  555   int_marker.controls.push_back(control);
 
  559     control.orientation_mode = visualization_msgs::InteractiveMarkerControl::FIXED;
 
  561   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
 
  562   control.orientation.w = 1;
 
  563   control.orientation.y = 0;
 
  565   control.markers.clear();
 
  567   control.markers.back().color.r = 1.0;
 
  568   control.markers.back().color.g = 0.0;
 
  569   control.markers.back().color.b = 0.0;
 
  570   control.name = 
"forward";
 
  571   int_marker.controls.push_back(control);
 
  573   control.markers.clear();
 
  575   control.markers.back().color.r = 1.0;
 
  576   control.markers.back().color.g = 0.0;
 
  577   control.markers.back().color.b = 0.0;
 
  578   control.name = 
"back";
 
  579   int_marker.controls.push_back(control);
 
  581   control.orientation.z = 1;
 
  582   control.markers.clear();
 
  584   control.markers.back().color.r = 1.0;
 
  585   control.markers.back().color.g = 0.0;
 
  586   control.markers.back().color.b = 0.0;
 
  587   control.name = 
"left";
 
  588   int_marker.controls.push_back(control);
 
  590   control.markers.clear();
 
  592   control.markers.back().color.r = 1.0;
 
  593   control.markers.back().color.g = 0.0;
 
  594   control.markers.back().color.b = 0.0;
 
  595   control.name = 
"right";
 
  596   int_marker.controls.push_back(control);
 
  598   control.markers.clear();
 
  601   control.markers.back().pose.position.x = 0.7;
 
  602   control.markers.back().color.r = 1.0;
 
  603   control.markers.back().color.g = 1.0;
 
  604   control.markers.back().color.b = 0.0;
 
  605   control.name = 
"rotate left";
 
  606   int_marker.controls.push_back(control);
 
  608   control.markers.clear();
 
  611   control.markers.back().pose.position.x = 0.7;
 
  612   control.markers.back().color.r = 1.0;
 
  613   control.markers.back().color.g = 1.0;
 
  614   control.markers.back().color.b = 0.0;
 
  615   control.name = 
"rotate right";
 
  616   int_marker.controls.push_back(control);
 
  620 visualization_msgs::InteractiveMarker 
makeGripperMarker( 
const char *name, 
const geometry_msgs::PoseStamped &stamped,
 
  621                                                          float scale, 
float angle, 
bool view_facing)
 
  623   std_msgs::ColorRGBA color;
 
  627 visualization_msgs::InteractiveMarker 
makeGripperMarker( 
const char *name, 
const geometry_msgs::PoseStamped &stamped,
 
  628                                                          float scale, 
float angle, 
bool view_facing, std_msgs::ColorRGBA color )
 
  634 visualization_msgs::InteractiveMarker 
makeGripperMarker( 
const char *name, 
const geometry_msgs::PoseStamped &stamped,
 
  635                                                          float scale, 
float angle, 
bool view_facing, std_msgs::ColorRGBA color, 
bool use_color )
 
  637   visualization_msgs::InteractiveMarker int_marker;
 
  638   int_marker.header =  stamped.header;
 
  639   int_marker.name = name;
 
  640   int_marker.scale = 1.0; 
 
  641   int_marker.pose = stamped.pose;
 
  645   visualization_msgs::InteractiveMarkerControl control;
 
  647   visualization_msgs::Marker mesh;
 
  648   mesh.mesh_use_embedded_materials = !use_color;
 
  649   mesh.type = visualization_msgs::Marker::MESH_RESOURCE;
 
  650   mesh.scale.x = 
scale;
 
  651   mesh.scale.y = 
scale;
 
  652   mesh.scale.z = 
scale;
 
  658   T1.
setOrigin(tf::Vector3(0.07691, 0.01, 0));
 
  660   T2.
setOrigin(tf::Vector3(0.09137, 0.00495, 0));
 
  665   mesh.mesh_resource = 
"package://pr2_description/meshes/gripper_v0/gripper_palm.dae";
 
  666   mesh.pose.orientation.w = 1;
 
  667   control.markers.push_back( mesh );
 
  668   mesh.mesh_resource = 
"package://pr2_description/meshes/gripper_v0/l_finger.dae";
 
  670   control.markers.push_back( mesh );
 
  671   mesh.mesh_resource = 
"package://pr2_description/meshes/gripper_v0/l_finger_tip.dae";
 
  673   control.markers.push_back( mesh );
 
  675   T1.
setOrigin(tf::Vector3(0.07691, -0.01, 0));
 
  677   T2.setOrigin(tf::Vector3(0.09137, 0.00495, 0));
 
  682   mesh.mesh_resource = 
"package://pr2_description/meshes/gripper_v0/l_finger.dae";
 
  684   control.markers.push_back( mesh );
 
  685   mesh.mesh_resource = 
"package://pr2_description/meshes/gripper_v0/l_finger_tip.dae";
 
  687   control.markers.push_back( mesh );
 
  689   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
 
  690   control.always_visible = 
true;
 
  691   int_marker.controls.push_back( control );
 
  697 visualization_msgs::InteractiveMarker 
makeGraspMarker( 
const char * name, 
const geometry_msgs::PoseStamped &stamped, 
float scale, 
PoseState pose_state)
 
  699   visualization_msgs::InteractiveMarker int_marker;
 
  700   int_marker.header =  stamped.header;
 
  702   int_marker.name = name;
 
  703   int_marker.scale = 
scale;
 
  704   int_marker.pose = stamped.pose;
 
  706   visualization_msgs::InteractiveMarkerControl control;
 
  707   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
 
  708   control.orientation.w = 1;
 
  709   visualization_msgs::Marker 
marker;
 
  710   marker.type = visualization_msgs::Marker::ARROW;
 
  718   control.markers.push_back(
marker);
 
  719   marker.type = visualization_msgs::Marker::CUBE;
 
  739   control.markers.push_back(
marker);
 
  746   int_marker.controls.push_back(control);
 
  753                                                                 const std::vector< geometry_msgs::PoseStamped> &mesh_poses,
 
  754                                                                 const std::vector<std::string> &mesh_paths, 
const float &scale,
 
  755                                                                 const bool button_only)
 
  758     visualization_msgs::InteractiveMarker int_marker;
 
  759     int_marker.header =  stamped.header;
 
  760     int_marker.name = name;
 
  761     int_marker.scale = 
scale;
 
  762     int_marker.pose = stamped.pose;
 
  765     visualization_msgs::InteractiveMarkerControl control;
 
  768         control.orientation_mode = fixed ? (uint8_t)visualization_msgs::InteractiveMarkerControl::FIXED : (uint8_t)visualization_msgs::InteractiveMarkerControl::INHERIT;
 
  769         control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
 
  770         control.orientation.w = 1;
 
  771         control.orientation.x = 0;
 
  772         control.orientation.y = 1;
 
  773         control.orientation.z = 0;
 
  774         int_marker.controls.push_back(control);
 
  777     control.markers.clear();
 
  779       control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
 
  782       control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_PLANE;
 
  784     control.always_visible = 
true;
 
  785     for(
size_t i = 0; 
i < mesh_poses.size(); 
i++)
 
  787         visualization_msgs::Marker mesh;
 
  788         mesh.color = std_msgs::ColorRGBA();
 
  789         mesh.mesh_resource = mesh_paths[
i];
 
  790         mesh.mesh_use_embedded_materials = 
true;
 
  791         mesh.type = visualization_msgs::Marker::MESH_RESOURCE;
 
  792         mesh.scale.x = mesh.scale.y = mesh.scale.z = 
scale;
 
  793         mesh.pose = mesh_poses[
i].pose;
 
  794         control.markers.push_back( mesh );
 
  796     int_marker.controls.push_back( control );
 
  803                                                                    const std::vector<std::string> &mesh_frames,
 
  804                                                                    const std::vector<std::string> &mesh_paths,
 
  807     visualization_msgs::InteractiveMarker int_marker;
 
  808     int_marker.header =  stamped.header;
 
  809     int_marker.name = name;
 
  810     int_marker.scale = 
scale;
 
  811     int_marker.pose = stamped.pose;
 
  813     if(mesh_frames.size() != mesh_paths.size())
 
  815       ROS_ERROR(
"The number of mesh frames and mesh paths is not equal!");
 
  819     visualization_msgs::InteractiveMarkerControl control;
 
  821     control.markers.clear();
 
  822     control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
 
  823     control.always_visible = 
true;
 
  824     for(
size_t i = 0; 
i < mesh_frames.size(); 
i++)
 
  826         visualization_msgs::Marker mesh;
 
  827         mesh.color = std_msgs::ColorRGBA();
 
  828         mesh.mesh_resource = mesh_paths[
i];
 
  829         mesh.mesh_use_embedded_materials = 
true;
 
  830         mesh.type = visualization_msgs::Marker::MESH_RESOURCE;
 
  831         mesh.scale.x = mesh.scale.y = mesh.scale.z = 
scale;
 
  832         mesh.pose.orientation.w = 1;
 
  833         mesh.header.frame_id = mesh_frames[
i];
 
  834         control.markers.push_back( mesh );
 
  835         mesh.frame_locked = 
true;
 
  837     int_marker.controls.push_back( control );