laser_assembler::BaseAssembler< T > Class Template Reference

Maintains a history of point clouds and generates an aggregate point cloud upon request. More...

#include <base_assembler.h>

List of all members.

Public Member Functions

 BaseAssembler (const std::string &max_size_param_name)
virtual void ConvertToCloud (const std::string &fixed_frame_id, const T &scan_in, sensor_msgs::PointCloud &cloud_out)=0
 Converts the current scan into a cloud in the specified fixed frame.
virtual unsigned int GetPointsInScan (const T &scan)=0
 Returns the number of points in the current scan.
void start ()
void start (const std::string &in_topic_name)
 Tells the assembler to start listening to input data It is possible that a derived class needs to initialize and configure various things before actually beginning to process scans. Calling start create subcribes to the input stream, thus allowing the scanCallback and ConvertToCloud to be called. Start should be called only once.
 ~BaseAssembler ()

Protected Attributes

ros::NodeHandle n_
ros::NodeHandle private_ns_
tf::TransformListener * tf_
tf::MessageFilter< T > * tf_filter_

Private Member Functions

bool assembleScans (AssembleScans::Request &req, AssembleScans::Response &resp)
bool buildCloud (AssembleScans::Request &req, AssembleScans::Response &resp)
 Service Callback function called whenever we need to build a cloud.
virtual void msgCallback (const boost::shared_ptr< const T > &scan_ptr)
 Callback function for every time we receive a new scan.

Private Attributes

ros::ServiceServer assemble_scans_server_
ros::ServiceServer build_cloud_server_
unsigned int downsample_factor_
 Specify how much to downsample the data. A value of 1 preserves all the data. 3 would keep 1/3 of the data.
std::string fixed_frame_
 The frame to transform data into upon receipt.
unsigned int max_scans_
 The max number of scans to store in the scan history.
std::deque
< sensor_msgs::PointCloud > 
scan_hist_
 Stores history of scans.
boost::mutex scan_hist_mutex_
message_filters::Subscriber< T > scan_sub_
message_filters::Connection tf_filter_connection_
unsigned int total_pts_
 The number points currently in the scan history.

Detailed Description

template<class T>
class laser_assembler::BaseAssembler< T >

Maintains a history of point clouds and generates an aggregate point cloud upon request.

Definition at line 48 of file base_assembler.h.


Constructor & Destructor Documentation

template<class T >
laser_assembler::BaseAssembler< T >::BaseAssembler ( const std::string &  max_size_param_name  )  [inline]

Definition at line 123 of file base_assembler.h.

template<class T >
laser_assembler::BaseAssembler< T >::~BaseAssembler (  )  [inline]

Definition at line 204 of file base_assembler.h.


Member Function Documentation

template<class T >
bool laser_assembler::BaseAssembler< T >::assembleScans ( AssembleScans::Request req,
AssembleScans::Response resp 
) [inline, private]

Definition at line 256 of file base_assembler.h.

template<class T >
bool laser_assembler::BaseAssembler< T >::buildCloud ( AssembleScans::Request req,
AssembleScans::Response resp 
) [inline, private]

Service Callback function called whenever we need to build a cloud.

Definition at line 248 of file base_assembler.h.

template<class T>
virtual void laser_assembler::BaseAssembler< T >::ConvertToCloud ( const std::string &  fixed_frame_id,
const T &  scan_in,
sensor_msgs::PointCloud &  cloud_out 
) [pure virtual]

Converts the current scan into a cloud in the specified fixed frame.

Note: Once implemented, ConvertToCloud should NOT catch TF exceptions. These exceptions are caught by BaseAssembler, and will be counted for diagnostic information

Parameters:
fixed_frame_id The name of the frame in which we want cloud_out to be in
scan_in The scan that we want to convert
cloud_out The result of transforming scan_in into a cloud in frame fixed_frame_id
template<class T>
virtual unsigned int laser_assembler::BaseAssembler< T >::GetPointsInScan ( const T &  scan  )  [pure virtual]

Returns the number of points in the current scan.

Parameters:
scan The scan for for which we want to know the number of points
Returns:
the number of points in scan

Implemented in laser_assembler::LaserScanAssembler, and laser_assembler::PointCloudAssembler.

template<class T>
void laser_assembler::BaseAssembler< T >::msgCallback ( const boost::shared_ptr< const T > &  scan_ptr  )  [inline, private, virtual]

Callback function for every time we receive a new scan.

Definition at line 213 of file base_assembler.h.

template<class T >
void laser_assembler::BaseAssembler< T >::start (  )  [inline]

Definition at line 190 of file base_assembler.h.

template<class T >
void laser_assembler::BaseAssembler< T >::start ( const std::string &  in_topic_name  )  [inline]

Tells the assembler to start listening to input data It is possible that a derived class needs to initialize and configure various things before actually beginning to process scans. Calling start create subcribes to the input stream, thus allowing the scanCallback and ConvertToCloud to be called. Start should be called only once.

Definition at line 176 of file base_assembler.h.


Member Data Documentation

template<class T>
ros::ServiceServer laser_assembler::BaseAssembler< T >::assemble_scans_server_ [private]

Definition at line 84 of file base_assembler.h.

template<class T>
ros::ServiceServer laser_assembler::BaseAssembler< T >::build_cloud_server_ [private]

Definition at line 83 of file base_assembler.h.

template<class T>
unsigned int laser_assembler::BaseAssembler< T >::downsample_factor_ [private]

Specify how much to downsample the data. A value of 1 preserves all the data. 3 would keep 1/3 of the data.

Definition at line 111 of file base_assembler.h.

template<class T>
std::string laser_assembler::BaseAssembler< T >::fixed_frame_ [private]

The frame to transform data into upon receipt.

Definition at line 108 of file base_assembler.h.

template<class T>
unsigned int laser_assembler::BaseAssembler< T >::max_scans_ [private]

The max number of scans to store in the scan history.

Definition at line 105 of file base_assembler.h.

template<class T>
ros::NodeHandle laser_assembler::BaseAssembler< T >::n_ [protected]

Definition at line 79 of file base_assembler.h.

template<class T>
ros::NodeHandle laser_assembler::BaseAssembler< T >::private_ns_ [protected]

Definition at line 78 of file base_assembler.h.

template<class T>
std::deque<sensor_msgs::PointCloud> laser_assembler::BaseAssembler< T >::scan_hist_ [private]

Stores history of scans.

Definition at line 98 of file base_assembler.h.

template<class T>
boost::mutex laser_assembler::BaseAssembler< T >::scan_hist_mutex_ [private]

Definition at line 99 of file base_assembler.h.

template<class T>
message_filters::Subscriber<T> laser_assembler::BaseAssembler< T >::scan_sub_ [private]

Definition at line 85 of file base_assembler.h.

template<class T>
tf::TransformListener* laser_assembler::BaseAssembler< T >::tf_ [protected]

Definition at line 75 of file base_assembler.h.

template<class T>
tf::MessageFilter<T>* laser_assembler::BaseAssembler< T >::tf_filter_ [protected]

Definition at line 76 of file base_assembler.h.

template<class T>
message_filters::Connection laser_assembler::BaseAssembler< T >::tf_filter_connection_ [private]

Definition at line 86 of file base_assembler.h.

template<class T>
unsigned int laser_assembler::BaseAssembler< T >::total_pts_ [private]

The number points currently in the scan history.

Definition at line 102 of file base_assembler.h.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs


laser_assembler
Author(s): Vijay Pradeep
autogenerated on Fri Jan 11 09:32:17 2013