Transformation tools for sensor_msgs messages. More...
#include <string>
#include <unordered_map>
#include <geometry_msgs/Transform.h>
#include <geometry_msgs/TransformStamped.h>
#include <sensor_msgs/PointCloud2.h>
#include <tf2_ros/buffer.h>
Go to the source code of this file.
Namespaces | |
cras | |
Enumerations | |
enum | cras::CloudChannelType { cras::CloudChannelType::POINT, cras::CloudChannelType::DIRECTION, cras::CloudChannelType::SCALAR } |
Type of a pointcloud channel. More... | |
Functions | |
void | cras::registerCloudChannelType (const ::std::string &channelPrefix, ::cras::CloudChannelType type) |
Register the given pointcloud channel prefix with the given type. This registration will be used by transformWithChannels() when called without an explicit channel list. More... | |
void | cras::transformChannel (::sensor_msgs::PointCloud2 &cloud, const ::geometry_msgs::Transform &transform, const ::std::string &channelPrefix, ::cras::CloudChannelType type) |
Transform the given channel in the given cloud using the given transform. More... | |
::sensor_msgs::PointCloud2 & | cras::transformOnlyChannels (const ::sensor_msgs::PointCloud2 &in, ::sensor_msgs::PointCloud2 &out, const ::geometry_msgs::TransformStamped &tf, const ::std::unordered_map<::std::string, ::cras::CloudChannelType > &channels) |
Copy the selected channels from in cloud to out and transform them using the given transform. More... | |
::sensor_msgs::PointCloud2 & | cras::transformOnlyXYZ (const ::sensor_msgs::PointCloud2 &in, ::sensor_msgs::PointCloud2 &out, const ::geometry_msgs::TransformStamped &tf) |
Copy only the XYZ channel from in cloud to out and transform it using the given transform. More... | |
::sensor_msgs::PointCloud2 & | cras::transformWithChannels (const ::sensor_msgs::PointCloud2 &in, ::sensor_msgs::PointCloud2 &out, const ::geometry_msgs::TransformStamped &tf) |
Copy in cloud to out and transform channels using the given transform. The list of channels to be transformed consists of the XYZ channel, vp_, normal_ and all channels registered by registerCloudChannelType(). More... | |
::sensor_msgs::PointCloud2 & | cras::transformWithChannels (const ::sensor_msgs::PointCloud2 &in, ::sensor_msgs::PointCloud2 &out, const ::geometry_msgs::TransformStamped &tf, const ::std::unordered_map<::std::string, ::cras::CloudChannelType > &channels) |
Copy in cloud to out and transform channels using the given transform. Only the channels passed in channels will be transformed, according to their type. More... | |
::sensor_msgs::PointCloud2 & | cras::transformWithChannels (const ::sensor_msgs::PointCloud2 &in, ::sensor_msgs::PointCloud2 &out, const ::tf2_ros::Buffer &tfBuffer, const ::std::string &targetFrame) |
Copy in cloud to out and transform channels using the given transform. The list of channels to be transformed consists of the XYZ channel, vp_, normal_ and all channels registered by registerCloudChannelType(). More... | |
::sensor_msgs::PointCloud2 & | cras::transformWithChannels (const ::sensor_msgs::PointCloud2 &in, ::sensor_msgs::PointCloud2 &out, const ::tf2_ros::Buffer &tfBuffer, const ::std::string &targetFrame, const ::std::unordered_map<::std::string, ::cras::CloudChannelType > &channels) |
Copy in cloud to out and transform channels using the given transform. Only the channels passed in channels will be transformed, according to their type. More... | |
void | cras::unregisterCloudChannelType (const ::std::string &channelPrefix) |
Unregister a cloud channel type registered earlier with registerCloudChannelType(). More... | |
Transformation tools for sensor_msgs messages.
Definition in file tf2_sensor_msgs.h.