depth_image_octomap_updater.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan */
36 
37 #pragma once
38 
39 #include <ros/ros.h>
40 #include <tf2_ros/buffer.h>
46 #include <memory>
47 
48 namespace occupancy_map_monitor
49 {
50 class DepthImageOctomapUpdater : public OccupancyMapUpdater
51 {
52 public:
54  ~DepthImageOctomapUpdater() override;
55 
56  bool setParams(XmlRpc::XmlRpcValue& params) override;
57  bool initialize() override;
58  void start() override;
59  void stop() override;
60  ShapeHandle excludeShape(const shapes::ShapeConstPtr& shape) override;
61  void forgetShape(ShapeHandle handle) override;
62 
63 private:
64  void depthImageCallback(const sensor_msgs::ImageConstPtr& depth_msg, const sensor_msgs::CameraInfoConstPtr& info_msg);
65  bool getShapeTransform(mesh_filter::MeshHandle h, Eigen::Isometry3d& transform) const;
66  void stopHelper();
67 
69  std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
74 
79 
81 
82  std::string filtered_cloud_topic_;
83  std::string ns_;
84  std::string sensor_type_;
85  std::string image_topic_;
86  std::size_t queue_size_;
89  double shadow_threshold_;
90  double padding_scale_;
91  double padding_offset_;
92  double max_update_rate_;
93  unsigned int skip_vertical_pixels_;
94  unsigned int skip_horizontal_pixels_;
95 
96  unsigned int image_callback_count_;
97  double average_callback_dt_;
98  unsigned int good_tf_;
99  unsigned int failed_tf_;
100 
101  std::unique_ptr<mesh_filter::MeshFilter<mesh_filter::StereoCameraModel> > mesh_filter_;
102  std::unique_ptr<LazyFreeSpaceUpdater> free_space_updater_;
103 
104  std::vector<float> x_cache_, y_cache_;
105  double inv_fx_, inv_fy_, K0_, K2_, K4_, K5_;
106  std::vector<unsigned int> filtered_labels_;
108 };
109 } // namespace occupancy_map_monitor
occupancy_map_monitor::DepthImageOctomapUpdater::filtered_labels_
std::vector< unsigned int > filtered_labels_
Definition: depth_image_octomap_updater.h:170
occupancy_map_monitor::DepthImageOctomapUpdater::failed_tf_
unsigned int failed_tf_
Definition: depth_image_octomap_updater.h:163
lazy_free_space_updater.h
occupancy_map_monitor::DepthImageOctomapUpdater::pub_model_depth_image_
image_transport::CameraPublisher pub_model_depth_image_
Definition: depth_image_octomap_updater.h:140
occupancy_map_monitor::DepthImageOctomapUpdater::max_update_rate_
double max_update_rate_
Definition: depth_image_octomap_updater.h:156
image_transport::ImageTransport
ros.h
occupancy_map_monitor::DepthImageOctomapUpdater::setParams
bool setParams(XmlRpc::XmlRpcValue &params) override
Definition: depth_image_octomap_updater.cpp:119
occupancy_map_monitor::DepthImageOctomapUpdater::K2_
double K2_
Definition: depth_image_octomap_updater.h:169
occupancy_map_monitor::DepthImageOctomapUpdater::K4_
double K4_
Definition: depth_image_octomap_updater.h:169
buffer.h
occupancy_map_monitor::DepthImageOctomapUpdater::image_callback_count_
unsigned int image_callback_count_
Definition: depth_image_octomap_updater.h:160
occupancy_map_monitor::DepthImageOctomapUpdater::free_space_updater_
std::unique_ptr< LazyFreeSpaceUpdater > free_space_updater_
Definition: depth_image_octomap_updater.h:166
occupancy_map_monitor::DepthImageOctomapUpdater::filtered_cloud_topic_
std::string filtered_cloud_topic_
Definition: depth_image_octomap_updater.h:146
occupancy_map_monitor::DepthImageOctomapUpdater::x_cache_
std::vector< float > x_cache_
Definition: depth_image_octomap_updater.h:168
stereo_camera_model.h
occupancy_map_monitor::DepthImageOctomapUpdater::queue_size_
std::size_t queue_size_
Definition: depth_image_octomap_updater.h:150
mesh_filter.h
occupancy_map_monitor::DepthImageOctomapUpdater::K5_
double K5_
Definition: depth_image_octomap_updater.h:169
occupancy_map_monitor::DepthImageOctomapUpdater::sensor_type_
std::string sensor_type_
Definition: depth_image_octomap_updater.h:148
occupancy_map_monitor::DepthImageOctomapUpdater::last_depth_callback_start_
ros::WallTime last_depth_callback_start_
Definition: depth_image_octomap_updater.h:171
occupancy_map_monitor::DepthImageOctomapUpdater::shadow_threshold_
double shadow_threshold_
Definition: depth_image_octomap_updater.h:153
occupancy_map_monitor::DepthImageOctomapUpdater::tf_buffer_
std::shared_ptr< tf2_ros::Buffer > tf_buffer_
Definition: depth_image_octomap_updater.h:133
image_transport::CameraSubscriber
occupancy_map_monitor::DepthImageOctomapUpdater::ns_
std::string ns_
Definition: depth_image_octomap_updater.h:147
occupancy_map_monitor::DepthImageOctomapUpdater::stop
void stop() override
Definition: depth_image_octomap_updater.cpp:190
occupancy_map_monitor::DepthImageOctomapUpdater::image_topic_
std::string image_topic_
Definition: depth_image_octomap_updater.h:149
image_transport::CameraPublisher
occupancy_map_monitor::DepthImageOctomapUpdater::good_tf_
unsigned int good_tf_
Definition: depth_image_octomap_updater.h:162
occupancy_map_monitor::DepthImageOctomapUpdater::last_update_time_
ros::Time last_update_time_
Definition: depth_image_octomap_updater.h:144
occupancy_map_monitor::DepthImageOctomapUpdater::getShapeTransform
bool getShapeTransform(mesh_filter::MeshHandle h, Eigen::Isometry3d &transform) const
Definition: depth_image_octomap_updater.cpp:225
ros::WallTime
occupancy_map_monitor::DepthImageOctomapUpdater::average_callback_dt_
double average_callback_dt_
Definition: depth_image_octomap_updater.h:161
occupancy_map_monitor::DepthImageOctomapUpdater::nh_
ros::NodeHandle nh_
Definition: depth_image_octomap_updater.h:132
occupancy_map_monitor::DepthImageOctomapUpdater::padding_offset_
double padding_offset_
Definition: depth_image_octomap_updater.h:155
image_transport.h
occupancy_map_monitor::DepthImageOctomapUpdater::input_depth_transport_
image_transport::ImageTransport input_depth_transport_
Definition: depth_image_octomap_updater.h:134
occupancy_map_monitor::DepthImageOctomapUpdater::K0_
double K0_
Definition: depth_image_octomap_updater.h:169
ShapeHandle
unsigned int ShapeHandle
occupancy_map_monitor::DepthImageOctomapUpdater::excludeShape
ShapeHandle excludeShape(const shapes::ShapeConstPtr &shape) override
Definition: depth_image_octomap_updater.cpp:200
mesh_filter::MeshHandle
unsigned int MeshHandle
Definition: mesh_filter_base.h:60
ros::Time
occupancy_map_monitor::DepthImageOctomapUpdater::forgetShape
void forgetShape(ShapeHandle handle) override
Definition: depth_image_octomap_updater.cpp:219
occupancy_map_monitor::DepthImageOctomapUpdater::start
void start() override
Definition: depth_image_octomap_updater.cpp:170
occupancy_map_monitor::DepthImageOctomapUpdater::filtered_label_transport_
image_transport::ImageTransport filtered_label_transport_
Definition: depth_image_octomap_updater.h:137
occupancy_map_monitor::DepthImageOctomapUpdater::y_cache_
std::vector< float > y_cache_
Definition: depth_image_octomap_updater.h:168
occupancy_map_monitor::DepthImageOctomapUpdater::DepthImageOctomapUpdater
DepthImageOctomapUpdater()
Definition: depth_image_octomap_updater.cpp:85
occupancy_map_monitor::DepthImageOctomapUpdater::filtered_depth_transport_
image_transport::ImageTransport filtered_depth_transport_
Definition: depth_image_octomap_updater.h:136
occupancy_map_monitor::DepthImageOctomapUpdater::model_depth_transport_
image_transport::ImageTransport model_depth_transport_
Definition: depth_image_octomap_updater.h:135
occupancy_map_monitor::DepthImageOctomapUpdater::pub_filtered_label_image_
image_transport::CameraPublisher pub_filtered_label_image_
Definition: depth_image_octomap_updater.h:142
occupancy_map_monitor
shapes::ShapeConstPtr
std::shared_ptr< const Shape > ShapeConstPtr
occupancy_map_monitor::DepthImageOctomapUpdater::far_clipping_plane_distance_
double far_clipping_plane_distance_
Definition: depth_image_octomap_updater.h:152
occupancy_map_monitor::DepthImageOctomapUpdater::mesh_filter_
std::unique_ptr< mesh_filter::MeshFilter< mesh_filter::StereoCameraModel > > mesh_filter_
Definition: depth_image_octomap_updater.h:165
occupancy_map_monitor::DepthImageOctomapUpdater::initialize
bool initialize() override
Definition: depth_image_octomap_updater.cpp:152
occupancy_map_monitor::DepthImageOctomapUpdater::padding_scale_
double padding_scale_
Definition: depth_image_octomap_updater.h:154
occupancy_map_monitor::DepthImageOctomapUpdater::pub_filtered_depth_image_
image_transport::CameraPublisher pub_filtered_depth_image_
Definition: depth_image_octomap_updater.h:141
occupancy_map_monitor::DepthImageOctomapUpdater::depthImageCallback
void depthImageCallback(const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
Definition: depth_image_octomap_updater.cpp:252
occupancy_map_monitor::DepthImageOctomapUpdater::inv_fx_
double inv_fx_
Definition: depth_image_octomap_updater.h:169
occupancy_map_monitor::DepthImageOctomapUpdater::inv_fy_
double inv_fy_
Definition: depth_image_octomap_updater.h:169
occupancy_map_monitor::DepthImageOctomapUpdater::skip_horizontal_pixels_
unsigned int skip_horizontal_pixels_
Definition: depth_image_octomap_updater.h:158
occupancy_map_monitor::DepthImageOctomapUpdater::stopHelper
void stopHelper()
Definition: depth_image_octomap_updater.cpp:195
occupancy_map_monitor::DepthImageOctomapUpdater::~DepthImageOctomapUpdater
~DepthImageOctomapUpdater() override
Definition: depth_image_octomap_updater.cpp:114
occupancy_map_monitor::DepthImageOctomapUpdater::skip_vertical_pixels_
unsigned int skip_vertical_pixels_
Definition: depth_image_octomap_updater.h:157
XmlRpc::XmlRpcValue
occupancy_map_monitor::DepthImageOctomapUpdater::near_clipping_plane_distance_
double near_clipping_plane_distance_
Definition: depth_image_octomap_updater.h:151
occupancy_map_monitor::DepthImageOctomapUpdater::sub_depth_image_
image_transport::CameraSubscriber sub_depth_image_
Definition: depth_image_octomap_updater.h:139
ros::NodeHandle
occupancy_map_updater.h


perception
Author(s): Ioan Sucan , Jon Binney , Suat Gedikli
autogenerated on Mon May 27 2024 02:27:57