Program Listing for File transforms.hpp
↰ Return to documentation for file (/tmp/ws/src/perception_pcl/pcl_ros/include/pcl_ros/transforms.hpp
)
/*
* Software License Agreement (BSD License)
*
* Copyright (c) 2010, Willow Garage, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of Willow Garage, Inc. nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
*
*/
#ifndef PCL_ROS__TRANSFORMS_HPP_
#define PCL_ROS__TRANSFORMS_HPP_
#include <pcl/point_cloud.h>
#include <tf2/LinearMath/Transform.h>
#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_listener.h>
#include <Eigen/Core>
#include <string>
#include <rclcpp/time.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <geometry_msgs/msg/transform_stamped.hpp>
namespace pcl_ros
{
template<typename PointT>
void
transformPointCloudWithNormals(
const pcl::PointCloud<PointT> & cloud_in,
pcl::PointCloud<PointT> & cloud_out,
const tf2::Transform & transform);
template<typename PointT>
void
transformPointCloudWithNormals(
const pcl::PointCloud<PointT> & cloud_in,
pcl::PointCloud<PointT> & cloud_out,
const geometry_msgs::msg::TransformStamped & transform);
template<typename PointT>
bool
transformPointCloudWithNormals(
const std::string & target_frame,
const pcl::PointCloud<PointT> & cloud_in,
pcl::PointCloud<PointT> & cloud_out,
const tf2_ros::Buffer & tf_buffer);
template<typename PointT>
bool
transformPointCloudWithNormals(
const std::string & target_frame,
const rclcpp::Time & target_time,
const pcl::PointCloud<PointT> & cloud_in,
const std::string & fixed_frame,
pcl::PointCloud<PointT> & cloud_out,
const tf2_ros::Buffer & tf_buffer);
template<typename PointT>
void
transformPointCloud(
const pcl::PointCloud<PointT> & cloud_in,
pcl::PointCloud<PointT> & cloud_out,
const tf2::Transform & transform);
template<typename PointT>
void
transformPointCloud(
const pcl::PointCloud<PointT> & cloud_in,
pcl::PointCloud<PointT> & cloud_out,
const geometry_msgs::msg::TransformStamped & transform);
template<typename PointT>
bool
transformPointCloud(
const std::string & target_frame,
const pcl::PointCloud<PointT> & cloud_in,
pcl::PointCloud<PointT> & cloud_out,
const tf2_ros::Buffer & tf_buffer);
template<typename PointT>
bool
transformPointCloud(
const std::string & target_frame,
const rclcpp::Time & target_time,
const pcl::PointCloud<PointT> & cloud_in,
const std::string & fixed_frame,
pcl::PointCloud<PointT> & cloud_out,
const tf2_ros::Buffer & tf_buffer);
bool
transformPointCloud(
const std::string & target_frame,
const sensor_msgs::msg::PointCloud2 & in,
sensor_msgs::msg::PointCloud2 & out,
const tf2_ros::Buffer & tf_buffer);
void
transformPointCloud(
const std::string & target_frame,
const tf2::Transform & net_transform,
const sensor_msgs::msg::PointCloud2 & in,
sensor_msgs::msg::PointCloud2 & out);
void
transformPointCloud(
const std::string & target_frame,
const geometry_msgs::msg::TransformStamped & net_transform,
const sensor_msgs::msg::PointCloud2 & in,
sensor_msgs::msg::PointCloud2 & out);
void
transformPointCloud(
const Eigen::Matrix4f & transform,
const sensor_msgs::msg::PointCloud2 & in,
sensor_msgs::msg::PointCloud2 & out);
void
transformAsMatrix(const tf2::Transform & bt, Eigen::Matrix4f & out_mat);
void
transformAsMatrix(const geometry_msgs::msg::TransformStamped & bt, Eigen::Matrix4f & out_mat);
} // namespace pcl_ros
#endif // PCL_ROS__TRANSFORMS_HPP_