30 #ifndef RVIZ_INTERACTIVE_MARKER_TOOLS_H 31 #define RVIZ_INTERACTIVE_MARKER_TOOLS_H 33 #include <visualization_msgs/InteractiveMarker.h> 44 void autoComplete( visualization_msgs::InteractiveMarker &msg,
bool enable_autocomplete_transparency =
true );
50 void autoComplete(
const visualization_msgs::InteractiveMarker &msg,
51 visualization_msgs::InteractiveMarkerControl &control,
bool enable_autocomplete_transparency =
true );
64 geometry_msgs::Quaternion
makeQuaternion(
float x,
float y,
float z );
74 void makeArrow(
const visualization_msgs::InteractiveMarker &msg,
75 visualization_msgs::InteractiveMarkerControl &control,
float pos );
81 void makeDisc(
const visualization_msgs::InteractiveMarker &msg,
82 visualization_msgs::InteractiveMarkerControl &control,
float width = 0.3 );
89 visualization_msgs::InteractiveMarkerControl &control, std::string text );
93 void assignDefaultColor(visualization_msgs::Marker &marker,
const geometry_msgs::Quaternion &quat );
97 visualization_msgs::InteractiveMarkerControl
makeTitle(
const visualization_msgs::InteractiveMarker &msg );
INTERACTIVE_MARKERS_PUBLIC 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
INTERACTIVE_MARKERS_PUBLIC geometry_msgs::Quaternion makeQuaternion(float x, float y, float z)
INTERACTIVE_MARKERS_PUBLIC visualization_msgs::InteractiveMarkerControl makeTitle(const visualization_msgs::InteractiveMarker &msg)
create a control which shows the description of the interactive marker
INTERACTIVE_MARKERS_PUBLIC void autoComplete(visualization_msgs::InteractiveMarker &msg, bool enable_autocomplete_transparency=true)
fill in default values & insert default controls when none are specified.
INTERACTIVE_MARKERS_PUBLIC void uniqueifyControlNames(visualization_msgs::InteractiveMarker &msg)
Make sure all the control names are unique within the given msg.
#define INTERACTIVE_MARKERS_PUBLIC
INTERACTIVE_MARKERS_PUBLIC void assignDefaultColor(visualization_msgs::Marker &marker, const geometry_msgs::Quaternion &quat)
assign an RGB value to the given marker based on the given orientation
INTERACTIVE_MARKERS_PUBLIC void makeArrow(const visualization_msgs::InteractiveMarker &msg, visualization_msgs::InteractiveMarkerControl &control, float pos)
— marker helpers —
INTERACTIVE_MARKERS_PUBLIC 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 ...