static_polygon_array_publisher_nodelet.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2014, 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 
38 
39 namespace jsk_pcl_ros_utils
40 {
41 
43  {
44  ConnectionBasedNodelet::onInit();
45  pnh_->param("use_periodic", use_periodic_, false);
46  pnh_->param("use_message", use_message_, false);
47  pnh_->param("use_trigger", use_trigger_, false);
48  pnh_->param("periodic_rate", periodic_rate_, 10.0);
49 
50  bool frame_id_read_p
52  frame_ids_);
53  if (!frame_id_read_p) {
54  NODELET_FATAL("failed to read frame_ids from ~frame_ids");
55  return;
56  }
57 
58  bool polygon_read_p = readPolygonArray("polygon_array");
59  if (!polygon_read_p) {
60  NODELET_FATAL("failed to read polygons from ~polygon_array");
61  return;
62  }
63 
64  if (frame_ids_.size() != polygons_.polygons.size()) {
65  NODELET_FATAL("the size of frame_ids(%lu) does not match the size of polygons(%lu)",
66  frame_ids_.size(), polygons_.polygons.size());
67  return;
68  }
69  else {
70  for (size_t i = 0; i < frame_ids_.size(); i++) {
71  polygons_.polygons[i].header.frame_id = frame_ids_[i];
72  coefficients_.coefficients[i].header.frame_id = frame_ids_[i];
73  }
74  }
75 
77  NODELET_FATAL("~use_periodic, ~use_trigger nor ~use_message is not true");
78  return;
79  }
80  polygons_.header.frame_id = frame_ids_[0];
81  coefficients_.header.frame_id = frame_ids_[0];
82 
83  if (!use_periodic_) {
84  polygon_pub_ = advertise<jsk_recognition_msgs::PolygonArray>(
85  *pnh_, "output_polygons", 1);
86  coefficients_pub_ = advertise<jsk_recognition_msgs::ModelCoefficientsArray>(
87  *pnh_, "output_coefficients", 1);
88  }
89  else {
90  polygon_pub_ = pnh_->advertise<jsk_recognition_msgs::PolygonArray>(
91  "output_polygons", 1);
92  coefficients_pub_ = pnh_->advertise<jsk_recognition_msgs::ModelCoefficientsArray>(
93  "output_coefficients", 1);
94  subscribe();
96  }
98  }
99 
101  {
102  if (use_message_) {
103  sub_ = pnh_->subscribe("input", 1, &StaticPolygonArrayPublisher::inputCallback, this);
104  }
105  if (use_trigger_) {
106  sub_input_.subscribe(*pnh_, "input", 1);
107  sub_trigger_.subscribe(*pnh_, "trigger", 1);
108  sync_
109  = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
110  sync_->connectInput(sub_input_, sub_trigger_);
111  sync_->registerCallback(boost::bind(
113  this, _1, _2));
114  }
115  }
116 
118  {
119  if (use_message_) {
120  sub_.shutdown();
121  }
122  if (use_trigger_) {
125  }
126  }
127 
129  const sensor_msgs::PointCloud2::ConstPtr& input,
130  const jsk_recognition_msgs::Int32Stamped::ConstPtr& trigger)
131  {
132  publishPolygon(input->header.stamp);
133  }
134 
136  {
137  Eigen::Vector3d A, B, C;
138  A[0] = polygon.polygon.points[0].x;
139  A[1] = polygon.polygon.points[0].y;
140  A[2] = polygon.polygon.points[0].z;
141  B[0] = polygon.polygon.points[1].x;
142  B[1] = polygon.polygon.points[1].y;
143  B[2] = polygon.polygon.points[1].z;
144  C[0] = polygon.polygon.points[2].x;
145  C[1] = polygon.polygon.points[2].y;
146  C[2] = polygon.polygon.points[2].z;
147  Eigen::Vector3d n = (B - A).cross(C - A).normalized();
148  double a = n[0];
149  double b = n[1];
150  double c = n[2];
151  double d = -(a * A[0] + b * A[1] + c * A[2]);
152  PCLModelCoefficientMsg coefficient;
153  coefficient.header = polygon.header;
154  coefficient.values.push_back(a);
155  coefficient.values.push_back(b);
156  coefficient.values.push_back(c);
157  coefficient.values.push_back(d);
158  return coefficient;
159  }
160 
161  /*
162  parameter format is:
163  polygon_array: [[[0, 0, 0], [0, 0, 1], [1, 0, 0]], ...]
164  */
165  bool StaticPolygonArrayPublisher::readPolygonArray(const std::string& param_name)
166  {
167  if (pnh_->hasParam(param_name)) {
169  pnh_->param(param_name, v, v);
171  for (size_t toplevel_i = 0; toplevel_i < v.size(); toplevel_i++) { // polygons
172  XmlRpc::XmlRpcValue polygon_v = v[toplevel_i];
173  geometry_msgs::PolygonStamped polygon;
174  if (polygon_v.getType() == XmlRpc::XmlRpcValue::TypeArray &&
175  polygon_v.size() >= 3) {
176  for (size_t secondlevel_i = 0; secondlevel_i < polygon_v.size(); secondlevel_i++) { // each polygon, vertices
177  XmlRpc::XmlRpcValue vertex_v = polygon_v[secondlevel_i];
178  if (vertex_v.getType() == XmlRpc::XmlRpcValue::TypeArray &&
179  vertex_v.size() == 3 ) { // vertex_v := [x, y, z]
180  double x = getXMLDoubleValue(vertex_v[0]);
181  double y = getXMLDoubleValue(vertex_v[1]);
182  double z = getXMLDoubleValue(vertex_v[2]);
183  geometry_msgs::Point32 point;
184  point.x = x;
185  point.y = y;
186  point.z = z;
187  polygon.polygon.points.push_back(point);
188  }
189  else {
190  NODELET_FATAL("%s[%lu][%lu] is not array or the length is not 3",
191  param_name.c_str(), toplevel_i, secondlevel_i);
192  return false;
193  }
194  }
195  polygons_.polygons.push_back(polygon);
196  // estimate model coefficients
197  coefficients_.coefficients.push_back(polygonToModelCoefficients(polygon));
198  }
199  else {
200  NODELET_FATAL("%s[%lu] is not array or not enough points", param_name.c_str(), toplevel_i);
201  return false;
202  }
203  }
204  return true;
205  }
206  else {
207  NODELET_FATAL("%s is not array", param_name.c_str());
208  return false;
209  }
210  }
211  else {
212  NODELET_FATAL("no %s is available on parameter server", param_name.c_str());
213  return false;
214  }
215  return true;
216  }
217 
219  switch(val.getType()) {
221  return (double)((int)val);
223  return (double)val;
224  default:
225  return 0;
226  }
227  }
228 
229 
230  void StaticPolygonArrayPublisher::inputCallback(const sensor_msgs::PointCloud2::ConstPtr& msg)
231  {
232  publishPolygon(msg->header.stamp);
233  }
234 
236  {
238  }
239 
241  {
242  polygons_.header.stamp = stamp;
243  for (size_t i = 0; i < polygons_.polygons.size(); i++) {
244  polygons_.polygons[i].header.stamp = stamp;
245  }
246 
247  coefficients_.header.stamp = stamp;
248  for (size_t i = 0; i < coefficients_.coefficients.size(); i++) {
249  coefficients_.coefficients[i].header.stamp = stamp;
250  }
251 
254  }
255 
256 }
257 
260 
d
jsk_recognition_msgs::ModelCoefficientsArray coefficients_
void publish(const boost::shared_ptr< M > &message) const
TFSIMD_FORCE_INLINE Vector3 cross(const Vector3 &v) const
int size() const
Type const & getType() const
double y
bool readVectorParameter(ros::NodeHandle &nh, const std::string &param_name, std::vector< double > &result)
virtual PCLModelCoefficientMsg polygonToModelCoefficients(const geometry_msgs::PolygonStamped &polygon)
boost::shared_ptr< ros::NodeHandle > pnh_
double z
virtual void triggerCallback(const sensor_msgs::PointCloud2::ConstPtr &input, const jsk_recognition_msgs::Int32Stamped::ConstPtr &trigger)
double x
virtual void inputCallback(const sensor_msgs::PointCloud2::ConstPtr &msg)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::StaticPolygonArrayPublisher, nodelet::Nodelet)
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)
c
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
message_filters::Subscriber< jsk_recognition_msgs::Int32Stamped > sub_trigger_
#define NODELET_FATAL(...)
double x
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
pcl::ModelCoefficients PCLModelCoefficientMsg


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