rapid
A ROS robotics library.
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Pages
rapid::RecordedPointCloudCamera Class Reference

A simulated camera that loads data from a bag file. More...

#include <recorded_point_cloud_camera.h>

Inheritance diagram for rapid::RecordedPointCloudCamera:
rapid::PointCloudCameraInterface

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 ()
 

Detailed Description

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:

  • One sensor_msgs/PointCloud2 on the "/cloud" topic.
  • One geometry_msgs/TransformStamped on the "/camera_in_base" topic.

Usage:

sim_cam.LoadBag(argv[1]);
sim_cam.cloud();
sim_cam.LoadBag(argv[2]);
sim_cam.cloud();

Definition at line 24 of file recorded_point_cloud_camera.h.

Constructor & Destructor Documentation

rapid::RecordedPointCloudCamera::RecordedPointCloudCamera ( )

Member Function Documentation

geometry_msgs::TransformStamped rapid::RecordedPointCloudCamera::camera_pose ( ) const
virtual

Returns the camera pose relative to the base frame.

Returns
The transform describing the camera frame with respect to the base frame.

Implements rapid::PointCloudCameraInterface.

pcl::PointCloud<pcl::PointXYZRGB>::Ptr rapid::RecordedPointCloudCamera::cloud ( ) const
virtual

Returns the most recent point cloud from the camera.

Returns
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.

Parameters
[in]pathThe file path to the bag file saved by save_cloud.

The documentation for this class was generated from the following file: