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

#include <pointcloud_octomap_updater.h>

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

Public Member Functions

ShapeHandle excludeShape (const shapes::ShapeConstPtr &shape) override
 
void forgetShape (ShapeHandle handle) override
 
bool initialize () override
 
 PointCloudOctomapUpdater ()
 
bool setParams (XmlRpc::XmlRpcValue &params) override
 
void start () override
 
void stop () override
 
 ~PointCloudOctomapUpdater () 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 ()
 

Protected Member Functions

virtual void updateMask (const sensor_msgs::PointCloud2 &cloud, const Eigen::Vector3d &sensor_origin, std::vector< int > &mask)
 
- Protected Member Functions inherited from occupancy_map_monitor::OccupancyMapUpdater
bool updateTransformCache (const std::string &target_frame, const ros::Time &target_time)
 

Private Member Functions

void cloudMsgCallback (const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)
 
bool getShapeTransform (ShapeHandle h, Eigen::Isometry3d &transform) const
 
void stopHelper ()
 

Private Attributes

ros::Publisher filtered_cloud_publisher_
 
std::string filtered_cloud_topic_
 
octomap::KeyRay key_ray_
 
ros::Time last_update_time_
 
std::vector< int > mask_
 
double max_range_
 
double max_update_rate_
 
std::string ns_
 
double padding_
 
tf2_ros::MessageFilter< sensor_msgs::PointCloud2 > * point_cloud_filter_
 
message_filters::Subscriber< sensor_msgs::PointCloud2 > * point_cloud_subscriber_
 
std::string point_cloud_topic_
 
unsigned int point_subsample_
 
ros::NodeHandle private_nh_
 
ros::NodeHandle root_nh_
 
double scale_
 
std::unique_ptr< point_containment_filter::ShapeMaskshape_mask_
 
std::shared_ptr< tf2_ros::Buffertf_buffer_
 
std::shared_ptr< tf2_ros::TransformListenertf_listener_
 

Additional Inherited Members

- 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 83 of file pointcloud_octomap_updater.h.

Constructor & Destructor Documentation

◆ PointCloudOctomapUpdater()

occupancy_map_monitor::PointCloudOctomapUpdater::PointCloudOctomapUpdater ( )

Definition at line 83 of file pointcloud_octomap_updater.cpp.

◆ ~PointCloudOctomapUpdater()

occupancy_map_monitor::PointCloudOctomapUpdater::~PointCloudOctomapUpdater ( )
override

Definition at line 96 of file pointcloud_octomap_updater.cpp.

Member Function Documentation

◆ cloudMsgCallback()

void occupancy_map_monitor::PointCloudOctomapUpdater::cloudMsgCallback ( const sensor_msgs::PointCloud2::ConstPtr &  cloud_msg)
private

Definition at line 213 of file pointcloud_octomap_updater.cpp.

◆ excludeShape()

ShapeHandle occupancy_map_monitor::PointCloudOctomapUpdater::excludeShape ( const shapes::ShapeConstPtr shape)
overridevirtual

◆ forgetShape()

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

◆ getShapeTransform()

bool occupancy_map_monitor::PointCloudOctomapUpdater::getShapeTransform ( ShapeHandle  h,
Eigen::Isometry3d &  transform 
) const
private

Definition at line 198 of file pointcloud_octomap_updater.cpp.

◆ initialize()

bool occupancy_map_monitor::PointCloudOctomapUpdater::initialize ( )
overridevirtual

◆ setParams()

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

◆ start()

void occupancy_map_monitor::PointCloudOctomapUpdater::start ( )
overridevirtual

◆ stop()

void occupancy_map_monitor::PointCloudOctomapUpdater::stop ( )
overridevirtual

◆ stopHelper()

void occupancy_map_monitor::PointCloudOctomapUpdater::stopHelper ( )
private

Definition at line 169 of file pointcloud_octomap_updater.cpp.

◆ updateMask()

