1 #ifndef _RAPID_ROBOT_RECORDED_POINT_CLOUD_CAMERA_H_
2 #define _RAPID_ROBOT_RECORDED_POINT_CLOUD_CAMERA_H_
36 void LoadBag(
const std::string& path);
38 pcl::PointCloud<pcl::PointXYZRGB>::Ptr
cloud()
const;
39 geometry_msgs::TransformStamped
camera_pose()
const;
42 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_;
43 geometry_msgs::TransformStamped camera_pose_;
47 #endif // _RAPID_ROBOT_RECORDED_POINT_CLOUD_CAMERA_H_
RecordedPointCloudCamera()
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.