Public Member Functions | Private Attributes
surface_perception::SurfaceHistoryRecorder Class Reference

SurfaceHistoryRecorder records information of time, iteration and history of each surface. More...

#include <surface_history_recorder.h>

List of all members.

Public Member Functions

void GetClock (size_t id, clock_t *clock_ptr) const
 Output the latest clock when the surface is found.
void GetCloudHistory (size_t id, pcl::PointCloud< pcl::PointXYZRGB >::Ptr output_cloud) const
 Output the point cloud history of a surface.
void GetIteration (size_t id, size_t *iteration_ptr) const
 Output the latest iteration number when the surface is found.
void Record (size_t id, const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::PointIndices::Ptr &indices, size_t iteration)
 Record the surface data when the surface is seen in the first time.
void Update (size_t old_id, size_t new_id, const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::PointIndices::Ptr &indices, size_t iteration)
 Update the existing surface data stored in this instance.

Private Attributes

std::map< size_t,
pcl::PointCloud
< pcl::PointXYZRGB >::Ptr > 
cloud_history_
std::map< size_t, size_t > iteration_history_
std::map< size_t, clock_t > time_history_

Detailed Description

SurfaceHistoryRecorder records information of time, iteration and history of each surface.

This class designed for SurfaceFinder in order to record the performance of the algorithm. In particular, SurfaceHistoryRecorder tracks clock info, the latest iteration and the concatenated point cloud that represents the evolution of a surface.

Example usage:

  SurfaceHistoryRecorder recorder;

  pcl::PointIndices::Ptr indices(new pcl::PointIndices);
  ...Find some surface and fill indices...
  recorder.Record(indices->indices.size(), input_cloud, indices,
                  iteration_number)

  pcl::PointIndices::Ptr new_indices(new pcl::PointIndices);
  ...Find another surface and fill new_indices...
  if (surface is already seen) {
    recorder.Update(indices->indices.size(), new_indices->indices.size(),
                    input_cloud, new_indices,
                    iteration_number);
  } else {
    recorder.Record(...)
  }

  ...

  // Get the recorded result for surface i
  pcl::PointCloud<pcl::PointXYZRGB>::Ptr surface_history(
      new pcl::PointCloud<pcl::PointXYZRGB>);
  clock_t current_clock;
  size_t latest_iteration;
  recorder.GetCloudHistory(indices_of_surface_i->indices.size(),
                           surface_history);
  recorder.GetClock(indices_of_surface_i->indices.size(), &current_clock);
  recorder.GetIteration(indices_of_surface_i->indices.size(),
                        &last_iteration);

Definition at line 52 of file surface_history_recorder.h.


Member Function Documentation

void surface_perception::SurfaceHistoryRecorder::GetClock ( size_t  id,
clock_t *  clock_ptr 
) const

Output the latest clock when the surface is found.

The clock indicates the system clock when the algorithm finds the surface. The resultant clock info is expected to be used to calculate time spent on finding a surface.

Parameters:
[in]idThe identification number of the surface.
[out]clock_ptrThe pointer to the recorded clock_t value.

Definition at line 57 of file surface_history_recorder.cpp.

void surface_perception::SurfaceHistoryRecorder::GetCloudHistory ( size_t  id,
pcl::PointCloud< pcl::PointXYZRGB >::Ptr  output_cloud 
) const

Output the point cloud history of a surface.

The point cloud history, or the evolution of surface, is defined as the concatenation of past and resent points for a surface.

Parameters:
[in]idThe identification number of the surface.
[out]output_cloudThe concatenated point cloud history as output.

Definition at line 48 of file surface_history_recorder.cpp.

void surface_perception::SurfaceHistoryRecorder::GetIteration ( size_t  id,
size_t *  iteration_ptr 
) const

Output the latest iteration number when the surface is found.

Parameters:
[in]idThe identification number of the surface.
[out]iteration_ptrThe pointer to the recorded iteration number.

Definition at line 64 of file surface_history_recorder.cpp.

void surface_perception::SurfaceHistoryRecorder::Record ( size_t  id,
const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &  cloud,
const pcl::PointIndices::Ptr &  indices,
size_t  iteration 
)

Record the surface data when the surface is seen in the first time.

This function records the data for the surface not stored in this instance. If the surface is already seen, please use Update(...).

Parameters:
[in]idThe identification number of data. In SurfaceFinder, the id is the number of points in the surface.
[in]cloudThe input cloud of SurfaceFinder.
[in]indicesThe indices of the surface found.
[in]iterationThe iteration number when this surface is found.

Definition at line 16 of file surface_history_recorder.cpp.

void surface_perception::SurfaceHistoryRecorder::Update ( size_t  old_id,
size_t  new_id,
const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &  cloud,
const pcl::PointIndices::Ptr &  indices,
size_t  iteration 
)

Update the existing surface data stored in this instance.

This function updates the surface data for a surface that the algorithm has already seen. If the surface found is not seen before, please use Record(...), because the id of a surface may change over time.

Parameters:
[in]old_idThe old identification number of the surface.
[in]new_idThe new identification number of the surface.
[in]cloudThe input point cloud of SurfaceFinder.
[in]indicesThe indices of the surface found.
[in]iterationThe iteration number when the surface is found.

Definition at line 22 of file surface_history_recorder.cpp.


Member Data Documentation

std::map<size_t, pcl::PointCloud<pcl::PointXYZRGB>::Ptr> surface_perception::SurfaceHistoryRecorder::cloud_history_ [private]

Definition at line 110 of file surface_history_recorder.h.

Definition at line 112 of file surface_history_recorder.h.

std::map<size_t, clock_t> surface_perception::SurfaceHistoryRecorder::time_history_ [private]

Definition at line 111 of file surface_history_recorder.h.


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


surface_perception
Author(s): Yu-Tang Peng
autogenerated on Thu Jun 6 2019 17:36:21