00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <industrial_collision_detection/collision_detection/collision_world_industrial.h>
00038 #include <fcl/shape/geometric_shape_to_BVH_model.h>
00039 #include <fcl/traversal/traversal_node_bvhs.h>
00040 #include <fcl/traversal/traversal_node_setup.h>
00041 #include <fcl/collision_node.h>
00042
00043 collision_detection::CollisionWorldIndustrial::CollisionWorldIndustrial() :
00044 CollisionWorld()
00045 {
00046 fcl::DynamicAABBTreeCollisionManager* m = new fcl::DynamicAABBTreeCollisionManager();
00047
00048 manager_.reset(m);
00049
00050
00051 observer_handle_ = getWorld()->addObserver(boost::bind(&CollisionWorldIndustrial::notifyObjectChange, this, _1, _2));
00052 }
00053
00054 collision_detection::CollisionWorldIndustrial::CollisionWorldIndustrial(const WorldPtr& world) :
00055 CollisionWorld(world)
00056 {
00057 fcl::DynamicAABBTreeCollisionManager* m = new fcl::DynamicAABBTreeCollisionManager();
00058
00059 manager_.reset(m);
00060
00061
00062 observer_handle_ = getWorld()->addObserver(boost::bind(&CollisionWorldIndustrial::notifyObjectChange, this, _1, _2));
00063 getWorld()->notifyObserverAllObjects(observer_handle_, World::CREATE);
00064 }
00065
00066 collision_detection::CollisionWorldIndustrial::CollisionWorldIndustrial(const CollisionWorldIndustrial &other, const WorldPtr& world) :
00067 CollisionWorld(other, world)
00068 {
00069 fcl::DynamicAABBTreeCollisionManager* m = new fcl::DynamicAABBTreeCollisionManager();
00070
00071 manager_.reset(m);
00072
00073 fcl_objs_ = other.fcl_objs_;
00074 for (std::map<std::string, FCLObject>::iterator it = fcl_objs_.begin() ; it != fcl_objs_.end() ; ++it)
00075 it->second.registerTo(manager_.get());
00076
00077
00078
00079 observer_handle_ = getWorld()->addObserver(boost::bind(&CollisionWorldIndustrial::notifyObjectChange, this, _1, _2));
00080 }
00081
00082 collision_detection::CollisionWorldIndustrial::~CollisionWorldIndustrial()
00083 {
00084 getWorld()->removeObserver(observer_handle_);
00085 }
00086
00087 void collision_detection::CollisionWorldIndustrial::checkRobotCollision(const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state) const
00088 {
00089 checkRobotCollisionHelper(req, res, robot, state, NULL);
00090 }
00091
00092 void collision_detection::CollisionWorldIndustrial::checkRobotCollision(const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state, const AllowedCollisionMatrix &acm) const
00093 {
00094 checkRobotCollisionHelper(req, res, robot, state, &acm);
00095 }
00096
00097 void collision_detection::CollisionWorldIndustrial::checkRobotCollision(const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state1, const robot_state::RobotState &state2) const
00098 {
00099 logError("FCL continuous collision checking not yet implemented");
00100 }
00101
00102 void collision_detection::CollisionWorldIndustrial::checkRobotCollision(const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state1, const robot_state::RobotState &state2, const AllowedCollisionMatrix &acm) const
00103 {
00104 logError("FCL continuous collision checking not yet implemented");
00105 }
00106
00107 void collision_detection::CollisionWorldIndustrial::checkRobotCollisionHelper(const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state, const AllowedCollisionMatrix *acm) const
00108 {
00109
00110 if (fcl_objs_.size() == 0)
00111 return;
00112
00113 const CollisionRobotIndustrial &robot_fcl = dynamic_cast<const CollisionRobotIndustrial&>(robot);
00114 FCLObject fcl_obj;
00115 robot_fcl.constructFCLObject(state, fcl_obj);
00116
00117 CollisionData cd(&req, &res, acm);
00118 cd.enableGroup(robot.getRobotModel());
00119 for (std::size_t i = 0 ; !cd.done_ && i < fcl_obj.collision_objects_.size() ; ++i)
00120 manager_->collide(fcl_obj.collision_objects_[i].get(), &cd, &collisionCallback);
00121
00122 if (req.distance)
00123 {
00124 DistanceRequest dreq(false, true, req.group_name, acm);
00125 DistanceResult dres;
00126
00127 dreq.enableGroup(robot.getRobotModel());
00128 distanceRobotHelper(dreq, dres, robot, state);
00129 res.distance = dres.minimum_distance.min_distance;
00130 }
00131 }
00132
00133 void collision_detection::CollisionWorldIndustrial::checkWorldCollision(const CollisionRequest &req, CollisionResult &res, const CollisionWorld &other_world) const
00134 {
00135 checkWorldCollisionHelper(req, res, other_world, NULL);
00136 }
00137
00138 void collision_detection::CollisionWorldIndustrial::checkWorldCollision(const CollisionRequest &req, CollisionResult &res, const CollisionWorld &other_world, const AllowedCollisionMatrix &acm) const
00139 {
00140 checkWorldCollisionHelper(req, res, other_world, &acm);
00141 }
00142
00143 void collision_detection::CollisionWorldIndustrial::checkWorldCollisionHelper(const CollisionRequest &req, CollisionResult &res, const CollisionWorld &other_world, const AllowedCollisionMatrix *acm) const
00144 {
00145 const CollisionWorldIndustrial &other_fcl_world = dynamic_cast<const CollisionWorldIndustrial&>(other_world);
00146 CollisionData cd(&req, &res, acm);
00147 manager_->collide(other_fcl_world.manager_.get(), &cd, &collisionCallback);
00148
00149 if (req.distance)
00150 res.distance = distanceWorldHelper(other_world, acm);
00151 }
00152
00153 void collision_detection::CollisionWorldIndustrial::constructFCLObject(const World::Object *obj, FCLObject &fcl_obj) const
00154 {
00155 for (std::size_t i = 0 ; i < obj->shapes_.size() ; ++i)
00156 {
00157 FCLGeometryConstPtr g = createCollisionGeometry(obj->shapes_[i], obj);
00158 if (g)
00159 {
00160 fcl::CollisionObject *co = new fcl::CollisionObject(g->collision_geometry_, transform2fcl(obj->shape_poses_[i]));
00161 fcl_obj.collision_objects_.push_back(boost::shared_ptr<fcl::CollisionObject>(co));
00162 fcl_obj.collision_geometry_.push_back(g);
00163 }
00164 }
00165 }
00166
00167 void collision_detection::CollisionWorldIndustrial::updateFCLObject(const std::string &id)
00168 {
00169
00170 std::map<std::string, FCLObject>::iterator jt = fcl_objs_.find(id);
00171 if (jt != fcl_objs_.end())
00172 {
00173 jt->second.unregisterFrom(manager_.get());
00174 jt->second.clear();
00175 }
00176
00177
00178 collision_detection::World::const_iterator it = getWorld()->find(id);
00179 if (it != getWorld()->end())
00180 {
00181
00182 if (jt != fcl_objs_.end())
00183 {
00184 constructFCLObject(it->second.get(), jt->second);
00185 jt->second.registerTo(manager_.get());
00186 }
00187 else
00188 {
00189 constructFCLObject(it->second.get(), fcl_objs_[id]);
00190 fcl_objs_[id].registerTo(manager_.get());
00191 }
00192 }
00193 else
00194 {
00195 if (jt != fcl_objs_.end())
00196 fcl_objs_.erase(jt);
00197 }
00198
00199
00200 }
00201
00202 void collision_detection::CollisionWorldIndustrial::setWorld(const WorldPtr& world)
00203 {
00204 if (world == getWorld())
00205 return;
00206
00207
00208 getWorld()->removeObserver(observer_handle_);
00209
00210
00211 manager_->clear();
00212 fcl_objs_.clear();
00213 cleanCollisionGeometryCache();
00214
00215 CollisionWorld::setWorld(world);
00216
00217
00218 observer_handle_ = getWorld()->addObserver(boost::bind(&CollisionWorldIndustrial::notifyObjectChange, this, _1, _2));
00219
00220
00221 getWorld()->notifyObserverAllObjects(observer_handle_, World::CREATE);
00222 }
00223
00224 void collision_detection::CollisionWorldIndustrial::notifyObjectChange(const ObjectConstPtr& obj, World::Action action)
00225 {
00226 if (action == World::DESTROY)
00227 {
00228 std::map<std::string, FCLObject>::iterator it = fcl_objs_.find(obj->id_);
00229 if (it != fcl_objs_.end())
00230 {
00231 it->second.unregisterFrom(manager_.get());
00232 it->second.clear();
00233 fcl_objs_.erase(it);
00234 }
00235 cleanCollisionGeometryCache();
00236 }
00237 else
00238 {
00239 updateFCLObject(obj->id_);
00240 if (action & (World::DESTROY|World::REMOVE_SHAPE))
00241 cleanCollisionGeometryCache();
00242 }
00243 }
00244
00245 double collision_detection::CollisionWorldIndustrial::distanceRobotHelper(const CollisionRobot &robot, const robot_state::RobotState &state, const AllowedCollisionMatrix *acm) const
00246 {
00247
00248 if (fcl_objs_.size() == 0)
00249 return std::numeric_limits<double>::max();
00250
00251 const CollisionRobotIndustrial& robot_fcl = dynamic_cast<const CollisionRobotIndustrial&>(robot);
00252 FCLObject fcl_obj;
00253 robot_fcl.constructFCLObject(state, fcl_obj);
00254
00255 CollisionRequest req;
00256 CollisionResult res;
00257 CollisionData cd(&req, &res, acm);
00258 cd.enableGroup(robot.getRobotModel());
00259
00260 for(std::size_t i = 0; !cd.done_ && i < fcl_obj.collision_objects_.size(); ++i)
00261 manager_->distance(fcl_obj.collision_objects_[i].get(), &cd, &distanceCallback);
00262
00263
00264 return res.distance;
00265 }
00266
00267 void collision_detection::CollisionWorldIndustrial::distanceRobotHelper(const DistanceRequest &req, DistanceResult &res, const collision_detection::CollisionRobot &robot, const robot_state::RobotState &state) const
00268 {
00269 const CollisionRobotIndustrial& robot_fcl = dynamic_cast<const CollisionRobotIndustrial&>(robot);
00270 FCLObject fcl_obj;
00271 robot_fcl.constructFCLObject(state, fcl_obj);
00272
00273 DistanceData drd(&req, &res);
00274 for(std::size_t i = 0; !drd.done && i < fcl_obj.collision_objects_.size(); ++i)
00275 manager_->distance(fcl_obj.collision_objects_[i].get(), &drd, &distanceDetailedCallback);
00276
00277 }
00278
00279 double collision_detection::CollisionWorldIndustrial::distanceRobot(const CollisionRobot &robot, const robot_state::RobotState &state) const
00280 {
00281 return distanceRobotHelper(robot, state, NULL);
00282 }
00283
00284 double collision_detection::CollisionWorldIndustrial::distanceRobot(const CollisionRobot &robot, const robot_state::RobotState &state, const AllowedCollisionMatrix &acm) const
00285 {
00286 return distanceRobotHelper(robot, state, &acm);
00287 }
00288
00289 void collision_detection::CollisionWorldIndustrial::distanceRobot(const DistanceRequest &req, DistanceResult &res, const collision_detection::CollisionRobot &robot, const robot_state::RobotState &state) const
00290 {
00291 distanceRobotHelper(req, res, robot, state);
00292 }
00293
00294 double collision_detection::CollisionWorldIndustrial::distanceWorld(const CollisionWorld &world) const
00295 {
00296 return distanceWorldHelper(world, NULL);
00297 }
00298
00299 double collision_detection::CollisionWorldIndustrial::distanceWorld(const CollisionWorld &world, const AllowedCollisionMatrix &acm) const
00300 {
00301 return distanceWorldHelper(world, &acm);
00302 }
00303
00304 double collision_detection::CollisionWorldIndustrial::distanceWorldHelper(const CollisionWorld &other_world, const AllowedCollisionMatrix *acm) const
00305 {
00306 const CollisionWorldIndustrial& other_fcl_world = dynamic_cast<const CollisionWorldIndustrial&>(other_world);
00307 CollisionRequest req;
00308 CollisionResult res;
00309 CollisionData cd(&req, &res, acm);
00310 manager_->distance(other_fcl_world.manager_.get(), &cd, &distanceCallback);
00311
00312 return res.distance;
00313 }
00314