find_object_on_plane.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_FIND_OBJECT_ON_PLANE_H_
00038 #define JSK_PCL_ROS_FIND_OBJECT_ON_PLANE_H_
00039 
00040 #include <jsk_topic_tools/diagnostic_nodelet.h>
00041 #include <message_filters/subscriber.h>
00042 #include <message_filters/synchronizer.h>
00043 #include <message_filters/sync_policies/exact_time.h>
00044 #include <message_filters/sync_policies/approximate_time.h>
00045 #include <sensor_msgs/Image.h>
00046 #include <sensor_msgs/CameraInfo.h>
00047 #include <pcl_msgs/ModelCoefficients.h>
00048 #include <image_geometry/pinhole_camera_model.h>
00049 #include <pcl_conversions/pcl_conversions.h>
00050 #include <jsk_recognition_utils/geo_util.h>
00051 
00052 namespace jsk_pcl_ros
00053 {
00054   class FindObjectOnPlane: public jsk_topic_tools::DiagnosticNodelet
00055   {
00056   public:
00057     typedef message_filters::sync_policies::ApproximateTime<
00058     sensor_msgs::Image,
00059     sensor_msgs::CameraInfo,
00060     pcl_msgs::ModelCoefficients > SyncPolicy;
00061 
00062     FindObjectOnPlane(): DiagnosticNodelet("FindObjectOnPlane") {}
00063   protected:
00064     virtual void onInit();
00065     virtual void subscribe();
00066     virtual void unsubscribe();
00067     virtual void find(
00068       const sensor_msgs::Image::ConstPtr& image_msg,
00069       const sensor_msgs::CameraInfo::ConstPtr& info_msg,
00070       const pcl_msgs::ModelCoefficients::ConstPtr& polygon_3d_coefficient_msg);
00071     virtual void generateStartPoints(
00072       const cv::Point2f& point_2d,
00073       const image_geometry::PinholeCameraModel& model,
00074       const pcl::ModelCoefficients::Ptr& coefficients,
00075       std::vector<cv::Point3f>& search_points_3d,
00076       std::vector<cv::Point2f>& search_points_2d);
00077     virtual void generateAngles(
00078       const cv::Mat& blob_image, const cv::Point2f& test_point,
00079       std::vector<double>& angles,
00080       std::vector<double>& max_x,
00081       std::vector<double>& max_y,
00082       const image_geometry::PinholeCameraModel& model,
00083       const jsk_recognition_utils::Plane::Ptr& plane);
00084     virtual double drawAngle(
00085       cv::Mat& out_image, const cv::Point2f& test_point, const double angle,
00086       const double max_x, const double max_y,
00087       const image_geometry::PinholeCameraModel& model,
00088       const jsk_recognition_utils::Plane::Ptr& plane,
00089       cv::Scalar color);
00090     Eigen::Vector3f rayPlaneInteersect(
00091       const cv::Point3d& ray,
00092       const jsk_recognition_utils::Plane::Ptr& plane);
00093 
00094     virtual cv::Point2d getUyEnd(
00095       const cv::Point2d& ux_start,
00096       const cv::Point2d& ux_end,
00097       const image_geometry::PinholeCameraModel& model,
00098       const jsk_recognition_utils::Plane::Ptr& plane);
00099       
00100     boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > sync_;
00101     message_filters::Subscriber<sensor_msgs::Image> sub_image_;
00102     message_filters::Subscriber<sensor_msgs::CameraInfo> sub_info_;
00103     message_filters::Subscriber<pcl_msgs::ModelCoefficients> sub_coefficients_;
00104     ros::Publisher pub_min_area_rect_image_;
00105     
00106   private:
00107     
00108   };
00109 }
00110 
00111 #endif


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Sun Oct 8 2017 02:43:49