Public Member Functions | Protected Attributes | Private Member Functions | Private Attributes | List of all members
laser_assembler::BaseAssembler< T > Class Template Referenceabstract

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

#include <base_assembler.h>

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. More...
 
virtual unsigned int GetPointsInScan (const T &scan)=0
 Returns the number of points in the current scan. More...
 
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. More...
 
 ~BaseAssembler ()
 

Protected Attributes

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

Private Member Functions

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

Private Attributes

ros::ServiceServer assemble_scans_server2_
 
ros::ServiceServer assemble_scans_server_
 
ros::ServiceServer build_cloud_server2_
 
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. More...
 
std::string fixed_frame_
 The frame to transform data into upon receipt. More...
 
unsigned int max_scans_
 The max number of scans to store in the scan history. More...
 
std::deque< sensor_msgs::PointCloud > scan_hist_
 Stores history of scans. More...
 
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. More...
 

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 92 of file base_assembler.h.

Constructor & Destructor Documentation

◆ BaseAssembler()

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

Definition at line 170 of file base_assembler.h.

◆ ~BaseAssembler()

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

Definition at line 253 of file base_assembler.h.

Member Function Documentation

◆ assembleScans()

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

Definition at line 305 of file base_assembler.h.

◆ assembleScans2()

template<class T >
bool laser_assembler::BaseAssembler< T >::assembleScans2 ( AssembleScans2::Request &  req,
AssembleScans2::Response &  resp 
)
private

Definition at line 391 of file base_assembler.h.

◆ buildCloud()

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

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

Definition at line 297 of file base_assembler.h.

◆ buildCloud2()

template<class T >
bool laser_assembler::BaseAssembler< T >::buildCloud2 ( AssembleScans2::Request &  req,
AssembleScans2::Response &  resp 
)
private

Definition at line 384 of file base_assembler.h.

◆ ConvertToCloud()

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_idThe name of the frame in which we want cloud_out to be in
scan_inThe scan that we want to convert
cloud_outThe result of transforming scan_in into a cloud in frame fixed_frame_id

◆ GetPointsInScan()

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
scanThe scan for for which we want to know the number of points
Returns
the number of points in scan

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

◆ msgCallback()

template<class T >
void laser_assembler::BaseAssembler< T >::msgCallback ( const boost::shared_ptr< const T > &  scan_ptr)
privatevirtual

Callback function for every time we receive a new scan.

Definition at line 262 of file base_assembler.h.

◆ start() [1/2]

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

Definition at line 239 of file base_assembler.h.

◆ start() [2/2]

template<class T >
void laser_assembler::BaseAssembler< T >::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.

Definition at line 225 of file base_assembler.h.

Member Data Documentation

◆ assemble_scans_server2_

template<class T >
ros::ServiceServer laser_assembler::BaseAssembler< T >::assemble_scans_server2_
private

Definition at line 169 of file base_assembler.h.

◆ assemble_scans_server_

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

Definition at line 167 of file base_assembler.h.

◆ build_cloud_server2_

template<class T >
ros::ServiceServer laser_assembler::BaseAssembler< T >::build_cloud_server2_
private

Definition at line 168 of file base_assembler.h.

◆ build_cloud_server_

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

Definition at line 166 of file base_assembler.h.

◆ downsample_factor_

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 197 of file base_assembler.h.

◆ fixed_frame_

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

The frame to transform data into upon receipt.

Definition at line 194 of file base_assembler.h.

◆ max_scans_

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 191 of file base_assembler.h.

◆ n_

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

Definition at line 162 of file base_assembler.h.

◆ private_ns_

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

Definition at line 161 of file base_assembler.h.

◆ scan_hist_

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

Stores history of scans.

Definition at line 184 of file base_assembler.h.

◆ scan_hist_mutex_

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

Definition at line 185 of file base_assembler.h.

◆ scan_sub_

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

Definition at line 170 of file base_assembler.h.

◆ tf_

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

Definition at line 158 of file base_assembler.h.

◆ tf_filter_

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

Definition at line 159 of file base_assembler.h.

◆ tf_filter_connection_

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

Definition at line 171 of file base_assembler.h.

◆ total_pts_

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

The number points currently in the scan history.

Definition at line 188 of file base_assembler.h.


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


laser_assembler
Author(s): Vijay Pradeep
autogenerated on Sat Aug 10 2024 02:10:39