1 #ifndef _RAPID_VIZ_LANDMARK_VIZ_H_
2 #define _RAPID_VIZ_LANDMARK_VIZ_H_
4 #include "geometry_msgs/Pose.h"
6 #include "sensor_msgs/PointCloud2.h"
7 #include "visualization_msgs/Marker.h"
9 #include "rapid_msgs/Roi3D.h"
17 const ros::Publisher& marker_pub);
18 LandmarkViz(
const ros::Publisher& cloud_pub,
const ros::Publisher& marker_pub,
19 const std::string& base_frame);
21 const rapid_msgs::Roi3D& roi);
24 void UpdatePose(
const geometry_msgs::Pose& pose);
29 ros::Publisher cloud_pub_;
30 std::string base_frame_;
32 sensor_msgs::PointCloud2 cloud_;
33 rapid_msgs::Roi3D roi_;
34 geometry_msgs::Pose pose_;
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)