00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2013, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of Willow Garage nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 *********************************************************************/ 00034 00035 /* Author: Ioan Sucan */ 00036 00037 #ifndef MOVEIT_OCCUPANCY_MAP_DEPTH_IMAGE_OCCUPANCY_MAP_UPDATER_ 00038 #define MOVEIT_OCCUPANCY_MAP_DEPTH_IMAGE_OCCUPANCY_MAP_UPDATER_ 00039 00040 #include <ros/ros.h> 00041 #include <tf/tf.h> 00042 #include <moveit/occupancy_map_monitor/occupancy_map_updater.h> 00043 #include <moveit/mesh_filter/mesh_filter.h> 00044 #include <moveit/mesh_filter/stereo_camera_model.h> 00045 #include <moveit/lazy_free_space_updater/lazy_free_space_updater.h> 00046 #include <image_transport/image_transport.h> 00047 #include <boost/scoped_ptr.hpp> 00048 00049 namespace occupancy_map_monitor 00050 { 00051 class DepthImageOctomapUpdater : public OccupancyMapUpdater 00052 { 00053 public: 00054 DepthImageOctomapUpdater(); 00055 virtual ~DepthImageOctomapUpdater(); 00056 00057 virtual bool setParams(XmlRpc::XmlRpcValue& params); 00058 virtual bool initialize(); 00059 virtual void start(); 00060 virtual void stop(); 00061 virtual ShapeHandle excludeShape(const shapes::ShapeConstPtr& shape); 00062 virtual void forgetShape(ShapeHandle handle); 00063 00064 private: 00065 void depthImageCallback(const sensor_msgs::ImageConstPtr& depth_msg, const sensor_msgs::CameraInfoConstPtr& info_msg); 00066 bool getShapeTransform(mesh_filter::MeshHandle h, Eigen::Affine3d& transform) const; 00067 void stopHelper(); 00068 00069 ros::NodeHandle nh_; 00070 boost::shared_ptr<tf::Transformer> tf_; 00071 image_transport::ImageTransport input_depth_transport_; 00072 image_transport::ImageTransport model_depth_transport_; 00073 image_transport::ImageTransport filtered_depth_transport_; 00074 image_transport::ImageTransport filtered_label_transport_; 00075 00076 image_transport::CameraSubscriber sub_depth_image_; 00077 image_transport::CameraPublisher pub_model_depth_image_; 00078 image_transport::CameraPublisher pub_filtered_depth_image_; 00079 image_transport::CameraPublisher pub_filtered_label_image_; 00080 00081 std::string filtered_cloud_topic_; 00082 std::string sensor_type_; 00083 std::string image_topic_; 00084 std::size_t queue_size_; 00085 double near_clipping_plane_distance_; 00086 double far_clipping_plane_distance_; 00087 double shadow_threshold_; 00088 double padding_scale_; 00089 double padding_offset_; 00090 unsigned int skip_vertical_pixels_; 00091 unsigned int skip_horizontal_pixels_; 00092 00093 unsigned int image_callback_count_; 00094 double average_callback_dt_; 00095 unsigned int good_tf_; 00096 unsigned int failed_tf_; 00097 00098 boost::scoped_ptr<mesh_filter::MeshFilter<mesh_filter::StereoCameraModel> > mesh_filter_; 00099 boost::scoped_ptr<LazyFreeSpaceUpdater> free_space_updater_; 00100 00101 std::vector<float> x_cache_, y_cache_; 00102 double inv_fx_, inv_fy_, K0_, K2_, K4_, K5_; 00103 std::vector<unsigned int> filtered_labels_; 00104 ros::WallTime last_depth_callback_start_; 00105 }; 00106 } 00107 00108 #endif