Skip to content

Commit

Permalink
Added compatibility with moveit#602
Browse files Browse the repository at this point in the history
  • Loading branch information
TheBrewCrew committed Aug 13, 2015
1 parent 6a2cd9f commit 3796a55
Showing 1 changed file with 2 additions and 0 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -473,6 +473,7 @@ void planning_scene_monitor::PlanningSceneMonitor::clearOctomap()
{
occupancy_map_monitor::WriteLock lock = octomap_monitor_->writingMap();
octomap_monitor_->getOcTreePtr()->clear();
octomap_monitor_->getOcTreePtr()->resetChangeDetection();
}

void planning_scene_monitor::PlanningSceneMonitor::newPlanningSceneMessage(const moveit_msgs::PlanningScene& scene)
Expand Down Expand Up @@ -1067,6 +1068,7 @@ void planning_scene_monitor::PlanningSceneMonitor::octomapUpdateCallback()
const Eigen::Affine3d rt = scene_->getCurrentState().getGlobalLinkTransform(robot_model_->getRootLinkName());
{
occupancy_map_monitor::WriteLock lock = octomap_monitor_->writingMap();
octomap_monitor_->getOcTreePtr()->enableChangeDetection(false);
octomap_monitor_->getOcTreePtr()->setBBXCenter(rt.translation().x(), rt.translation().y(), rt.translation().z());
octomap_monitor_->getOcTreePtr()->pruneBBX();
}
Expand Down

0 comments on commit 3796a55

Please sign in to comment.