occupancy_map_monitor.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2011, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 /* Author: Ioan Sucan, Jon Binney */
00036 
00037 #include <ros/ros.h>
00038 #include <moveit_msgs/SaveMap.h>
00039 #include <moveit_msgs/LoadMap.h>
00040 #include <moveit/occupancy_map_monitor/occupancy_map.h>
00041 #include <moveit/occupancy_map_monitor/occupancy_map_monitor.h>
00042 #include <XmlRpcException.h>
00043 
00044 namespace occupancy_map_monitor
00045 {
00046 
00047 OccupancyMapMonitor::OccupancyMapMonitor(double map_resolution) :
00048   nh_("~"),
00049   map_resolution_(map_resolution),
00050   mesh_handle_count_(0),
00051   debug_info_(false)
00052 {
00053   initialize();
00054 }
00055 
00056 OccupancyMapMonitor::OccupancyMapMonitor(const boost::shared_ptr<tf::Transformer> &tf, const std::string &map_frame, double map_resolution) :
00057   nh_("~"),
00058   tf_(tf),
00059   map_frame_(map_frame),
00060   map_resolution_(map_resolution),
00061   mesh_handle_count_(0),
00062   debug_info_(false)
00063 {
00064   initialize();
00065 }
00066 
00067 void OccupancyMapMonitor::initialize()
00068 {
00069   /* load params from param server */
00070   if (map_resolution_ <= std::numeric_limits<double>::epsilon())
00071     if (!nh_.getParam("octomap_resolution", map_resolution_))
00072     {
00073       map_resolution_ = 0.1;
00074       ROS_WARN("Resolution not specified for Octomap. Assuming resolution = %g instead", map_resolution_);
00075     }
00076   ROS_DEBUG("Using resolution = %lf m for building octomap", map_resolution_);
00077 
00078   if (map_frame_.empty())
00079     if (!nh_.getParam("octomap_frame", map_frame_))
00080       if (tf_)
00081         ROS_WARN("No target frame specified for Octomap. No transforms will be applied to received data.");
00082 
00083   if (!tf_ && !map_frame_.empty())
00084     ROS_WARN("Target frame specified but no TF instance specified. No transforms will be applied to received data.");
00085 
00086   tree_.reset(new OccMapTree(map_resolution_));
00087   tree_const_ = tree_;
00088 
00089   XmlRpc::XmlRpcValue sensor_list;
00090   if (nh_.getParam("sensors", sensor_list))
00091   {
00092     try
00093     {
00094       if (sensor_list.getType() == XmlRpc::XmlRpcValue::TypeArray)
00095         for (int32_t i = 0; i < sensor_list.size(); ++i)
00096         {
00097           if (!sensor_list[i].getType() == XmlRpc::XmlRpcValue::TypeStruct)
00098           {
00099             ROS_ERROR("Params for octomap updater %d not a struct; ignoring.", i);
00100             continue;
00101           }
00102 
00103           if (!sensor_list[i].hasMember ("sensor_plugin"))
00104           {
00105             ROS_ERROR("No sensor plugin specified for octomap updater %d; ignoring.", i);
00106             continue;
00107           }
00108 
00109           std::string sensor_plugin = std::string(sensor_list[i]["sensor_plugin"]);
00110           if (sensor_plugin.empty() || sensor_plugin[0] == '~')
00111           {
00112             ROS_INFO("Skipping octomap updater plugin '%s'", sensor_plugin.c_str());
00113             continue;
00114           }
00115 
00116           if (!updater_plugin_loader_)
00117           {
00118             try
00119             {
00120               updater_plugin_loader_.reset(new pluginlib::ClassLoader<OccupancyMapUpdater>("moveit_ros_perception", "occupancy_map_monitor::OccupancyMapUpdater"));
00121             }
00122             catch(pluginlib::PluginlibException& ex)
00123             {
00124               ROS_FATAL_STREAM("Exception while creating octomap updater plugin loader " << ex.what());
00125             }
00126           }
00127 
00128           OccupancyMapUpdaterPtr up;
00129           try
00130           {
00131             up.reset(updater_plugin_loader_->createUnmanagedInstance(sensor_plugin));
00132             up->setMonitor(this);
00133           }
00134           catch(pluginlib::PluginlibException& ex)
00135           {
00136             ROS_ERROR_STREAM("Exception while loading octomap updater '" << sensor_plugin << "': " << ex.what() << std::endl);
00137           }
00138           if (up)
00139           {
00140             /* pass the params struct directly in to the updater */
00141             if (!up->setParams(sensor_list[i]))
00142             {
00143               ROS_ERROR("Failed to configure updater of type %s", up->getType().c_str());
00144               continue;
00145             }
00146 
00147             if (!up->initialize())
00148             {
00149               ROS_ERROR("Unable to initialize map updater of type %s (plugin %s)", up->getType().c_str(), sensor_plugin.c_str());
00150               continue;
00151             }
00152 
00153             addUpdater(up);
00154           }
00155         }
00156       else
00157         ROS_ERROR("List of sensors must be an array!");
00158     }
00159     catch (XmlRpc::XmlRpcException &ex)
00160     {
00161       ROS_ERROR("XmlRpc Exception: %s", ex.getMessage().c_str());
00162     }
00163   }
00164 
00165   /* advertise a service for loading octomaps from disk */
00166   save_map_srv_ = nh_.advertiseService("save_map", &OccupancyMapMonitor::saveMapCallback, this);
00167   load_map_srv_ = nh_.advertiseService("load_map", &OccupancyMapMonitor::loadMapCallback, this);
00168 }
00169 
00170 void OccupancyMapMonitor::addUpdater(const OccupancyMapUpdaterPtr &updater)
00171 {
00172   if (updater)
00173   {
00174     map_updaters_.push_back(updater);
00175     updater->publishDebugInformation(debug_info_);
00176     if (map_updaters_.size() > 1)
00177     {
00178       mesh_handles_.resize(map_updaters_.size());
00179       if (map_updaters_.size() == 2) // when we had one updater only, we passed direcly the transform cache callback to that updater
00180       {
00181         map_updaters_[0]->setTransformCacheCallback(boost::bind(&OccupancyMapMonitor::getShapeTransformCache, this, 0, _1, _2, _3));
00182         map_updaters_[1]->setTransformCacheCallback(boost::bind(&OccupancyMapMonitor::getShapeTransformCache, this, 1, _1, _2, _3));
00183       }
00184       else
00185         map_updaters_.back()->setTransformCacheCallback(boost::bind(&OccupancyMapMonitor::getShapeTransformCache, this, map_updaters_.size() - 1, _1, _2, _3));
00186     }
00187     else
00188       updater->setTransformCacheCallback(transform_cache_callback_);
00189   }
00190   else
00191     ROS_ERROR("NULL updater was specified");
00192 }
00193 
00194 void OccupancyMapMonitor::publishDebugInformation(bool flag)
00195 {
00196   debug_info_ = flag;
00197   for (std::size_t i = 0 ; i < map_updaters_.size() ; ++i)
00198     map_updaters_[i]->publishDebugInformation(debug_info_);
00199 }
00200 
00201 void OccupancyMapMonitor::setMapFrame(const std::string &frame)
00202 {
00203   boost::mutex::scoped_lock _(parameters_lock_); // we lock since an updater could specify a new frame for us
00204   map_frame_ = frame;
00205 }
00206 
00207 ShapeHandle OccupancyMapMonitor::excludeShape(const shapes::ShapeConstPtr &shape)
00208 {
00209   // if we have just one updater, remove the additional level of indirection
00210   if (map_updaters_.size() == 1)
00211     return map_updaters_[0]->excludeShape(shape);
00212 
00213   ShapeHandle h = 0;
00214   for (std::size_t i = 0 ; i < map_updaters_.size() ; ++i)
00215   {
00216     ShapeHandle mh = map_updaters_[i]->excludeShape(shape);
00217     if (mh)
00218     {
00219       h = ++mesh_handle_count_;
00220       mesh_handles_[i][h] = mh;
00221     }
00222   }
00223   return h;
00224 }
00225 
00226 void OccupancyMapMonitor::forgetShape(ShapeHandle handle)
00227 {
00228   // if we have just one updater, remove the additional level of indirection
00229   if (map_updaters_.size() == 1)
00230   {
00231     map_updaters_[0]->forgetShape(handle);
00232     return;
00233   }
00234 
00235   for (std::size_t i = 0 ; i < map_updaters_.size() ; ++i)
00236   {
00237     std::map<ShapeHandle, ShapeHandle>::const_iterator it = mesh_handles_[i].find(handle);
00238     if (it == mesh_handles_[i].end())
00239       continue;
00240     map_updaters_[i]->forgetShape(it->second);
00241   }
00242 }
00243 
00244 void OccupancyMapMonitor::setTransformCacheCallback(const TransformCacheProvider& transform_callback)
00245 {
00246   // if we have just one updater, we connect it directly to the transform provider
00247   if (map_updaters_.size() == 1)
00248     map_updaters_[0]->setTransformCacheCallback(transform_callback);
00249   else
00250     transform_cache_callback_ = transform_callback;
00251 }
00252 
00253 bool OccupancyMapMonitor::getShapeTransformCache(std::size_t index, const std::string &target_frame, const ros::Time &target_time, ShapeTransformCache &cache) const
00254 {
00255   if (transform_cache_callback_)
00256   {
00257     ShapeTransformCache tempCache;
00258     if (transform_cache_callback_(target_frame, target_time, tempCache))
00259     {
00260       for (ShapeTransformCache::iterator it = tempCache.begin() ; it != tempCache.end() ; ++it)
00261       {
00262         std::map<ShapeHandle, ShapeHandle>::const_iterator jt = mesh_handles_[index].find(it->first);
00263         if (jt == mesh_handles_[index].end())
00264         {
00265           ROS_ERROR_THROTTLE(1, "Incorrect mapping of mesh handles");
00266           return false;
00267         }
00268         else
00269           cache[jt->second] = it->second;
00270       }
00271       return true;
00272     }
00273     else
00274       return false;
00275   }
00276   else
00277     return false;
00278 }
00279 
00280 bool OccupancyMapMonitor::saveMapCallback(moveit_msgs::SaveMap::Request& request, moveit_msgs::SaveMap::Response& response)
00281 {
00282   ROS_INFO("Writing map to %s", request.filename.c_str());
00283   tree_->lockRead();
00284   try
00285   {
00286     response.success = tree_->writeBinary(request.filename);
00287   }
00288   catch (...)
00289   {
00290     response.success = false;
00291   }
00292   tree_->unlockRead();
00293   return true;
00294 }
00295 
00296 bool OccupancyMapMonitor::loadMapCallback(moveit_msgs::LoadMap::Request& request, moveit_msgs::LoadMap::Response& response)
00297 {
00298   ROS_INFO("Reading map from %s", request.filename.c_str());
00299 
00300   /* load the octree from disk */
00301   tree_->lockWrite();
00302   try
00303   {
00304     response.success = tree_->readBinary(request.filename);
00305   }
00306   catch (...)
00307   {
00308     ROS_ERROR("Failed to load map from file");
00309     response.success = false;
00310   }
00311   tree_->unlockWrite();
00312 
00313   return true;
00314 }
00315 
00316 void OccupancyMapMonitor::startMonitor()
00317 {
00318   /* initialize all of the occupancy map updaters */
00319   for (std::size_t i = 0 ; i < map_updaters_.size() ; ++i)
00320     map_updaters_[i]->start();
00321 }
00322 
00323 void OccupancyMapMonitor::stopMonitor()
00324 {
00325   for (std::size_t i = 0 ; i < map_updaters_.size() ; ++i)
00326     map_updaters_[i]->stop();
00327 }
00328 
00329 OccupancyMapMonitor::~OccupancyMapMonitor()
00330 {
00331   stopMonitor();
00332 }
00333 
00334 }


perception
Author(s): Ioan Sucan , Jon Binney
autogenerated on Mon Oct 6 2014 02:31:20