Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 
00037 #ifndef JSK_PCL_ROS_HEIGHTMAP_TIME_ACCUMULATION_H_
00038 #define JSK_PCL_ROS_HEIGHTMAP_TIME_ACCUMULATION_H_
00039 
00040 #include <jsk_topic_tools/connection_based_nodelet.h>
00041 #include <jsk_recognition_msgs/HeightmapConfig.h>
00042 #include <jsk_pcl_ros/HeightmapTimeAccumulationConfig.h>
00043 #include <dynamic_reconfigure/server.h>
00044 #include <sensor_msgs/PointCloud2.h>
00045 #include <sensor_msgs/Image.h>
00046 #include <opencv2/opencv.hpp>
00047 #include "jsk_recognition_utils/pcl_conversion_util.h"
00048 #include <tf/transform_listener.h>
00049 #include <tf/message_filter.h>
00050 #include <message_filters/subscriber.h>
00051 #include "jsk_pcl_ros/heightmap_utils.h"
00052 #include <std_srvs/Empty.h>
00053 
00054 
00055 #include <boost/accumulators/accumulators.hpp>
00056 #include <boost/accumulators/statistics/mean.hpp>
00057 #include <boost/accumulators/statistics/variance.hpp>
00058 #include <boost/accumulators/statistics/count.hpp>
00059 #include <boost/accumulators/statistics/stats.hpp>
00060 
00061 namespace jsk_pcl_ros
00062 {
00063   typedef pcl::PointXYZI PointType;
00064 
00065   class HeightmapTimeAccumulation:
00066     public jsk_topic_tools::ConnectionBasedNodelet
00067   {
00068   public:
00069     typedef boost::shared_ptr<HeightmapTimeAccumulation> Ptr;
00070     typedef HeightmapTimeAccumulationConfig Config;
00071     typedef boost::accumulators::accumulator_set<
00072       float,
00073       boost::accumulators::stats<
00074         boost::accumulators::tag::variance,
00075         boost::accumulators::tag::count,
00076         boost::accumulators::tag::mean> >  Accumulator;
00077     HeightmapTimeAccumulation(): ConnectionBasedNodelet() {}
00078   protected:
00079     virtual void onInit();
00080     virtual void subscribe();
00081     virtual void unsubscribe();
00082     virtual void accumulate(
00083       const sensor_msgs::Image::ConstPtr& new_heightmap);
00084     virtual void publishHeightmap(
00085       const cv::Mat& heightmap, const std_msgs::Header& header);
00086     virtual cv::Point toIndex(const PointType& p, const cv::Mat& map);
00087     virtual bool isValidIndex(const cv::Point& index, const cv::Mat& map);
00088     virtual bool isValidCell(const cv::Point& index, const cv::Mat& map);
00089     virtual void configTopicCallback(
00090       const jsk_recognition_msgs::HeightmapConfig::ConstPtr& config);
00091     virtual void prevPointCloud(
00092       const sensor_msgs::PointCloud2::ConstPtr& msg);
00093     virtual bool resetCallback(std_srvs::Empty::Request& req,
00094                                std_srvs::Empty::Response& res);
00095     virtual void overwriteAccmulation(pcl::PointCloud<PointType > &transformed_pointcloud,
00096                                       cv::Mat &new_heightmap);
00097     virtual void mergedAccmulation(pcl::PointCloud<PointType > &transformed_pointcloud,
00098                                    cv::Mat &new_heightmap);
00099     virtual void configCallback(Config& config, uint32_t level);
00100 
00101     boost::mutex mutex_;
00102     boost::shared_ptr<dynamic_reconfigure::Server<Config> > srv_;
00103     tf::TransformListener* tf_;
00104     Eigen::Affine3f prev_from_center_to_fixed_;
00105     std::string center_frame_id_;
00106     std::string fixed_frame_id_;
00107     cv::Mat accumulated_heightmap_;
00108     ros::Publisher pub_output_;
00109     ros::Publisher pub_config_;
00110     ros::ServiceServer srv_reset_;
00111     boost::shared_ptr<tf::MessageFilter<sensor_msgs::Image> > tf_filter_;
00112     message_filters::Subscriber<sensor_msgs::Image> sub_heightmap_;
00113     ros::Subscriber sub_previous_pointcloud_;
00114     ros::Subscriber sub_config_;
00115     pcl::PointCloud<PointType> prev_cloud_;
00116     jsk_recognition_msgs::HeightmapConfig::ConstPtr config_;
00117     double min_x_;
00118     double min_y_;
00119     double max_x_;
00120     double max_y_;
00121     int tf_queue_size_;
00122     bool use_offset_;
00123     int bilateral_filter_size_;
00124     double bilateral_sigma_color_;
00125     double bilateral_sigma_space_;
00126     bool use_bilateral_;
00127   private:
00128   };
00129 }
00130 
00131 #endif