42 #include <geometric_shapes/shapes.h>
43 #include <rclcpp/rclcpp.hpp>
46 #include <Eigen/Geometry>
56 Eigen::aligned_allocator<std::pair<const ShapeHandle, Eigen::Isometry3d> > >;
76 virtual bool setParams(
const std::string& name_space) = 0;
80 virtual bool initialize(
const rclcpp::Node::SharedPtr& node) = 0;
Base class for classes which update the occupancy map.
TransformCacheProvider transform_provider_callback_
virtual ~OccupancyMapUpdater()
virtual bool initialize(const rclcpp::Node::SharedPtr &node)=0
Do any necessary setup (subscribe to ros topics, etc.). This call assumes setMonitor() and setParams(...
virtual void forgetShape(ShapeHandle handle)=0
void publishDebugInformation(bool flag)
void setTransformCacheCallback(const TransformCacheProvider &transform_callback)
const std::string & getType() const
OccupancyMapMonitor * monitor_
collision_detection::OccMapTreePtr tree_
virtual ShapeHandle excludeShape(const shapes::ShapeConstPtr &shape)=0
virtual bool setParams(const std::string &name_space)=0
Set updater params using struct that comes from parsing a yaml string. This must be called after setM...
ShapeTransformCache transform_cache_
bool updateTransformCache(const std::string &target_frame, const rclcpp::Time &target_time)
void setMonitor(OccupancyMapMonitor *monitor)
This is the first function to be called after construction.
OccupancyMapUpdater(const std::string &type)
std::shared_ptr< OccMapTree > OccMapTreePtr
MOVEIT_CLASS_FORWARD(OccupancyMapUpdater)
std::function< bool(const std::string &, const rclcpp::Time &, ShapeTransformCache &)> TransformCacheProvider
std::map< ShapeHandle, Eigen::Isometry3d, std::less< ShapeHandle >, Eigen::aligned_allocator< std::pair< const ShapeHandle, Eigen::Isometry3d > > > ShapeTransformCache