polygon_flipper_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
39 #include <algorithm>
40 #include <iterator>
41 
42 namespace jsk_pcl_ros_utils
43 {
45  {
46  DiagnosticNodelet::onInit();
47  if (!pnh_->getParam("sensor_frame", sensor_frame_)) {
48  NODELET_FATAL("no ~sensor_frame is specified");
49  return;
50  }
51 
52  pnh_->param<int>("queue_size", queue_size_, 100);
53  pnh_->param<bool>("use_indices", use_indices_, true);
54 
56  pub_polygons_ = advertise<jsk_recognition_msgs::PolygonArray>(
57  *pnh_, "output/polygons", 1);
58  pub_coefficients_ = advertise<jsk_recognition_msgs::ModelCoefficientsArray>(
59  *pnh_, "output/coefficients", 1);
60  if (use_indices_)
61  pub_indices_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(
62  *pnh_, "output/indices", 1);
63 
65  }
66 
68  {
69  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(queue_size_);
70  sub_polygons_.subscribe(*pnh_, "input/polygons", 1);
71  sub_coefficients_.subscribe(*pnh_, "input/coefficients", 1);
72  if (use_indices_) {
73  sub_indices_.subscribe(*pnh_, "input/indices", 1);
75  } else {
78  }
79  sync_->registerCallback(boost::bind(&PolygonFlipper::flip, this, _1, _2, _3));
80  }
81 
83  {
86  if (use_indices_)
88  }
89 
91  const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons_msg)
92  {
93  jsk_recognition_msgs::ClusterPointIndices indices;
94  indices.header.stamp = polygons_msg->header.stamp;
95  indices.cluster_indices.resize(polygons_msg->polygons.size());
97  boost::make_shared<jsk_recognition_msgs::ClusterPointIndices>(indices));
98  }
99 
101  const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons_msg,
102  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg,
103  const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg)
104  {
105  vital_checker_->poke();
106  if (polygons_msg->polygons.size() != coefficients_msg->coefficients.size()) {
107  NODELET_ERROR("The size of polygons and coefficients are not same");
108  return;
109  }
110  jsk_recognition_msgs::PolygonArray flipped_polygons = *polygons_msg;
111  jsk_recognition_msgs::ModelCoefficientsArray flipped_coefficients;
112  jsk_recognition_msgs::ClusterPointIndices flipped_indices;
113  flipped_polygons.polygons.clear();
114  flipped_coefficients.header = coefficients_msg->header;
115  flipped_indices.header = indices_msg->header;
116  try {
117  for (size_t i = 0; i < polygons_msg->polygons.size(); i++) {
118  geometry_msgs::PolygonStamped target_polygon = polygons_msg->polygons[i];
119  PCLModelCoefficientMsg target_coefficients = coefficients_msg->coefficients[i];
120  PCLIndicesMsg target_indices = indices_msg->cluster_indices[i];
121  tf::StampedTransform tf_transform
123  tf_listener_, target_coefficients.header.frame_id,
124  sensor_frame_, target_coefficients.header.stamp,
125  ros::Duration(1.0));
126  Eigen::Affine3f sensor_transform;
127  tf::transformTFToEigen(tf_transform, sensor_transform);
128  {
129  // poygons
131  Eigen::Vector3f polygon_normal = convex.getNormal();
132  if (polygon_normal.dot(Eigen::Vector3f(sensor_transform.translation()))
133  < 0) {
134  geometry_msgs::PolygonStamped flipped_polygon;
135  std::reverse_copy(
136  target_polygon.polygon.points.begin(),
137  target_polygon.polygon.points.end(),
138  std::back_inserter(flipped_polygon.polygon.points));
139  flipped_polygon.header = target_polygon.header;
140  flipped_polygons.polygons.push_back(flipped_polygon);
141  }
142  else {
143  flipped_polygons.polygons.push_back(target_polygon);
144  }
145  }
146 
147  {
148  // coefficients
149  Eigen::Vector3f local_normal(target_coefficients.values[0],
150  target_coefficients.values[1],
151  target_coefficients.values[2]);
152  if (local_normal.dot(Eigen::Vector3f(sensor_transform.translation()))
153  < 0) {
154  PCLModelCoefficientMsg the_flipped_coefficients;
155  PCLIndicesMsg the_flipped_indices;
156  for (size_t j = 0; j < target_coefficients.values.size(); j++) {
157  the_flipped_coefficients.values.push_back(
158  - target_coefficients.values[j]);
159  }
160  std::reverse_copy(target_indices.indices.begin(), target_indices.indices.end(),
161  std::back_inserter(the_flipped_indices.indices));
162  the_flipped_coefficients.header = target_coefficients.header;
163  the_flipped_indices.header = target_indices.header;
164  flipped_coefficients.coefficients.push_back(the_flipped_coefficients);
165  //flipped_coefficients.coefficients.push_back(target_coefficients);
166  flipped_indices.cluster_indices.push_back(the_flipped_indices);
167  //flipped_indices.cluster_indices.push_back(target_indices);
168  }
169  else {
170  // no need to flip
171  flipped_coefficients.coefficients.push_back(target_coefficients);
172  flipped_indices.cluster_indices.push_back(target_indices);
173  }
174  }
175  }
176  pub_polygons_.publish(flipped_polygons);
177  pub_coefficients_.publish(flipped_coefficients);
178  if (use_indices_)
179  pub_indices_.publish(flipped_indices);
180  }
181  catch (tf2::TransformException& e) {
182  NODELET_ERROR("Failed to lookup transformation: %s", e.what());
183  }
184  }
185 }
186 
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
#define NODELET_ERROR(...)
static ConvexPolygon fromROSMsg(const geometry_msgs::Polygon &polygon)
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)
virtual void flip(const jsk_recognition_msgs::PolygonArray::ConstPtr &polygon_msg, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &indices_msg, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients_msg)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::PolygonFlipper, nodelet::Nodelet)
virtual void fillEmptyIndices(const jsk_recognition_msgs::PolygonArray::ConstPtr &polygon_msg)
message_filters::PassThrough< jsk_recognition_msgs::ClusterPointIndices > sub_indices_null_
boost::shared_ptr< ros::NodeHandle > pnh_
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
jsk_topic_tools::VitalChecker::Ptr vital_checker_
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygons_
tf::TransformListener * tf_listener_
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_indices_
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 add(const MConstPtr &msg)
static tf::TransformListener * getInstance()
#define NODELET_FATAL(...)
pcl::PointIndices PCLIndicesMsg
pcl::ModelCoefficients PCLModelCoefficientMsg
virtual Eigen::Vector3f getNormal()
Connection registerCallback(const C &callback)


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