Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes
occupancy_map_monitor::PointCloudOctomapUpdater Class Reference

#include <pointcloud_octomap_updater.h>

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

List of all members.

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.
 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()
virtual void start ()
virtual void stop ()
virtual ~PointCloudOctomapUpdater ()

Protected Member Functions

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

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_
std::vector< int > mask_
double max_range_
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_
boost::scoped_ptr
< point_containment_filter::ShapeMask
shape_mask_
boost::shared_ptr
< tf::Transformer
tf_

Detailed Description

Definition at line 50 of file pointcloud_octomap_updater.h.


Constructor & Destructor Documentation

Definition at line 46 of file pointcloud_octomap_updater.cpp.

Definition at line 58 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 164 of file pointcloud_octomap_updater.cpp.

bool occupancy_map_monitor::PointCloudOctomapUpdater::getShapeTransform ( ShapeHandle  h,
Eigen::Affine3d &  transform 
) const [private]

Definition at line 147 of file pointcloud_octomap_updater.cpp.

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 87 of file pointcloud_octomap_updater.cpp.

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 63 of file pointcloud_octomap_updater.cpp.

Definition at line 118 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 
) [protected, virtual]

Definition at line 159 of file pointcloud_octomap_updater.cpp.


Member Data Documentation

Definition at line 84 of file pointcloud_octomap_updater.h.

Definition at line 83 of file pointcloud_octomap_updater.h.

Definition at line 91 of file pointcloud_octomap_updater.h.

Definition at line 94 of file pointcloud_octomap_updater.h.

Definition at line 81 of file pointcloud_octomap_updater.h.

Definition at line 80 of file pointcloud_octomap_updater.h.

Definition at line 87 of file pointcloud_octomap_updater.h.

Definition at line 86 of file pointcloud_octomap_updater.h.

Definition at line 78 of file pointcloud_octomap_updater.h.

Definition at line 82 of file pointcloud_octomap_updater.h.

Definition at line 74 of file pointcloud_octomap_updater.h.

Definition at line 73 of file pointcloud_octomap_updater.h.

Definition at line 79 of file pointcloud_octomap_updater.h.

Definition at line 93 of file pointcloud_octomap_updater.h.

Definition at line 75 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 Jun 19 2019 19:24:12