plane_reasoner_nodelet.cpp
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2014, JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the JSK Lab nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 
00036 #include "jsk_recognition_utils/pcl_conversion_util.h"
00037 #include "jsk_pcl_ros_utils/plane_reasoner.h"
00038 #include <tf_conversions/tf_eigen.h>
00039 
00040 namespace jsk_pcl_ros_utils
00041 {
00042   void PlaneReasoner::onInit()
00043   {
00045     // Diagnostics
00047     DiagnosticNodelet::onInit();
00048     tf_listener_ = jsk_recognition_utils::TfListenerSingleton::getInstance();
00049     
00051     // Dynamic Reconfigure
00053     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00054     dynamic_reconfigure::Server<Config>::CallbackType f =
00055       boost::bind (
00056         &PlaneReasoner::configCallback, this, _1, _2);
00057     srv_->setCallback (f);
00058 
00060     // Publishers
00062     pub_vertical_inliers_
00063       = advertise<jsk_recognition_msgs::ClusterPointIndices>(*pnh_, "output/vertical/inliers", 1);
00064     pub_vertical_coefficients_
00065       = advertise<jsk_recognition_msgs::ModelCoefficientsArray>(*pnh_, "output/vertical/coefficients", 1);
00066     pub_vertical_polygons_
00067       = advertise<jsk_recognition_msgs::PolygonArray>(*pnh_, "output/vertical/polygons", 1);
00068     pub_horizontal_inliers_
00069       = advertise<jsk_recognition_msgs::ClusterPointIndices>(*pnh_, "output/horizontal/inliers", 1);
00070     pub_horizontal_coefficients_
00071       = advertise<jsk_recognition_msgs::ModelCoefficientsArray>(*pnh_, "output/horizontal/coefficients", 1);
00072     pub_horizontal_polygons_
00073       = advertise<jsk_recognition_msgs::PolygonArray>(*pnh_, "output/horizontal/polygons", 1);
00074 
00075     onInitPostProcess();
00076   }
00077 
00078   void PlaneReasoner::subscribe()
00079   {
00081     // Subscribers
00083     sub_input_.subscribe(*pnh_, "input", 1);
00084     sub_inliers_.subscribe(*pnh_, "input_inliers", 1);
00085     sub_coefficients_.subscribe(*pnh_, "input_coefficients", 1);
00086     sub_polygons_.subscribe(*pnh_, "input_polygons", 1);
00087     sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00088     sync_->connectInput(sub_input_, sub_inliers_,
00089                         sub_coefficients_, sub_polygons_);
00090     sync_->registerCallback(boost::bind(&PlaneReasoner::reason,
00091                                         this, _1, _2, _3, _4));
00092   }
00093 
00094   void PlaneReasoner::unsubscribe()
00095   {
00096     sub_input_.unsubscribe();
00097     sub_inliers_.unsubscribe();
00098     sub_coefficients_.unsubscribe();
00099     sub_polygons_.unsubscribe();
00100   }
00101                                 
00102   
00103   void PlaneReasoner::configCallback(Config &config, uint32_t level)
00104   {
00105     boost::mutex::scoped_lock lock(mutex_);
00106     global_frame_id_ = config.global_frame_id;
00107     horizontal_angular_threshold_ = config.horizontal_angular_threshold;
00108     vertical_angular_threshold_ = config.vertical_angular_threshold;
00109   }
00110 
00111   void PlaneReasoner::reason(
00112       const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
00113       const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& inliers_msg,
00114       const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg,
00115       const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons_msg)
00116   {
00117     boost::mutex::scoped_lock lock(mutex_);
00118     // Check the size of the array messages first
00119     if ((inliers_msg->cluster_indices.size()
00120          != coefficients_msg->coefficients.size()) ||
00121         (inliers_msg->cluster_indices.size()
00122          != polygons_msg->polygons.size())) {
00123       NODELET_FATAL("the size of inliers, coefficients and polygons are not same");
00124       return;
00125     }
00126     vital_checker_->poke();
00127     pcl::PointCloud<PointT>::Ptr input_cloud (new pcl::PointCloud<PointT>);
00128     pcl::fromROSMsg(*cloud_msg, *input_cloud);
00129     
00130     // convert ROS msg to PCL/jsk_pcl messages
00131     std::vector<pcl::PointIndices::Ptr> inliers
00132       = pcl_conversions::convertToPCLPointIndices(inliers_msg->cluster_indices);
00133     std::vector<pcl::ModelCoefficients::Ptr> coefficients
00134       = pcl_conversions::convertToPCLModelCoefficients(
00135         coefficients_msg->coefficients);
00136     std::vector<jsk_recognition_utils::Plane::Ptr> planes = jsk_recognition_utils::convertToPlanes(coefficients);
00137     std::vector<geometry_msgs::PolygonStamped> polygons = polygons_msg->polygons;
00138     std::vector<PlaneInfoContainer> plane_infos
00139       = packInfo(inliers, coefficients, planes, polygons);
00140     std::vector<PlaneInfoContainer> horizontal_planes
00141       = filterHorizontalPlanes(plane_infos);
00142     std::vector<PlaneInfoContainer> vertical_planes
00143       = filterVerticalPlanes(plane_infos);
00144     publishPlaneInfo(vertical_planes,
00145                      cloud_msg->header,
00146                      input_cloud,
00147                      pub_vertical_inliers_,
00148                      pub_vertical_coefficients_,
00149                      pub_vertical_polygons_);
00150     publishPlaneInfo(horizontal_planes,
00151                      cloud_msg->header,
00152                      input_cloud,
00153                      pub_horizontal_inliers_,
00154                      pub_horizontal_coefficients_,
00155                      pub_horizontal_polygons_);
00156   }
00157 
00158   void PlaneReasoner::publishPlaneInfo(
00159     std::vector<PlaneInfoContainer>& containers,
00160     const std_msgs::Header& header,
00161     pcl::PointCloud<PointT>::Ptr cloud,
00162     ros::Publisher& pub_inlier,
00163     ros::Publisher& pub_coefficients,
00164     ros::Publisher& pub_polygons)
00165   {
00166     std::vector<pcl::PointIndices::Ptr> inliers;
00167     std::vector<pcl::ModelCoefficients::Ptr> coefficients;
00168     std::vector<geometry_msgs::PolygonStamped> polygons;
00169     for (size_t i = 0; i < containers.size(); i++) {
00170       inliers.push_back(containers[i].get<0>());
00171       coefficients.push_back(containers[i].get<1>());
00172       polygons.push_back(containers[i].get<3>());
00173     }
00174     jsk_recognition_msgs::ClusterPointIndices ros_indices;
00175     jsk_recognition_msgs::ModelCoefficientsArray ros_coefficients;
00176     jsk_recognition_msgs::PolygonArray ros_polygons;
00177     ros_indices.header = header;
00178     ros_coefficients.header = header;
00179     ros_polygons.header = header;
00180     ros_indices.cluster_indices = pcl_conversions::convertToROSPointIndices(
00181       inliers, header);
00182     ros_coefficients.coefficients
00183       = pcl_conversions::convertToROSModelCoefficients(
00184         coefficients, header);
00185     ros_polygons.polygons = polygons;
00186     pub_inlier.publish(ros_indices);
00187     pub_coefficients.publish(ros_coefficients);
00188     pub_polygons.publish(ros_polygons);
00189   }
00190   
00191   std::vector<PlaneInfoContainer>
00192   PlaneReasoner::filterPlanesAroundAngle(
00193     double reference_angle,
00194     double thrshold,
00195     std::vector<PlaneInfoContainer>& infos)
00196   {
00197     
00198     std::vector<PlaneInfoContainer> ret;
00199     for (size_t i = 0; i < infos.size(); i++) {
00200       PlaneInfoContainer plane_info = infos[i];
00201       if (tf_listener_->canTransform(global_frame_id_,
00202                                      plane_info.get<3>().header.frame_id,
00203                                      plane_info.get<3>().header.stamp)) {
00204         tf::StampedTransform transform;
00205         tf_listener_->lookupTransform(plane_info.get<3>().header.frame_id, global_frame_id_,
00206                                       
00207                                       plane_info.get<3>().header.stamp,
00208                                       transform);
00209         Eigen::Affine3d eigen_transform;
00210         tf::transformTFToEigen(transform, eigen_transform);
00211         Eigen::Affine3f eigen_transform_3f;
00212         Eigen::Vector3d up_d =  (eigen_transform.rotation() * Eigen::Vector3d(0, 0, 1));
00213         Eigen::Vector3f up;
00214         jsk_recognition_utils::pointFromVectorToVector<Eigen::Vector3d, Eigen::Vector3f>(up_d, up);
00215         jsk_recognition_utils::Plane::Ptr plane = plane_info.get<2>();
00216         double angle = plane->angle(up);
00217         // ROS_INFO("axis: [%f, %f, %f]", up[0], up[1], up[2]);
00218         // 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]);
00219         // ROS_INFO("angle: %f", angle);
00220         if (fabs(angle - reference_angle) < thrshold) {
00221           ret.push_back(plane_info);
00222         }
00223       }
00224     }
00225     return ret;
00226   }
00227   
00228   std::vector<PlaneInfoContainer>
00229   PlaneReasoner::filterHorizontalPlanes(
00230     std::vector<PlaneInfoContainer>& infos)
00231   {
00232     return filterPlanesAroundAngle(
00233       0,
00234       horizontal_angular_threshold_,
00235       infos);
00236   }
00237   
00238   std::vector<PlaneInfoContainer>
00239   PlaneReasoner::filterVerticalPlanes(
00240     std::vector<PlaneInfoContainer>& infos)
00241   {
00242     return filterPlanesAroundAngle(
00243       M_PI / 2.0,
00244       vertical_angular_threshold_,
00245       infos);
00246   }
00247 
00248   std::vector<PlaneInfoContainer>
00249   PlaneReasoner::packInfo(
00250     std::vector<pcl::PointIndices::Ptr>& inliers,
00251     std::vector<pcl::ModelCoefficients::Ptr>& coefficients,
00252     std::vector<jsk_recognition_utils::Plane::Ptr>& planes,
00253     std::vector<geometry_msgs::PolygonStamped>& polygons)
00254   {
00255     std::vector<PlaneInfoContainer> ret;
00256     for (size_t i = 0; i < inliers.size(); i++) {
00257       ret.push_back(boost::make_tuple<pcl::PointIndices::Ptr,
00258                     pcl::ModelCoefficients::Ptr,
00259                     jsk_recognition_utils::Plane::Ptr>(inliers[i], coefficients[i],
00260                                 planes[i], polygons[i]));
00261     }
00262     return ret;
00263   }
00264 
00265   
00266 }
00267 
00268 #include <pluginlib/class_list_macros.h>
00269 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros_utils::PlaneReasoner, nodelet::Nodelet);


jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Tue Jul 2 2019 19:40:52