1 #ifndef _RAPID_VIZ_MARKERS_H_
2 #define _RAPID_VIZ_MARKERS_H_
7 #include "geometry_msgs/Point.h"
8 #include "geometry_msgs/PoseStamped.h"
9 #include "geometry_msgs/Vector3.h"
10 #include "std_msgs/ColorRGBA.h"
11 #include "visualization_msgs/Marker.h"
18 visualization_msgs::Marker
OutlineBox(
const geometry_msgs::PoseStamped& pose,
19 const geometry_msgs::Vector3& scale);
42 const geometry_msgs::PoseStamped& pose,
43 const geometry_msgs::Vector3& scale);
47 const geometry_msgs::PoseStamped& pose,
48 const geometry_msgs::Vector3& scale);
56 const std::string& uri);
58 const std::string& uri,
const std_msgs::ColorRGBA& color);
63 const geometry_msgs::PoseStamped& pose,
64 const std::string& text,
double size);
69 const geometry_msgs::Point& origin,
70 const geometry_msgs::Vector3& vector);
80 void SetColor(
double r,
double g,
double b,
double a = 0.9);
81 void SetFrame(
const std::string& frame_id);
83 void SetPoints(
const std::vector<geometry_msgs::Point>& points);
84 void SetPose(
const geometry_msgs::PoseStamped& ps);
85 void SetScale(
const geometry_msgs::Vector3& scale);
86 void SetText(
const std::string& text);
89 visualization_msgs::Marker
marker()
const;
94 visualization_msgs::Marker marker_;
98 #endif // _RAPID_VIZ_MARKERS_H_
Marker(const Marker &rhs)
void SetFrame(const std::string &frame_id)
visualization_msgs::Marker marker() const
void SetText(const std::string &text)
void SetPose(const geometry_msgs::PoseStamped &ps)
visualization_msgs::Marker OutlineBox(const geometry_msgs::PoseStamped &pose, const geometry_msgs::Vector3 &scale)
static Marker Text(const MarkerPub *pub, const geometry_msgs::PoseStamped &pose, const std::string &text, double size)
void SetNamespace(const std::string &ns)
rapid_ros::PublisherInterface< visualization_msgs::Marker > MarkerPub
static Marker Box(const MarkerPub *pub, const geometry_msgs::PoseStamped &pose, const geometry_msgs::Vector3 &scale)
void SetColor(double r, double g, double b, double a=0.9)
void SetType(uint8_t type)
static Marker OutlineBox(const MarkerPub *pub, const geometry_msgs::PoseStamped &pose, const geometry_msgs::Vector3 &scale)
Marker & operator=(const Marker &rhs)
void SetScale(const geometry_msgs::Vector3 &scale)
static Marker Vector(const MarkerPub *pub, const std::string &frame_id, const geometry_msgs::Point &origin, const geometry_msgs::Vector3 &vector)
static Marker Mesh(const MarkerPub *pub, const geometry_msgs::PoseStamped &ps, const std::string &uri)
void SetPoints(const std::vector< geometry_msgs::Point > &points)