Public Member Functions | Private Member Functions | Private Attributes | List of all members
occupancy_map_monitor::DepthImageOctomapUpdater Class Reference

#include <depth_image_octomap_updater.h>

Inheritance diagram for occupancy_map_monitor::DepthImageOctomapUpdater:
Inheritance graph
[legend]

Public Member Functions

 DepthImageOctomapUpdater ()
 
ShapeHandle excludeShape (const shapes::ShapeConstPtr &shape) override
 
void forgetShape (ShapeHandle handle) override
 
bool initialize () override
 
bool setParams (XmlRpc::XmlRpcValue &params) override
 
void start () override
 
void stop () override
 
 ~DepthImageOctomapUpdater () override
 
- Public Member Functions inherited from occupancy_map_monitor::OccupancyMapUpdater
const std::string & getType () const
 
 OccupancyMapUpdater (const std::string &type)
 
void publishDebugInformation (bool flag)
 
void setMonitor (OccupancyMapMonitor *monitor)
 
void setTransformCacheCallback (const TransformCacheProvider &transform_callback)
 
virtual ~OccupancyMapUpdater ()
 

Private Member Functions

void depthImageCallback (const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
 
bool getShapeTransform (mesh_filter::MeshHandle h, Eigen::Isometry3d &transform) const
 
void stopHelper ()
 

Private Attributes

double average_callback_dt_
 
unsigned int failed_tf_
 
double far_clipping_plane_distance_
 
std::string filtered_cloud_topic_
 
image_transport::ImageTransport filtered_depth_transport_
 
image_transport::ImageTransport filtered_label_transport_
 
std::vector< unsigned int > filtered_labels_
 
std::unique_ptr< LazyFreeSpaceUpdaterfree_space_updater_
 
unsigned int good_tf_
 
unsigned int image_callback_count_
 
std::string image_topic_
 
image_transport::ImageTransport input_depth_transport_
 
double inv_fx_
 
double inv_fy_
 
double K0_
 
double K2_
 
double K4_
 
double K5_
 
ros::WallTime last_depth_callback_start_
 
ros::Time last_update_time_
 
double max_update_rate_
 
std::unique_ptr< mesh_filter::MeshFilter< mesh_filter::StereoCameraModel > > mesh_filter_
 
image_transport::ImageTransport model_depth_transport_
 
double near_clipping_plane_distance_
 
ros::NodeHandle nh_
 
std::string ns_
 
double padding_offset_
 
double padding_scale_
 
image_transport::CameraPublisher pub_filtered_depth_image_
 
image_transport::CameraPublisher pub_filtered_label_image_
 
image_transport::CameraPublisher pub_model_depth_image_
 
std::size_t queue_size_
 
std::string sensor_type_
 
double shadow_threshold_
 
unsigned int skip_horizontal_pixels_
 
unsigned int skip_vertical_pixels_
 
image_transport::CameraSubscriber sub_depth_image_
 
std::shared_ptr< tf2_ros::Buffertf_buffer_
 
std::vector< float > x_cache_
 
std::vector< float > y_cache_
 

Additional Inherited Members

- Protected Member Functions inherited from occupancy_map_monitor::OccupancyMapUpdater
bool updateTransformCache (const std::string &target_frame, const ros::Time &target_time)
 
- Static Protected Member Functions inherited from occupancy_map_monitor::OccupancyMapUpdater
static void readXmlParam (XmlRpc::XmlRpcValue &params, const std::string &param_name, double *value)
 
static void readXmlParam (XmlRpc::XmlRpcValue &params, const std::string &param_name, unsigned int *value)
 
- Protected Attributes inherited from occupancy_map_monitor::OccupancyMapUpdater
bool debug_info_
 
OccupancyMapMonitormonitor_
 
ShapeTransformCache transform_cache_
 
TransformCacheProvider transform_provider_callback_
 
collision_detection::OccMapTreePtr tree_
 
std::string type_
 

Detailed Description

Definition at line 82 of file depth_image_octomap_updater.h.

Constructor & Destructor Documentation

◆ DepthImageOctomapUpdater()

occupancy_map_monitor::DepthImageOctomapUpdater::DepthImageOctomapUpdater ( )

Definition at line 85 of file depth_image_octomap_updater.cpp.

◆ ~DepthImageOctomapUpdater()

occupancy_map_monitor::DepthImageOctomapUpdater::~DepthImageOctomapUpdater ( )
override

Definition at line 114 of file depth_image_octomap_updater.cpp.

Member Function Documentation

◆ depthImageCallback()

void occupancy_map_monitor::DepthImageOctomapUpdater::depthImageCallback ( const sensor_msgs::ImageConstPtr &  depth_msg,
const sensor_msgs::CameraInfoConstPtr &  info_msg 
)
private

Definition at line 252 of file depth_image_octomap_updater.cpp.

◆ excludeShape()

mesh_filter::MeshHandle occupancy_map_monitor::DepthImageOctomapUpdater::excludeShape ( const shapes::ShapeConstPtr shape)
overridevirtual

◆ forgetShape()

void occupancy_map_monitor::DepthImageOctomapUpdater::forgetShape ( ShapeHandle  handle)
overridevirtual

◆ getShapeTransform()

bool occupancy_map_monitor::DepthImageOctomapUpdater::getShapeTransform ( mesh_filter::MeshHandle  h,
Eigen::Isometry3d &  transform 
) const
private

Definition at line 225 of file depth_image_octomap_updater.cpp.

◆ initialize()

bool occupancy_map_monitor::DepthImageOctomapUpdater::initialize ( )
overridevirtual

◆ setParams()

bool occupancy_map_monitor::DepthImageOctomapUpdater::setParams ( XmlRpc::XmlRpcValue params)
overridevirtual

◆ start()

void occupancy_map_monitor::DepthImageOctomapUpdater::start ( )
overridevirtual

◆ stop()

void occupancy_map_monitor::DepthImageOctomapUpdater::stop ( )
overridevirtual

◆ stopHelper()

void occupancy_map_monitor::DepthImageOctomapUpdater::stopHelper ( )
private

Definition at line 195 of file depth_image_octomap_updater.cpp.

Member Data Documentation

◆ average_callback_dt_

double occupancy_map_monitor::DepthImageOctomapUpdater::average_callback_dt_
private

Definition at line 161 of file depth_image_octomap_updater.h.

◆ failed_tf_

unsigned int occupancy_map_monitor::DepthImageOctomapUpdater::failed_tf_
private

Definition at line 163 of file depth_image_octomap_updater.h.

◆ far_clipping_plane_distance_

double occupancy_map_monitor::DepthImageOctomapUpdater::far_clipping_plane_distance_
private

Definition at line 152 of file depth_image_octomap_updater.h.

◆ filtered_cloud_topic_

std::string occupancy_map_monitor::DepthImageOctomapUpdater::filtered_cloud_topic_
private

Definition at line 146 of file depth_image_octomap_updater.h.

◆ filtered_depth_transport_

image_transport::ImageTransport occupancy_map_monitor::DepthImageOctomapUpdater::filtered_depth_transport_
private

Definition at line 136 of file depth_image_octomap_updater.h.

◆ filtered_label_transport_

image_transport::ImageTransport occupancy_map_monitor::DepthImageOctomapUpdater::filtered_label_transport_
private

Definition at line 137 of file depth_image_octomap_updater.h.

◆ filtered_labels_

std::vector<unsigned int> occupancy_map_monitor::DepthImageOctomapUpdater::filtered_labels_
private

Definition at line 170 of file depth_image_octomap_updater.h.

◆ free_space_updater_

std::unique_ptr<LazyFreeSpaceUpdater> occupancy_map_monitor::DepthImageOctomapUpdater::free_space_updater_
private

Definition at line 166 of file depth_image_octomap_updater.h.

◆ good_tf_

unsigned int occupancy_map_monitor::DepthImageOctomapUpdater::good_tf_
private

Definition at line 162 of file depth_image_octomap_updater.h.

◆ image_callback_count_

unsigned int occupancy_map_monitor::DepthImageOctomapUpdater::image_callback_count_
private

Definition at line 160 of file depth_image_octomap_updater.h.

◆ image_topic_

std::string occupancy_map_monitor::DepthImageOctomapUpdater::image_topic_
private

Definition at line 149 of file depth_image_octomap_updater.h.

◆ input_depth_transport_

image_transport::ImageTransport occupancy_map_monitor::DepthImageOctomapUpdater::input_depth_transport_
private

Definition at line 134 of file depth_image_octomap_updater.h.

◆ inv_fx_

double occupancy_map_monitor::DepthImageOctomapUpdater::inv_fx_
private

Definition at line 169 of file depth_image_octomap_updater.h.

◆ inv_fy_

double occupancy_map_monitor::DepthImageOctomapUpdater::inv_fy_
private

Definition at line 169 of file depth_image_octomap_updater.h.

◆ K0_

double occupancy_map_monitor::DepthImageOctomapUpdater::K0_
private

Definition at line 169 of file depth_image_octomap_updater.h.

◆ K2_

double occupancy_map_monitor::DepthImageOctomapUpdater::K2_
private

Definition at line 169 of file depth_image_octomap_updater.h.

◆ K4_

double occupancy_map_monitor::DepthImageOctomapUpdater::K4_
private

Definition at line 169 of file depth_image_octomap_updater.h.

◆ K5_

double occupancy_map_monitor::DepthImageOctomapUpdater::K5_
private

Definition at line 169 of file depth_image_octomap_updater.h.

◆ last_depth_callback_start_

ros::WallTime occupancy_map_monitor::DepthImageOctomapUpdater::last_depth_callback_start_
private

Definition at line 171 of file depth_image_octomap_updater.h.

◆ last_update_time_

ros::Time occupancy_map_monitor::DepthImageOctomapUpdater::last_update_time_
private

Definition at line 144 of file depth_image_octomap_updater.h.

◆ max_update_rate_

double occupancy_map_monitor::DepthImageOctomapUpdater::max_update_rate_
private

Definition at line 156 of file depth_image_octomap_updater.h.

◆ mesh_filter_

std::unique_ptr<mesh_filter::MeshFilter<mesh_filter::StereoCameraModel> > occupancy_map_monitor::DepthImageOctomapUpdater::mesh_filter_
private

Definition at line 165 of file depth_image_octomap_updater.h.

◆ model_depth_transport_

image_transport::ImageTransport occupancy_map_monitor::DepthImageOctomapUpdater::model_depth_transport_
private

Definition at line 135 of file depth_image_octomap_updater.h.

◆ near_clipping_plane_distance_

double occupancy_map_monitor::DepthImageOctomapUpdater::near_clipping_plane_distance_
private

Definition at line 151 of file depth_image_octomap_updater.h.

◆ nh_

ros::NodeHandle occupancy_map_monitor::DepthImageOctomapUpdater::nh_
private

Definition at line 132 of file depth_image_octomap_updater.h.

◆ ns_

std::string occupancy_map_monitor::DepthImageOctomapUpdater::ns_
private

Definition at line 147 of file depth_image_octomap_updater.h.

◆ padding_offset_

double occupancy_map_monitor::DepthImageOctomapUpdater::padding_offset_
private

Definition at line 155 of file depth_image_octomap_updater.h.

◆ padding_scale_

double occupancy_map_monitor::DepthImageOctomapUpdater::padding_scale_
private

Definition at line 154 of file depth_image_octomap_updater.h.

◆ pub_filtered_depth_image_

image_transport::CameraPublisher occupancy_map_monitor::DepthImageOctomapUpdater::pub_filtered_depth_image_
private

Definition at line 141 of file depth_image_octomap_updater.h.

◆ pub_filtered_label_image_

image_transport::CameraPublisher occupancy_map_monitor::DepthImageOctomapUpdater::pub_filtered_label_image_
private

Definition at line 142 of file depth_image_octomap_updater.h.

◆ pub_model_depth_image_

image_transport::CameraPublisher occupancy_map_monitor::DepthImageOctomapUpdater::pub_model_depth_image_
private

Definition at line 140 of file depth_image_octomap_updater.h.

◆ queue_size_

std::size_t occupancy_map_monitor::DepthImageOctomapUpdater::queue_size_
private

Definition at line 150 of file depth_image_octomap_updater.h.

◆ sensor_type_

std::string occupancy_map_monitor::DepthImageOctomapUpdater::sensor_type_
private

Definition at line 148 of file depth_image_octomap_updater.h.

◆ shadow_threshold_

double occupancy_map_monitor::DepthImageOctomapUpdater::shadow_threshold_
private

Definition at line 153 of file depth_image_octomap_updater.h.

◆ skip_horizontal_pixels_

unsigned int occupancy_map_monitor::DepthImageOctomapUpdater::skip_horizontal_pixels_
private

Definition at line 158 of file depth_image_octomap_updater.h.

◆ skip_vertical_pixels_

unsigned int occupancy_map_monitor::DepthImageOctomapUpdater::skip_vertical_pixels_
private

Definition at line 157 of file depth_image_octomap_updater.h.

◆ sub_depth_image_

image_transport::CameraSubscriber occupancy_map_monitor::DepthImageOctomapUpdater::sub_depth_image_
private

Definition at line 139 of file depth_image_octomap_updater.h.

◆ tf_buffer_

std::shared_ptr<tf2_ros::Buffer> occupancy_map_monitor::DepthImageOctomapUpdater::tf_buffer_
private

Definition at line 133 of file depth_image_octomap_updater.h.

◆ x_cache_

std::vector<float> occupancy_map_monitor::DepthImageOctomapUpdater::x_cache_
private

Definition at line 168 of file depth_image_octomap_updater.h.

◆ y_cache_

std::vector<float> occupancy_map_monitor::DepthImageOctomapUpdater::y_cache_
private

Definition at line 168 of file depth_image_octomap_updater.h.


The documentation for this class was generated from the following files:


perception
Author(s): Ioan Sucan , Jon Binney , Suat Gedikli
autogenerated on Wed Feb 21 2024 03:26:19