rapid
A ROS robotics library.
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Pages
landmark_viz.h
Go to the documentation of this file.
1 #ifndef _RAPID_VIZ_LANDMARK_VIZ_H_
2 #define _RAPID_VIZ_LANDMARK_VIZ_H_
3 
4 #include "geometry_msgs/Pose.h"
5 #include "ros/ros.h"
6 #include "sensor_msgs/PointCloud2.h"
7 #include "visualization_msgs/Marker.h"
8 
9 #include "rapid_msgs/Roi3D.h"
10 #include "rapid_viz/markers.h"
11 
12 namespace rapid {
13 namespace viz {
14 class LandmarkViz {
15  public:
16  LandmarkViz(const ros::Publisher& cloud_pub,
17  const ros::Publisher& marker_pub);
18  LandmarkViz(const ros::Publisher& cloud_pub, const ros::Publisher& marker_pub,
19  const std::string& base_frame);
20  void set_landmark(const sensor_msgs::PointCloud2& cloud,
21  const rapid_msgs::Roi3D& roi);
22  // Update the pose, which refers to the center of the landmark box.
23  // Give the pose in the base frame.
24  void UpdatePose(const geometry_msgs::Pose& pose);
25  void Publish();
26  void Clear();
27 
28  private:
29  ros::Publisher cloud_pub_;
30  std::string base_frame_;
31 
32  sensor_msgs::PointCloud2 cloud_;
33  rapid_msgs::Roi3D roi_;
34  geometry_msgs::Pose pose_; // Refers to center of landmark box.
36  Marker box_marker_;
37 };
38 } // namespace viz
39 } // namespace rapid
40 
41 #endif // _RAPID_VIZ_LANDMARK_VIZ_H_
LandmarkViz(const ros::Publisher &cloud_pub, const ros::Publisher &marker_pub)
void UpdatePose(const geometry_msgs::Pose &pose)
void set_landmark(const sensor_msgs::PointCloud2 &cloud, const rapid_msgs::Roi3D &roi)