heightmap_time_accumulation.h
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2015, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/o2r other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 
37 #ifndef JSK_PCL_ROS_HEIGHTMAP_TIME_ACCUMULATION_H_
38 #define JSK_PCL_ROS_HEIGHTMAP_TIME_ACCUMULATION_H_
39 
41 #include <jsk_recognition_msgs/HeightmapConfig.h>
42 #include <jsk_pcl_ros/HeightmapTimeAccumulationConfig.h>
43 #include <dynamic_reconfigure/server.h>
44 #include <sensor_msgs/PointCloud2.h>
45 #include <sensor_msgs/Image.h>
46 #include <opencv2/opencv.hpp>
48 #include <tf/transform_listener.h>
49 #include <tf/message_filter.h>
52 #include <std_srvs/Empty.h>
53 
54 // accumulate
55 #include <boost/accumulators/accumulators.hpp>
56 #include <boost/accumulators/statistics/mean.hpp>
57 #include <boost/accumulators/statistics/variance.hpp>
58 #include <boost/accumulators/statistics/count.hpp>
59 #include <boost/accumulators/statistics/stats.hpp>
60 
61 namespace jsk_pcl_ros
62 {
63  typedef pcl::PointXYZI PointType;
64 
67  {
68  public:
70  typedef HeightmapTimeAccumulationConfig Config;
71  typedef boost::accumulators::accumulator_set<
72  float,
78  protected:
79  virtual void onInit();
80  virtual void subscribe();
81  virtual void unsubscribe();
82  virtual void accumulate(
83  const sensor_msgs::Image::ConstPtr& new_heightmap);
84  virtual void publishHeightmap(
85  const cv::Mat& heightmap, const std_msgs::Header& header);
86  virtual cv::Point toIndex(const PointType& p, const cv::Mat& map);
87  virtual bool isValidIndex(const cv::Point& index, const cv::Mat& map);
88  virtual bool isValidCell(const cv::Point& index, const cv::Mat& map);
89  virtual void configTopicCallback(
90  const jsk_recognition_msgs::HeightmapConfig::ConstPtr& config);
91  virtual void prevPointCloud(
92  const sensor_msgs::PointCloud2::ConstPtr& msg);
93  virtual bool resetCallback(std_srvs::Empty::Request& req,
94  std_srvs::Empty::Response& res);
95  virtual void overwriteAccmulation(pcl::PointCloud<PointType > &transformed_pointcloud,
96  cv::Mat &new_heightmap);
97  virtual void mergedAccmulation(pcl::PointCloud<PointType > &transformed_pointcloud,
98  cv::Mat &new_heightmap);
99  virtual void configCallback(Config& config, uint32_t level);
100 
104  Eigen::Affine3f prev_from_center_to_fixed_;
105  std::string center_frame_id_;
106  std::string fixed_frame_id_;
115  pcl::PointCloud<PointType> prev_cloud_;
116  jsk_recognition_msgs::HeightmapConfig::ConstPtr config_;
117  double min_x_;
118  double min_y_;
119  double max_x_;
120  double max_y_;
127  private:
128  };
129 }
130 
131 #endif
virtual void configTopicCallback(const jsk_recognition_msgs::HeightmapConfig::ConstPtr &config)
virtual bool resetCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
std::vector< OneDataStat::Ptr > stats
global variable to store stats.
boost::shared_ptr< HeightmapTimeAccumulation > Ptr
message_filters::Subscriber< sensor_msgs::Image > sub_heightmap_
jsk_recognition_msgs::HeightmapConfig::ConstPtr config_
config
virtual bool isValidCell(const cv::Point &index, const cv::Mat &map)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
virtual void prevPointCloud(const sensor_msgs::PointCloud2::ConstPtr &msg)
pcl::PointXYZI PointType
float
unsigned int index
virtual bool isValidIndex(const cv::Point &index, const cv::Mat &map)
virtual void configCallback(Config &config, uint32_t level)
virtual void overwriteAccmulation(pcl::PointCloud< PointType > &transformed_pointcloud, cv::Mat &new_heightmap)
virtual void mergedAccmulation(pcl::PointCloud< PointType > &transformed_pointcloud, cv::Mat &new_heightmap)
boost::accumulators::accumulator_set< float, boost::accumulators::stats< boost::accumulators::tag::variance, boost::accumulators::tag::count, boost::accumulators::tag::mean > > Accumulator
virtual cv::Point toIndex(const PointType &p, const cv::Mat &map)
virtual void publishHeightmap(const cv::Mat &heightmap, const std_msgs::Header &header)
virtual void accumulate(const sensor_msgs::Image::ConstPtr &new_heightmap)
boost::mutex mutex
global mutex.
p
double count(const OneDataStat &d)
wrapper function for count method for boost::function
boost::shared_ptr< tf::MessageFilter< sensor_msgs::Image > > tf_filter_


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:46