#include <interactive_markers/tools.h>
#include <visualization_msgs/InteractiveMarker.h>
#include <visualization_msgs/InteractiveMarkerControl.h>
#include <visualization_msgs/Marker.h>
#include <visualization_msgs/MenuEntry.h>
#include <geometry_msgs/PoseStamped.h>
Go to the source code of this file.
Namespaces | |
namespace | im_helpers |
Enumerations | |
enum | im_helpers::PoseState { im_helpers::UNTESTED, im_helpers::VALID, im_helpers::INVALID } |
Functions | |
void | im_helpers::add3Dof2DControl (visualization_msgs::InteractiveMarker &msg, bool fixed=false) |
void | im_helpers::add6DofControl (visualization_msgs::InteractiveMarker &msg, bool fixed=false) |
void | im_helpers::addVisible6DofControl (visualization_msgs::InteractiveMarker &msg, bool fixed=false, bool visible=true) |
visualization_msgs::InteractiveMarker | im_helpers::make6DofMarker (const char *name, const geometry_msgs::PoseStamped &stamped, float scale, bool fixed, bool view_facing) |
visualization_msgs::InteractiveMarker | im_helpers::makeBaseMarker (const char *name, const geometry_msgs::PoseStamped &stamped, float scale, bool fixed) |
visualization_msgs::Marker | im_helpers::makeBox (float scale) |
visualization_msgs::InteractiveMarkerControl & | im_helpers::makeBoxControl (visualization_msgs::InteractiveMarker &msg) |
visualization_msgs::InteractiveMarker | im_helpers::makeButtonBox (const char *name, const geometry_msgs::PoseStamped &stamped, float scale, bool fixed, bool view_facing) |
visualization_msgs::InteractiveMarker | im_helpers::makeButtonSphere (const char *name, const geometry_msgs::PoseStamped &stamped, float scale, bool fixed, bool view_facing) |
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) |
visualization_msgs::InteractiveMarker | im_helpers::makeElevatorMarker (const char *name, const geometry_msgs::PoseStamped &stamped, float scale, bool fixed) |
visualization_msgs::InteractiveMarker | im_helpers::makeEmptyMarker (const char *frame_id="") |
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) |
visualization_msgs::InteractiveMarker | im_helpers::makeGraspMarker (const char *name, const geometry_msgs::PoseStamped &stamped, float scale, PoseState pose_state) |
visualization_msgs::InteractiveMarker | im_helpers::makeGripperMarker (const char *name, const geometry_msgs::PoseStamped &stamped, float scale, float angle, bool view_facing) |
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) |
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) |
visualization_msgs::InteractiveMarker | im_helpers::makeHeadGoalMarker (const char *name, const geometry_msgs::PoseStamped &stamped, float scale) |
visualization_msgs::InteractiveMarker | im_helpers::makeListControl (const char *name, const geometry_msgs::PoseStamped &stamped, int num, int total, float scale) |
visualization_msgs::MenuEntry | im_helpers::makeMenuEntry (const char *title) |
visualization_msgs::MenuEntry | im_helpers::makeMenuEntry (const char *title, const char *command, int type) |
visualization_msgs::InteractiveMarker | im_helpers::makeMeshMarker (const std::string &name, const std::string &mesh_resource, const geometry_msgs::PoseStamped &stamped, float scale) |
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) |
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) |
visualization_msgs::InteractiveMarker | im_helpers::makePlanarMarker (const char *name, const geometry_msgs::PoseStamped &stamped, float scale, bool fixed) |
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) |
visualization_msgs::InteractiveMarker | im_helpers::makePostureMarker (const char *name, const geometry_msgs::PoseStamped &stamped, float scale, bool fixed, bool view_facing) |
visualization_msgs::InteractiveMarker | im_helpers::makeProjectorMarker (const char *name, const geometry_msgs::PoseStamped &stamped, float scale) |
visualization_msgs::Marker | im_helpers::makeSphere (float scale) |
visualization_msgs::InteractiveMarkerControl & | im_helpers::makeSphereControl (visualization_msgs::InteractiveMarker &msg) |