39 #include <visualization_msgs/msg/interactive_marker.hpp>
40 #include <geometry_msgs/msg/pose_stamped.hpp>
41 #include <std_msgs/msg/color_rgba.hpp>
45 visualization_msgs::msg::InteractiveMarker
49 const geometry_msgs::msg::PoseStamped& stamped,
double scale,
50 bool orientation_fixed =
false);
53 const geometry_msgs::msg::PoseStamped& stamped,
54 double scale,
bool orientation_fixed =
false);
58 void addErrorMarker(visualization_msgs::msg::InteractiveMarker& im);
60 void add6DOFControl(visualization_msgs::msg::InteractiveMarker& int_marker,
bool orientation_fixed =
false);
62 void addPlanarXYControl(visualization_msgs::msg::InteractiveMarker& int_marker,
bool orientation_fixed =
false);
64 void addOrientationControl(visualization_msgs::msg::InteractiveMarker& int_marker,
bool orientation_fixed =
false);
66 void addPositionControl(visualization_msgs::msg::InteractiveMarker& int_marker,
bool orientation_fixed =
false);
68 void addViewPlaneControl(visualization_msgs::msg::InteractiveMarker& int_marker,
double radius,
69 const std_msgs::msg::ColorRGBA& color,
bool position =
true,
bool orientation =
true);
void addViewPlaneControl(visualization_msgs::msg::InteractiveMarker &int_marker, double radius, const std_msgs::msg::ColorRGBA &color, bool position=true, bool orientation=true)
void addTArrowMarker(visualization_msgs::msg::InteractiveMarker &im)
void add6DOFControl(visualization_msgs::msg::InteractiveMarker &int_marker, bool orientation_fixed=false)
visualization_msgs::msg::InteractiveMarker make6DOFMarker(const std::string &name, const geometry_msgs::msg::PoseStamped &stamped, double scale, bool orientation_fixed=false)
void addOrientationControl(visualization_msgs::msg::InteractiveMarker &int_marker, bool orientation_fixed=false)
visualization_msgs::msg::InteractiveMarker makeEmptyInteractiveMarker(const std::string &name, const geometry_msgs::msg::PoseStamped &stamped, double scale)
void addErrorMarker(visualization_msgs::msg::InteractiveMarker &im)
void addPlanarXYControl(visualization_msgs::msg::InteractiveMarker &int_marker, bool orientation_fixed=false)
visualization_msgs::msg::InteractiveMarker makePlanarXYMarker(const std::string &name, const geometry_msgs::msg::PoseStamped &stamped, double scale, bool orientation_fixed=false)
void addPositionControl(visualization_msgs::msg::InteractiveMarker &int_marker, bool orientation_fixed=false)