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 );