1 #ifndef _RAPID_ROBOT_POINT_CLOUD_CAMERA_H_
2 #define _RAPID_ROBOT_POINT_CLOUD_CAMERA_H_
7 #include "tf/transform_listener.h"
31 const std::string& base_link);
33 pcl::PointCloud<pcl::PointXYZRGB>::Ptr
cloud()
const;
35 geometry_msgs::TransformStamped
camera_pose()
const;
39 mutable std::string base_link_;
40 tf::TransformListener tf_listener_;
42 mutable std::string camera_frame_id_;
46 #endif // _RAPID_ROBOT_POINT_CLOUD_CAMERA_H_
Gets point cloud and camera pose.
PointCloudCamera(const std::string &topic, const std::string &base_link)
Constructor.
pcl::PointCloud< pcl::PointXYZRGB >::Ptr cloud() const
Returns the most recent point cloud from the camera.
Interface for a camera that outputs point clouds.
geometry_msgs::TransformStamped camera_pose() const
Returns the camera pose relative to the base frame.