pointcloud_relative_from_pose_stamped_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2015, 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 #define BOOST_PARAMETER_MAX_ARITY 7
37 
42 #include <pcl/common/transforms.h>
43 
44 namespace jsk_pcl_ros_utils
45 {
47  {
48  DiagnosticNodelet::onInit();
49  pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output", 1);
50  pnh_->param<bool>("approximate_sync", approximate_sync_, false);
52  }
53 
55  {
56  sub_cloud_.subscribe(*pnh_, "input", 1);
57  sub_pose_.subscribe(*pnh_, "input/pose", 1);
58  if (approximate_sync_) {
59  async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> >(100);
60  async_->connectInput(sub_cloud_, sub_pose_);
61  async_->registerCallback(boost::bind(&PointCloudRelativeFromPoseStamped::transform, this, _1, _2));
62  } else {
63  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
64  sync_->connectInput(sub_cloud_, sub_pose_);
65  sync_->registerCallback(boost::bind(&PointCloudRelativeFromPoseStamped::transform, this, _1, _2));
66  }
67  }
68 
70  {
73  }
74 
75  void PointCloudRelativeFromPoseStamped::transform(const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
76  const geometry_msgs::PoseStamped::ConstPtr& pose_msg)
77  {
78  vital_checker_->poke();
79  if (!jsk_recognition_utils::isSameFrameId(cloud_msg->header.frame_id,
80  pose_msg->header.frame_id)) {
81  NODELET_ERROR("frame_id does not match. cloud: %s, pose: %s",
82  cloud_msg->header.frame_id.c_str(),
83  pose_msg->header.frame_id.c_str());
84  return;
85  }
86  Eigen::Affine3f transform;
87  tf::poseMsgToEigen(pose_msg->pose, transform);
88  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);
89  pcl::PointCloud<pcl::PointXYZ>::Ptr transformed_cloud (new pcl::PointCloud<pcl::PointXYZ>);
90  pcl::fromROSMsg(*cloud_msg, *cloud);
91  Eigen::Affine3f inverse_transform = transform.inverse();
92  pcl::transformPointCloud(*cloud, *transformed_cloud, inverse_transform);
93  sensor_msgs::PointCloud2 ros_cloud;
94  pcl::toROSMsg(*transformed_cloud, ros_cloud);
95  ros_cloud.header = cloud_msg->header;
96  pub_.publish(ros_cloud);
97  }
98 }
99 
#define NODELET_ERROR(...)
virtual void transform(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const geometry_msgs::PoseStamped::ConstPtr &pose_msg)
void publish(const boost::shared_ptr< M > &message) const
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
message_filters::Subscriber< geometry_msgs::PoseStamped > sub_pose_
boost::shared_ptr< ros::NodeHandle > pnh_
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
jsk_topic_tools::VitalChecker::Ptr vital_checker_
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
bool isSameFrameId(const std::string &a, const std::string &b)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::PointCloudRelativeFromPoseStamped, nodelet::Nodelet)


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