| 
    moveit2
    
   The MoveIt Motion Planning Framework for ROS 2. 
   | 
 
#include <pointcloud_octomap_updater.h>


Public Member Functions | |
| PointCloudOctomapUpdater () | |
| ~PointCloudOctomapUpdater () override | |
| bool | setParams (const std::string &name_space) override | 
| Set updater params using struct that comes from parsing a yaml string. This must be called after setMonitor()  More... | |
| bool | initialize (const rclcpp::Node::SharedPtr &node) override | 
| Do any necessary setup (subscribe to ros topics, etc.). This call assumes setMonitor() and setParams() have been previously called.  More... | |
| void | start () override | 
| void | stop () override | 
| ShapeHandle | excludeShape (const shapes::ShapeConstPtr &shape) override | 
| void | forgetShape (ShapeHandle handle) override | 
  Public Member Functions inherited from occupancy_map_monitor::OccupancyMapUpdater | |
| OccupancyMapUpdater (const std::string &type) | |
| virtual | ~OccupancyMapUpdater () | 
| void | setMonitor (OccupancyMapMonitor *monitor) | 
| This is the first function to be called after construction.  More... | |
| const std::string & | getType () const | 
| void | setTransformCacheCallback (const TransformCacheProvider &transform_callback) | 
| void | publishDebugInformation (bool flag) | 
Protected Member Functions | |
| virtual void | updateMask (const sensor_msgs::msg::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 rclcpp::Time &target_time) | 
Additional Inherited Members | |
  Protected Attributes inherited from occupancy_map_monitor::OccupancyMapUpdater | |
| OccupancyMapMonitor * | monitor_ | 
| std::string | type_ | 
| collision_detection::OccMapTreePtr | tree_ | 
| TransformCacheProvider | transform_provider_callback_ | 
| ShapeTransformCache | transform_cache_ | 
| bool | debug_info_ | 
Definition at line 52 of file pointcloud_octomap_updater.h.
| occupancy_map_monitor::PointCloudOctomapUpdater::PointCloudOctomapUpdater | ( | ) | 
Definition at line 61 of file pointcloud_octomap_updater.cpp.
      
  | 
  override | 
Definition at line 73 of file pointcloud_octomap_updater.cpp.
      
  | 
  overridevirtual | 
Implements occupancy_map_monitor::OccupancyMapUpdater.
Definition at line 157 of file pointcloud_octomap_updater.cpp.
      
  | 
  overridevirtual | 
Implements occupancy_map_monitor::OccupancyMapUpdater.
Definition at line 167 of file pointcloud_octomap_updater.cpp.
      
  | 
  overridevirtual | 
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 91 of file pointcloud_octomap_updater.cpp.
      
  | 
  overridevirtual | 
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 78 of file pointcloud_octomap_updater.cpp.
      
  | 
  overridevirtual | 
Implements occupancy_map_monitor::OccupancyMapUpdater.
Definition at line 106 of file pointcloud_octomap_updater.cpp.

      
  | 
  overridevirtual | 
Implements occupancy_map_monitor::OccupancyMapUpdater.
Definition at line 150 of file pointcloud_octomap_updater.cpp.
      
  | 
  protectedvirtual | 
Definition at line 183 of file pointcloud_octomap_updater.cpp.