tf_transform_cloud_nodelet.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, Yuto Inagaki and JSK Lab
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/o2r other materials provided
16  * with the distribution.
17  * * Neither the name of the JSK Lab nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 
38 
39 #include <tf2_ros/buffer_client.h>
40 #include <pcl/common/centroid.h>
41 
42 namespace jsk_pcl_ros_utils
43 {
44  void TfTransformCloud::transform(const sensor_msgs::PointCloud2ConstPtr &input)
45  {
46  vital_checker_->poke();
47  sensor_msgs::PointCloud2 output;
48  try
49  {
50  if (use_latest_tf_) {
51  sensor_msgs::PointCloud2 latest_pointcloud(*input);
52  latest_pointcloud.header.stamp = ros::Time(0);
53  if (pcl_ros::transformPointCloud(target_frame_id_, latest_pointcloud, output,
54  *tf_listener_)) {
55  output.header.stamp = input->header.stamp;
56  pub_cloud_.publish(output);
57  }
58  }
59  else {
61  *tf_listener_)) {
62  pub_cloud_.publish(output);
63  }
64  }
65  }
67  {
68  NODELET_ERROR("Transform error: %s", e.what());
69  }
71  {
72  NODELET_ERROR("Transform error: %s", e.what());
73  }
74  catch (...)
75  {
76  NODELET_ERROR("Unknown transform error");
77  }
78  }
79 
81  {
82  DiagnosticNodelet::onInit();
83 
84  if (!pnh_->getParam("target_frame_id", target_frame_id_))
85  {
86  ROS_WARN("~target_frame_id is not specified, using %s", "/base_footprint");
87  }
88  pnh_->param("duration", duration_, 1.0);
89  pnh_->param("use_latest_tf", use_latest_tf_, false);
90  pnh_->param("tf_queue_size", tf_queue_size_, 10);
92  pub_cloud_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output", 1);
93 
95  }
96 
98  {
99  if (use_latest_tf_) {
100  sub_cloud_ = pnh_->subscribe("input", 1, &TfTransformCloud::transform, this);
101  }
102  else {
105  *tf_listener_,
107  tf_queue_size_));
108  tf_filter_->registerCallback(boost::bind(&TfTransformCloud::transform, this, _1));
109  }
110  }
111 
113  {
114  if (use_latest_tf_) {
116  }
117  else {
119  }
120  }
121 }
122 
#define NODELET_ERROR(...)
void publish(const boost::shared_ptr< M > &message) const
tf::TransformListener * tf_listener_
#define ROS_WARN(...)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_message_filters_
void output(int index, double value)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::TfTransformCloud, nodelet::Nodelet)
boost::shared_ptr< tf::MessageFilter< sensor_msgs::PointCloud2 > > tf_filter_
boost::shared_ptr< ros::NodeHandle > pnh_
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)
void transformPointCloud(const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const tf::Transform &transform)
virtual void transform(const sensor_msgs::PointCloud2ConstPtr &input)
static tf::TransformListener * getInstance()


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