40 #include <moveit_msgs/srv/load_map.hpp>
41 #include <moveit_msgs/srv/save_map.hpp>
42 #include <rclcpp/clock.hpp>
43 #include <rclcpp/logger.hpp>
44 #include <rclcpp/logging.hpp>
45 #include <rclcpp/node.hpp>
55 static const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"moveit.ros.occupancy_map_monitor");
64 const std::shared_ptr<tf2_ros::Buffer>& tf_buffer,
65 const std::string& map_frame,
double map_resolution)
72 const std::shared_ptr<tf2_ros::Buffer>& tf_buffer)
73 : middleware_handle_{ std::move(middleware_handle) }
74 , tf_buffer_{ tf_buffer }
75 , parameters_{ 0.0,
"", {} }
76 , debug_info_{
false }
77 , mesh_handle_count_{ 0 }
80 if (middleware_handle_ ==
nullptr)
82 throw std::invalid_argument(
"OccupancyMapMonitor cannot be constructed with nullptr MiddlewareHandle");
86 parameters_ = middleware_handle_->getParameters();
88 RCLCPP_DEBUG(LOGGER,
"Using resolution = %lf m for building octomap", parameters_.map_resolution);
90 if (tf_buffer_ !=
nullptr && parameters_.map_frame.empty())
92 RCLCPP_WARN(LOGGER,
"No target frame specified for Octomap. No transforms will be applied to received data.");
94 if (tf_buffer_ ==
nullptr && !parameters_.map_frame.empty())
96 RCLCPP_WARN(LOGGER,
"Target frame specified but no TF instance (buffer) specified."
97 "No transforms will be applied to received data.");
100 tree_ = std::make_shared<collision_detection::OccMapTree>(parameters_.map_resolution);
103 for (
const auto& [sensor_name, sensor_type] : parameters_.sensor_plugins)
105 auto occupancy_map_updater = middleware_handle_->loadOccupancyMapUpdater(sensor_type);
108 if (occupancy_map_updater ==
nullptr)
110 RCLCPP_ERROR_STREAM(LOGGER,
"Failed to load sensor: `" << sensor_name <<
"` of type: `" << sensor_type <<
"`");
115 occupancy_map_updater->setMonitor(
this);
118 middleware_handle_->initializeOccupancyMapUpdater(occupancy_map_updater);
121 if (!occupancy_map_updater->setParams(sensor_name))
123 RCLCPP_ERROR_STREAM(LOGGER,
"Failed to configure updater of type " << occupancy_map_updater->getType());
128 addUpdater(occupancy_map_updater);
132 auto save_map_service_callback = [
this](
const std::shared_ptr<rmw_request_id_t>& request_header,
133 const std::shared_ptr<moveit_msgs::srv::SaveMap::Request>& request,
134 const std::shared_ptr<moveit_msgs::srv::SaveMap::Response>& response) ->
bool {
135 return saveMapCallback(request_header, request, response);
138 auto load_map_service_callback = [
this](
const std::shared_ptr<rmw_request_id_t>& request_header,
139 const std::shared_ptr<moveit_msgs::srv::LoadMap::Request>& request,
140 const std::shared_ptr<moveit_msgs::srv::LoadMap::Response>& response) ->
bool {
141 return loadMapCallback(request_header, request, response);
144 middleware_handle_->createSaveMapService(save_map_service_callback);
145 middleware_handle_->createLoadMapService(load_map_service_callback);
148 void OccupancyMapMonitor::addUpdater(
const OccupancyMapUpdaterPtr& updater)
152 map_updaters_.push_back(updater);
153 updater->publishDebugInformation(debug_info_);
154 if (map_updaters_.size() > 1)
156 mesh_handles_.resize(map_updaters_.size());
158 if (map_updaters_.size() == 2)
160 map_updaters_[0]->setTransformCacheCallback(
162 return getShapeTransformCache(0, frame, stamp, cache);
164 map_updaters_[1]->setTransformCacheCallback(
166 return getShapeTransformCache(1, frame, stamp, cache);
170 map_updaters_.back()->setTransformCacheCallback(
171 [
this, i = map_updaters_.size() - 1](
const std::string& frame,
const rclcpp::Time& stamp,
173 return getShapeTransformCache(i, frame, stamp, cache);
177 updater->setTransformCacheCallback(transform_cache_callback_);
180 RCLCPP_ERROR(LOGGER,
"nullptr updater was specified");
183 void OccupancyMapMonitor::publishDebugInformation(
bool flag)
186 for (OccupancyMapUpdaterPtr& map_updater : map_updaters_)
187 map_updater->publishDebugInformation(debug_info_);
190 void OccupancyMapMonitor::setMapFrame(
const std::string& frame)
192 std::lock_guard<std::mutex> _(parameters_lock_);
193 parameters_.map_frame = frame;
196 ShapeHandle OccupancyMapMonitor::excludeShape(
const shapes::ShapeConstPtr& shape)
199 if (map_updaters_.size() == 1)
200 return map_updaters_[0]->excludeShape(shape);
203 for (std::size_t i = 0; i < map_updaters_.size(); ++i)
205 ShapeHandle mh = map_updaters_[i]->excludeShape(shape);
209 h = ++mesh_handle_count_;
210 mesh_handles_[i][h] = mh;
219 if (map_updaters_.size() == 1)
221 map_updaters_[0]->forgetShape(handle);
225 for (std::size_t i = 0; i < map_updaters_.size(); ++i)
227 std::map<ShapeHandle, ShapeHandle>::const_iterator it = mesh_handles_[i].find(handle);
228 if (it == mesh_handles_[i].end())
230 map_updaters_[i]->forgetShape(it->second);
237 if (map_updaters_.size() == 1)
238 map_updaters_[0]->setTransformCacheCallback(transform_callback);
240 transform_cache_callback_ = transform_callback;
243 bool OccupancyMapMonitor::getShapeTransformCache(std::size_t index,
const std::string& target_frame,
246 if (transform_cache_callback_)
249 if (transform_cache_callback_(target_frame, target_time, temp_cache))
251 for (std::pair<const ShapeHandle, Eigen::Isometry3d>& it : temp_cache)
253 std::map<ShapeHandle, ShapeHandle>::const_iterator jt = mesh_handles_[index].find(it.first);
254 if (jt == mesh_handles_[index].end())
256 rclcpp::Clock steady_clock(RCL_STEADY_TIME);
257 RCLCPP_ERROR_THROTTLE(LOGGER, steady_clock, 1000,
"Incorrect mapping of mesh handles");
261 cache[jt->second] = it.second;
272 bool OccupancyMapMonitor::saveMapCallback(
const std::shared_ptr<rmw_request_id_t>& ,
273 const std::shared_ptr<moveit_msgs::srv::SaveMap::Request>& request,
274 const std::shared_ptr<moveit_msgs::srv::SaveMap::Response>& response)
276 RCLCPP_INFO(LOGGER,
"Writing map to %s", request->filename.c_str());
280 response->success = tree_->writeBinary(request->filename);
284 response->success =
false;
290 bool OccupancyMapMonitor::loadMapCallback(
const std::shared_ptr<rmw_request_id_t>& ,
291 const std::shared_ptr<moveit_msgs::srv::LoadMap::Request>& request,
292 const std::shared_ptr<moveit_msgs::srv::LoadMap::Response>& response)
294 RCLCPP_INFO(LOGGER,
"Reading map from %s", request->filename.c_str());
300 response->success = tree_->readBinary(request->filename);
304 RCLCPP_ERROR(LOGGER,
"Failed to load map from file");
305 response->success =
false;
307 tree_->unlockWrite();
309 if (response->success)
310 tree_->triggerUpdateCallback();
315 void OccupancyMapMonitor::startMonitor()
319 for (OccupancyMapUpdaterPtr& map_updater : map_updaters_)
320 map_updater->start();
323 void OccupancyMapMonitor::stopMonitor()
326 for (OccupancyMapUpdaterPtr& map_updater : map_updaters_)
330 OccupancyMapMonitor::~OccupancyMapMonitor()
This class contains the ros interfaces for OccupancyMapMontior.
OccupancyMapMonitor(std::unique_ptr< MiddlewareHandle > middleware_handle, const std::shared_ptr< tf2_ros::Buffer > &tf_buffer)
Occupancy map monitor constructor with the MiddlewareHandle.
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
const rclcpp::Logger LOGGER