Functions
PointMatcher_ros Namespace Reference

Functions

template<typename T >
sensor_msgs::PointCloud2 pointMatcherCloudToRosMsg (const typename PointMatcher< T >::DataPoints &pmCloud, const std::string &frame_id, const ros::Time &stamp)
template sensor_msgs::PointCloud2 pointMatcherCloudToRosMsg< double > (const PointMatcher< double >::DataPoints &pmCloud, const std::string &frame_id, const ros::Time &stamp)
template sensor_msgs::PointCloud2 pointMatcherCloudToRosMsg< float > (const PointMatcher< float >::DataPoints &pmCloud, const std::string &frame_id, const ros::Time &stamp)
template<typename T >
PointMatcher< T >::DataPoints rosMsgToPointMatcherCloud (const sensor_msgs::PointCloud2 &rosMsg)
 Transform a ROS PointCloud2 message into a libpointmatcher point cloud.
template<typename T >
PointMatcher< T >::DataPoints rosMsgToPointMatcherCloud (const sensor_msgs::LaserScan &rosMsg, const tf::TransformListener *listener=0, const std::string &fixed_frame="/world", const bool force3D=false, const bool addTimestamps=false)
template PointMatcher< double >
::DataPoints 
rosMsgToPointMatcherCloud< double > (const sensor_msgs::PointCloud2 &rosMsg)
template PointMatcher< double >
::DataPoints 
rosMsgToPointMatcherCloud< double > (const sensor_msgs::LaserScan &rosMsg, const tf::TransformListener *listener, const std::string &fixedFrame, const bool force3D, const bool addTimestamps)
template PointMatcher< float >
::DataPoints 
rosMsgToPointMatcherCloud< float > (const sensor_msgs::PointCloud2 &rosMsg)
template PointMatcher< float >
::DataPoints 
rosMsgToPointMatcherCloud< float > (const sensor_msgs::LaserScan &rosMsg, const tf::TransformListener *listener, const std::string &fixedFrame, const bool force3D, const bool addTimestamps)

Function Documentation

template<typename T >
sensor_msgs::PointCloud2 PointMatcher_ros::pointMatcherCloudToRosMsg ( const typename PointMatcher< T >::DataPoints &  pmCloud,
const std::string &  frame_id,
const ros::Time stamp 
)

Definition at line 328 of file point_cloud_conversions.cpp.

template sensor_msgs::PointCloud2 PointMatcher_ros::pointMatcherCloudToRosMsg< double > ( const PointMatcher< double >::DataPoints &  pmCloud,
const std::string &  frame_id,
const ros::Time stamp 
)
template sensor_msgs::PointCloud2 PointMatcher_ros::pointMatcherCloudToRosMsg< float > ( const PointMatcher< float >::DataPoints &  pmCloud,
const std::string &  frame_id,
const ros::Time stamp 
)
template<typename T >
PointMatcher< T >::DataPoints PointMatcher_ros::rosMsgToPointMatcherCloud ( const sensor_msgs::PointCloud2 &  rosMsg)

Transform a ROS PointCloud2 message into a libpointmatcher point cloud.

Definition at line 14 of file point_cloud_conversions.cpp.

template<typename T >
PointMatcher< T >::DataPoints PointMatcher_ros::rosMsgToPointMatcherCloud ( const sensor_msgs::LaserScan &  rosMsg,
const tf::TransformListener listener = 0,
const std::string &  fixed_frame = "/world",
const bool  force3D = false,
const bool  addTimestamps = false 
)

Definition at line 164 of file point_cloud_conversions.cpp.

template PointMatcher<double>::DataPoints PointMatcher_ros::rosMsgToPointMatcherCloud< double > ( const sensor_msgs::PointCloud2 &  rosMsg)
template PointMatcher<double>::DataPoints PointMatcher_ros::rosMsgToPointMatcherCloud< double > ( const sensor_msgs::LaserScan &  rosMsg,
const tf::TransformListener listener,
const std::string &  fixedFrame,
const bool  force3D,
const bool  addTimestamps 
)
template PointMatcher<float>::DataPoints PointMatcher_ros::rosMsgToPointMatcherCloud< float > ( const sensor_msgs::PointCloud2 &  rosMsg)
template PointMatcher<float>::DataPoints PointMatcher_ros::rosMsgToPointMatcherCloud< float > ( const sensor_msgs::LaserScan &  rosMsg,
const tf::TransformListener listener,
const std::string &  fixedFrame,
const bool  force3D,
const bool  addTimestamps 
)


shape_tracker
Author(s): Roberto Martín-Martín
autogenerated on Sat Jun 8 2019 18:54:11