rapid
A ROS robotics library.
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Pages
recorded_point_cloud_camera.h
Go to the documentation of this file.
1 #ifndef _RAPID_ROBOT_RECORDED_POINT_CLOUD_CAMERA_H_
2 #define _RAPID_ROBOT_RECORDED_POINT_CLOUD_CAMERA_H_
3 
5 
6 namespace rapid {
25  public:
36  void LoadBag(const std::string& path);
37 
38  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud() const;
39  geometry_msgs::TransformStamped camera_pose() const;
40 
41  private:
42  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_;
43  geometry_msgs::TransformStamped camera_pose_;
44 };
45 } // namespace rapid
46 
47 #endif // _RAPID_ROBOT_RECORDED_POINT_CLOUD_CAMERA_H_
pcl::PointCloud< pcl::PointXYZRGB >::Ptr cloud() const
Returns the most recent point cloud from the camera.
geometry_msgs::TransformStamped camera_pose() const
Returns the camera pose relative to the base frame.
Interface for a camera that outputs point clouds.
A simulated camera that loads data from a bag file.
void LoadBag(const std::string &path)
Loads a bag file saved by rapid_perception's save_cloud.