39 #include <visualization_msgs/InteractiveMarker.h>
40 #include <geometry_msgs/PoseStamped.h>
41 #include <std_msgs/ColorRGBA.h>
45 visualization_msgs::InteractiveMarker
48 visualization_msgs::InteractiveMarker
make6DOFMarker(
const std::string& name,
const geometry_msgs::PoseStamped& stamped,
49 double scale,
bool orientation_fixed =
false);
52 const geometry_msgs::PoseStamped& stamped,
double scale,
53 bool orientation_fixed =
false);
59 void add6DOFControl(visualization_msgs::InteractiveMarker& int_marker,
bool orientation_fixed =
false);
61 void addPlanarXYControl(visualization_msgs::InteractiveMarker& int_marker,
bool orientation_fixed =
false);
63 void addOrientationControl(visualization_msgs::InteractiveMarker& int_marker,
bool orientation_fixed =
false);
65 void addPositionControl(visualization_msgs::InteractiveMarker& int_marker,
bool orientation_fixed =
false);
68 const std_msgs::ColorRGBA& color,
bool position =
true,
bool orientation =
true);