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/or 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 
40 #include <jsk_topic_tools/connection_based_nodelet.h>
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 
65  class HeightmapTimeAccumulation:
66  public jsk_topic_tools::ConnectionBasedNodelet
67  {
68  public:
70  typedef HeightmapTimeAccumulationConfig Config;
71  typedef boost::accumulators::accumulator_set<
72  float,
77  HeightmapTimeAccumulation(): ConnectionBasedNodelet() {}
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_;
107  cv::Mat accumulated_heightmap_;
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_;
121  int tf_queue_size_;
122  bool use_offset_;
124  double bilateral_sigma_color_;
125  double bilateral_sigma_space_;
126  bool use_bilateral_;
127  private:
128  };
129 }
130 
131 #endif
jsk_pcl_ros::HeightmapTimeAccumulation::srv_reset_
ros::ServiceServer srv_reset_
Definition: heightmap_time_accumulation.h:142
jsk_pcl_ros::HeightmapTimeAccumulation::prev_from_center_to_fixed_
Eigen::Affine3f prev_from_center_to_fixed_
Definition: heightmap_time_accumulation.h:136
jsk_pcl_ros::HeightmapTimeAccumulation::isValidCell
virtual bool isValidCell(const cv::Point &index, const cv::Mat &map)
Definition: heightmap_time_accumulation_nodelet.cpp:127
jsk_pcl_ros::HeightmapTimeAccumulation::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: heightmap_time_accumulation.h:134
ros::Publisher
stats
std::vector< OneDataStat::Ptr > stats
global variable to store stats.
Definition: depth_camera_error_visualization.cpp:98
jsk_pcl_ros::HeightmapTimeAccumulation::min_y_
double min_y_
Definition: heightmap_time_accumulation.h:150
boost::shared_ptr
jsk_pcl_ros::HeightmapTimeAccumulation::Accumulator
boost::accumulators::accumulator_set< float, boost::accumulators::stats< boost::accumulators::tag::variance, boost::accumulators::tag::count, boost::accumulators::tag::mean > > Accumulator
Definition: heightmap_time_accumulation.h:108
jsk_pcl_ros::HeightmapTimeAccumulation::tf_
tf::TransformListener * tf_
Definition: heightmap_time_accumulation.h:135
sample_simulate_tabletop_cloud.header
header
Definition: sample_simulate_tabletop_cloud.py:162
jsk_pcl_ros::HeightmapTimeAccumulation::unsubscribe
virtual void unsubscribe()
Definition: heightmap_time_accumulation_nodelet.cpp:91
jsk_pcl_ros::HeightmapTimeAccumulation::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: heightmap_time_accumulation_nodelet.cpp:324
jsk_pcl_ros::HeightmapTimeAccumulation::toIndex
virtual cv::Point toIndex(const PointType &p, const cv::Mat &map)
Definition: heightmap_time_accumulation_nodelet.cpp:106
jsk_pcl_ros::HeightmapTimeAccumulation::pub_output_
ros::Publisher pub_output_
Definition: heightmap_time_accumulation.h:140
jsk_pcl_ros::HeightmapTimeAccumulation::pub_config_
ros::Publisher pub_config_
Definition: heightmap_time_accumulation.h:141
jsk_pcl_ros::HeightmapTimeAccumulation::max_x_
double max_x_
Definition: heightmap_time_accumulation.h:151
jsk_pcl_ros::HeightmapTimeAccumulation::Ptr
boost::shared_ptr< HeightmapTimeAccumulation > Ptr
Definition: heightmap_time_accumulation.h:101
jsk_pcl_ros::HeightmapTimeAccumulation::tf_filter_
boost::shared_ptr< tf::MessageFilter< sensor_msgs::Image > > tf_filter_
Definition: heightmap_time_accumulation.h:143
message_filters::Subscriber< sensor_msgs::Image >
ros::ServiceServer
jsk_pcl_ros::HeightmapTimeAccumulation::min_x_
double min_x_
Definition: heightmap_time_accumulation.h:149
jsk_pcl_ros::HeightmapTimeAccumulation::resetCallback
virtual bool resetCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
Definition: heightmap_time_accumulation_nodelet.cpp:315
jsk_pcl_ros::HeightmapTimeAccumulation::configTopicCallback
virtual void configTopicCallback(const jsk_recognition_msgs::HeightmapConfig::ConstPtr &config)
Definition: heightmap_time_accumulation_nodelet.cpp:303
jsk_pcl_ros::HeightmapTimeAccumulation::subscribe
virtual void subscribe()
Definition: heightmap_time_accumulation_nodelet.cpp:87
jsk_pcl_ros::PointType
pcl::PointXYZI PointType
Definition: heightmap_time_accumulation.h:95
jsk_pcl_ros
Definition: add_color_from_image.h:51
message_filter.h
jsk_pcl_ros::HeightmapTimeAccumulation::max_y_
double max_y_
Definition: heightmap_time_accumulation.h:152
jsk_pcl_ros::HeightmapTimeAccumulation::config_
jsk_recognition_msgs::HeightmapConfig::ConstPtr config_
Definition: heightmap_time_accumulation.h:148
subscriber.h
jsk_pcl_ros::HeightmapTimeAccumulation::use_bilateral_
bool use_bilateral_
Definition: heightmap_time_accumulation.h:158
jsk_pcl_ros::HeightmapTimeAccumulation::onInit
virtual void onInit()
Definition: heightmap_time_accumulation_nodelet.cpp:46
jsk_pcl_ros::HeightmapTimeAccumulation::Config
HeightmapTimeAccumulationConfig Config
Definition: heightmap_time_accumulation.h:102
jsk_pcl_ros::HeightmapTimeAccumulation::prev_cloud_
pcl::PointCloud< PointType > prev_cloud_
Definition: heightmap_time_accumulation.h:147
jsk_pcl_ros::HeightmapTimeAccumulation::sub_heightmap_
message_filters::Subscriber< sensor_msgs::Image > sub_heightmap_
Definition: heightmap_time_accumulation.h:144
jsk_pcl_ros::HeightmapTimeAccumulation::sub_previous_pointcloud_
ros::Subscriber sub_previous_pointcloud_
Definition: heightmap_time_accumulation.h:145
jsk_pcl_ros::count
double count(const OneDataStat &d)
wrapper function for count method for boost::function
Definition: one_data_stat.h:144
jsk_pcl_ros::HeightmapTimeAccumulation::bilateral_filter_size_
int bilateral_filter_size_
Definition: heightmap_time_accumulation.h:155
plot_gaussian.mean
mean
Definition: plot_gaussian.py:12
jsk_pcl_ros::HeightmapTimeAccumulation::tf_queue_size_
int tf_queue_size_
Definition: heightmap_time_accumulation.h:153
jsk_pcl_ros::HeightmapTimeAccumulation::fixed_frame_id_
std::string fixed_frame_id_
Definition: heightmap_time_accumulation.h:138
jsk_pcl_ros::HeightmapTimeAccumulation::isValidIndex
virtual bool isValidIndex(const cv::Point &index, const cv::Mat &map)
Definition: heightmap_time_accumulation_nodelet.cpp:121
jsk_pcl_ros::HeightmapTimeAccumulation::bilateral_sigma_color_
double bilateral_sigma_color_
Definition: heightmap_time_accumulation.h:156
pcl_conversion_util.h
jsk_pcl_ros::HeightmapTimeAccumulation::HeightmapTimeAccumulation
HeightmapTimeAccumulation()
Definition: heightmap_time_accumulation.h:109
jsk_pcl_ros::HeightmapTimeAccumulation::accumulate
virtual void accumulate(const sensor_msgs::Image::ConstPtr &new_heightmap)
Definition: heightmap_time_accumulation_nodelet.cpp:133
transform_listener.h
jsk_pcl_ros::HeightmapTimeAccumulation::bilateral_sigma_space_
double bilateral_sigma_space_
Definition: heightmap_time_accumulation.h:157
jsk_pcl_ros::HeightmapTimeAccumulation::center_frame_id_
std::string center_frame_id_
Definition: heightmap_time_accumulation.h:137
jsk_pcl_ros::HeightmapTimeAccumulation::mergedAccmulation
virtual void mergedAccmulation(pcl::PointCloud< PointType > &transformed_pointcloud, cv::Mat &new_heightmap)
Definition: heightmap_time_accumulation_nodelet.cpp:192
heightmap_utils.h
jsk_pcl_ros::HeightmapTimeAccumulation::sub_config_
ros::Subscriber sub_config_
Definition: heightmap_time_accumulation.h:146
tf::TransformListener
jsk_pcl_ros::HeightmapTimeAccumulation::accumulated_heightmap_
cv::Mat accumulated_heightmap_
Definition: heightmap_time_accumulation.h:139
mutex
boost::mutex mutex
global mutex.
Definition: depth_camera_error_visualization.cpp:86
jsk_pcl_ros::HeightmapTimeAccumulation::use_offset_
bool use_offset_
Definition: heightmap_time_accumulation.h:154
jsk_pcl_ros::HeightmapTimeAccumulation::mutex_
boost::mutex mutex_
Definition: heightmap_time_accumulation.h:133
plot_gaussian.variance
variance
Definition: plot_gaussian.py:13
pose_with_covariance_sample.msg
msg
Definition: pose_with_covariance_sample.py:22
sample_pointcloud_localization_client.req
req
Definition: sample_pointcloud_localization_client.py:15
sample_empty_service_caller.res
res
Definition: sample_empty_service_caller.py:14
jsk_pcl_ros::HeightmapTimeAccumulation::publishHeightmap
virtual void publishHeightmap(const cv::Mat &heightmap, const std_msgs::Header &header)
Definition: heightmap_time_accumulation_nodelet.cpp:97
ros::Subscriber
jsk_pcl_ros::HeightmapTimeAccumulation::prevPointCloud
virtual void prevPointCloud(const sensor_msgs::PointCloud2::ConstPtr &msg)
Definition: heightmap_time_accumulation_nodelet.cpp:283
jsk_pcl_ros::HeightmapTimeAccumulation::overwriteAccmulation
virtual void overwriteAccmulation(pcl::PointCloud< PointType > &transformed_pointcloud, cv::Mat &new_heightmap)
Definition: heightmap_time_accumulation_nodelet.cpp:167


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:44