12 #include <unordered_map> 14 #include <geometry_msgs/Transform.h> 15 #include <geometry_msgs/TransformStamped.h> 16 #include <sensor_msgs/PointCloud2.h> 58 void transformChannel(::sensor_msgs::PointCloud2& cloud, const ::geometry_msgs::Transform& transform,
70 ::sensor_msgs::PointCloud2&
transformWithChannels(const ::sensor_msgs::PointCloud2& in, ::sensor_msgs::PointCloud2& out,
71 const ::geometry_msgs::TransformStamped& tf);
82 ::sensor_msgs::PointCloud2&
transformWithChannels(const ::sensor_msgs::PointCloud2& in, ::sensor_msgs::PointCloud2& out,
83 const ::geometry_msgs::TransformStamped& tf,
84 const ::std::unordered_map<::std::string, ::cras::CloudChannelType>& channels);
97 ::sensor_msgs::PointCloud2&
transformWithChannels(const ::sensor_msgs::PointCloud2& in, ::sensor_msgs::PointCloud2& out,
98 const ::tf2_ros::Buffer& tfBuffer, const ::std::string& targetFrame);
111 ::sensor_msgs::PointCloud2&
transformWithChannels(const ::sensor_msgs::PointCloud2& in, ::sensor_msgs::PointCloud2& out,
112 const ::tf2_ros::Buffer& tfBuffer, const ::std::string& targetFrame,
113 const ::std::unordered_map<::std::string, ::cras::CloudChannelType>& channels);
124 ::sensor_msgs::PointCloud2&
transformOnlyChannels(const ::sensor_msgs::PointCloud2& in, ::sensor_msgs::PointCloud2& out,
125 const ::geometry_msgs::TransformStamped& tf,
126 const ::std::unordered_map<::std::string, ::cras::CloudChannelType>& channels);
135 ::sensor_msgs::PointCloud2&
transformOnlyXYZ(const ::sensor_msgs::PointCloud2& in, ::sensor_msgs::PointCloud2& out,
136 const ::geometry_msgs::TransformStamped& tf);
void registerCloudChannelType(const ::std::string &channelPrefix, ::cras::CloudChannelType type)
Register the given pointcloud channel prefix with the given type. This registration will be used by t...
::sensor_msgs::PointCloud2 & 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...
A scalar value (not affected by transforms).
::sensor_msgs::PointCloud2 & 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 tra...
A 3D vector/direction (if transformed, only rotation is applied).
void unregisterCloudChannelType(const ::std::string &channelPrefix)
Unregister a cloud channel type registered earlier with registerCloudChannelType().
void 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.
::sensor_msgs::PointCloud2 & 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.
CloudChannelType
Type of a pointcloud channel.
A 3D point (if transformed, both translation and rotation is applied).