Demonstrates basic TF and PCL integrations for TsScan data. More...
#include <logging.h>
Public Member Functions | |
Logging (ros::NodeHandle nh, ros::NodeHandle private_nh) | |
void | save (const ros::TimerEvent &event) |
~Logging () | |
Static Public Member Functions | |
static void | logPointcloud () |
Private Member Functions | |
void | _accumulate (const XYZINCloud::ConstPtr &msg) |
Private Attributes | |
ros::Subscriber | cloud_sub_ |
std::string | pcd_path_ |
XYZINCloud::Ptr | store_ |
boost::mutex | store_mutex_ |
ros::Timer | timer_ |
Demonstrates basic TF and PCL integrations for TsScan data.
Subscribes to a topic publishing TsPoints and maintains an cummulative pointcloud structure of all points.
Maintains a persistent PointCloud structure holding the cumulative of all scans received during a run. This cumulative data is saved periodically as a PCD file in the package folder for subsequent use with other PCL tools (like pcl_octree_viewer).
toposens_pointcloud::Logging::Logging | ( | ros::NodeHandle | nh, |
ros::NodeHandle | private_nh | ||
) |
Subscribes to a #kCloudTopic and prepares a PointCloud structure for persistent storage.
nh | Public nodehandle for pub-sub ops on ROS topics. |
private_nh | Private nodehandle for accessing launch parameters. |
pcd_save_rate | defines save interval of cumulative pointcloud. |
If no file is specified as a launch argument, the default path "/home/$USER/.ros/toposens.pcd" is used to store the PCD.
Definition at line 5 of file logging.cpp.
toposens_pointcloud::Logging::~Logging | ( | ) |
Destructor frees memory from heap
Definition at line 29 of file logging.cpp.
|
private |
Waits for pointcloud updates to become available and accumulates them in a perisistent pointcloud structure.
Waits for a pointcloud updates to become available and accumulates them in a persistent pointcloud structure.
msg | Pointer to an incoming TsScan message. |
Definition at line 54 of file logging.cpp.
|
inlinestatic |
void toposens_pointcloud::Logging::save | ( | const ros::TimerEvent & | event | ) |
Saves all pointcloud data contained in #store as a PCD file whose path is specified by #pcd_path.
Filename is provided as a launch argument. File is saved as a .pcd.
event | TimerEvent, currently ignored. |
Definition at line 31 of file logging.cpp.
|
private |
|
private |
|
private |
|
private |
|
private |