plane_rejector_nodelet.cpp
Go to the documentation of this file.
00001 // -*- mode: C++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2013, Ryohei Ueda and 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_pcl_ros_utils/plane_rejector.h"
00037 #include <pluginlib/class_list_macros.h>
00038 
00039 #include <geometry_msgs/Vector3Stamped.h>
00040 #include <eigen_conversions/eigen_msg.h>
00041 
00042 namespace jsk_pcl_ros_utils
00043 {
00044   void PlaneRejector::onInit()
00045   {
00046     ConnectionBasedNodelet::onInit();
00047     tf_success_.reset(new jsk_recognition_utils::SeriesedBoolean(30));
00048     listener_ = jsk_recognition_utils::TfListenerSingleton::getInstance();
00049     double vital_rate;
00050     pnh_->param("vital_rate", vital_rate, 1.0);
00051     vital_checker_.reset(
00052       new jsk_topic_tools::VitalChecker(1 / vital_rate));
00053     
00054     diagnostic_updater_.reset(new diagnostic_updater::Updater);
00055     diagnostic_updater_->setHardwareID(getName());
00056     diagnostic_updater_->add(
00057       getName() + "::PlaneRejector",
00058       boost::bind(
00059         &PlaneRejector::updateDiagnosticsPlaneRejector,
00060         this, _1));
00061     if (!pnh_->getParam("processing_frame_id", processing_frame_id_)) {
00062       NODELET_FATAL("You need to specify ~processing_frame_id");
00063       return;
00064     }
00065     pnh_->param("use_inliers", use_inliers_, false);
00066     pnh_->param("allow_flip", allow_flip_, false);
00067 
00068     std::vector<double> reference_axis;
00069     if (!jsk_topic_tools::readVectorParameter(
00070           *pnh_, "reference_axis", reference_axis)) {
00071       NODELET_FATAL("you need to specify ~reference_axis");
00072       return;
00073     }
00074     else if (reference_axis.size() != 3){
00075       NODELET_FATAL("~reference_axis is not 3 length vector");
00076       return;
00077     }
00078     else {
00079       jsk_recognition_utils::pointFromVectorToVector(reference_axis, reference_axis_);
00080       reference_axis_.normalize();
00081     }
00082     
00083     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00084     dynamic_reconfigure::Server<Config>::CallbackType f =
00085       boost::bind (&PlaneRejector::configCallback, this, _1, _2);
00086     srv_->setCallback (f);
00087     
00088     polygons_pub_ = advertise<jsk_recognition_msgs::PolygonArray>(
00089       *pnh_, "output_polygons", 1);
00090     coefficients_pub_ = advertise<jsk_recognition_msgs::ModelCoefficientsArray>(
00091       *pnh_, "output_coefficients", 1);
00092     if (use_inliers_) {
00093       inliers_pub_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(*pnh_, "output_inliers", 1);
00094     }
00095     else {
00096     }
00097     diagnostics_timer_ = pnh_->createTimer(
00098       ros::Duration(1.0),
00099       boost::bind(&PlaneRejector::updateDiagnostics,
00100                   this,
00101                   _1));
00102     onInitPostProcess();
00103   }
00104 
00105   void PlaneRejector::subscribe()
00106   {
00107     if (use_inliers_) {
00108       sync_inlier_ = boost::make_shared<message_filters::Synchronizer<SyncInlierPolicy> >(100);
00109       sub_polygons_.subscribe(*pnh_, "input_polygons", 1);
00110       sub_coefficients_.subscribe(*pnh_, "input_coefficients", 1);
00111       sub_inliers_.subscribe(*pnh_, "input_inliers", 1);
00112       sync_inlier_->connectInput(sub_polygons_, sub_coefficients_, sub_inliers_);
00113       sync_inlier_->registerCallback(boost::bind(&PlaneRejector::reject, this, _1, _2, _3));
00114     }
00115     else {
00116       sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00117       sub_polygons_.subscribe(*pnh_, "input_polygons", 1);
00118       sub_coefficients_.subscribe(*pnh_, "input_coefficients", 1);
00119       sync_->connectInput(sub_polygons_, sub_coefficients_);
00120       sync_->registerCallback(boost::bind(&PlaneRejector::reject, this, _1, _2));
00121     }
00122   }
00123 
00124   void PlaneRejector::unsubscribe()
00125   {
00126     sub_polygons_.unsubscribe();
00127     sub_coefficients_.unsubscribe();
00128   }
00129   
00130   void PlaneRejector::updateDiagnosticsPlaneRejector(
00131     diagnostic_updater::DiagnosticStatusWrapper &stat)
00132   {
00133     bool alivep = vital_checker_->isAlive();
00134     // check tf successeed or not
00135     if (alivep) {
00136       if (tf_success_->getValue()) {
00137         stat.summary(diagnostic_msgs::DiagnosticStatus::OK,
00138                      "PlaneRejector running");
00139       }
00140       else {
00141         stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR,
00142                      "failed to tf transform");
00143       }
00144       stat.add("Input planes (Avg.)", input_plane_counter_.mean());
00145       stat.add("Rejected Planes (Avg.)", rejected_plane_counter_.mean());
00146       stat.add("Passed Planes (Avg.)", passed_plane_counter_.mean());
00147       stat.add("Angular Threahold", angle_thr_);
00148       stat.add("Reference Axis",
00149                (boost::format("[%f, %f, %f]")
00150                 % (reference_axis_[0])
00151                 %  (reference_axis_[1])
00152                 % (reference_axis_[2])).str());
00153       stat.add("Processing Frame ID", processing_frame_id_);
00154     }
00155     else {
00156       stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR,
00157                    "PlaneRejector not running");
00158     }
00159     
00160   }
00161   
00162   void PlaneRejector::updateDiagnostics(const ros::TimerEvent& event)
00163   {
00164     boost::mutex::scoped_lock lock(mutex_);
00165     diagnostic_updater_->update();
00166   }
00167   
00168   void PlaneRejector::configCallback (Config &config, uint32_t level)
00169   {
00170     boost::mutex::scoped_lock lock(mutex_);
00171     angle_thr_ = config.angle_thr;
00172     angle_ = config.angle;
00173   }
00174   
00175   void PlaneRejector::reject(
00176     const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons,
00177     const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients)
00178   {
00179     reject(polygons, coefficients, jsk_recognition_msgs::ClusterPointIndices::ConstPtr());
00180   }
00181 
00182   void PlaneRejector::reject(
00183     const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons,
00184     const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients,
00185     const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& inliers)
00186   {
00187     boost::mutex::scoped_lock lock(mutex_);
00188     vital_checker_->poke();
00189     jsk_recognition_msgs::PolygonArray result_polygons;
00190     jsk_recognition_msgs::ModelCoefficientsArray result_coefficients;
00191     jsk_recognition_msgs::ClusterPointIndices result_inliers;
00192     result_polygons.header = polygons->header;
00193     result_coefficients.header = coefficients->header;
00194     result_inliers.header = polygons->header;
00195     input_plane_counter_.add(polygons->polygons.size());
00196     int rejected_plane_counter = 0;
00197     int passed_plane_counter = 0;
00198     for (size_t i = 0; i < polygons->polygons.size(); i++) {
00199       geometry_msgs::PolygonStamped polygon = polygons->polygons[i];
00200       PCLModelCoefficientMsg coefficient = coefficients->coefficients[i];
00201       // transform the coefficients to processing_frame_id_
00202       if (listener_->canTransform(coefficient.header.frame_id,
00203                                   processing_frame_id_,
00204                                   coefficient.header.stamp)) {
00205         tf_success_->addValue(true);
00206         geometry_msgs::Vector3Stamped plane_axis;
00207         plane_axis.header = coefficient.header;
00208         plane_axis.vector.x = coefficient.values[0];
00209         plane_axis.vector.y = coefficient.values[1];
00210         plane_axis.vector.z = coefficient.values[2];
00211         geometry_msgs::Vector3Stamped transformed_plane_axis;
00212         listener_->transformVector(processing_frame_id_,
00213                                    plane_axis,
00214                                    transformed_plane_axis);
00215         Eigen::Vector3d eigen_transformed_plane_axis;
00216         tf::vectorMsgToEigen(transformed_plane_axis.vector,
00217                              eigen_transformed_plane_axis);
00218         if (allow_flip_ && eigen_transformed_plane_axis.normalized().dot(reference_axis_) < 0) {
00219           // flip normal vector to make its direction same as reference axis
00220           eigen_transformed_plane_axis = -eigen_transformed_plane_axis;
00221         }
00222         double ang = std::abs(acos(eigen_transformed_plane_axis.normalized().dot(reference_axis_)) - angle_);
00223         if (ang < angle_thr_) {
00224           ++passed_plane_counter;
00225           result_polygons.polygons.push_back(polygons->polygons[i]);
00226           result_coefficients.coefficients.push_back(coefficient);
00227           if (use_inliers_) {
00228             result_inliers.cluster_indices.push_back(inliers->cluster_indices[i]);
00229           }
00230         }
00231         else {
00232           ++rejected_plane_counter;
00233         }
00234       }
00235       else {
00236         tf_success_->addValue(false);
00237      }
00238     }
00239     rejected_plane_counter_.add(rejected_plane_counter);
00240     passed_plane_counter_.add(passed_plane_counter);
00241     polygons_pub_.publish(result_polygons);
00242     coefficients_pub_.publish(result_coefficients);
00243     if (use_inliers_) {
00244       inliers_pub_.publish(result_inliers);
00245     }
00246     diagnostic_updater_->update();
00247   }
00248   
00249 }
00250 
00251 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros_utils::PlaneRejector, nodelet::Nodelet);


jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Sun Oct 8 2017 02:43:05