Maintains a history of point clouds and generates an aggregate point cloud upon request. More...
#include <base_assembler_srv.h>
Public Member Functions | |
BaseAssemblerSrv () | |
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 () |
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... | |
~BaseAssemblerSrv () | |
Protected Attributes | |
ros::NodeHandle | n_ |
ros::NodeHandle | private_ns_ |
tf::TransformListener * | tf_ |
Private Member Functions | |
bool | buildCloud (AssembleScans::Request &req, AssembleScans::Response &resp) |
Service Callback function called whenever we need to build a cloud. More... | |
void | scansCallback (const boost::shared_ptr< const T > &scan_ptr) |
Callback function for every time we receive a new scan. More... | |
Private Attributes | |
ros::ServiceServer | cloud_srv_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_ |
tf::MessageFilter< T > * | tf_filter_ |
message_filters::Connection | tf_filter_connection_ |
double | tf_tolerance_secs_ |
How long we should wait before processing the input data. Very useful for laser scans. More... | |
unsigned int | total_pts_ |
The number points currently in the scan history. More... | |
Maintains a history of point clouds and generates an aggregate point cloud upon request.
Reads the following parameters from the parameter server
Definition at line 104 of file base_assembler_srv.h.
laser_assembler::BaseAssemblerSrv< T >::BaseAssemblerSrv |
Definition at line 179 of file base_assembler_srv.h.
laser_assembler::BaseAssemblerSrv< T >::~BaseAssemblerSrv |
Definition at line 251 of file base_assembler_srv.h.
|
private |
Service Callback function called whenever we need to build a cloud.
Definition at line 293 of file base_assembler_srv.h.
|
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 BaseAssemblerSrv, and will be counted for diagnostic information
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 |
|
pure virtual |
Returns the number of points in the current scan.
scan | The scan for for which we want to know the number of points |
Implemented in laser_assembler::PointCloudAssemblerSrv, and laser_assembler::LaserScanAssemblerSrv.
|
private |
Callback function for every time we receive a new scan.
Definition at line 260 of file base_assembler_srv.h.
void laser_assembler::BaseAssemblerSrv< T >::start |
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 236 of file base_assembler_srv.h.
|
private |
Definition at line 176 of file base_assembler_srv.h.
|
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 206 of file base_assembler_srv.h.
|
private |
The frame to transform data into upon receipt.
Definition at line 200 of file base_assembler_srv.h.
|
private |
The max number of scans to store in the scan history.
Definition at line 197 of file base_assembler_srv.h.
|
protected |
Definition at line 172 of file base_assembler_srv.h.
|
protected |
Definition at line 171 of file base_assembler_srv.h.
|
private |
Stores history of scans.
Definition at line 190 of file base_assembler_srv.h.
|
private |
Definition at line 191 of file base_assembler_srv.h.
|
private |
Definition at line 177 of file base_assembler_srv.h.
|
protected |
Definition at line 169 of file base_assembler_srv.h.
|
private |
Definition at line 178 of file base_assembler_srv.h.
|
private |
Definition at line 179 of file base_assembler_srv.h.
|
private |
How long we should wait before processing the input data. Very useful for laser scans.
Definition at line 203 of file base_assembler_srv.h.
|
private |
The number points currently in the scan history.
Definition at line 194 of file base_assembler_srv.h.