Public Member Functions | Private Member Functions | Private Attributes | List of all members
toposens_pointcloud::TSPointCloudROS Class Reference

ROS interface for transforming the pointclouds. More...

#include <ts_pointcloud_ros.h>

Public Member Functions

 TSPointCloudROS (ros::NodeHandle nh, ros::NodeHandle private_nh)
 
 ~TSPointCloudROS ()
 

Private Member Functions

void cloudCallback (const toposens_msgs::TsScan::ConstPtr &msg)
 
void doTransform (geometry_msgs::TransformStamped transform, pcl::PointXYZINormal &pt, std_msgs::Header h)
 
void publishNormals (XYZINCloud::ConstPtr tc)
 

Private Attributes

ros::Publisher cloud_pub_
 
float lifetime_normals_vis_
 
boost::thread * log_thread_
 
visualization_msgs::Marker marker
 
int marker_id_ = 0
 
ros::Publisher marker_pub_
 
std::unique_ptr< MappingpointTransform_
 
ros::Subscriber scans_sub_
 
std::string scans_topic_
 
std::string target_frame_
 
tf2_ros::Buffer tf2_buffer_
 
tf2_ros::TransformListenertf2_listener_
 

Detailed Description

ROS interface for transforming the pointclouds.

Implements methods that set up publishers, subscribers and methods for using the Mapping library in a ROS framework.

Subscribes to a topic for receiving TsScans and converts incoming data into PointCloud messages using PCL, optionally mapped to another frame of reference. Visual behavior of the pointcloud (scale, color, direction, lifetime, etc) can be controlled via the PointCloud2 display in Rviz.

Each incoming scan is converted to a new PointCloud message of template XYZI, which corresponds well with a TsPoint structure. A second persistent PointCloud structure holds the cumulative of all scans received during a run. At the end of each run, this cumulative data is saved as a PCD file in the package folder for subsequent use with other PCL tools (like pcl_octree_viewer).

Prior to pointcloud conversion, each scan can also be optionally transformed to a different reference frame (usually, 'world' or 'base_link' frame). This can be used, for instance, to efficiently map an area using sensor or odometry data.

Definition at line 39 of file ts_pointcloud_ros.h.

Constructor & Destructor Documentation

◆ TSPointCloudROS()

toposens_pointcloud::TSPointCloudROS::TSPointCloudROS ( ros::NodeHandle  nh,
ros::NodeHandle  private_nh 
)

Initializes subscribers, publishers, transform object

Parameters
nhpublic nodehandle for publishers and subscribers
private_nhprivate nodehandle for dynamic reconfigure server

Definition at line 5 of file ts_pointcloud_ros.cpp.

◆ ~TSPointCloudROS()

toposens_pointcloud::TSPointCloudROS::~TSPointCloudROS ( )

Destructor frees memory from heap

Definition at line 40 of file ts_pointcloud_ros.cpp.

Member Function Documentation

◆ cloudCallback()

void toposens_pointcloud::TSPointCloudROS::cloudCallback ( const toposens_msgs::TsScan::ConstPtr &  msg)
private

Converts and broadcasts incoming scans as PointCloud messages. Maintains a local copy of all accumulated scans in their corresponding PointCloud form.

Waits for a target frame transform to become available and maps incoming TsPoints to this frame. Transformed points are added to a instantaneous pointcloud structure for publishing.

Parameters
msgPointer to an incoming TsScan message.

Convert to PCL

< Transform variable for processing.

Publish point cloud and normals, if activated

Definition at line 52 of file ts_pointcloud_ros.cpp.

◆ doTransform()

void toposens_pointcloud::TSPointCloudROS::doTransform ( geometry_msgs::TransformStamped  transform,
pcl::PointXYZINormal &  pt,
std_msgs::Header  h 
)
private

Maps a point to the reference frame defined in #target_frame.

Converts a PointXYZINormal to intermediate Vector Transformation variables. After transformation converts them back to a PointXYZINormal. Transformation is skipped if #target_frame is same as the pcl_point's current frame.

Parameters
transformStampedTransform from original frame to target frame.
pPointXYZINormal that is transformed to #target_frame.
hHeader data of TsScan the point originates from.

Definition at line 95 of file ts_pointcloud_ros.cpp.

◆ publishNormals()

void toposens_pointcloud::TSPointCloudROS::publishNormals ( XYZINCloud::ConstPtr  tc)
private

Publishes normals as markers for visualiation in RViz.

Publishes markers that contain arrows that visualize the normal vectors of points. Each arrow is defined by a starting point and an end point.

Parameters
tcThe point cloud whose normals are to be published.

Definition at line 127 of file ts_pointcloud_ros.cpp.

Member Data Documentation

◆ cloud_pub_

ros::Publisher toposens_pointcloud::TSPointCloudROS::cloud_pub_
private

Handler for publishing PCL messages.

Definition at line 91 of file ts_pointcloud_ros.h.

◆ lifetime_normals_vis_

float toposens_pointcloud::TSPointCloudROS::lifetime_normals_vis_
private

Lifetime for visualization of normals.

Definition at line 95 of file ts_pointcloud_ros.h.

◆ log_thread_

boost::thread* toposens_pointcloud::TSPointCloudROS::log_thread_
private

Accumulates pointcloud and periodically saves to file.

Definition at line 101 of file ts_pointcloud_ros.h.

◆ marker

visualization_msgs::Marker toposens_pointcloud::TSPointCloudROS::marker
private

Marker for the arrow(s) to be published.

Definition at line 105 of file ts_pointcloud_ros.h.

◆ marker_id_

int toposens_pointcloud::TSPointCloudROS::marker_id_ = 0
private

Id for publishing unique markers for normals.

Definition at line 96 of file ts_pointcloud_ros.h.

◆ marker_pub_

ros::Publisher toposens_pointcloud::TSPointCloudROS::marker_pub_
private

Handler for publishing marker messages.

Definition at line 93 of file ts_pointcloud_ros.h.

◆ pointTransform_

std::unique_ptr<Mapping> toposens_pointcloud::TSPointCloudROS::pointTransform_
private

Point Transform object to perform transformation

Definition at line 104 of file ts_pointcloud_ros.h.

◆ scans_sub_

ros::Subscriber toposens_pointcloud::TSPointCloudROS::scans_sub_
private

Handler for subscribing to TsScans.

Definition at line 92 of file ts_pointcloud_ros.h.

◆ scans_topic_

std::string toposens_pointcloud::TSPointCloudROS::scans_topic_
private

Topic name to look for TsScan messages.

Definition at line 88 of file ts_pointcloud_ros.h.

◆ target_frame_

std::string toposens_pointcloud::TSPointCloudROS::target_frame_
private

Target frame for scan transformations.

Definition at line 89 of file ts_pointcloud_ros.h.

◆ tf2_buffer_

tf2_ros::Buffer toposens_pointcloud::TSPointCloudROS::tf2_buffer_
private

Definition at line 98 of file ts_pointcloud_ros.h.

◆ tf2_listener_

tf2_ros::TransformListener* toposens_pointcloud::TSPointCloudROS::tf2_listener_
private

Listener for frame mapping.

Definition at line 99 of file ts_pointcloud_ros.h.


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


toposens_pointcloud
Author(s): Adi Singh, Sebastian Dengler, Christopher Lang, Inshal Uddin
autogenerated on Mon Feb 28 2022 23:57:49