hinted_stick_finder.h
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2015, 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 
00037 #ifndef JSK_PCL_ROS_HINTED_STICK_FINDER_H_
00038 #define JSK_PCL_ROS_HINTED_STICK_FINDER_H_
00039 
00040 #include <jsk_topic_tools/diagnostic_nodelet.h>
00041 #include <message_filters/subscriber.h>
00042 #include <message_filters/time_synchronizer.h>
00043 #include <message_filters/synchronizer.h>
00044 #include <message_filters/synchronizer.h>
00045 #include <message_filters/sync_policies/approximate_time.h>
00046 
00047 #include <sensor_msgs/Image.h>
00048 #include <geometry_msgs/PolygonStamped.h>
00049 #include <sensor_msgs/CameraInfo.h>
00050 #include <sensor_msgs/PointCloud2.h>
00051 
00052 #include <image_geometry/pinhole_camera_model.h>
00053 #include "jsk_pcl_ros/geo_util.h"
00054 #include <dynamic_reconfigure/server.h>
00055 #include <jsk_pcl_ros/HintedStickFinderConfig.h>
00056 
00057 namespace jsk_pcl_ros
00058 {
00059   class HintedStickFinder: public jsk_topic_tools::DiagnosticNodelet
00060   {
00061   public:
00062     typedef message_filters::sync_policies::ApproximateTime<
00063     geometry_msgs::PolygonStamped, // line
00064     sensor_msgs::CameraInfo,       // camera info
00065     sensor_msgs::PointCloud2> ASyncPolicy;
00066     typedef HintedStickFinderConfig Config;
00067     HintedStickFinder(): DiagnosticNodelet("HintedStickFinder") {}
00068   protected:
00069 
00070     virtual void onInit();
00071     virtual void subscribe();
00072     virtual void unsubscribe();
00073     virtual void configCallback(Config &config, uint32_t level);
00074 
00078     virtual void detect(
00079       const geometry_msgs::PolygonStamped::ConstPtr& polygon_msg,
00080       const sensor_msgs::CameraInfo::ConstPtr& camera_info_msg,
00081       const sensor_msgs::PointCloud2::ConstPtr& cloud_msg);
00082 
00086     virtual void cloudCallback(
00087       const sensor_msgs::PointCloud2::ConstPtr& cloud_msg);
00088 
00092     virtual void hintCallback(
00093       const geometry_msgs::PolygonStamped::ConstPtr& hint_msg);
00094 
00098     virtual void infoCallback(
00099       const sensor_msgs::CameraInfo::ConstPtr& info_msg);
00100     
00101     virtual ConvexPolygon::Ptr polygonFromLine(
00102       const geometry_msgs::PolygonStamped::ConstPtr& polygon_msg,
00103       const image_geometry::PinholeCameraModel& model,
00104       Eigen::Vector3f& a,
00105       Eigen::Vector3f& b);
00106     
00107     virtual void filterPointCloud(
00108       const pcl::PointCloud<pcl::PointXYZ>::Ptr& cloud,
00109       const ConvexPolygon::Ptr polygon,
00110       pcl::PointIndices& output_indices);
00111     virtual void normalEstimate(
00112       const pcl::PointCloud<pcl::PointXYZ>::Ptr& cloud,
00113       const pcl::PointIndices::Ptr indices,
00114       pcl::PointCloud<pcl::Normal>& normals,
00115       pcl::PointCloud<pcl::PointXYZ>& normals_cloud);
00116     
00117     virtual void fittingCylinder(
00118       const pcl::PointCloud<pcl::PointXYZ>::Ptr& filtered_cloud,
00119       const pcl::PointCloud<pcl::Normal>::Ptr& cloud_nromals,
00120       const Eigen::Vector3f& a,
00121       const Eigen::Vector3f& b);
00122 
00131     virtual bool rejected2DHint(
00132       const Cylinder::Ptr& cylinder,
00133       const Eigen::Vector3f& a,
00134       const Eigen::Vector3f& b);
00135     
00136     boost::mutex mutex_;
00137     
00138     message_filters::Subscriber<geometry_msgs::PolygonStamped> sub_polygon_;
00139     message_filters::Subscriber<sensor_msgs::CameraInfo> sub_info_;
00140     message_filters::Subscriber<sensor_msgs::PointCloud2> sub_cloud_;
00141     message_filters::Subscriber<sensor_msgs::PointCloud2> sub_normal_;
00142     boost::shared_ptr<message_filters::Synchronizer<ASyncPolicy> > sync_;
00143 
00144     ros::Publisher pub_line_filtered_indices_;
00145     ros::Publisher pub_line_filtered_normal_;
00146     ros::Publisher pub_cylinder_marker_;
00147     ros::Publisher pub_cylinder_pose_;
00148     ros::Publisher pub_inliers_;
00149     ros::Publisher pub_coefficients_;
00150     // params from continuous_mode
00151     ros::Subscriber sub_no_sync_cloud_;
00152     ros::Subscriber sub_no_sync_camera_info_;
00153     ros::Subscriber sub_no_sync_polygon_;
00154     boost::shared_ptr <dynamic_reconfigure::Server<Config> > srv_;
00155     
00156     double max_radius_;
00157     double min_radius_;
00158     double filter_distance_;
00159     double outlier_threshold_;
00160     int max_iteration_;
00161     double eps_angle_;
00162     double min_probability_;
00163     int cylinder_fitting_trial_;
00164     int min_inliers_;
00165     double eps_2d_angle_;
00166     
00170     bool use_normal_;
00171 
00176     bool not_synchronize_;
00177     
00178     sensor_msgs::CameraInfo::ConstPtr latest_camera_info_;
00179     geometry_msgs::PolygonStamped::ConstPtr latest_hint_;
00180     
00181   private:
00182     
00183   };
00184 }
00185 
00186 #endif


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