$search

im_helpers Namespace Reference

Enumerations

enum  PoseState { UNTESTED, VALID, INVALID }

Functions

void add6DofControl (visualization_msgs::InteractiveMarker &msg, bool fixed=false)
visualization_msgs::InteractiveMarker make6DofMarker (const char *name, const geometry_msgs::PoseStamped &stamped, float scale, bool fixed, bool view_facing)
visualization_msgs::InteractiveMarker makeBaseMarker (const char *name, const geometry_msgs::PoseStamped &stamped, float scale, bool fixed)
visualization_msgs::Marker makeBox (float scale)
visualization_msgs::InteractiveMarkerControlmakeBoxControl (visualization_msgs::InteractiveMarker &msg)
visualization_msgs::InteractiveMarker makeButtonBox (const char *name, const geometry_msgs::PoseStamped &stamped, float scale, bool fixed, bool view_facing)
visualization_msgs::InteractiveMarker makeButtonSphere (const char *name, const geometry_msgs::PoseStamped &stamped, float scale, bool fixed, bool view_facing, std_msgs::ColorRGBA color)
visualization_msgs::InteractiveMarker makeButtonSphere (const char *name, const geometry_msgs::PoseStamped &stamped, float scale, bool fixed, bool view_facing)
visualization_msgs::InteractiveMarker makeElevatorMarker (const char *name, const geometry_msgs::PoseStamped &stamped, float scale, bool fixed)
visualization_msgs::InteractiveMarker makeEmptyMarker (const char *frame_id="")
visualization_msgs::InteractiveMarker makeGraspMarker (const char *name, const geometry_msgs::PoseStamped &stamped, float scale, PoseState pose_state)
visualization_msgs::InteractiveMarker makeGripperMarker (const char *name, const geometry_msgs::PoseStamped &stamped, float scale, float angle, bool view_facing, std_msgs::ColorRGBA color, bool use_color)
visualization_msgs::InteractiveMarker makeGripperMarker (const char *name, const geometry_msgs::PoseStamped &stamped, float scale, float angle, bool view_facing, std_msgs::ColorRGBA color)
visualization_msgs::InteractiveMarker makeGripperMarker (const char *name, const geometry_msgs::PoseStamped &stamped, float scale, float angle, bool view_facing)
visualization_msgs::InteractiveMarker makeHeadGoalMarker (const char *name, const geometry_msgs::PoseStamped &stamped, float scale)
visualization_msgs::InteractiveMarker makeListControl (const char *name, const geometry_msgs::PoseStamped &stamped, int num, int total, float scale)
visualization_msgs::MenuEntry makeMenuEntry (const char *title, const char *command, int type)
visualization_msgs::MenuEntry makeMenuEntry (const char *title)
visualization_msgs::InteractiveMarker makeMeshMarker (const std::string &name, const std::string &mesh_resource, const geometry_msgs::PoseStamped &stamped, float scale, const std_msgs::ColorRGBA &color, bool use_color)
visualization_msgs::InteractiveMarker makeMeshMarker (const std::string &name, const std::string &mesh_resource, const geometry_msgs::PoseStamped &stamped, float scale, const std_msgs::ColorRGBA &color)
visualization_msgs::InteractiveMarker makeMeshMarker (const std::string &name, const std::string &mesh_resource, const geometry_msgs::PoseStamped &stamped, float scale)
visualization_msgs::InteractiveMarker makePlanarMarker (const char *name, const geometry_msgs::PoseStamped &stamped, float scale, bool fixed)
visualization_msgs::InteractiveMarker makePostureMarker (const char *name, const geometry_msgs::PoseStamped &stamped, float scale, bool fixed, bool view_facing)
visualization_msgs::InteractiveMarker makeProjectorMarker (const char *name, const geometry_msgs::PoseStamped &stamped, float scale)
visualization_msgs::InteractiveMarker makeRobotModelMarker (const char *name, const geometry_msgs::PoseStamped &stamped, const std::vector< geometry_msgs::PoseStamped > &mesh_poses, const std::vector< std::string > &mesh_paths, const float &scale, const bool robot_button_only=false)
visualization_msgs::Marker makeSphere (float scale)
visualization_msgs::InteractiveMarkerControlmakeSphereControl (visualization_msgs::InteractiveMarker &msg)

Enumeration Type Documentation

Enumerator:
UNTESTED 
VALID 
INVALID 

Definition at line 46 of file interactive_marker_helpers.h.


Function Documentation

void im_helpers::add6DofControl ( visualization_msgs::InteractiveMarker msg,
bool  fixed = false 
)

Definition at line 80 of file interactive_marker_helpers.cpp.

visualization_msgs::InteractiveMarker im_helpers::make6DofMarker ( const char *  name,
const geometry_msgs::PoseStamped stamped,
float  scale,
bool  fixed,
bool  view_facing 
)

Definition at line 330 of file interactive_marker_helpers.cpp.

visualization_msgs::InteractiveMarker im_helpers::makeBaseMarker ( const char *  name,
const geometry_msgs::PoseStamped stamped,
float  scale,
bool  fixed 
)

Definition at line 451 of file interactive_marker_helpers.cpp.

visualization_msgs::Marker im_helpers::makeBox ( float  scale  ) 

Definition at line 48 of file interactive_marker_helpers.cpp.

Definition at line 116 of file interactive_marker_helpers.cpp.

visualization_msgs::InteractiveMarker im_helpers::makeButtonBox ( const char *  name,
const geometry_msgs::PoseStamped stamped,
float  scale,
bool  fixed,
bool  view_facing 
)

