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>
61 const std::shared_ptr<tf2_ros::Buffer>& tf_buffer,
62 const std::string& map_frame,
double map_resolution)
69 const std::shared_ptr<tf2_ros::Buffer>& tf_buffer)
70 : middleware_handle_{ std::move(middleware_handle) }
71 , tf_buffer_{ tf_buffer }
72 , parameters_{ 0.0,
"", {} }
73 , debug_info_{
false }
74 , mesh_handle_count_{ 0 }
78 if (middleware_handle_ ==
nullptr)
80 throw std::invalid_argument(
"OccupancyMapMonitor cannot be constructed with nullptr MiddlewareHandle");
84 parameters_ = middleware_handle_->getParameters();
86 RCLCPP_DEBUG(logger_,
"Using resolution = %lf m for building octomap", parameters_.map_resolution);
88 if (tf_buffer_ !=
nullptr && parameters_.map_frame.empty())
90 RCLCPP_WARN(logger_,
"No target frame specified for Octomap. No transforms will be applied to received data.");
92 if (tf_buffer_ ==
nullptr && !parameters_.map_frame.empty())
94 RCLCPP_WARN(logger_,
"Target frame specified but no TF instance (buffer) specified."
95 "No transforms will be applied to received data.");
98 tree_ = std::make_shared<collision_detection::OccMapTree>(parameters_.map_resolution);
101 for (
const auto& [sensor_name, sensor_type] : parameters_.sensor_plugins)
103 auto occupancy_map_updater = middleware_handle_->loadOccupancyMapUpdater(sensor_type);
106 if (occupancy_map_updater ==
nullptr)
108 RCLCPP_ERROR_STREAM(logger_,
"Failed to load sensor: `" << sensor_name <<
"` of type: `" << sensor_type <<
'`');
113 occupancy_map_updater->setMonitor(
this);
116 middleware_handle_->initializeOccupancyMapUpdater(occupancy_map_updater);
119 if (!occupancy_map_updater->setParams(sensor_name))
121 RCLCPP_ERROR_STREAM(logger_,
"Failed to configure updater of type " << occupancy_map_updater->getType());
126 addUpdater(occupancy_map_updater);
130 auto save_map_service_callback = [
this](
const std::shared_ptr<rmw_request_id_t>& request_header,
131 const std::shared_ptr<moveit_msgs::srv::SaveMap::Request>& request,
132 const std::shared_ptr<moveit_msgs::srv::SaveMap::Response>& response) ->
bool {
133 return saveMapCallback(request_header, request, response);
136 auto load_map_service_callback = [
this](
const std::shared_ptr<rmw_request_id_t>& request_header,
137 const std::shared_ptr<moveit_msgs::srv::LoadMap::Request>& request,
138 const std::shared_ptr<moveit_msgs::srv::LoadMap::Response>& response) ->
bool {
139 return loadMapCallback(request_header, request, response);
142 middleware_handle_->createSaveMapService(save_map_service_callback);
143 middleware_handle_->createLoadMapService(load_map_service_callback);
146 void OccupancyMapMonitor::addUpdater(
const OccupancyMapUpdaterPtr& updater)
150 map_updaters_.push_back(updater);
151 updater->publishDebugInformation(debug_info_);
152 if (map_updaters_.size() > 1)
154 mesh_handles_.resize(map_updaters_.size());
156 if (map_updaters_.size() == 2)
158 map_updaters_[0]->setTransformCacheCallback(
160 return getShapeTransformCache(0, frame, stamp, cache);
162 map_updaters_[1]->setTransformCacheCallback(
164 return getShapeTransformCache(1, frame, stamp, cache);
169 map_updaters_.back()->setTransformCacheCallback(
170 [
this, i = map_updaters_.size() - 1](
const std::string& frame,
const rclcpp::Time& stamp,
172 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)
239 map_updaters_[0]->setTransformCacheCallback(transform_callback);
243 transform_cache_callback_ = transform_callback;
247 bool OccupancyMapMonitor::getShapeTransformCache(std::size_t index,
const std::string& target_frame,
250 if (transform_cache_callback_)
253 if (transform_cache_callback_(target_frame, target_time, temp_cache))
255 for (std::pair<const ShapeHandle, Eigen::Isometry3d>& it : temp_cache)
257 std::map<ShapeHandle, ShapeHandle>::const_iterator jt = mesh_handles_[index].find(it.first);
258 if (jt == mesh_handles_[index].end())
260 rclcpp::Clock steady_clock(RCL_STEADY_TIME);
261 #pragma GCC diagnostic push
262 #pragma GCC diagnostic ignored "-Wold-style-cast"
263 RCLCPP_ERROR_THROTTLE(logger_, steady_clock, 1000,
"Incorrect mapping of mesh handles");
264 #pragma GCC diagnostic pop
268 cache[jt->second] = it.second;
279 bool OccupancyMapMonitor::saveMapCallback(
const std::shared_ptr<rmw_request_id_t>& ,
280 const std::shared_ptr<moveit_msgs::srv::SaveMap::Request>& request,
281 const std::shared_ptr<moveit_msgs::srv::SaveMap::Response>& response)
283 RCLCPP_INFO(logger_,
"Writing map to %s", request->filename.c_str());
287 response->success = tree_->writeBinary(request->filename);
291 response->success =
false;
297 bool OccupancyMapMonitor::loadMapCallback(
const std::shared_ptr<rmw_request_id_t>& ,
298 const std::shared_ptr<moveit_msgs::srv::LoadMap::Request>& request,
299 const std::shared_ptr<moveit_msgs::srv::LoadMap::Response>& response)
301 RCLCPP_INFO(logger_,
"Reading map from %s", request->filename.c_str());
307 response->success = tree_->readBinary(request->filename);
311 RCLCPP_ERROR(logger_,
"Failed to load map from file");
312 response->success =
false;
314 tree_->unlockWrite();
316 if (response->success)
317 tree_->triggerUpdateCallback();
322 void OccupancyMapMonitor::startMonitor()
326 for (OccupancyMapUpdaterPtr& map_updater : map_updaters_)
327 map_updater->start();
330 void OccupancyMapMonitor::stopMonitor()
333 for (OccupancyMapUpdaterPtr& map_updater : map_updaters_)
337 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.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
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