plane_reasoner_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/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 
39 
40 namespace jsk_pcl_ros_utils
41 {
43  {
45  // Diagnostics
47  DiagnosticNodelet::onInit();
49 
51  // Dynamic Reconfigure
53  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
54  dynamic_reconfigure::Server<Config>::CallbackType f =
55  boost::bind (
56  &PlaneReasoner::configCallback, this, _1, _2);
57  srv_->setCallback (f);
58 
60  // Publishers
63  = advertise<jsk_recognition_msgs::ClusterPointIndices>(*pnh_, "output/vertical/inliers", 1);
65  = advertise<jsk_recognition_msgs::ModelCoefficientsArray>(*pnh_, "output/vertical/coefficients", 1);
67  = advertise<jsk_recognition_msgs::PolygonArray>(*pnh_, "output/vertical/polygons", 1);
69  = advertise<jsk_recognition_msgs::ClusterPointIndices>(*pnh_, "output/horizontal/inliers", 1);
71  = advertise<jsk_recognition_msgs::ModelCoefficientsArray>(*pnh_, "output/horizontal/coefficients", 1);
73  = advertise<jsk_recognition_msgs::PolygonArray>(*pnh_, "output/horizontal/polygons", 1);
74 
76  }
77 
79  {
81  // Subscribers
83  sub_input_.subscribe(*pnh_, "input", 1);
84  sub_inliers_.subscribe(*pnh_, "input_inliers", 1);
85  sub_coefficients_.subscribe(*pnh_, "input_coefficients", 1);
86  sub_polygons_.subscribe(*pnh_, "input_polygons", 1);
87  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
88  sync_->connectInput(sub_input_, sub_inliers_,
90  sync_->registerCallback(boost::bind(&PlaneReasoner::reason,
91  this, _1, _2, _3, _4));
92  }
93 
95  {
100  }
101 
102 
103  void PlaneReasoner::configCallback(Config &config, uint32_t level)
104  {
105  boost::mutex::scoped_lock lock(mutex_);
106  global_frame_id_ = config.global_frame_id;
107  horizontal_angular_threshold_ = config.horizontal_angular_threshold;
108  vertical_angular_threshold_ = config.vertical_angular_threshold;
109  }
110 
112  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
113  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& inliers_msg,
114  const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg,
115  const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons_msg)
116  {
117  boost::mutex::scoped_lock lock(mutex_);
118  // Check the size of the array messages first
119  if ((inliers_msg->cluster_indices.size()
120  != coefficients_msg->coefficients.size()) ||
121  (inliers_msg->cluster_indices.size()
122  != polygons_msg->polygons.size())) {
123  NODELET_FATAL("the size of inliers, coefficients and polygons are not same");
124  return;
125  }
126  vital_checker_->poke();
127  pcl::PointCloud<PointT>::Ptr input_cloud (new pcl::PointCloud<PointT>);
128  pcl::fromROSMsg(*cloud_msg, *input_cloud);
129 
130  // convert ROS msg to PCL/jsk_pcl messages
131  std::vector<pcl::PointIndices::Ptr> inliers
132  = pcl_conversions::convertToPCLPointIndices(inliers_msg->cluster_indices);
133  std::vector<pcl::ModelCoefficients::Ptr> coefficients
135  coefficients_msg->coefficients);
136  std::vector<jsk_recognition_utils::Plane::Ptr> planes = jsk_recognition_utils::convertToPlanes(coefficients);
137  std::vector<geometry_msgs::PolygonStamped> polygons = polygons_msg->polygons;
138  std::vector<PlaneInfoContainer> plane_infos
139  = packInfo(inliers, coefficients, planes, polygons);
140  std::vector<PlaneInfoContainer> horizontal_planes
141  = filterHorizontalPlanes(plane_infos);
142  std::vector<PlaneInfoContainer> vertical_planes
143  = filterVerticalPlanes(plane_infos);
144  publishPlaneInfo(vertical_planes,
145  cloud_msg->header,
146  input_cloud,
150  publishPlaneInfo(horizontal_planes,
151  cloud_msg->header,
152  input_cloud,
156  }
157 
159  std::vector<PlaneInfoContainer>& containers,
160  const std_msgs::Header& header,
161  pcl::PointCloud<PointT>::Ptr cloud,
162  ros::Publisher& pub_inlier,
163  ros::Publisher& pub_coefficients,
164  ros::Publisher& pub_polygons)
165  {
166  std::vector<pcl::PointIndices::Ptr> inliers;
167  std::vector<pcl::ModelCoefficients::Ptr> coefficients;
168  std::vector<geometry_msgs::PolygonStamped> polygons;
169  for (size_t i = 0; i < containers.size(); i++) {
170  inliers.push_back(containers[i].get<0>());
171  coefficients.push_back(containers[i].get<1>());
172  polygons.push_back(containers[i].get<3>());
173  }
174  jsk_recognition_msgs::ClusterPointIndices ros_indices;
175  jsk_recognition_msgs::ModelCoefficientsArray ros_coefficients;
176  jsk_recognition_msgs::PolygonArray ros_polygons;
177  ros_indices.header = header;
178  ros_coefficients.header = header;
179  ros_polygons.header = header;
180  ros_indices.cluster_indices = pcl_conversions::convertToROSPointIndices(
181  inliers, header);
182  ros_coefficients.coefficients
184  coefficients, header);
185  ros_polygons.polygons = polygons;
186  pub_inlier.publish(ros_indices);
187  pub_coefficients.publish(ros_coefficients);
188  pub_polygons.publish(ros_polygons);
189  }
190 
191  std::vector<PlaneInfoContainer>
193  double reference_angle,
194  double thrshold,
195  std::vector<PlaneInfoContainer>& infos)
196  {
197 
198  std::vector<PlaneInfoContainer> ret;
199  for (size_t i = 0; i < infos.size(); i++) {
200  PlaneInfoContainer plane_info = infos[i];
202  plane_info.get<3>().header.frame_id,
203  plane_info.get<3>().header.stamp)) {
204  tf::StampedTransform transform;
205  tf_listener_->lookupTransform(plane_info.get<3>().header.frame_id, global_frame_id_,
206 
207  plane_info.get<3>().header.stamp,
208  transform);
209  Eigen::Affine3d eigen_transform;
210  tf::transformTFToEigen(transform, eigen_transform);
211  Eigen::Affine3f eigen_transform_3f;
212  Eigen::Vector3d up_d = (eigen_transform.rotation() * Eigen::Vector3d(0, 0, 1));
213  Eigen::Vector3f up;
214  jsk_recognition_utils::pointFromVectorToVector<Eigen::Vector3d, Eigen::Vector3f>(up_d, up);
215  jsk_recognition_utils::Plane::Ptr plane = plane_info.get<2>();
216  double angle = plane->angle(up);
217  // ROS_INFO("axis: [%f, %f, %f]", up[0], up[1], up[2]);
218  // ROS_INFO("plane: [%f, %f, %f, %f]", plane_info.get<1>()->values[0], plane_info.get<1>()->values[1], plane_info.get<1>()->values[2], plane_info.get<1>()->values[3]);
219  // ROS_INFO("angle: %f", angle);
220  if (fabs(angle - reference_angle) < thrshold) {
221  ret.push_back(plane_info);
222  }
223  }
224  }
225  return ret;
226  }
227 
228  std::vector<PlaneInfoContainer>
230  std::vector<PlaneInfoContainer>& infos)
231  {
233  0,
235  infos);
236  }
237 
238  std::vector<PlaneInfoContainer>
240  std::vector<PlaneInfoContainer>& infos)
241  {
243  M_PI / 2.0,
245  infos);
246  }
247 
248  std::vector<PlaneInfoContainer>
250  std::vector<pcl::PointIndices::Ptr>& inliers,
251  std::vector<pcl::ModelCoefficients::Ptr>& coefficients,
252  std::vector<jsk_recognition_utils::Plane::Ptr>& planes,
253  std::vector<geometry_msgs::PolygonStamped>& polygons)
254  {
255  std::vector<PlaneInfoContainer> ret;
256  for (size_t i = 0; i < inliers.size(); i++) {
257  ret.push_back(boost::make_tuple<pcl::PointIndices::Ptr,
258  pcl::ModelCoefficients::Ptr,
259  jsk_recognition_utils::Plane::Ptr>(inliers[i], coefficients[i],
260  planes[i], polygons[i]));
261  }
262  return ret;
263  }
264 
265 
266 }
267 
f
std::vector< Plane::Ptr > convertToPlanes(std::vector< pcl::ModelCoefficients::Ptr >)
lock
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::PlaneReasoner, nodelet::Nodelet)
void publish(const boost::shared_ptr< M > &message) const
void transformTFToEigen(const tf::Transform &t, Eigen::Affine3d &e)
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
std::vector< PCLModelCoefficientMsg > convertToROSModelCoefficients(const std::vector< pcl::ModelCoefficients::Ptr > &coefficients, const std_msgs::Header &header)
std::vector< pcl::ModelCoefficients::Ptr > convertToPCLModelCoefficients(const std::vector< PCLModelCoefficientMsg > &coefficients)
virtual std::vector< PlaneInfoContainer > packInfo(std::vector< pcl::PointIndices::Ptr > &inliers, std::vector< pcl::ModelCoefficients::Ptr > &coefficients, std::vector< jsk_recognition_utils::Plane::Ptr > &planes, std::vector< geometry_msgs::PolygonStamped > &polygons)
coefficients
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
#define M_PI
std::vector< pcl::PointIndices::Ptr > convertToPCLPointIndices(const std::vector< PCLIndicesMsg > &cluster_indices)
bool canTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, std::string *error_msg=NULL) const
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
virtual void configCallback(Config &config, uint32_t level)
boost::tuple< pcl::PointIndices::Ptr, pcl::ModelCoefficients::Ptr, jsk_recognition_utils::Plane::Ptr, geometry_msgs::PolygonStamped > PlaneInfoContainer
tf::TransformListener * tf_listener_
boost::shared_ptr< ros::NodeHandle > pnh_
jsk_pcl_ros_utils::PlaneReasonerConfig Config
virtual void reason(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &inliers_msg, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients_msg, const jsk_recognition_msgs::PolygonArray::ConstPtr &polygons_msg)
void lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, StampedTransform &transform) const
std::vector< PCLIndicesMsg > convertToROSPointIndices(const std::vector< pcl::PointIndices::Ptr > cluster_indices, const std_msgs::Header &header)
jsk_topic_tools::VitalChecker::Ptr vital_checker_
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygons_
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)
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_inliers_
virtual std::vector< PlaneInfoContainer > filterHorizontalPlanes(std::vector< PlaneInfoContainer > &infos)
ros::Publisher pub_horizontal_coefficients_
virtual std::vector< PlaneInfoContainer > filterPlanesAroundAngle(double reference_angle, double thrshold, std::vector< PlaneInfoContainer > &infos)
static tf::TransformListener * getInstance()
#define NODELET_FATAL(...)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
virtual void publishPlaneInfo(std::vector< PlaneInfoContainer > &containers, const std_msgs::Header &header, pcl::PointCloud< PointT >::Ptr cloud, ros::Publisher &pub_inlier, ros::Publisher &pub_coefficients, ros::Publisher &pub_polygons)
virtual std::vector< PlaneInfoContainer > filterVerticalPlanes(std::vector< PlaneInfoContainer > &infos)
polygons
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_


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