tf2_sensor_msgs.h
Go to the documentation of this file.
1 #pragma once
2 
11 #include <string>
12 #include <unordered_map>
13 
14 #include <geometry_msgs/Transform.h>
15 #include <geometry_msgs/TransformStamped.h>
16 #include <sensor_msgs/PointCloud2.h>
17 #include <tf2_ros/buffer.h>
18 
19 namespace cras
20 {
21 
25 enum class CloudChannelType
26 {
28  POINT,
29 
31  DIRECTION,
32 
34  SCALAR
35 };
36 
43 void registerCloudChannelType(const ::std::string& channelPrefix, ::cras::CloudChannelType type);
44 
49 void unregisterCloudChannelType(const ::std::string& channelPrefix);
50 
58 void transformChannel(::sensor_msgs::PointCloud2& cloud, const ::geometry_msgs::Transform& transform,
59  const ::std::string& channelPrefix, ::cras::CloudChannelType type);
60 
70 ::sensor_msgs::PointCloud2& transformWithChannels(const ::sensor_msgs::PointCloud2& in, ::sensor_msgs::PointCloud2& out,
71  const ::geometry_msgs::TransformStamped& tf);
72 
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);
85 
97 ::sensor_msgs::PointCloud2& transformWithChannels(const ::sensor_msgs::PointCloud2& in, ::sensor_msgs::PointCloud2& out,
98  const ::tf2_ros::Buffer& tfBuffer, const ::std::string& targetFrame);
99 
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);
114 
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);
127 
135 ::sensor_msgs::PointCloud2& transformOnlyXYZ(const ::sensor_msgs::PointCloud2& in, ::sensor_msgs::PointCloud2& out,
136  const ::geometry_msgs::TransformStamped& tf);
137 
138 }
cras::transformChannel
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.
cras
Definition: any.hpp:15
cras::CloudChannelType::POINT
@ POINT
A 3D point (if transformed, both translation and rotation is applied).
buffer.h
cras::CloudChannelType::DIRECTION
@ DIRECTION
A 3D vector/direction (if transformed, only rotation is applied).
cras::transformOnlyXYZ
::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.
cras::CloudChannelType::SCALAR
@ SCALAR
A scalar value (not affected by transforms).
cras::CloudChannelType
CloudChannelType
Type of a pointcloud channel.
Definition: tf2_sensor_msgs.h:25
cras::transformWithChannels
::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...
cras::registerCloudChannelType
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...
cras::transformOnlyChannels
::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.
cras::unregisterCloudChannelType
void unregisterCloudChannelType(const ::std::string &channelPrefix)
Unregister a cloud channel type registered earlier with registerCloudChannelType().


cras_cpp_common
Author(s): Martin Pecka
autogenerated on Sun Jan 14 2024 03:48:14