normal_flip_to_frame_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 
40 
41 
42 namespace jsk_pcl_ros_utils
43 {
45  {
46  DiagnosticNodelet::onInit();
47  pcl::console::setVerbosityLevel(pcl::console::L_ERROR);
49  if (!pnh_->getParam("frame_id", frame_id_)) {
50  NODELET_FATAL("[%s] no ~frame_id is specified", __PRETTY_FUNCTION__);
51  }
52  pnh_->param("strict_tf", strict_tf_, false);
53  pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output", 1);
55  }
56 
58  {
59  sub_ = pnh_->subscribe("input", 1, &NormalFlipToFrame::flip, this);
60  }
61 
63  {
64  sub_.shutdown();
65  }
66 
67  void NormalFlipToFrame::flip(const sensor_msgs::PointCloud2::ConstPtr& cloud_msg)
68  {
69  vital_checker_->poke();
70  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr cloud
71  (new pcl::PointCloud<pcl::PointXYZRGBNormal>);
72  pcl::fromROSMsg(*cloud_msg, *cloud);
73  // check tf is available
74  try {
76  if (strict_tf_) {
77  stamp = cloud_msg->header.stamp;
78  }
79  else {
80  stamp = ros::Time(0);
81  }
82  tf::StampedTransform sensor_transform_tf
85  cloud_msg->header.frame_id,
86  stamp,
87  ros::Duration(1.0));
88  Eigen::Affine3f sensor_transform;
89  tf::transformTFToEigen(sensor_transform_tf, sensor_transform);
90  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr flipped_cloud
91  (new pcl::PointCloud<pcl::PointXYZRGBNormal>);
92  flipped_cloud->points.resize(cloud->points.size());
93  Eigen::Vector3f s(sensor_transform.translation());
94  for (size_t i = 0; i < cloud->points.size(); i++) {
95  // Check point is not nan
96  if (pcl_isfinite(cloud->points[i].x) &&
97  pcl_isfinite(cloud->points[i].y) &&
98  pcl_isfinite(cloud->points[i].z) &&
99  pcl_isfinite(cloud->points[i].normal_x) &&
100  pcl_isfinite(cloud->points[i].normal_y) &&
101  pcl_isfinite(cloud->points[i].normal_z)) {
102  Eigen::Vector3f p = cloud->points[i].getVector3fMap();
103  Eigen::Vector3f n(cloud->points[i].normal_x,
104  cloud->points[i].normal_y,
105  cloud->points[i].normal_z);
106  if ((s - p).dot(n) < 0) {
107  pcl::PointXYZRGBNormal new_p;
108  jsk_recognition_utils::pointFromVectorToXYZ<Eigen::Vector3f, pcl::PointXYZRGBNormal>(
109  p, new_p);
110  new_p.rgb = cloud->points[i].rgb;
111  new_p.normal_x = - n[0];
112  new_p.normal_y = - n[1];
113  new_p.normal_z = - n[2];
114  flipped_cloud->points[i] = new_p;
115  }
116  else {
117  flipped_cloud->points[i] = cloud->points[i];
118  }
119  }
120  else {
121  flipped_cloud->points[i] = cloud->points[i];
122  }
123 
124  }
125  sensor_msgs::PointCloud2 ros_cloud;
126  pcl::toROSMsg(*flipped_cloud, ros_cloud);
127  ros_cloud.header = cloud_msg->header;
128  pub_.publish(ros_cloud);
129  }
130  catch (tf2::ConnectivityException &e)
131  {
132  NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
133  }
135  {
136  NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
137  }
138  catch (tf2::TransformException &e)
139  {
140  NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
141  }
142  }
143 }
144 
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::NormalFlipToFrame, nodelet::Nodelet)
#define NODELET_ERROR(...)
void publish(const boost::shared_ptr< M > &message) const
void transformTFToEigen(const tf::Transform &t, Eigen::Affine3d &e)
tf::StampedTransform lookupTransformWithDuration(tf::TransformListener *listener, const std::string &to_frame, const std::string &from_frame, const ros::Time &stamp, ros::Duration duration)
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
virtual void flip(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)
boost::shared_ptr< ros::NodeHandle > pnh_
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
jsk_topic_tools::VitalChecker::Ptr vital_checker_
p
s
static tf::TransformListener * getInstance()
#define NODELET_FATAL(...)


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