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_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 <sensor_msgs/PointCloud2.h> 00043 #include <sensor_msgs/Image.h> 00044 #include <opencv2/opencv.hpp> 00045 #include "jsk_pcl_ros/pcl_conversion_util.h" 00046 #include <tf/transform_listener.h> 00047 #include <tf/message_filter.h> 00048 #include <message_filters/subscriber.h> 00049 #include "jsk_pcl_ros/heightmap_utils.h" 00050 #include <std_srvs/Empty.h> 00051 00052 namespace jsk_pcl_ros 00053 { 00054 class HeightmapTimeAccumulation: 00055 public jsk_topic_tools::ConnectionBasedNodelet 00056 { 00057 public: 00058 typedef boost::shared_ptr<HeightmapTimeAccumulation> Ptr; 00059 HeightmapTimeAccumulation(): ConnectionBasedNodelet() {} 00060 protected: 00061 virtual void onInit(); 00062 virtual void subscribe(); 00063 virtual void unsubscribe(); 00064 virtual void accumulate( 00065 const sensor_msgs::Image::ConstPtr& new_heightmap); 00066 virtual void publishHeightmap( 00067 const cv::Mat& heightmap, const std_msgs::Header& header); 00068 virtual cv::Point toIndex(const pcl::PointXYZ& p, const cv::Mat& map); 00069 virtual bool isValidIndex(const cv::Point& index, const cv::Mat& map); 00070 virtual bool isValidCell(const cv::Point& index, const cv::Mat& map); 00071 virtual void configCallback( 00072 const jsk_recognition_msgs::HeightmapConfig::ConstPtr& config); 00073 virtual void prevPointCloud( 00074 const sensor_msgs::PointCloud2::ConstPtr& msg); 00075 virtual bool resetCallback(std_srvs::Empty::Request& req, 00076 std_srvs::Empty::Response& res); 00077 00078 boost::mutex mutex_; 00079 tf::TransformListener* tf_; 00080 Eigen::Affine3f prev_from_center_to_fixed_; 00081 std::string center_frame_id_; 00082 std::string fixed_frame_id_; 00083 cv::Mat accumulated_heightmap_; 00084 ros::Publisher pub_output_; 00085 ros::Publisher pub_config_; 00086 ros::ServiceServer srv_reset_; 00087 boost::shared_ptr<tf::MessageFilter<sensor_msgs::Image> > tf_filter_; 00088 message_filters::Subscriber<sensor_msgs::Image> sub_heightmap_; 00089 ros::Subscriber sub_previous_pointcloud_; 00090 ros::Subscriber sub_config_; 00091 pcl::PointCloud<pcl::PointXYZ> prev_cloud_; 00092 jsk_recognition_msgs::HeightmapConfig::ConstPtr config_; 00093 double min_x_; 00094 double min_y_; 00095 double max_x_; 00096 double max_y_; 00097 int tf_queue_size_; 00098 private: 00099 }; 00100 } 00101 00102 #endif