Class OccupancyMapUpdater
Defined in File occupancy_map_updater.h
Class Documentation
-
class OccupancyMapUpdater
Base class for classes which update the occupancy map.
Public Functions
-
OccupancyMapUpdater(const std::string &type)
-
virtual ~OccupancyMapUpdater()
-
void setMonitor(OccupancyMapMonitor *monitor)
This is the first function to be called after construction.
-
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 setMonitor()
Do any necessary setup (subscribe to ros topics, etc.). This call assumes setMonitor() and setParams() have been previously called.
-
virtual void start() = 0
-
virtual void stop() = 0
-
virtual ShapeHandle excludeShape(const shapes::ShapeConstPtr &shape) = 0
-
virtual void forgetShape(ShapeHandle handle) = 0
-
inline const std::string &getType() const
-
inline void setTransformCacheCallback(const TransformCacheProvider &transform_callback)
-
inline void publishDebugInformation(bool flag)
Protected Functions
-
bool updateTransformCache(const std::string &target_frame, const rclcpp::Time &target_time)
Protected Attributes
-
OccupancyMapMonitor *monitor_
-
std::string type_
-
collision_detection::OccMapTreePtr tree_
-
TransformCacheProvider transform_provider_callback_
-
ShapeTransformCache transform_cache_
-
bool debug_info_
-
OccupancyMapUpdater(const std::string &type)