#include <pointcloud_octomap_updater.h>
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 ¶ms) |
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 pcl::PointCloud< pcl::PointXYZ > &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_ |
Definition at line 53 of file pointcloud_octomap_updater.h.
Definition at line 47 of file pointcloud_octomap_updater.cpp.
Definition at line 58 of file pointcloud_octomap_updater.cpp.
void occupancy_map_monitor::PointCloudOctomapUpdater::cloudMsgCallback | ( | const sensor_msgs::PointCloud2::ConstPtr & | cloud_msg | ) | [private] |
Definition at line 161 of file pointcloud_octomap_updater.cpp.
ShapeHandle occupancy_map_monitor::PointCloudOctomapUpdater::excludeShape | ( | const shapes::ShapeConstPtr & | shape | ) | [virtual] |
Implements occupancy_map_monitor::OccupancyMapUpdater.
Definition at line 129 of file pointcloud_octomap_updater.cpp.
void occupancy_map_monitor::PointCloudOctomapUpdater::forgetShape | ( | ShapeHandle | handle | ) | [virtual] |
Implements occupancy_map_monitor::OccupancyMapUpdater.
Definition at line 139 of file pointcloud_octomap_updater.cpp.
bool occupancy_map_monitor::PointCloudOctomapUpdater::getShapeTransform | ( | ShapeHandle | h, |
Eigen::Affine3d & | transform | ||
) | const [private] |
Definition at line 145 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 87 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 63 of file pointcloud_octomap_updater.cpp.
void occupancy_map_monitor::PointCloudOctomapUpdater::start | ( | void | ) | [virtual] |
Implements occupancy_map_monitor::OccupancyMapUpdater.
Definition at line 97 of file pointcloud_octomap_updater.cpp.
void occupancy_map_monitor::PointCloudOctomapUpdater::stop | ( | void | ) | [virtual] |
Implements occupancy_map_monitor::OccupancyMapUpdater.
Definition at line 122 of file pointcloud_octomap_updater.cpp.
void occupancy_map_monitor::PointCloudOctomapUpdater::stopHelper | ( | ) | [private] |
Definition at line 116 of file pointcloud_octomap_updater.cpp.
void occupancy_map_monitor::PointCloudOctomapUpdater::updateMask | ( | const pcl::PointCloud< pcl::PointXYZ > & | cloud, |
const Eigen::Vector3d & | sensor_origin, | ||
std::vector< int > & | mask | ||
) | [protected, virtual] |
Definition at line 157 of file pointcloud_octomap_updater.cpp.
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.
Definition at line 96 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 86 of file pointcloud_octomap_updater.h.
double occupancy_map_monitor::PointCloudOctomapUpdater::padding_ [private] |
Definition at line 85 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 83 of file pointcloud_octomap_updater.h.
unsigned int occupancy_map_monitor::PointCloudOctomapUpdater::point_subsample_ [private] |
Definition at line 87 of file pointcloud_octomap_updater.h.
Definition at line 79 of file pointcloud_octomap_updater.h.
Definition at line 78 of file pointcloud_octomap_updater.h.
double occupancy_map_monitor::PointCloudOctomapUpdater::scale_ [private] |
Definition at line 84 of file pointcloud_octomap_updater.h.
boost::scoped_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 80 of file pointcloud_octomap_updater.h.