polygon_array_transformer_nodelet.cpp
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/or 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 
40 
41 namespace jsk_pcl_ros_utils
42 {
43 
45  {
46  ConnectionBasedNodelet::onInit();
47  if (!pnh_->getParam("frame_id", frame_id_)) {
48  NODELET_FATAL("~frame_id is not specified");
49  return;
50  }
52  polygons_pub_ = advertise<jsk_recognition_msgs::PolygonArray>(*pnh_, "output_polygons", 1);
53  coefficients_pub_ = advertise<jsk_recognition_msgs::ModelCoefficientsArray>(
54  *pnh_, "output_coefficients", 1);
55  onInitPostProcess();
56  }
57 
59  // message_filters::Synchronizer needs to be called reset
60  // before message_filters::Subscriber is freed.
61  // Calling reset fixes the following error on shutdown of the nodelet:
62  // terminate called after throwing an instance of
63  // 'boost::exception_detail::clone_impl<boost::exception_detail::error_info_injector<boost::lock_error> >'
64  // what(): boost: mutex lock failed in pthread_mutex_lock: Invalid argument
65  // Also see https://github.com/ros/ros_comm/issues/720 .
66  sync_.reset();
67  }
68 
70  {
71  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
72  sub_polygons_.subscribe(*pnh_, "input_polygons", 1);
73  sub_coefficients_.subscribe(*pnh_, "input_coefficients", 1);
74  sync_->connectInput(sub_polygons_, sub_coefficients_);
75  sync_->registerCallback(boost::bind(&PolygonArrayTransformer::transform, this, _1, _2));
76  }
77 
79  {
82  }
83 
84  void PolygonArrayTransformer::computeCoefficients(const geometry_msgs::PolygonStamped& polygon,
85  PCLModelCoefficientMsg& coefficient)
86  {
87  Eigen::Vector3d A, B, C;
88  A[0] = polygon.polygon.points[0].x;
89  A[1] = polygon.polygon.points[0].y;
90  A[2] = polygon.polygon.points[0].z;
91  B[0] = polygon.polygon.points[1].x;
92  B[1] = polygon.polygon.points[1].y;
93  B[2] = polygon.polygon.points[1].z;
94  C[0] = polygon.polygon.points[2].x;
95  C[1] = polygon.polygon.points[2].y;
96  C[2] = polygon.polygon.points[2].z;
97  Eigen::Vector3d n = (B - A).cross(C - A).normalized();
98  double a = n[0];
99  double b = n[1];
100  double c = n[2];
101  double d = -(a * A[0] + b * A[1] + c * A[2]);
102  coefficient.header = polygon.header;
103  coefficient.values.push_back(a);
104  coefficient.values.push_back(b);
105  coefficient.values.push_back(c);
106  coefficient.values.push_back(d);
107 
108  }
109 
110  void PolygonArrayTransformer::transformModelCoefficient(const Eigen::Affine3d& transform,
111  const PCLModelCoefficientMsg& coefficient,
112  PCLModelCoefficientMsg& result)
113  {
114  jsk_recognition_utils::Plane plane(coefficient.values);
115  jsk_recognition_utils::Plane transformed_plane = plane.transform(transform);
116  result.header.stamp = coefficient.header.stamp;
117  result.header.frame_id = frame_id_;
118  transformed_plane.toCoefficients(result.values);
119  NODELET_DEBUG("[%f, %f, %f, %f] => [%f, %f, %f, %f]",
120  coefficient.values[0], coefficient.values[1], coefficient.values[2], coefficient.values[3],
121  result.values[0], result.values[1], result.values[2], result.values[3]);
122  }
123 
124  void PolygonArrayTransformer::transformPolygon(const Eigen::Affine3d& transform,
125  const geometry_msgs::PolygonStamped& polygon,
126  geometry_msgs::PolygonStamped& result)
127  {
128  result.header = polygon.header;
129  result.header.frame_id = frame_id_;
130  for (size_t i = 0; i < polygon.polygon.points.size(); i++) {
131  Eigen::Vector4d point;
132  point[0] = polygon.polygon.points[i].x;
133  point[1] = polygon.polygon.points[i].y;
134  point[2] = polygon.polygon.points[i].z;
135  point[3] = 1; // homogenious
136  Eigen::Vector4d transformed_point_eigen = transform.inverse() * point;
137  geometry_msgs::Point32 transformed_point;
138  transformed_point.x = transformed_point_eigen[0];
139  transformed_point.y = transformed_point_eigen[1];
140  transformed_point.z = transformed_point_eigen[2];
141  result.polygon.points.push_back(transformed_point);
142  }
143  }
144 
145  void PolygonArrayTransformer::transform(const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons,
146  const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients)
147  {
148  if (polygons->polygons.size() != coefficients->coefficients.size()) {
149  NODELET_ERROR("the size of polygons(%lu) does not match with the size of coefficients(%lu)",
150  polygons->polygons.size(),
151  coefficients->coefficients.size());
152  return;
153  }
154 
155  jsk_recognition_msgs::PolygonArray transformed_polygon_array;
156  jsk_recognition_msgs::ModelCoefficientsArray transformed_model_coefficients_array;
157  transformed_polygon_array.header = polygons->header;
158  transformed_model_coefficients_array.header = coefficients->header;
159  transformed_polygon_array.header.frame_id = frame_id_;
160  transformed_model_coefficients_array.header.frame_id = frame_id_;
161  for (size_t i = 0; i < polygons->polygons.size(); i++) {
162  geometry_msgs::PolygonStamped polygon = polygons->polygons[i];
163  PCLModelCoefficientMsg coefficient = coefficients->coefficients[i];
164 
165  if (polygon.header.frame_id != coefficient.header.frame_id) {
166  NODELET_ERROR("frame_id of polygon[%lu] is %s and frame_id of coefficient[%lu] is %s, they does not point to the same frame_id",
167  i, polygon.header.frame_id.c_str(),
168  i, coefficient.header.frame_id.c_str());
169  return;
170  }
171  listener_->waitForTransform(coefficient.header.frame_id,
172  frame_id_,
173  coefficient.header.stamp,
174  ros::Duration(1.0));
175  if (listener_->canTransform(coefficient.header.frame_id,
176  frame_id_,
177  coefficient.header.stamp)) {
178  tf::StampedTransform transform; // header -> frame_id_
179  listener_->lookupTransform(coefficient.header.frame_id, frame_id_,
180  //ros::Time(0.0), transform);
181  coefficient.header.stamp, transform);
182  Eigen::Affine3d eigen_transform;
183  tf::transformTFToEigen(transform, eigen_transform);
184  PCLModelCoefficientMsg transformed_coefficient;
185  //transformModelCoefficient(eigen_transform, coefficient, transformed_coefficient);
186 
187  geometry_msgs::PolygonStamped transformed_polygon;
188  if (polygon.polygon.points.size() == 0) {
189  transformed_polygon.header = polygon.header;
190  transformed_polygon.header.frame_id = frame_id_;
191  transformed_polygon_array.polygons.push_back(transformed_polygon);
192  transformed_coefficient.values = coefficient.values;
193  transformed_coefficient.header = polygon.header;
194  transformed_coefficient.header.frame_id = frame_id_;
195  transformed_model_coefficients_array.coefficients.push_back(transformed_coefficient);
196  }
197  else {
198  transformPolygon(eigen_transform, polygon, transformed_polygon);
199  //computeCoefficients(transformed_polygon, transformed_coefficient);
200  transformModelCoefficient(eigen_transform, coefficient,
201  transformed_coefficient);
202  if (isnan(transformed_coefficient.values[0]) ||
203  isnan(transformed_coefficient.values[1]) ||
204  isnan(transformed_coefficient.values[2]) ||
205  isnan(transformed_coefficient.values[3])) {
206  continue;
207  }
208  transformed_polygon_array.polygons.push_back(transformed_polygon);
209  transformed_model_coefficients_array.coefficients.push_back(transformed_coefficient);
210  }
211  }
212  else {
213  NODELET_ERROR("cannot lookup transform from %s to %s at %f",
214  frame_id_.c_str(), coefficient.header.frame_id.c_str(),
215  coefficient.header.stamp.toSec());
216  return;
217  }
218  }
219  polygons_pub_.publish(transformed_polygon_array);
220  coefficients_pub_.publish(transformed_model_coefficients_array);
221  }
222 
223 }
224 
jsk_pcl_ros_utils
Definition: add_point_indices.h:51
polygons
polygons
NODELET_FATAL
#define NODELET_FATAL(...)
NODELET_ERROR
#define NODELET_ERROR(...)
jsk_recognition_utils::Plane::transform
virtual Plane transform(const Eigen::Affine3d &transform)
i
int i
jsk_pcl_ros_utils::PolygonArrayTransformer::sub_polygons_
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygons_
Definition: polygon_array_transformer.h:147
jsk_pcl_ros_utils::PolygonArrayTransformer::polygons_pub_
ros::Publisher polygons_pub_
Definition: polygon_array_transformer.h:144
geo_util.h
tf::StampedTransform
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
message_filters::Subscriber::unsubscribe
void unsubscribe()
jsk_pcl_ros_utils::PolygonArrayTransformer::sub_coefficients_
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
Definition: polygon_array_transformer.h:148
class_list_macros.h
jsk_pcl_ros_utils::PolygonArrayTransformer::computeCoefficients
virtual void computeCoefficients(const geometry_msgs::PolygonStamped &polygon, PCLModelCoefficientMsg &coefficient)
Definition: polygon_array_transformer_nodelet.cpp:116
jsk_pcl_ros_utils::PolygonArrayTransformer::~PolygonArrayTransformer
virtual ~PolygonArrayTransformer()
Definition: polygon_array_transformer_nodelet.cpp:90
A
tf_eigen.h
PCLModelCoefficientMsg
pcl::ModelCoefficients PCLModelCoefficientMsg
jsk_pcl_ros_utils::PolygonArrayTransformer
Definition: polygon_array_transformer.h:91
polygon_array_transformer.h
jsk_pcl_ros_utils::PolygonArrayTransformer::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: polygon_array_transformer.h:149
tf::transformTFToEigen
void transformTFToEigen(const tf::Transform &t, Eigen::Affine3f &eigen)
tf::Transformer::canTransform
bool canTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, std::string *error_msg=NULL) const
jsk_pcl_ros_utils::PolygonArrayTransformer::frame_id_
std::string frame_id_
Definition: polygon_array_transformer.h:146
d
d
jsk_recognition_utils::Plane::toCoefficients
virtual std::vector< float > toCoefficients()
cross
double3 cross(const double3 &a, const double3 &b)
tf::Transformer::waitForTransform
bool waitForTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
jsk_pcl_ros_utils::PolygonArrayTransformer::transform
virtual void transform(const jsk_recognition_msgs::PolygonArray::ConstPtr &polygons, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients)
Definition: polygon_array_transformer_nodelet.cpp:177
jsk_pcl_ros_utils::PolygonArrayTransformer::unsubscribe
virtual void unsubscribe()
Definition: polygon_array_transformer_nodelet.cpp:110
point
std::chrono::system_clock::time_point point
message_filters::Subscriber::subscribe
void subscribe()
jsk_pcl_ros_utils::PolygonArrayTransformer::onInit
virtual void onInit()
Definition: polygon_array_transformer_nodelet.cpp:76
jsk_pcl_ros_utils::PolygonArrayTransformer::transformModelCoefficient
virtual void transformModelCoefficient(const Eigen::Affine3d &transform, const PCLModelCoefficientMsg &coefficient, PCLModelCoefficientMsg &result)
Definition: polygon_array_transformer_nodelet.cpp:142
nodelet::Nodelet
jsk_pcl_ros_utils::PolygonArrayTransformer::listener_
tf::TransformListener * listener_
Definition: polygon_array_transformer.h:145
coefficients
coefficients
jsk_recognition_utils::Plane
jsk_recognition_utils::TfListenerSingleton::getInstance
static tf::TransformListener * getInstance()
jsk_pcl_ros_utils::PolygonArrayTransformer::transformPolygon
virtual void transformPolygon(const Eigen::Affine3d &transform, const geometry_msgs::PolygonStamped &polygon, geometry_msgs::PolygonStamped &result)
Definition: polygon_array_transformer_nodelet.cpp:156
tf::Transformer::lookupTransform
void lookupTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, StampedTransform &transform) const
jsk_pcl_ros_utils::PolygonArrayTransformer::coefficients_pub_
ros::Publisher coefficients_pub_
Definition: polygon_array_transformer.h:144
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::PolygonArrayTransformer, nodelet::Nodelet)
jsk_pcl_ros_utils::PolygonArrayTransformer::subscribe
virtual void subscribe()
Definition: polygon_array_transformer_nodelet.cpp:101
ros::Duration
NODELET_DEBUG
#define NODELET_DEBUG(...)


jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Fri May 16 2025 03:11:43