snapit_nodelet.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2013, JSK Lab
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/o2r other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the JSK Lab nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 #include "jsk_pcl_ros/snapit.h"
00036 #include <pluginlib/class_list_macros.h>
00037 #include <geometry_msgs/PolygonStamped.h>
00038 #include <Eigen/StdVector>
00039 #include <pcl/ModelCoefficients.h>
00040 #include <pcl/filters/project_inliers.h>
00041 #include <pcl/filters/extract_indices.h>
00042 #include <pcl/sample_consensus/method_types.h>
00043 #include <pcl/sample_consensus/model_types.h>
00044 #include <pcl/segmentation/sac_segmentation.h>
00045 #include <pcl/common/distances.h>
00046 #include <pcl/features/normal_3d.h>
00047 #include <pcl/surface/concave_hull.h>
00048 #include <pcl/common/centroid.h>
00049 #include <visualization_msgs/Marker.h>
00050 #include <eigen_conversions/eigen_msg.h>
00051 #include <tf_conversions/tf_eigen.h>
00052 #include <eigen_conversions/eigen_msg.h>
00053 #include "jsk_pcl_ros/pcl_conversion_util.h"
00054 #include <visualization_msgs/MarkerArray.h>
00055 #include <algorithm>
00056 
00057 namespace jsk_pcl_ros
00058 {
00059   void SnapIt::onInit()
00060   {
00061     DiagnosticNodelet::onInit();
00062     tf_listener_ = TfListenerSingleton::getInstance();
00063     pnh_->param("use_service", use_service_, false);
00064     polygon_aligned_pub_ = advertise<geometry_msgs::PoseStamped>(
00065       *pnh_, "output/plane_aligned", 1);
00066     convex_aligned_pub_ = advertise<geometry_msgs::PoseStamped>(
00067       *pnh_, "output/convex_aligned", 1);
00068     convex_aligned_pose_array_pub_ = advertise<geometry_msgs::PoseArray>(
00069       *pnh_, "output/convex_aligned_pose_array", 1);
00070     if (use_service_) {
00071       subscribe();
00072       align_footstep_srv_ = pnh_->advertiseService(
00073         "align_footstep", &SnapIt::footstepAlignServiceCallback, this);
00074     }
00075   }
00076 
00077   void SnapIt::subscribe()
00078   {
00079     sub_polygons_.subscribe(*pnh_, "input/polygons", 1);
00080     sub_coefficients_.subscribe(*pnh_, "input/polygon_coefficients", 1);
00081     sync_polygon_
00082       = boost::make_shared<message_filters::Synchronizer<SyncPolygonPolicy> >(100);
00083     sync_polygon_->connectInput(sub_polygons_, sub_coefficients_);
00084     sync_polygon_->registerCallback(
00085       boost::bind(&SnapIt::polygonCallback, this, _1, _2));
00086     polygon_align_sub_ = pnh_->subscribe("input/plane_align", 1,
00087                                          &SnapIt::polygonAlignCallback, this);
00088     convex_align_sub_ = pnh_->subscribe("input/convex_align", 1,
00089                                         &SnapIt::convexAlignCallback, this);
00090     convex_align_polygon_sub_ = pnh_->subscribe(
00091       "input/convex_align_polygon", 1,
00092       &SnapIt::convexAlignPolygonCallback, this);
00093   }
00094 
00095   void SnapIt::unsubscribe()
00096   {
00097     if (!use_service_) {
00098       sub_polygons_.unsubscribe();
00099       sub_coefficients_.unsubscribe();
00100       polygon_align_sub_.shutdown();
00101       convex_align_sub_.shutdown();
00102     }
00103     polygons_.reset();
00104   }
00105   
00106   void SnapIt::polygonCallback(
00107     const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg,
00108     const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg)
00109   {
00110     boost::mutex::scoped_lock lock(mutex_);
00111     vital_checker_->poke();
00112     polygons_ = polygon_msg;
00113   }
00114 
00115   void SnapIt::polygonAlignCallback(
00116     const geometry_msgs::PoseStamped::ConstPtr& pose_msg)
00117   {
00118     boost::mutex::scoped_lock lock(mutex_);
00119     if (!polygons_) {
00120       JSK_NODELET_ERROR("no polygon is ready");
00121       polygon_aligned_pub_.publish(pose_msg);
00122       return;
00123     }
00124     std::vector<ConvexPolygon::Ptr> convexes
00125       = createConvexes(pose_msg->header.frame_id,
00126                        pose_msg->header.stamp,
00127                        polygons_);
00128     Eigen::Affine3d pose_eigend;
00129     Eigen::Affine3f pose_eigen;
00130     tf::poseMsgToEigen(pose_msg->pose, pose_eigend);
00131     convertEigenAffine3(pose_eigend, pose_eigen);
00132     Eigen::Vector3f pose_point(pose_eigen.translation());
00133     double min_distance = DBL_MAX;
00134     ConvexPolygon::Ptr min_convex;
00135     for (size_t i = 0; i < convexes.size(); i++) {
00136       ConvexPolygon::Ptr convex = convexes[i];
00137       double d = convex->distanceToPoint(pose_point);
00138       if (d < min_distance) {
00139         min_convex = convex;
00140         min_distance = d;
00141       }
00142     }
00143     
00144     if (min_convex) {
00145       geometry_msgs::PoseStamped aligned_pose = alignPose(pose_eigen, min_convex);
00146       aligned_pose.header = pose_msg->header;
00147       polygon_aligned_pub_.publish(aligned_pose);
00148     }
00149     else {
00150       polygon_aligned_pub_.publish(pose_msg);
00151     }
00152   }
00153 
00154   bool SnapIt::footstepAlignServiceCallback(
00155     jsk_pcl_ros::SnapFootstep::Request& req,
00156     jsk_pcl_ros::SnapFootstep::Response& res)
00157   {
00158     boost::mutex::scoped_lock lock(mutex_);
00159     jsk_footstep_msgs::FootstepArray input_footsteps = req.input;
00160     res.output.header = input_footsteps.header;
00161     std::vector<ConvexPolygon::Ptr> convexes
00162       = createConvexes(input_footsteps.header.frame_id,
00163                        input_footsteps.header.stamp,
00164                        polygons_);
00165     for (size_t i = 0; i < input_footsteps.footsteps.size(); i++) {
00166       jsk_footstep_msgs::Footstep footstep = input_footsteps.footsteps[i];
00167       Eigen::Affine3d pose_eigend;
00168       Eigen::Affine3f pose_eigen;
00169       tf::poseMsgToEigen(footstep.pose, pose_eigen);
00170       Eigen::Vector3f pose_point(pose_eigen.translation());
00171       int min_index = findNearestConvex(pose_point, convexes);
00172       jsk_footstep_msgs::Footstep aligned_footstep;
00173       if (min_index != -1) {
00174         ConvexPolygon::Ptr min_convex = convexes[min_index];
00175         geometry_msgs::PoseStamped aligned_pose = alignPose(pose_eigen, min_convex);
00176         aligned_footstep.pose = aligned_pose.pose;
00177       }
00178       else {
00179         aligned_footstep.pose = footstep.pose;
00180         //convex_aligned_pub_.publish(pose_msg); // shoud we publish this?
00181       }
00182       aligned_footstep.leg = footstep.leg;
00183       aligned_footstep.dimensions = footstep.dimensions;
00184       aligned_footstep.duration = footstep.duration;
00185       aligned_footstep.footstep_group = footstep.footstep_group;
00186       res.output.footsteps.push_back(aligned_footstep);
00187     }
00188     return true;
00189   }
00190 
00191   void SnapIt::convexAlignPolygonCallback(
00192     const geometry_msgs::PolygonStamped::ConstPtr& poly_msg)
00193   {
00194     boost::mutex::scoped_lock lock(mutex_);
00195     geometry_msgs::PoseArray pose_array;
00196     pose_array.header = poly_msg->header;
00197     if (!polygons_) {
00198       JSK_NODELET_ERROR("no polygon is ready");
00199       return;
00200     }
00201     std::vector<ConvexPolygon::Ptr> convexes
00202       = createConvexes(poly_msg->header.frame_id,
00203                        poly_msg->header.stamp,
00204                        polygons_);
00205     for (size_t i = 0; i < poly_msg->polygon.points.size(); i++) {
00206       geometry_msgs::Point32 p = poly_msg->polygon.points[i];
00207       Eigen::Vector3f pose_point(p.x, p.y, p.z);
00208       int min_index = findNearestConvex(pose_point, convexes);
00209       if (min_index == -1) {
00210         JSK_NODELET_ERROR("cannot project onto convex");
00211         return;
00212       }
00213       else {
00214         ConvexPolygon::Ptr min_convex = convexes[min_index];
00215         Eigen::Affine3f pose_eigen = Eigen::Affine3f::Identity();
00216         pose_eigen.translate(pose_point);
00217         geometry_msgs::PoseStamped aligned_pose = alignPose(pose_eigen, min_convex);
00218         aligned_pose.header = poly_msg->header;
00219         pose_array.poses.push_back(aligned_pose.pose);
00220       }
00221     }
00222     convex_aligned_pose_array_pub_.publish(pose_array);
00223   }
00224   
00225   int SnapIt::findNearestConvex(
00226     const Eigen::Vector3f& pose_point, 
00227     const std::vector<ConvexPolygon::Ptr>& convexes)
00228   {
00229     int min_index = -1;
00230     double min_distance = DBL_MAX;
00231     ConvexPolygon::Ptr min_convex;
00232     for (size_t i = 0; i < convexes.size(); i++) {
00233       ConvexPolygon::Ptr convex = convexes[i];
00234       if (convex->isProjectableInside(pose_point)) {
00235         double d = convex->distanceToPoint(pose_point);
00236         if (d < min_distance) {
00237           min_distance = d;
00238           min_convex = convex;
00239           min_index = i;
00240         }
00241       }
00242     }
00243     return min_index;
00244   }
00245 
00246   void SnapIt::convexAlignCallback(
00247       const geometry_msgs::PoseStamped::ConstPtr& pose_msg)
00248   {
00249     boost::mutex::scoped_lock lock(mutex_);
00250     if (!polygons_) {
00251       JSK_NODELET_ERROR("no polygon is ready");
00252       convex_aligned_pub_.publish(pose_msg);
00253       return;
00254     }
00255     std::vector<ConvexPolygon::Ptr> convexes
00256       = createConvexes(pose_msg->header.frame_id,
00257                        pose_msg->header.stamp,
00258                        polygons_);
00259     Eigen::Affine3d pose_eigend;
00260     Eigen::Affine3f pose_eigen;
00261     tf::poseMsgToEigen(pose_msg->pose, pose_eigend);
00262     convertEigenAffine3(pose_eigend, pose_eigen);
00263     Eigen::Vector3f pose_point(pose_eigen.translation());
00264     int min_index = findNearestConvex(pose_point, convexes);
00265     if (min_index != -1) {
00266       ConvexPolygon::Ptr min_convex = convexes[min_index];
00267       geometry_msgs::PoseStamped aligned_pose = alignPose(pose_eigen, min_convex);
00268       aligned_pose.header = pose_msg->header;
00269       convex_aligned_pub_.publish(aligned_pose);
00270     }
00271     else {
00272       convex_aligned_pub_.publish(pose_msg); // shoud we publish this?
00273     }
00274   }
00275 
00276   geometry_msgs::PoseStamped SnapIt::alignPose(
00277     Eigen::Affine3f& pose, ConvexPolygon::Ptr convex)
00278   {
00279     Eigen::Affine3f aligned_pose(pose);
00280     Eigen::Vector3f original_point(pose.translation());
00281     Eigen::Vector3f projected_point;
00282     convex->project(original_point, projected_point);
00283     
00284     Eigen::Vector3f normal = convex->getNormal();
00285     Eigen::Vector3f old_normal;
00286     old_normal[0] = pose(0, 2);
00287     old_normal[1] = pose(1, 2);
00288     old_normal[2] = pose(2, 2);
00289     Eigen::Quaternionf rot;
00290     if (normal.dot(old_normal) < 0) {
00291       normal = - normal;
00292     }
00293     rot.setFromTwoVectors(old_normal, normal);
00294     aligned_pose = aligned_pose * rot;
00295     aligned_pose.translation() = projected_point;
00296     Eigen::Affine3d aligned_posed;
00297     convertEigenAffine3(aligned_pose, aligned_posed);
00298     geometry_msgs::PoseStamped ret;
00299     tf::poseEigenToMsg(aligned_posed, ret.pose);
00300     return ret;
00301   }
00302   
00303   std::vector<ConvexPolygon::Ptr> SnapIt::createConvexes(
00304     const std::string& frame_id, const ros::Time& stamp,
00305     jsk_recognition_msgs::PolygonArray::ConstPtr polygons)
00306   {
00307     std::vector<ConvexPolygon::Ptr> result;
00308     try
00309     {
00310       for (size_t i = 0; i < polygons->polygons.size(); i++) {
00311         geometry_msgs::PolygonStamped polygon = polygons->polygons[i];
00312         Vertices vertices;
00313         
00314         tf::StampedTransform transform = lookupTransformWithDuration(
00315           tf_listener_,
00316           polygon.header.frame_id, frame_id, stamp, ros::Duration(5.0));
00317         for (size_t j = 0; j < polygon.polygon.points.size(); j++) {
00318           Eigen::Vector4d p;
00319           p[0] = polygon.polygon.points[j].x;
00320           p[1] = polygon.polygon.points[j].y;
00321           p[2] = polygon.polygon.points[j].z;
00322           p[3] = 1;
00323           Eigen::Affine3d eigen_transform;
00324           tf::transformTFToEigen(transform, eigen_transform);
00325           Eigen::Vector4d transformed_pointd = eigen_transform.inverse() * p;
00326           Eigen::Vector3f transformed_point;
00327           transformed_point[0] = transformed_pointd[0];
00328           transformed_point[1] = transformed_pointd[1];
00329           transformed_point[2] = transformed_pointd[2];
00330           vertices.push_back(transformed_point);
00331         }
00332         std::reverse(vertices.begin(), vertices.end());
00333         ConvexPolygon::Ptr convex(new ConvexPolygon(vertices));
00334         result.push_back(convex);
00335       }
00336     }
00337     catch (tf2::ConnectivityException &e)
00338     {
00339       JSK_NODELET_ERROR("Transform error: %s", e.what());
00340     }
00341     catch (tf2::InvalidArgumentException &e)
00342     {
00343       JSK_NODELET_ERROR("Transform error: %s", e.what());
00344     }
00345     catch (tf2::ExtrapolationException &e)
00346     {
00347       JSK_NODELET_ERROR("Transform error: %s", e.what());
00348     }
00349     return result;
00350   }
00351 }
00352 
00353 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::SnapIt, nodelet::Nodelet);


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Wed Sep 16 2015 04:36:48