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

virtual ShapeHandle excludeShape (const shapes::ShapeConstPtr &shape)
 
virtual void forgetShape (ShapeHandle handle)
 
virtual bool initialize ()
 Do any necessary setup (subscribe to ros topics, etc.). This call assumes setMonitor() and setParams() have been previously called. More...
 
 PointCloudOctomapUpdater ()
 
virtual bool setParams (XmlRpc::XmlRpcValue &params)
 Set updater params using struct that comes from parsing a yaml string. This must be called after setMonitor() More...
 
virtual void start ()
 
virtual void stop ()
 
virtual ~PointCloudOctomapUpdater ()
 
- 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)
 This is the first function to be called after construction. More...
 
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::Affine3d &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_
 
double padding_
 
tf::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_
 
boost::shared_ptr< tf::Transformertf_
 

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_
 
OccMapTreePtr tree_
 
std::string type_
 

Detailed Description

Definition at line 52 of file pointcloud_octomap_updater.h.

Constructor & Destructor Documentation

occupancy_map_monitor::PointCloudOctomapUpdater::PointCloudOctomapUpdater ( )

Definition at line 48 of file pointcloud_octomap_updater.cpp.

occupancy_map_monitor::PointCloudOctomapUpdater::~PointCloudOctomapUpdater ( )
virtual

Definition at line 61 of file pointcloud_octomap_updater.cpp.

Member Function Documentation

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

Definition at line 168 of file pointcloud_octomap_updater.cpp.

ShapeHandle occupancy_map_monitor::PointCloudOctomapUpdater::excludeShape ( const shapes::ShapeConstPtr shape)
virtual
void occupancy_map_monitor::PointCloudOctomapUpdater::forgetShape ( ShapeHandle  handle)
virtual
bool occupancy_map_monitor::PointCloudOctomapUpdater::getShapeTransform ( ShapeHandle  h,
Eigen::Affine3d &  transform 
) const
private

Definition at line 152 of file pointcloud_octomap_updater.cpp.

bool occupancy_map_monitor::PointCloudOctomapUpdater::initialize ( )
virtual

Do any necessary setup (subscribe to ros topics, etc.). This call assumes setMonitor() and setParams() have been previously called.

Implements occupancy_map_monitor::OccupancyMapUpdater.

Definition at line 92 of file pointcloud_octomap_updater.cpp.

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

Set updater params using struct that comes from parsing a yaml string. This must be called after setMonitor()

Implements occupancy_map_monitor::OccupancyMapUpdater.

Definition at line 66 of file pointcloud_octomap_updater.cpp.

void occupancy_map_monitor::PointCloudOctomapUpdater::start ( void  )
virtual
void occupancy_map_monitor::PointCloudOctomapUpdater::stop ( void  )
virtual
void occupancy_map_monitor::PointCloudOctomapUpdater::stopHelper ( )
private

Definition at line 123 of file pointcloud_octomap_updater.cpp.

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

Definition at line 163 of file pointcloud_octomap_updater.cpp.

Member Data Documentation

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

Definition at line 89 of file pointcloud_octomap_updater.h.

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

Definition at line 88 of file pointcloud_octomap_updater.h.

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

Definition at line 96 of file pointcloud_octomap_updater.h.

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

Definition at line 79 of file pointcloud_octomap_updater.h.

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

Definition at line 99 of file pointcloud_octomap_updater.h.

double occupancy_map_monitor::PointCloudOctomapUpdater::max_range_
private

Definition at line 85 of file pointcloud_octomap_updater.h.

double occupancy_map_monitor::PointCloudOctomapUpdater::max_update_rate_
private

Definition at line 87 of file pointcloud_octomap_updater.h.

double occupancy_map_monitor::PointCloudOctomapUpdater::padding_
private

Definition at line 84 of file pointcloud_octomap_updater.h.

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

Definition at line 92 of file pointcloud_octomap_updater.h.

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

Definition at line 91 of file pointcloud_octomap_updater.h.

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

Definition at line 82 of file pointcloud_octomap_updater.h.

unsigned int occupancy_map_monitor::PointCloudOctomapUpdater::point_subsample_
private

Definition at line 86 of file pointcloud_octomap_updater.h.

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

Definition at line 76 of file pointcloud_octomap_updater.h.

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

Definition at line 75 of file pointcloud_octomap_updater.h.

double occupancy_map_monitor::PointCloudOctomapUpdater::scale_
private

Definition at line 83 of file pointcloud_octomap_updater.h.

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

Definition at line 98 of file pointcloud_octomap_updater.h.

boost::shared_ptr<tf::Transformer> occupancy_map_monitor::PointCloudOctomapUpdater::tf_
private

Definition at line 77 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 Sun Oct 18 2020 13:17:23