Public Member Functions | Private Member Functions | Private Attributes
srs_ui_but::PointCloudTools Class Reference

This class gathers actual point cloud data and provides method which returns closest point from a specified link. More...

#include <point_cloud_tools.h>

List of all members.

Public Member Functions

srs_ui_but::ClosestPoint getClosestPoint (std::string link)
 This function calculates closest point from a robot link from latest point cloud.
std::string getPointCloudTopic ()
 This function gets the Point Cloud 2 topic.
 PointCloudTools ()
 Constructor.
void setPointCloudTopic (std::string topic)
 This function sets Point Cloud 2 topic to get closest points from it.
virtual ~PointCloudTools ()
 Destructor.

Private Member Functions

void incomingCloudCallback (const sensor_msgs::PointCloud2ConstPtr &cloud)
 Callback function for handling incoming point cloud data.

Private Attributes

srs_ui_but::ClosestPoint closestPoint
tf::StampedTransform linkToSensorTf
pcl::PointCloud< pcl::PointXYZpcl_pointCloud
message_filters::Subscriber
< sensor_msgs::PointCloud2 > 
point_cloud
ros::Time pointCloud_stamp
tf::StampedTransform sensorToLinkTf
tf::TransformListenertfListener
ros::NodeHandle threaded_nh_
std::string topic_
tf::MessageFilter
< sensor_msgs::PointCloud2 > * 
transform_filter
tf::Transformer transformer

Detailed Description

This class gathers actual point cloud data and provides method which returns closest point from a specified link.

Author:
Tomas Lokaj

Definition at line 57 of file point_cloud_tools.h.


Constructor & Destructor Documentation

Constructor.

Definition at line 36 of file point_cloud_tools.cpp.

virtual srs_ui_but::PointCloudTools::~PointCloudTools ( ) [inline, virtual]

Destructor.

Definition at line 67 of file point_cloud_tools.h.


Member Function Documentation

srs_ui_but::ClosestPoint srs_ui_but::PointCloudTools::getClosestPoint ( std::string  link)

This function calculates closest point from a robot link from latest point cloud.

Parameters:
linkis robot link from which we want to get the closest point

Definition at line 56 of file point_cloud_tools.cpp.

This function gets the Point Cloud 2 topic.

Returns:
point cloud topic

Definition at line 93 of file point_cloud_tools.h.

void srs_ui_but::PointCloudTools::incomingCloudCallback ( const sensor_msgs::PointCloud2ConstPtr &  cloud) [private]

Callback function for handling incoming point cloud data.

Parameters:
cloudis incoming point cloud

Definition at line 47 of file point_cloud_tools.cpp.

void srs_ui_but::PointCloudTools::setPointCloudTopic ( std::string  topic) [inline]

This function sets Point Cloud 2 topic to get closest points from it.

Parameters:
topicis Point Cloud 2 topic

Definition at line 81 of file point_cloud_tools.h.


Member Data Documentation

srs_ui_but::ClosestPoint srs_ui_but::PointCloudTools::closestPoint [private]

Definition at line 112 of file point_cloud_tools.h.

Definition at line 118 of file point_cloud_tools.h.

Definition at line 106 of file point_cloud_tools.h.

Definition at line 130 of file point_cloud_tools.h.

Definition at line 109 of file point_cloud_tools.h.

Definition at line 118 of file point_cloud_tools.h.

Definition at line 124 of file point_cloud_tools.h.

Definition at line 127 of file point_cloud_tools.h.

std::string srs_ui_but::PointCloudTools::topic_ [private]

Definition at line 133 of file point_cloud_tools.h.

Definition at line 121 of file point_cloud_tools.h.

Definition at line 115 of file point_cloud_tools.h.


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


srs_ui_but
Author(s): Vit Stancl (stancl@fit.vutbr.cz), Michal Spanel (spanel@fit.vutbr.cz), Tomas Lokaj
autogenerated on Mon Oct 6 2014 08:49:31