transform_pointcloud_in_bounding_box.h
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2014, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/o2r other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 
37 #ifndef JSK_PCL_ROS_UTILS_TRANSFORM_POINTCLOUD_IN_BOUNDING_BOX_H_
38 #define JSK_PCL_ROS_UTILS_TRANSFORM_POINTCLOUD_IN_BOUNDING_BOX_H_
39 
40 #include <pcl_ros/pcl_nodelet.h>
41 #include <jsk_recognition_msgs/BoundingBox.h>
48 #include <pcl/common/transforms.h>
49 
50 namespace jsk_pcl_ros_utils
51 {
52  template <class PointT>
54  const jsk_recognition_msgs::BoundingBox& box_msg,
55  const sensor_msgs::PointCloud2& cloud_msg,
56  pcl::PointCloud<PointT>& output,
57  Eigen::Affine3f& offset,
58  tf::TransformListener& tf_listener)
59  {
60  geometry_msgs::PoseStamped box_pose;
61  box_pose.header = box_msg.header;
62  box_pose.pose = box_msg.pose;
63  // transform box_pose into msg frame
64  geometry_msgs::PoseStamped box_pose_respected_to_cloud;
65  tf_listener.transformPose(cloud_msg.header.frame_id,
66  box_pose,
67  box_pose_respected_to_cloud);
68  // convert the pose into eigen
69  Eigen::Affine3d box_pose_respected_to_cloud_eigend;
70  tf::poseMsgToEigen(box_pose_respected_to_cloud.pose,
71  box_pose_respected_to_cloud_eigend);
72  Eigen::Affine3d box_pose_respected_to_cloud_eigend_inversed
73  = box_pose_respected_to_cloud_eigend.inverse();
74  Eigen::Matrix4f box_pose_respected_to_cloud_eigen_inversed_matrixf;
75  Eigen::Matrix4d box_pose_respected_to_cloud_eigen_inversed_matrixd
76  = box_pose_respected_to_cloud_eigend_inversed.matrix();
77  jsk_recognition_utils::convertMatrix4<Eigen::Matrix4d, Eigen::Matrix4f>(
78  box_pose_respected_to_cloud_eigen_inversed_matrixd,
79  box_pose_respected_to_cloud_eigen_inversed_matrixf);
80  offset = Eigen::Affine3f(box_pose_respected_to_cloud_eigen_inversed_matrixf);
81  pcl::PointCloud<PointT> input;
82  pcl::fromROSMsg(cloud_msg, input);
83  pcl::transformPointCloud(input, output, offset);
84  }
85 
87  {
88  public:
89  typedef pcl::PointXYZRGB PointT;
91  sensor_msgs::PointCloud2,
92  jsk_recognition_msgs::BoundingBox > SyncPolicy;
93  protected:
95  // methods
97  virtual void onInit();
98  virtual void transform(const sensor_msgs::PointCloud2::ConstPtr& msg,
99  const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg);
100 
102  // ROS variables
110  private:
111 
112  };
113 }
114 
115 #endif
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
virtual void transform(const sensor_msgs::PointCloud2::ConstPtr &msg, const jsk_recognition_msgs::BoundingBox::ConstPtr &box_msg)
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
void transformPointcloudInBoundingBox(const jsk_recognition_msgs::BoundingBox &box_msg, const sensor_msgs::PointCloud2 &cloud_msg, pcl::PointCloud< PointT > &output, Eigen::Affine3f &offset, tf::TransformListener &tf_listener)
void transformPose(const std::string &target_frame, const geometry_msgs::PoseStamped &stamped_in, geometry_msgs::PoseStamped &stamped_out) const
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::BoundingBox > SyncPolicy
message_filters::Subscriber< jsk_recognition_msgs::BoundingBox > sub_box_


jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:15