void occupancy_map_monitor::PointCloudOctomapUpdater::updateMask ( const sensor_msgs::PointCloud2 &  cloud,
const Eigen::Vector3d sensor_origin,
std::vector< int > &  mask 
)
protectedvirtual

Definition at line 208 of file pointcloud_octomap_updater.cpp.

Member Data Documentation

◆ filtered_cloud_publisher_

ros::Publisher occupancy_map_monitor::PointCloudOctomapUpdater::filtered_cloud_publisher_
private

Definition at line 155 of file pointcloud_octomap_updater.h.

◆ filtered_cloud_topic_

std::string occupancy_map_monitor::PointCloudOctomapUpdater::filtered_cloud_topic_
private

Definition at line 153 of file pointcloud_octomap_updater.h.

◆ key_ray_

octomap::KeyRay occupancy_map_monitor::PointCloudOctomapUpdater::key_ray_
private

Definition at line 162 of file pointcloud_octomap_updater.h.

◆ last_update_time_

ros::Time occupancy_map_monitor::PointCloudOctomapUpdater::last_update_time_
private

Definition at line 144 of file pointcloud_octomap_updater.h.

◆ mask_

std::vector<int> occupancy_map_monitor::PointCloudOctomapUpdater::mask_
private

Definition at line 165 of file pointcloud_octomap_updater.h.

◆ max_range_

double occupancy_map_monitor::PointCloudOctomapUpdater::max_range_
private

Definition at line 150 of file pointcloud_octomap_updater.h.

◆ max_update_rate_

double occupancy_map_monitor::PointCloudOctomapUpdater::max_update_rate_
private

Definition at line 152 of file pointcloud_octomap_updater.h.

◆ ns_

std::string occupancy_map_monitor::PointCloudOctomapUpdater::ns_
private

Definition at line 154 of file pointcloud_octomap_updater.h.

◆ padding_

double occupancy_map_monitor::PointCloudOctomapUpdater::padding_
private

Definition at line 149 of file pointcloud_octomap_updater.h.

◆ point_cloud_filter_

tf2_ros::MessageFilter<sensor_msgs::PointCloud2>* occupancy_map_monitor::PointCloudOctomapUpdater::point_cloud_filter_
private

Definition at line 158 of file pointcloud_octomap_updater.h.

◆ point_cloud_subscriber_

message_filters::Subscriber<sensor_msgs::PointCloud2>* occupancy_map_monitor::PointCloudOctomapUpdater::point_cloud_subscriber_
private

Definition at line 157 of file pointcloud_octomap_updater.h.

◆ point_cloud_topic_

std::string occupancy_map_monitor::PointCloudOctomapUpdater::point_cloud_topic_
private

Definition at line 147 of file pointcloud_octomap_updater.h.

◆ point_subsample_

unsigned int occupancy_map_monitor::PointCloudOctomapUpdater::point_subsample_
private

Definition at line 151 of file pointcloud_octomap_updater.h.

◆ private_nh_

ros::NodeHandle occupancy_map_monitor::PointCloudOctomapUpdater::private_nh_
private

Definition at line 139 of file pointcloud_octomap_updater.h.

◆ root_nh_

ros::NodeHandle occupancy_map_monitor::PointCloudOctomapUpdater::root_nh_
private

Definition at line 138 of file pointcloud_octomap_updater.h.

◆ scale_

double occupancy_map_monitor::PointCloudOctomapUpdater::scale_
private

Definition at line 148 of file pointcloud_octomap_updater.h.

◆ shape_mask_

std::unique_ptr<point_containment_filter::ShapeMask> occupancy_map_monitor::PointCloudOctomapUpdater::shape_mask_
private

Definition at line 164 of file pointcloud_octomap_updater.h.

◆ tf_buffer_

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

Definition at line 141 of file pointcloud_octomap_updater.h.

◆ tf_listener_

std::shared_ptr<tf2_ros::TransformListener> occupancy_map_monitor::PointCloudOctomapUpdater::tf_listener_
private

Definition at line 142 of file pointcloud_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