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);