Program Listing for File occupancy_map_monitor.h
↰ Return to documentation for file (include/moveit/occupancy_map_monitor/occupancy_map_monitor.h
)
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2011, Willow Garage, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of Willow Garage nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
/* Author: Ioan Sucan, Jon Binney */
#pragma once
#include <moveit/collision_detection/occupancy_map.h>
#include <moveit/occupancy_map_monitor/occupancy_map_updater.h>
#include <moveit_msgs/srv/load_map.hpp>
#include <moveit_msgs/srv/save_map.hpp>
#include <rclcpp/rclcpp.hpp>
#include <tf2_ros/buffer.h>
#include <functional>
#include <memory>
#include <mutex>
#include <string>
#include <utility>
#include <vector>
namespace occupancy_map_monitor
{
class OccupancyMapMonitor
{
public:
struct Parameters
{
double map_resolution;
std::string map_frame;
std::vector<std::pair<std::string, std::string>> sensor_plugins;
};
class MiddlewareHandle
{
public:
using SaveMapServiceCallback = 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)>;
using LoadMapServiceCallback = 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)>;
virtual ~MiddlewareHandle() = default;
virtual Parameters getParameters() const = 0;
virtual OccupancyMapUpdaterPtr loadOccupancyMapUpdater(const std::string& sensor_plugin) = 0;
virtual void initializeOccupancyMapUpdater(OccupancyMapUpdaterPtr occupancy_map_updater) = 0;
virtual void createSaveMapService(SaveMapServiceCallback callback) = 0;
virtual void createLoadMapService(LoadMapServiceCallback callback) = 0;
};
OccupancyMapMonitor(std::unique_ptr<MiddlewareHandle> middleware_handle,
const std::shared_ptr<tf2_ros::Buffer>& tf_buffer);
OccupancyMapMonitor(const rclcpp::Node::SharedPtr& node, const std::shared_ptr<tf2_ros::Buffer>& tf_buffer,
const std::string& map_frame = "", double map_resolution = 0.0);
OccupancyMapMonitor(const rclcpp::Node::SharedPtr& node, double map_resolution = 0.0);
~OccupancyMapMonitor();
void startMonitor();
void stopMonitor();
const collision_detection::OccMapTreePtr& getOcTreePtr()
{
return tree_;
}
const collision_detection::OccMapTreeConstPtr& getOcTreePtr() const
{
return tree_const_;
}
const std::string& getMapFrame() const
{
return parameters_.map_frame;
}
void setMapFrame(const std::string& frame);
double getMapResolution() const
{
return parameters_.map_resolution;
}
const std::shared_ptr<tf2_ros::Buffer>& getTFClient() const
{
return tf_buffer_;
}
void addUpdater(const OccupancyMapUpdaterPtr& updater);
ShapeHandle excludeShape(const shapes::ShapeConstPtr& shape);
void forgetShape(ShapeHandle handle);
void setUpdateCallback(const std::function<void()>& update_callback)
{
tree_->setUpdateCallback(update_callback);
}
void setTransformCacheCallback(const TransformCacheProvider& transform_cache_callback);
void publishDebugInformation(bool flag);
bool isActive() const
{
return active_;
}
private:
bool saveMapCallback(const std::shared_ptr<rmw_request_id_t>& request_header,
const std::shared_ptr<moveit_msgs::srv::SaveMap::Request>& request,
const std::shared_ptr<moveit_msgs::srv::SaveMap::Response>& response);
bool loadMapCallback(const std::shared_ptr<rmw_request_id_t>& request_header,
const std::shared_ptr<moveit_msgs::srv::LoadMap::Request>& request,
const std::shared_ptr<moveit_msgs::srv::LoadMap::Response>& response);
bool getShapeTransformCache(std::size_t index, const std::string& target_frame, const rclcpp::Time& target_time,
ShapeTransformCache& cache) const;
std::unique_ptr<MiddlewareHandle> middleware_handle_;
std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
Parameters parameters_;
std::mutex parameters_lock_;
collision_detection::OccMapTreePtr tree_;
collision_detection::OccMapTreeConstPtr tree_const_;
std::vector<OccupancyMapUpdaterPtr> map_updaters_;
std::vector<std::map<ShapeHandle, ShapeHandle>> mesh_handles_;
TransformCacheProvider transform_cache_callback_;
bool debug_info_;
std::size_t mesh_handle_count_;
bool active_;
rclcpp::Logger logger_;
};
} // namespace occupancy_map_monitor