Skip to content
This repository has been archived by the owner on Nov 13, 2017. It is now read-only.

Commit

Permalink
Moved map lock from OccMapTree to OccMapMonitor and updated locking t…
Browse files Browse the repository at this point in the history
…o RAII wherever possible
  • Loading branch information
TheBrewCrew committed Jul 18, 2015
1 parent ba3764f commit 373f94f
Show file tree
Hide file tree
Showing 9 changed files with 92 additions and 145 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -105,7 +105,7 @@ bool DepthImageOctomapUpdater::setParams(XmlRpc::XmlRpcValue &params)
bool DepthImageOctomapUpdater::initialize()
{
tf_ = monitor_->getTFClient();
free_space_updater_.reset(new LazyFreeSpaceUpdater(tree_, boost::bind(&OccupancyMapMonitor::triggerUpdateCallback, monitor_)));
free_space_updater_.reset(new LazyFreeSpaceUpdater(tree_, monitor_));

// create our mesh filter
mesh_filter_.reset(new mesh_filter::MeshFilter<mesh_filter::StereoCameraModel>(mesh_filter::MeshFilterBase::TransformCallback(),
Expand Down Expand Up @@ -422,10 +422,11 @@ void DepthImageOctomapUpdater::depthImageCallback(const sensor_msgs::ImageConstP
}

// figure out occupied cells and model cells
tree_->lockRead();


try
{
ReadLock lock = monitor_->readingMap();
const int h_bound = h - skip_vertical_pixels_;
const int w_bound = w - skip_horizontal_pixels_;

Expand Down Expand Up @@ -491,19 +492,17 @@ void DepthImageOctomapUpdater::depthImageCallback(const sensor_msgs::ImageConstP
}
catch (...)
{
tree_->unlockRead();
return;
}
tree_->unlockRead();

/* cells that overlap with the model are not occupied */
for (octomap::KeySet::iterator it = model_cells.begin(), end = model_cells.end(); it != end; ++it)
occupied_cells.erase(*it);

// mark occupied cells
tree_->lockWrite();
try
{
WriteLock lock = monitor_->writingMap();
/* now mark all occupied cells */
for (octomap::KeySet::iterator it = occupied_cells.begin(), end = occupied_cells.end(); it != end; ++it)
tree_->updateNode(*it, true);
Expand All @@ -512,7 +511,6 @@ void DepthImageOctomapUpdater::depthImageCallback(const sensor_msgs::ImageConstP
{
ROS_ERROR("Internal error while updating octree");
}
tree_->unlockWrite();
monitor_->triggerUpdateCallback();

// at this point we still have not freed the space
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@
#define MOVEIT_OCCUPANCY_MAP_MONITOR_LAZY_FREE_SPACE_UPDATER_

#include <moveit/occupancy_map_monitor/occupancy_map.h>
#include <moveit/occupancy_map_monitor/occupancy_map_monitor.h>
#include <boost/thread.hpp>
#include <deque>

Expand All @@ -48,7 +49,7 @@ class LazyFreeSpaceUpdater
{
public:

LazyFreeSpaceUpdater(const OccMapTreePtr &tree, const boost::function<void()> &update_callback, unsigned int max_batch_size = 10);
LazyFreeSpaceUpdater(const OccMapTreePtr &tree, OccupancyMapMonitor *monitor, unsigned int max_batch_size = 10);
~LazyFreeSpaceUpdater();

void pushLazyUpdate(octomap::KeySet *occupied_cells, octomap::KeySet *model_cells, const octomap::point3d &sensor_origin);
Expand All @@ -66,23 +67,11 @@ class LazyFreeSpaceUpdater
void lazyUpdateThread();
void processThread();

void triggerUpdateCallback()
{
if (update_callback_)
update_callback_();
}

/** @brief Set the callback to trigger when updates are received */
void setUpdateCallback(const boost::function<void()> &update_callback)
{
update_callback_ = update_callback;
}

OccMapTreePtr tree_;
OccupancyMapMonitor *monitor_;
bool running_;
std::size_t max_batch_size_;
double max_sensor_delta_;
boost::function<void()> update_callback_;

std::deque<octomap::KeySet*> occupied_cells_sets_;
std::deque<octomap::KeySet*> model_cells_sets_;
Expand Down
44 changes: 21 additions & 23 deletions perception/lazy_free_space_updater/src/lazy_free_space_updater.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,12 +40,12 @@
namespace occupancy_map_monitor
{

LazyFreeSpaceUpdater::LazyFreeSpaceUpdater(const OccMapTreePtr &tree, const boost::function<void()> &update_callback, unsigned int max_batch_size) :
LazyFreeSpaceUpdater::LazyFreeSpaceUpdater(const OccMapTreePtr &tree, OccupancyMapMonitor *monitor, unsigned int max_batch_size) :
tree_(tree),
running_(true),
max_batch_size_(max_batch_size),
max_sensor_delta_(1e-3), // 1mm
update_callback_(update_callback),
monitor_(monitor),
process_occupied_cells_set_(NULL),
process_model_cells_set_(NULL),
update_thread_(boost::bind(&LazyFreeSpaceUpdater::lazyUpdateThread, this)),
Expand Down Expand Up @@ -122,32 +122,32 @@ void LazyFreeSpaceUpdater::processThread()
ROS_DEBUG("Begin processing batched update: marking free cells due to %lu occupied cells and %lu model cells", (long unsigned int)process_occupied_cells_set_->size(), (long unsigned int)process_model_cells_set_->size());

ros::WallTime start = ros::WallTime::now();
tree_->lockRead();
{
ReadLock lock = monitor_->readingMap();

#pragma omp sections
{
{

#pragma omp section
{
/* compute the free cells along each ray that ends at an occupied cell */
for (OcTreeKeyCountMap::iterator it = process_occupied_cells_set_->begin(), end = process_occupied_cells_set_->end(); it != end; ++it)
if (tree_->computeRayKeys(process_sensor_origin_, tree_->keyToCoord(it->first), key_ray1))
for (octomap::KeyRay::iterator jt = key_ray1.begin(), end = key_ray1.end() ; jt != end ; ++jt)
free_cells1[*jt] += it->second;
}
{
/* compute the free cells along each ray that ends at an occupied cell */
for (OcTreeKeyCountMap::iterator it = process_occupied_cells_set_->begin(), end = process_occupied_cells_set_->end(); it != end; ++it)
if (tree_->computeRayKeys(process_sensor_origin_, tree_->keyToCoord(it->first), key_ray1))
for (octomap::KeyRay::iterator jt = key_ray1.begin(), end = key_ray1.end() ; jt != end ; ++jt)
free_cells1[*jt] += it->second;
}

#pragma omp section
{
/* compute the free cells along each ray that ends at a model cell */
for (octomap::KeySet::iterator it = process_model_cells_set_->begin(), end = process_model_cells_set_->end(); it != end; ++it)
if (tree_->computeRayKeys(process_sensor_origin_, tree_->keyToCoord(*it), key_ray2))
for (octomap::KeyRay::iterator jt = key_ray2.begin(), end = key_ray2.end() ; jt != end ; ++jt)
free_cells2[*jt]++;
{
/* compute the free cells along each ray that ends at a model cell */
for (octomap::KeySet::iterator it = process_model_cells_set_->begin(), end = process_model_cells_set_->end(); it != end; ++it)
if (tree_->computeRayKeys(process_sensor_origin_, tree_->keyToCoord(*it), key_ray2))
for (octomap::KeyRay::iterator jt = key_ray2.begin(), end = key_ray2.end() ; jt != end ; ++jt)
free_cells2[*jt]++;
}
}
}

tree_->unlockRead();

for (OcTreeKeyCountMap::iterator it = process_occupied_cells_set_->begin(), end = process_occupied_cells_set_->end(); it != end; ++it)
{
free_cells1.erase(it->first);
Expand All @@ -161,10 +161,9 @@ void LazyFreeSpaceUpdater::processThread()
}
ROS_DEBUG("Marking %lu cells as free...", (long unsigned int)(free_cells1.size() + free_cells2.size()));

tree_->lockWrite();

try
{
WriteLock lock = monitor_->writingMap();
// set the logodds to the minimum for the cells that are part of the model
for (octomap::KeySet::iterator it = process_model_cells_set_->begin(), end = process_model_cells_set_->end(); it != end; ++it)
tree_->updateNode(*it, lg_0);
Expand All @@ -179,8 +178,7 @@ void LazyFreeSpaceUpdater::processThread()
{
ROS_ERROR("Internal error while updating octree");
}
tree_->unlockWrite();
triggerUpdateCallback();
monitor_->triggerUpdateCallback();

ROS_DEBUG("Marked free cells in %lf ms", (ros::WallTime::now() - start).toSec() * 1000.0);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,72 +39,13 @@

#include <octomap/octomap.h>
#include <boost/shared_ptr.hpp>
#include <boost/thread/shared_mutex.hpp>
#include <boost/function.hpp>

namespace occupancy_map_monitor
{

typedef octomap::OcTreeNode OccMapNode;

class OccMapTree : public octomap::OcTree
{
public:

OccMapTree(double resolution) : octomap::OcTree(resolution)
{
}

OccMapTree(const std::string &filename) : octomap::OcTree(filename)
{
}

/** @brief lock the underlying octree. it will not be read or written by the
* monitor until unlockTree() is called */
void lockRead()
{
tree_mutex_.lock_shared();
}

/** @brief unlock the underlying octree. */
void unlockRead()
{
tree_mutex_.unlock_shared();
}

/** @brief lock the underlying octree. it will not be read or written by the
* monitor until unlockTree() is called */
void lockWrite()
{
tree_mutex_.lock();
}

/** @brief unlock the underlying octree. */
void unlockWrite()
{
tree_mutex_.unlock();
}

typedef boost::shared_lock<boost::shared_mutex> ReadLock;
typedef boost::unique_lock<boost::shared_mutex> WriteLock;

ReadLock reading()
{
return ReadLock(tree_mutex_);
}

WriteLock writing()
{
return WriteLock(tree_mutex_);
}

private:
boost::shared_mutex tree_mutex_;

};

typedef boost::shared_ptr<OccMapTree> OccMapTreePtr;
typedef boost::shared_ptr<const OccMapTree> OccMapTreeConstPtr;
typedef boost::shared_ptr<octomap::OcTree> OccMapTreePtr;
typedef boost::shared_ptr<const octomap::OcTree> OccMapTreeConstPtr;

}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,10 +49,15 @@
#include <moveit/occupancy_map_monitor/occupancy_map_updater.h>

#include <boost/thread/mutex.hpp>
#include <boost/thread/shared_mutex.hpp>
#include <boost/function.hpp>

namespace occupancy_map_monitor
{

typedef boost::shared_lock<boost::shared_mutex> ReadLock;
typedef boost::unique_lock<boost::shared_mutex> WriteLock;

class OccupancyMapMonitor
{
public:
Expand Down Expand Up @@ -129,6 +134,42 @@ class OccupancyMapMonitor
return active_;
}

/** @brief lock the underlying octree. it will not be read or written by the
* monitor until unlockTree() is called */
void lockMapRead()
{
map_mutex_.lock_shared();
}

/** @brief unlock the underlying octree. */
void unlockMapRead()
{
map_mutex_.unlock_shared();
}

/** @brief lock the underlying octree. it will not be read or written by the
* monitor until unlockTree() is called */
void lockMapWrite()
{
map_mutex_.lock();
}

/** @brief unlock the underlying octree. */
void unlockMapWrite()
{
map_mutex_.unlock();
}

ReadLock readingMap()
{
return ReadLock(map_mutex_);
}

WriteLock writingMap()
{
return WriteLock(map_mutex_);
}

private:

void initialize();
Expand All @@ -145,6 +186,7 @@ class OccupancyMapMonitor
std::string map_frame_;
double map_resolution_;
boost::mutex parameters_lock_;
boost::shared_mutex map_mutex_;

OccMapTreePtr tree_;
OccMapTreeConstPtr tree_const_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,7 @@ void OccupancyMapMonitor::initialize()
if (!tf_ && !map_frame_.empty())
ROS_WARN("Target frame specified but no TF instance specified. No transforms will be applied to received data.");

tree_.reset(new OccMapTree(map_resolution_));
tree_.reset(new octomap::OcTree(map_resolution_));
tree_const_ = tree_;

XmlRpc::XmlRpcValue sensor_list;
Expand Down Expand Up @@ -283,16 +283,15 @@ bool OccupancyMapMonitor::getShapeTransformCache(std::size_t index, const std::s
bool OccupancyMapMonitor::saveMapCallback(moveit_msgs::SaveMap::Request& request, moveit_msgs::SaveMap::Response& response)
{
ROS_INFO("Writing map to %s", request.filename.c_str());
tree_->lockRead();
try
{
ReadLock lock = readingMap();
response.success = tree_->writeBinary(request.filename);
}
catch (...)
{
response.success = false;
}
tree_->unlockRead();
return true;
}

Expand All @@ -301,17 +300,16 @@ bool OccupancyMapMonitor::loadMapCallback(moveit_msgs::LoadMap::Request& request
ROS_INFO("Reading map from %s", request.filename.c_str());

/* load the octree from disk */
tree_->lockWrite();
try
{
WriteLock lock = writingMap();
response.success = tree_->readBinary(request.filename);
}
catch (...)
{
ROS_ERROR("Failed to load map from file");
response.success = false;
}
tree_->unlockWrite();

return true;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -48,17 +48,16 @@ static void publishOctomap(ros::Publisher *octree_binary_pub, occupancy_map_moni
map.header.frame_id = server->getMapFrame();
map.header.stamp = ros::Time::now();

server->getOcTreePtr()->lockRead();
try
{
occupancy_map_monitor::ReadLock lock = server->readingMap();
if (!octomap_msgs::binaryMapToMsgData(*server->getOcTreePtr(), map.data))
ROS_ERROR_THROTTLE(1, "Could not generate OctoMap message");
}
catch(...)
{
ROS_ERROR_THROTTLE(1, "Exception thrown while generating OctoMap message");
}
server->getOcTreePtr()->unlockRead();

octree_binary_pub->publish(map);
}
Expand Down
Loading

0 comments on commit 373f94f

Please sign in to comment.