41#include <moveit_msgs/srv/load_map.hpp>
42#include <moveit_msgs/srv/save_map.hpp>
44#include <rclcpp/rclcpp.hpp>
45#include <tf2_ros/buffer.h>
76 const std::shared_ptr<moveit_msgs::srv::SaveMap::Request> request,
77 std::shared_ptr<moveit_msgs::srv::SaveMap::Response> response)>;
79 const std::shared_ptr<moveit_msgs::srv::LoadMap::Request> request,
80 std::shared_ptr<moveit_msgs::srv::LoadMap::Response> response)>;
132 const std::shared_ptr<tf2_ros::Buffer>& tf_buffer);
142 OccupancyMapMonitor(
const rclcpp::Node::SharedPtr& node,
const std::shared_ptr<tf2_ros::Buffer>& tf_buffer,
143 const std::string& map_frame =
"",
double map_resolution = 0.0);
224 void addUpdater(
const OccupancyMapUpdaterPtr& updater);
249 tree_->setUpdateCallback(update_callback);
286 bool saveMapCallback(
const std::shared_ptr<rmw_request_id_t>& request_header,
287 const std::shared_ptr<moveit_msgs::srv::SaveMap::Request>& request,
288 const std::shared_ptr<moveit_msgs::srv::SaveMap::Response>& response);
299 bool loadMapCallback(
const std::shared_ptr<rmw_request_id_t>& request_header,
300 const std::shared_ptr<moveit_msgs::srv::LoadMap::Request>& request,
301 const std::shared_ptr<moveit_msgs::srv::LoadMap::Response>& response);
313 bool getShapeTransformCache(std::size_t index,
const std::string& target_frame,
const rclcpp::Time& target_time,
316 std::unique_ptr<MiddlewareHandle> middleware_handle_;
317 std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
318 Parameters parameters_;
319 std::mutex parameters_lock_;
324 std::vector<OccupancyMapUpdaterPtr> map_updaters_;
325 std::vector<std::map<ShapeHandle, ShapeHandle>> mesh_handles_;
329 std::size_t mesh_handle_count_;
333 rclcpp::Logger logger_;
This class contains the rcl interfaces for easier testing.
virtual OccupancyMapUpdaterPtr loadOccupancyMapUpdater(const std::string &sensor_plugin)=0
Loads an occupancy map updater based on string.
virtual ~MiddlewareHandle()=default
Destroys the object. Needed because this is pure virtual interface.
virtual void createLoadMapService(LoadMapServiceCallback callback)=0
Creates a load map service.
std::function< bool(const std::shared_ptr< rmw_request_id_t > request_header, const std::shared_ptr< moveit_msgs::srv::LoadMap::Request > request, std::shared_ptr< moveit_msgs::srv::LoadMap::Response > response)> LoadMapServiceCallback
virtual Parameters getParameters() const =0
Gets the parameters struct.
std::function< bool(const std::shared_ptr< rmw_request_id_t > request_header, const std::shared_ptr< moveit_msgs::srv::SaveMap::Request > request, std::shared_ptr< moveit_msgs::srv::SaveMap::Response > response)> SaveMapServiceCallback
virtual void createSaveMapService(SaveMapServiceCallback callback)=0
Creates a save map service.
virtual void initializeOccupancyMapUpdater(OccupancyMapUpdaterPtr occupancy_map_updater)=0
Initializes the occupancy map updater. Needed because of interface to OccupancyMapUpdater.
const collision_detection::OccMapTreeConstPtr & getOcTreePtr() const
Get a const pointer to the underlying octree for this monitor. Lock the tree before reading this poin...
const collision_detection::OccMapTreePtr & getOcTreePtr()
Get a pointer to the underlying octree for this monitor. Lock the tree before reading or writing usin...
~OccupancyMapMonitor()
Destroys the object.
void startMonitor()
start the monitor (will begin updating the octomap
void setTransformCacheCallback(const TransformCacheProvider &transform_cache_callback)
Sets the transform cache callback.
const std::shared_ptr< tf2_ros::Buffer > & getTFClient() const
Gets the tf client.
const std::string & getMapFrame() const
Gets the map frame (this is set either by the constor or a parameter).
void publishDebugInformation(bool flag)
Set the debug flag on the updaters.
double getMapResolution() const
Gets the map resolution.
void stopMonitor()
Stops the monitor, this also stops the updaters.
ShapeHandle excludeShape(const shapes::ShapeConstPtr &shape)
Add this shape to the set of shapes to be filtered out from the octomap.
bool isActive() const
Determines if active.
void addUpdater(const OccupancyMapUpdaterPtr &updater)
Adds an OccupancyMapUpdater to be monitored.
void setMapFrame(const std::string &frame)
Sets the map frame.
void setUpdateCallback(const std::function< void()> &update_callback)
Set the callback to trigger when updates to the maintained octomap are received.
void forgetShape(ShapeHandle handle)
Forget about this shape handle and the shapes it corresponds to.
std::shared_ptr< const OccMapTree > OccMapTreeConstPtr
std::shared_ptr< OccMapTree > OccMapTreePtr
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
This class describes parameters that are normally provided through ROS Parameters.
std::vector< std::pair< std::string, std::string > > sensor_plugins