Enumerations | |
enum | PoseState { UNTESTED, VALID, INVALID } |
Functions | |
void | add3Dof2DControl (visualization_msgs::InteractiveMarker &msg, bool fixed=false) |
void | add6DofControl (visualization_msgs::InteractiveMarker &msg, bool fixed=false) |
void | addVisible6DofControl (visualization_msgs::InteractiveMarker &msg, bool fixed=false, bool visible=true) |
geometry_msgs::Pose | createPoseMsg (const tf::Transform &transform) |
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::InteractiveMarkerControl & | makeBoxControl (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) |
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 | makeElevatorMarker (const char *name, const geometry_msgs::PoseStamped &stamped, float scale, bool fixed) |
visualization_msgs::InteractiveMarker | makeEmptyMarker (const char *frame_id="") |
visualization_msgs::InteractiveMarker | makeFollowerMultiMeshMarker (const char *name, const geometry_msgs::PoseStamped &stamped, const std::vector< std::string > &mesh_frames, const std::vector< std::string > &mesh_paths, const float &scale) |
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) |
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, std_msgs::ColorRGBA color, bool use_color) |
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) |
visualization_msgs::MenuEntry | makeMenuEntry (const char *title, const char *command, int type) |
visualization_msgs::InteractiveMarker | makeMeshMarker (const std::string &name, const std::string &mesh_resource, const geometry_msgs::PoseStamped &stamped, float scale) |
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, const std_msgs::ColorRGBA &color, bool use_color) |
visualization_msgs::InteractiveMarker | makePlanarMarker (const char *name, const geometry_msgs::PoseStamped &stamped, float scale, bool fixed) |
visualization_msgs::InteractiveMarker | makePosedMultiMeshMarker (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 button_only=true) |
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::Marker | makeSphere (float scale) |
visualization_msgs::InteractiveMarkerControl & | makeSphereControl (visualization_msgs::InteractiveMarker &msg) |
Definition at line 46 of file interactive_marker_helpers.h.
void im_helpers::add3Dof2DControl | ( | visualization_msgs::InteractiveMarker & | msg, |
bool | fixed = false |
||
) |
Definition at line 96 of file interactive_marker_helpers.cpp.
void im_helpers::add6DofControl | ( | visualization_msgs::InteractiveMarker & | msg, |
bool | fixed = false |
||
) |
Definition at line 132 of file interactive_marker_helpers.cpp.
void im_helpers::addVisible6DofControl | ( | visualization_msgs::InteractiveMarker & | msg, |
bool | fixed = false , |
||
bool | visible = true |
||
) |
Definition at line 167 of file interactive_marker_helpers.cpp.
geometry_msgs::Pose im_helpers::createPoseMsg | ( | const tf::Transform & | transform | ) |
Definition at line 40 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 420 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 542 of file interactive_marker_helpers.cpp.
visualization_msgs::Marker im_helpers::makeBox | ( | float | scale | ) |
Definition at line 64 of file interactive_marker_helpers.cpp.
visualization_msgs::InteractiveMarkerControl & im_helpers::makeBoxControl | ( | visualization_msgs::InteractiveMarker & | msg | ) |
Definition at line 206 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 321 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 338 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 345 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 480 of file interactive_marker_helpers.cpp.
visualization_msgs::InteractiveMarker im_helpers::makeEmptyMarker | ( | const char * | frame_id = "" | ) |
Definition at line 55 of file interactive_marker_helpers.cpp.
visualization_msgs::InteractiveMarker im_helpers::makeFollowerMultiMeshMarker | ( | const char * | name, |
const geometry_msgs::PoseStamped & | stamped, | ||
const std::vector< std::string > & | mesh_frames, | ||
const std::vector< std::string > & | mesh_paths, | ||
const float & | scale | ||
) |
Definition at line 802 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 697 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 620 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 627 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 634 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 260 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 365 of file interactive_marker_helpers.cpp.
visualization_msgs::MenuEntry im_helpers::makeMenuEntry | ( | const char * | title | ) |
Definition at line 226 of file interactive_marker_helpers.cpp.
visualization_msgs::MenuEntry im_helpers::makeMenuEntry | ( | const char * | title, |
const char * | command, | ||
int | type | ||
) |
Definition at line 234 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 308 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 315 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 282 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 449 of file interactive_marker_helpers.cpp.
visualization_msgs::InteractiveMarker im_helpers::makePosedMultiMeshMarker | ( | 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 | button_only = true |
||
) |
Definition at line 752 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 243 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 517 of file interactive_marker_helpers.cpp.
visualization_msgs::Marker im_helpers::makeSphere | ( | float | scale | ) |
Definition at line 80 of file interactive_marker_helpers.cpp.
visualization_msgs::InteractiveMarkerControl & im_helpers::makeSphereControl | ( | visualization_msgs::InteractiveMarker & | msg | ) |
Definition at line 216 of file interactive_marker_helpers.cpp.