Public Member Functions | Private Member Functions | Private Attributes
rc::CloudAccumulator Class Reference

Demonstration for how to create a registered point cloud map using the rc_visard. More...

#include <cloud_accumulator.h>

List of all members.

Public Member Functions

 CloudAccumulator (double voxelgrid_size_display, double voxelgrid_size_save, double min_distance, double max_distance, std::string output_filename, bool keep_high_res, bool start_paused)
void pointCloudCallback (const pointcloud_t::ConstPtr &pointcloud)
 For each cloud.
void poseCallback (const geometry_msgs::PoseStampedConstPtr &current_pose)
 Saves camera pose.
pointcloud_t::Ptr rebuildCloud ()
 For all saved clouds.
bool saveCloud (std_srvs::Empty::Request &req, std_srvs::Empty::Request &resp)
bool togglePause (std_srvs::Empty::Request &req, std_srvs::Empty::Request &resp)
 Toggle whether to ignore incoming data.
void trajectoryCallback (const nav_msgs::PathConstPtr &path)
 Replace all saved camera poses by those in path.

Private Member Functions

Eigen::Affine3f lookupTransform (double timestamp)

Private Attributes

std::deque< pointcloud_t::Ptr > clouds_
 Storage for later corraection and saving.
pointcloud_t::Ptr display_cloud_
 Cloud that is displayed.
boost::mutex display_cloud_mutex_
bool keep_high_res_
 If false, do not store clouds. On save, save display cloud.
ros::Time last_pose_stamp_
double max_distance_
 Discard points farther than this.
double min_distance_
 Discard points closer than this.
size_t num_poses_
 Keep track of pose count (to show a good error message)
std::string output_filename_
 Where to save the cloud.
bool pause_
 Whether to ignore input data.
tf2_ros::Buffer tf_buffer_
 Stores the history of poses and allows to interpolate.
boost::mutex tf_buffer_mutex_
CloudVisualizer viewer_
boost::thread viewer_thread_
double voxelgrid_size_display_
 Filter size for the display cloud.
double voxelgrid_size_save_
 Filter size for the saved cloud.

Detailed Description

Demonstration for how to create a registered point cloud map using the rc_visard.

Definition at line 24 of file cloud_accumulator.h.


Constructor & Destructor Documentation

rc::CloudAccumulator::CloudAccumulator ( double  voxelgrid_size_display,
double  voxelgrid_size_save,
double  min_distance,
double  max_distance,
std::string  output_filename,
bool  keep_high_res,
bool  start_paused 
)

Definition at line 78 of file cloud_accumulator.cc.


Member Function Documentation

Eigen::Affine3f rc::CloudAccumulator::lookupTransform ( double  timestamp) [private]

Definition at line 168 of file cloud_accumulator.cc.

void rc::CloudAccumulator::pointCloudCallback ( const pointcloud_t::ConstPtr &  pointcloud)

For each cloud.

  • Filter by distance along the optical axis
  • Store filtered cloud for later saving (if keep_high_res_)
  • Transform to world coordinates according to live pose
  • Merge with previous clouds
  • Apply "display" voxel grid filter on merged cloud
  • Update viewer with the result

Definition at line 105 of file cloud_accumulator.cc.

void rc::CloudAccumulator::poseCallback ( const geometry_msgs::PoseStampedConstPtr &  current_pose)

Saves camera pose.

Definition at line 157 of file cloud_accumulator.cc.

pointcloud_t::Ptr rc::CloudAccumulator::rebuildCloud ( )

For all saved clouds.

  • Merge
  • Voxel-grid filter
  • Display

Definition at line 199 of file cloud_accumulator.cc.

bool rc::CloudAccumulator::saveCloud ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Request &  resp 
)
  • rebuild cloud (if keep_high_res is set) and update viewer
  • Save as .pcd to disk

Definition at line 227 of file cloud_accumulator.cc.

bool rc::CloudAccumulator::togglePause ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Request &  resp 
)

Toggle whether to ignore incoming data.

Definition at line 247 of file cloud_accumulator.cc.

void rc::CloudAccumulator::trajectoryCallback ( const nav_msgs::PathConstPtr &  path)

Replace all saved camera poses by those in path.

Definition at line 143 of file cloud_accumulator.cc.


Member Data Documentation

std::deque<pointcloud_t::Ptr> rc::CloudAccumulator::clouds_ [private]

Storage for later corraection and saving.

Definition at line 74 of file cloud_accumulator.h.

pointcloud_t::Ptr rc::CloudAccumulator::display_cloud_ [private]

Cloud that is displayed.

Definition at line 79 of file cloud_accumulator.h.

Definition at line 78 of file cloud_accumulator.h.

If false, do not store clouds. On save, save display cloud.

Definition at line 85 of file cloud_accumulator.h.

Definition at line 89 of file cloud_accumulator.h.

Discard points farther than this.

Definition at line 83 of file cloud_accumulator.h.

Discard points closer than this.

Definition at line 82 of file cloud_accumulator.h.

Keep track of pose count (to show a good error message)

Definition at line 77 of file cloud_accumulator.h.

Where to save the cloud.

Definition at line 84 of file cloud_accumulator.h.

Whether to ignore input data.

Definition at line 86 of file cloud_accumulator.h.

Stores the history of poses and allows to interpolate.

Definition at line 76 of file cloud_accumulator.h.

Definition at line 75 of file cloud_accumulator.h.

Definition at line 87 of file cloud_accumulator.h.

boost::thread rc::CloudAccumulator::viewer_thread_ [private]

Definition at line 88 of file cloud_accumulator.h.

Filter size for the display cloud.

Definition at line 80 of file cloud_accumulator.h.

Filter size for the saved cloud.

Definition at line 81 of file cloud_accumulator.h.


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


rc_cloud_accumulator
Author(s): Felix Endres
autogenerated on Thu Jun 6 2019 19:56:20