rapid
A ROS robotics library.
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Pages
point_cloud_camera.h
Go to the documentation of this file.
1 #ifndef _RAPID_ROBOT_POINT_CLOUD_CAMERA_H_
2 #define _RAPID_ROBOT_POINT_CLOUD_CAMERA_H_
3 
4 #include <string>
5 
7 #include "tf/transform_listener.h"
8 
9 namespace rapid {
25  public:
30  explicit PointCloudCamera(const std::string& topic,
31  const std::string& base_link);
32 
33  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud() const;
34 
35  geometry_msgs::TransformStamped camera_pose() const;
36 
37  private:
38  std::string topic_;
39  mutable std::string base_link_;
40  tf::TransformListener tf_listener_;
41 
42  mutable std::string camera_frame_id_;
43 };
44 } // namespace rapid
45 
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.