$search

interactive_markers Namespace Reference

Namespaces

namespace  interactive_marker_server
namespace  menu_handler

Classes

class  InteractiveMarkerServer
class  MenuHandler

Functions

void assignDefaultColor (visualization_msgs::Marker &marker, const geometry_msgs::Quaternion &quat)
 assign an RGB value to the given marker based on the given orientation
void autoComplete (const visualization_msgs::InteractiveMarker &msg, visualization_msgs::InteractiveMarkerControl &control)
 fill in default values & insert default controls when none are specified
void autoComplete (visualization_msgs::InteractiveMarker &msg)
 fill in default values & insert default controls when none are specified
void makeArrow (const visualization_msgs::InteractiveMarker &msg, visualization_msgs::InteractiveMarkerControl &control, float pos)
 --- marker helpers ---
void makeDisc (const visualization_msgs::InteractiveMarker &msg, visualization_msgs::InteractiveMarkerControl &control, float width=0.3)
 make a default-style disc marker (e.g for rotating) based on the properties of the given interactive marker
geometry_msgs::Quaternion makeQuaternion (float x, float y, float z)
visualization_msgs::InteractiveMarkerControl makeTitle (visualization_msgs::InteractiveMarker &msg)
 create a control which shows the description of the interactive marker
void makeViewFacingButton (const visualization_msgs::InteractiveMarker &msg, visualization_msgs::InteractiveMarkerControl &control, std::string text)
 make a box which shows the given text and is view facing

Function Documentation

void interactive_markers::assignDefaultColor ( visualization_msgs::Marker marker,
const geometry_msgs::Quaternion quat 
)

assign an RGB value to the given marker based on the given orientation

Definition at line 407 of file tools.cpp.

void interactive_markers::autoComplete ( const visualization_msgs::InteractiveMarker msg,
visualization_msgs::InteractiveMarkerControl control 
)

fill in default values & insert default controls when none are specified

Parameters:
msg interactive marker which contains the control
control the control to be completed

Definition at line 78 of file tools.cpp.

void interactive_markers::autoComplete ( visualization_msgs::InteractiveMarker msg  ) 

fill in default values & insert default controls when none are specified

Parameters:
msg interactive marker to be completed

Definition at line 41 of file tools.cpp.

void interactive_markers::makeArrow ( const visualization_msgs::InteractiveMarker msg,
visualization_msgs::InteractiveMarkerControl control,
float  pos 
)

--- marker helpers ---

make a default-style arrow marker based on the properties of the given interactive marker

Parameters:
msg the interactive marker that this will go into
control the control where to insert the arrow marker
pos how far from the center should the arrow be, and on which side

Definition at line 225 of file tools.cpp.

void interactive_markers::makeDisc ( const visualization_msgs::InteractiveMarker msg,
visualization_msgs::InteractiveMarkerControl control,
float  width = 0.3 
)

make a default-style disc marker (e.g for rotating) based on the properties of the given interactive marker

Parameters:
msg the interactive marker that this will go into
width width of the disc, relative to its inner radius

Definition at line 253 of file tools.cpp.

geometry_msgs::Quaternion interactive_markers::makeQuaternion ( float  x,
float  y,
float  z 
)

make a quaternion with a fixed local x axis. The rotation around that axis will be chosen automatically.

Parameters:
x,y,z the designated x axis

create a control which shows the description of the interactive marker

Definition at line 430 of file tools.cpp.

void interactive_markers::makeViewFacingButton ( const visualization_msgs::InteractiveMarker msg,
visualization_msgs::InteractiveMarkerControl control,
std::string  text 
)

make a box which shows the given text and is view facing

Parameters:
msg the interactive marker that this will go into
text the text to display

Definition at line 380 of file tools.cpp.

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends


interactive_markers
Author(s): David Gossow (C++), Michael Ferguson (Python)
autogenerated on Sat Mar 2 14:16:07 2013