32 #ifndef _MARKER_HELPERS_H_ 
   33 #define _MARKER_HELPERS_H_ 
   36 #include <visualization_msgs/InteractiveMarker.h> 
   37 #include <visualization_msgs/InteractiveMarkerControl.h> 
   38 #include <visualization_msgs/Marker.h> 
   39 #include <visualization_msgs/MenuEntry.h> 
   40 #include <geometry_msgs/PoseStamped.h> 
   50 visualization_msgs::Marker 
makeBox( 
float scale );
 
   52 visualization_msgs::Marker 
makeSphere( 
float scale );
 
   53 void add3Dof2DControl( visualization_msgs::InteractiveMarker &msg, 
bool fixed = 
false);
 
   54 void add6DofControl( visualization_msgs::InteractiveMarker &msg, 
bool fixed = 
false );
 
   55 void addVisible6DofControl( visualization_msgs::InteractiveMarker &msg, 
bool fixed = 
false, 
bool visible = 
true );
 
   58 visualization_msgs::InteractiveMarkerControl& 
makeBoxControl( visualization_msgs::InteractiveMarker &msg );
 
   60 visualization_msgs::InteractiveMarkerControl& 
makeSphereControl( visualization_msgs::InteractiveMarker &msg );
 
   62 visualization_msgs::MenuEntry 
makeMenuEntry(
const char *title);
 
   64 visualization_msgs::MenuEntry 
makeMenuEntry(
const char *title, 
const char *command, 
int type  );
 
   66 visualization_msgs::InteractiveMarker 
makePostureMarker( 
const char *name, 
const geometry_msgs::PoseStamped &stamped, 
 
   67                                                          float scale, 
bool fixed, 
bool view_facing );
 
   69 visualization_msgs::InteractiveMarker 
makeHeadGoalMarker( 
const char *name, 
const geometry_msgs::PoseStamped &stamped, 
 
   72 visualization_msgs::InteractiveMarker 
makeMeshMarker( 
const std::string &name, 
const std::string &mesh_resource,
 
   73                                                       const geometry_msgs::PoseStamped &stamped, 
float scale );
 
   75 visualization_msgs::InteractiveMarker 
makeMeshMarker( 
const std::string &name, 
const std::string &mesh_resource,
 
   76                                                       const geometry_msgs::PoseStamped &stamped, 
float scale, 
const std_msgs::ColorRGBA &color );
 
   78 visualization_msgs::InteractiveMarker 
makeMeshMarker( 
const std::string &name, 
const std::string &mesh_resource,
 
   79                                                       const geometry_msgs::PoseStamped &stamped, 
float scale, 
const std_msgs::ColorRGBA &color, 
bool use_color );
 
   81 visualization_msgs::InteractiveMarker 
makeButtonBox( 
const char *name, 
const geometry_msgs::PoseStamped &stamped,
 
   82                                                      float scale, 
bool fixed, 
bool view_facing );
 
   84 visualization_msgs::InteractiveMarker 
makeButtonSphere( 
const char *name, 
const geometry_msgs::PoseStamped &stamped,
 
   85                                                      float scale, 
bool fixed, 
bool view_facing );
 
   87 visualization_msgs::InteractiveMarker 
makeButtonSphere( 
const char *name, 
const geometry_msgs::PoseStamped &stamped,
 
   88                                                      float scale, 
bool fixed, 
bool view_facing, std_msgs::ColorRGBA color );
 
   90 visualization_msgs::InteractiveMarker 
makeListControl( 
const char *name, 
const geometry_msgs::PoseStamped &stamped, 
int num, 
int total, 
float scale);
 
   92 visualization_msgs::InteractiveMarker 
make6DofMarker( 
const char *name, 
const geometry_msgs::PoseStamped &stamped,
 
   93                                                       float scale, 
bool fixed, 
bool view_facing );
 
   95 visualization_msgs::InteractiveMarker 
makePlanarMarker( 
const char *name, 
const geometry_msgs::PoseStamped &stamped,
 
   96                                                       float scale, 
bool fixed );
 
   98 visualization_msgs::InteractiveMarker 
makeElevatorMarker( 
const char *name, 
const geometry_msgs::PoseStamped &stamped,
 
   99                                                           float scale, 
bool fixed);
 
  101 visualization_msgs::InteractiveMarker 
makeProjectorMarker( 
const char *name, 
const geometry_msgs::PoseStamped &stamped,
 
  105 visualization_msgs::InteractiveMarker 
makeBaseMarker( 
const char *name, 
const geometry_msgs::PoseStamped &stamped,
 
  106                                                       float scale, 
bool fixed);
 
  108 visualization_msgs::InteractiveMarker 
makeGripperMarker( 
const char *name, 
const geometry_msgs::PoseStamped &stamped,
 
  109                                                          float scale, 
float angle, 
bool view_facing );
 
  111 visualization_msgs::InteractiveMarker 
makeGripperMarker( 
const char *name, 
const geometry_msgs::PoseStamped &stamped,
 
  112                                                          float scale, 
float angle, 
bool view_facing, std_msgs::ColorRGBA color );
 
  114 visualization_msgs::InteractiveMarker 
makeGripperMarker( 
const char *name, 
const geometry_msgs::PoseStamped &stamped,
 
  115                                                          float scale, 
float angle, 
bool view_facing, std_msgs::ColorRGBA color, 
bool use_color );
 
  117 visualization_msgs::InteractiveMarker 
makeGraspMarker( 
const char * name, 
const geometry_msgs::PoseStamped &stamped, 
float scale, 
PoseState pose_state);
 
  119 visualization_msgs::InteractiveMarker 
makePosedMultiMeshMarker( 
const char * name, 
const geometry_msgs::PoseStamped &stamped,
 
  120                                                             const std::vector< geometry_msgs::PoseStamped> &mesh_poses,
 
  121                                                             const std::vector<std::string> &mesh_paths, 
const float &scale, 
const bool button_only = 
true);
 
  124                                                                    const std::vector<std::string> &mesh_frames,
 
  125                                                                    const std::vector<std::string> &mesh_paths,