#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. More... | |
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() 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::ShapeMask > | shape_mask_ |
boost::shared_ptr< tf::Transformer > | tf_ |
Additional Inherited Members | |
Static Protected Member Functions inherited from occupancy_map_monitor::OccupancyMapUpdater | |
static void | readXmlParam (XmlRpc::XmlRpcValue ¶ms, const std::string ¶m_name, double *value) |
static void | readXmlParam (XmlRpc::XmlRpcValue ¶ms, const std::string ¶m_name, unsigned int *value) |
Protected Attributes inherited from occupancy_map_monitor::OccupancyMapUpdater | |
bool | debug_info_ |
OccupancyMapMonitor * | monitor_ |
ShapeTransformCache | transform_cache_ |
TransformCacheProvider | transform_provider_callback_ |
OccMapTreePtr | tree_ |
std::string | type_ |
Definition at line 52 of file pointcloud_octomap_updater.h.
occupancy_map_monitor::PointCloudOctomapUpdater::PointCloudOctomapUpdater | ( | ) |
Definition at line 48 of file pointcloud_octomap_updater.cpp.
|
virtual |
Definition at line 61 of file pointcloud_octomap_updater.cpp.
|
private |
Definition at line 168 of file pointcloud_octomap_updater.cpp.
|
virtual |
Implements occupancy_map_monitor::OccupancyMapUpdater.
Definition at line 136 of file pointcloud_octomap_updater.cpp.
|
virtual |
Implements occupancy_map_monitor::OccupancyMapUpdater.
Definition at line 146 of file pointcloud_octomap_updater.cpp.
|
private |
Definition at line 152 of file pointcloud_octomap_updater.cpp.
|
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.
|
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.
|
virtual |
Implements occupancy_map_monitor::OccupancyMapUpdater.
Definition at line 102 of file pointcloud_octomap_updater.cpp.
|
virtual |
Implements occupancy_map_monitor::OccupancyMapUpdater.
Definition at line 129 of file pointcloud_octomap_updater.cpp.
|
private |
Definition at line 123 of file pointcloud_octomap_updater.cpp.
|
protectedvirtual |
Definition at line 163 of file pointcloud_octomap_updater.cpp.
|
private |
Definition at line 89 of file pointcloud_octomap_updater.h.
|
private |
Definition at line 88 of file pointcloud_octomap_updater.h.
|
private |
Definition at line 96 of file pointcloud_octomap_updater.h.
|
private |
Definition at line 79 of file pointcloud_octomap_updater.h.
|
private |
Definition at line 99 of file pointcloud_octomap_updater.h.
|
private |
Definition at line 85 of file pointcloud_octomap_updater.h.
|
private |
Definition at line 87 of file pointcloud_octomap_updater.h.
|
private |
Definition at line 84 of file pointcloud_octomap_updater.h.
|
private |
Definition at line 92 of file pointcloud_octomap_updater.h.
|
private |
Definition at line 91 of file pointcloud_octomap_updater.h.
|
private |
Definition at line 82 of file pointcloud_octomap_updater.h.
|
private |
Definition at line 86 of file pointcloud_octomap_updater.h.
|
private |
Definition at line 76 of file pointcloud_octomap_updater.h.
|
private |
Definition at line 75 of file pointcloud_octomap_updater.h.
|
private |
Definition at line 83 of file pointcloud_octomap_updater.h.
|
private |
Definition at line 98 of file pointcloud_octomap_updater.h.
|
private |
Definition at line 77 of file pointcloud_octomap_updater.h.