$search
00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2008, 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 00045 #include "planning_environment/monitors/planning_monitor.h" 00046 #include <arm_navigation_msgs/CollisionMap.h> 00047 00048 #include <iostream> 00049 #include <sstream> 00050 #include <string> 00051 #include <map> 00052 00053 class RemoveObjectExample 00054 { 00055 public: 00056 00057 RemoveObjectExample(void) 00058 { 00059 collisionModels_ = new planning_environment::CollisionModels("robot_description"); 00060 if (collisionModels_->loadedModels()) 00061 { 00062 collisionMapPublisher_ = nh_.advertise<arm_navigation_msgs::CollisionMap>("collision_map_with_removed_box", 1); 00063 planningMonitor_ = new planning_environment::PlanningMonitor(collisionModels_, &tf_); 00064 planningMonitor_->setOnAfterMapUpdateCallback(boost::bind(&RemoveObjectExample::afterWorldUpdate, this, _1, _2)); 00065 } 00066 } 00067 00068 virtual ~RemoveObjectExample(void) 00069 { 00070 if (planningMonitor_) 00071 delete planningMonitor_; 00072 if (collisionModels_) 00073 delete collisionModels_; 00074 } 00075 00076 protected: 00077 00078 void afterWorldUpdate(const arm_navigation_msgs::CollisionMapConstPtr &collisionMap, bool clear) 00079 { 00080 // we do not care about incremental updates, only re-writes of the map 00081 if (!clear) 00082 return; 00083 00084 // at this point, the environment model has the collision map inside it 00085 00086 00087 // get exclusive access 00088 planningMonitor_->getEnvironmentModel()->lock(); 00089 00090 // get a copy of our own, to play with :) 00091 collision_space::EnvironmentModel *env = planningMonitor_->getEnvironmentModel()->clone(); 00092 00093 // release our hold 00094 planningMonitor_->getEnvironmentModel()->unlock(); 00095 00096 00097 // create a box 00098 shapes::Shape *box = new shapes::Box(2, 2, 2); 00099 btTransform pose; 00100 pose.setIdentity(); 00101 00102 // remove the objects colliding with the box 00103 env->removeCollidingObjects(box, pose); 00104 00105 // forward the updated map 00106 arm_navigation_msgs::CollisionMap cmap; 00107 planningMonitor_->recoverCollisionMap(env, cmap); 00108 collisionMapPublisher_.publish(cmap); 00109 00110 // throw away our copy 00111 delete env; 00112 00113 ROS_INFO("Received collision map with %d points and published one with %d points", 00114 (int)collisionMap->boxes.size(), (int)cmap.boxes.size()); 00115 00116 } 00117 00118 private: 00119 00120 ros::NodeHandle nh_; 00121 tf::TransformListener tf_; 00122 00123 ros::Publisher collisionMapPublisher_; 00124 planning_environment::CollisionModels *collisionModels_; 00125 planning_environment::PlanningMonitor *planningMonitor_; 00126 }; 00127 00128 int main(int argc, char **argv) 00129 { 00130 ros::init(argc, argv, "remove_object_example"); 00131 00132 RemoveObjectExample example; 00133 ros::spin(); 00134 00135 return 0; 00136 }