Definition at line 231 of file interactive_marker_helpers.cpp.

visualization_msgs::InteractiveMarker im_helpers::makeButtonSphere ( const char *  name,
const geometry_msgs::PoseStamped stamped,
float  scale,
bool  fixed,
bool  view_facing,
std_msgs::ColorRGBA  color 
)

Definition at line 255 of file interactive_marker_helpers.cpp.

visualization_msgs::InteractiveMarker im_helpers::makeButtonSphere ( const char *  name,
const geometry_msgs::PoseStamped stamped,
float  scale,
bool  fixed,
bool  view_facing 
)

Definition at line 248 of file interactive_marker_helpers.cpp.

visualization_msgs::InteractiveMarker im_helpers::makeElevatorMarker ( const char *  name,
const geometry_msgs::PoseStamped stamped,
float  scale,
bool  fixed 
)

Definition at line 389 of file interactive_marker_helpers.cpp.

visualization_msgs::InteractiveMarker im_helpers::makeEmptyMarker ( const char *  frame_id = ""  ) 

Definition at line 39 of file interactive_marker_helpers.cpp.

visualization_msgs::InteractiveMarker im_helpers::makeGraspMarker ( const char *  name,
const geometry_msgs::PoseStamped stamped,
float  scale,
PoseState  pose_state 
)

Definition at line 605 of file interactive_marker_helpers.cpp.

visualization_msgs::InteractiveMarker im_helpers::makeGripperMarker ( const char *  name,
const geometry_msgs::PoseStamped stamped,
float  scale,
float  angle,
bool  view_facing,
std_msgs::ColorRGBA  color,
bool  use_color 
)

Definition at line 543 of file interactive_marker_helpers.cpp.

visualization_msgs::InteractiveMarker im_helpers::makeGripperMarker ( const char *  name,
const geometry_msgs::PoseStamped stamped,
float  scale,
float  angle,
bool  view_facing,
std_msgs::ColorRGBA  color 
)

Definition at line 536 of file interactive_marker_helpers.cpp.

visualization_msgs::InteractiveMarker im_helpers::makeGripperMarker ( const char *  name,
const geometry_msgs::PoseStamped stamped,
float  scale,
float  angle,
bool  view_facing 
)

Definition at line 529 of file interactive_marker_helpers.cpp.

visualization_msgs::InteractiveMarker im_helpers::makeHeadGoalMarker ( const char *  name,
const geometry_msgs::PoseStamped stamped,
float  scale 
)

Definition at line 170 of file interactive_marker_helpers.cpp.

visualization_msgs::InteractiveMarker im_helpers::makeListControl ( const char *  name,
const geometry_msgs::PoseStamped stamped,
int  num,
int  total,
float  scale 
)

Definition at line 275 of file interactive_marker_helpers.cpp.

visualization_msgs::MenuEntry im_helpers::makeMenuEntry ( const char *  title,
const char *  command,
int  type 
)

Definition at line 144 of file interactive_marker_helpers.cpp.

visualization_msgs::MenuEntry im_helpers::makeMenuEntry ( const char *  title  ) 

Definition at line 136 of file interactive_marker_helpers.cpp.

visualization_msgs::InteractiveMarker im_helpers::makeMeshMarker ( const std::string &  name,
const std::string &  mesh_resource,
const geometry_msgs::PoseStamped stamped,
float  scale,
const std_msgs::ColorRGBA &  color,
bool  use_color 
)

Definition at line 192 of file interactive_marker_helpers.cpp.

visualization_msgs::InteractiveMarker im_helpers::makeMeshMarker ( const std::string &  name,
const std::string &  mesh_resource,
const geometry_msgs::PoseStamped stamped,
float  scale,
const std_msgs::ColorRGBA &  color 
)

Definition at line 225 of file interactive_marker_helpers.cpp.

visualization_msgs::InteractiveMarker im_helpers::makeMeshMarker ( const std::string &  name,
const std::string &  mesh_resource,
const geometry_msgs::PoseStamped stamped,
float  scale 
)

Definition at line 218 of file interactive_marker_helpers.cpp.

visualization_msgs::InteractiveMarker im_helpers::makePlanarMarker ( const char *  name,
const geometry_msgs::PoseStamped stamped,
float  scale,
bool  fixed 
)

Definition at line 358 of file interactive_marker_helpers.cpp.

visualization_msgs::InteractiveMarker im_helpers::makePostureMarker ( const char *  name,
const geometry_msgs::PoseStamped stamped,
float  scale,
bool  fixed,
bool  view_facing 
)

Definition at line 153 of file interactive_marker_helpers.cpp.

visualization_msgs::InteractiveMarker im_helpers::makeProjectorMarker ( const char *  name,
const geometry_msgs::PoseStamped stamped,
float  scale 
)

Definition at line 426 of file interactive_marker_helpers.cpp.

visualization_msgs::InteractiveMarker im_helpers::makeRobotModelMarker ( const char *  name,
const geometry_msgs::PoseStamped stamped,
const std::vector< geometry_msgs::PoseStamped > &  mesh_poses,
const std::vector< std::string > &  mesh_paths,
const float &  scale,
const bool  robot_button_only = false 
)

Definition at line 660 of file interactive_marker_helpers.cpp.

visualization_msgs::Marker im_helpers::makeSphere ( float  scale  ) 

Definition at line 64 of file interactive_marker_helpers.cpp.

Definition at line 126 of file interactive_marker_helpers.cpp.

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends


interactive_marker_helpers
Author(s): Adam Leeper
autogenerated on Fri Mar 1 19:31:25 2013