$search
Definition at line 46 of file interactive_marker_helpers.h.
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.
visualization_msgs::InteractiveMarkerControl & im_helpers::makeBoxControl | ( | visualization_msgs::InteractiveMarker & | msg | ) |
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.
visualization_msgs::InteractiveMarkerControl & im_helpers::makeSphereControl | ( | visualization_msgs::InteractiveMarker & | msg | ) |
Definition at line 126 of file interactive_marker_helpers.cpp.