|
rapid
A ROS robotics library.
|
A simulated camera that loads data from a bag file. More...
#include <recorded_point_cloud_camera.h>
Public Member Functions | |
| RecordedPointCloudCamera () | |
| void | LoadBag (const std::string &path) |
| Loads a bag file saved by rapid_perception's save_cloud. More... | |
| pcl::PointCloud < pcl::PointXYZRGB >::Ptr | cloud () const |
| Returns the most recent point cloud from the camera. More... | |
| geometry_msgs::TransformStamped | camera_pose () const |
| Returns the camera pose relative to the base frame. More... | |
Public Member Functions inherited from rapid::PointCloudCameraInterface | |
| virtual | ~PointCloudCameraInterface () |
A simulated camera that loads data from a bag file.
Specifically, the bag file should be in the format output by rapid_perception's save_cloud executable:
Usage:
Definition at line 24 of file recorded_point_cloud_camera.h.
| rapid::RecordedPointCloudCamera::RecordedPointCloudCamera | ( | ) |
|
virtual |
Returns the camera pose relative to the base frame.
Implements rapid::PointCloudCameraInterface.
|
virtual |
Returns the most recent point cloud from the camera.
Implements rapid::PointCloudCameraInterface.
| void rapid::RecordedPointCloudCamera::LoadBag | ( | const std::string & | path | ) |
Loads a bag file saved by rapid_perception's save_cloud.
This method can be called multiple times. Whatever cloud was saved will be returned in the next call to cloud(), and the same with camera_pose().
If there is more than one message on either topic, only the first will be loaded.
| [in] | path | The file path to the bag file saved by save_cloud. |