border_estimator.h
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 
00037 #ifndef JSK_PCL_ROS_BORDER_ESTIMATOR_H_
00038 #define JSK_PCL_ROS_BORDER_ESTIMATOR_H_
00039 
00040 #include <pcl_ros/pcl_nodelet.h>
00041 #include <pcl/range_image/range_image.h>
00042 #include <pcl/features/range_image_border_extractor.h>
00043 
00044 #include <sensor_msgs/PointCloud2.h>
00045 #include <sensor_msgs/CameraInfo.h>
00046 #include "jsk_pcl_ros/pcl_conversion_util.h"
00047 
00048 #include <message_filters/subscriber.h>
00049 #include <message_filters/time_synchronizer.h>
00050 #include <message_filters/synchronizer.h>
00051 
00052 #include "jsk_topic_tools/connection_based_nodelet.h"
00053 
00054 #include <jsk_pcl_ros/BorderEstimatorConfig.h>
00055 #include <dynamic_reconfigure/server.h>
00056 
00057 namespace jsk_pcl_ros
00058 {
00059   class BorderEstimator: public jsk_topic_tools::ConnectionBasedNodelet
00060   {
00061   public:
00062     typedef message_filters::sync_policies::ApproximateTime<
00063     sensor_msgs::PointCloud2, sensor_msgs::CameraInfo> SyncPolicy;
00064     typedef BorderEstimatorConfig Config;
00065   protected:
00066     virtual void onInit();
00067     virtual void estimate(const sensor_msgs::PointCloud2::ConstPtr& msg,
00068                           const sensor_msgs::CameraInfo::ConstPtr& caminfo);
00069     virtual void estimate(const sensor_msgs::PointCloud2::ConstPtr& msg);
00070     virtual void computeBorder(
00071       const pcl::RangeImage& image,
00072       const std_msgs::Header& header);
00073     virtual void publishCloud(ros::Publisher& pub,
00074                               const pcl::PointIndices& inlier,
00075                               const std_msgs::Header& header);
00076     
00077     virtual void subscribe();
00078     virtual void unsubscribe();
00079     virtual void configCallback(Config &config, uint32_t level);
00080     message_filters::Subscriber<sensor_msgs::PointCloud2> sub_point_;
00081     message_filters::Subscriber<sensor_msgs::CameraInfo> sub_camera_info_;
00082     boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> >sync_;
00083     boost::shared_ptr <dynamic_reconfigure::Server<Config> > srv_;
00084     ros::Publisher pub_border_, pub_veil_, pub_shadow_;
00085     ros::Publisher pub_range_image_;
00086     ros::Publisher pub_cloud_;
00087     ros::Subscriber sub_;
00088     std::string model_type_;
00089     boost::mutex mutex_;
00090     double noise_level_;
00091     double min_range_;
00092     int border_size_;
00093     double angular_resolution_;
00094     double max_angle_height_;
00095     double max_angle_width_;
00096 
00097   private:
00098     
00099   };
00100 }
00101 
00102 #endif


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