collision_robot_industrial.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 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 */
00036 
00037 #include <industrial_collision_detection/collision_detection/collision_robot_industrial.h>
00038 
00039 collision_detection::CollisionRobotIndustrial::CollisionRobotIndustrial(const robot_model::RobotModelConstPtr &model, double padding, double scale)
00040   : CollisionRobot(model, padding, scale)
00041 {
00042   const std::vector<const robot_model::LinkModel*>& links = robot_model_->getLinkModelsWithCollisionGeometry();
00043   std::size_t index;
00044   geoms_.resize(robot_model_->getLinkGeometryCount());
00045   fcl_objs_.resize(robot_model_->getLinkGeometryCount());
00046   // we keep the same order of objects as what RobotState *::getLinkState() returns
00047   for (std::size_t i = 0 ; i < links.size() ; ++i)
00048     for (std::size_t j = 0 ; j < links[i]->getShapes().size() ; ++j)
00049     {
00050       FCLGeometryConstPtr g = createCollisionGeometry(links[i]->getShapes()[j], getLinkScale(links[i]->getName()), getLinkPadding(links[i]->getName()), links[i], j);
00051       if (g)
00052       {
00053         index = links[i]->getFirstCollisionBodyTransformIndex() + j;
00054         geoms_[index] = g;
00055 
00056         // Need to store the FCL object so the AABB does not get recreated very time.
00057         // Every time this object is created, g->computeLocalAABB() is called  which is
00058         // very expensive and should only be calculated once. To update the AABB, use the
00059         // collObj->setTsetTransform and then call collObj->computeAABB() to tranform the AABB.
00060         fcl_objs_[index] = FCLCollisionObjectConstPtr(new fcl::CollisionObject(g->collision_geometry_));
00061       }
00062       else
00063         logError("Unable to construct collision geometry for link '%s'", links[i]->getName().c_str());
00064     }
00065 }
00066 
00067 collision_detection::CollisionRobotIndustrial::CollisionRobotIndustrial(const CollisionRobotIndustrial &other) : CollisionRobot(other)
00068 {
00069   geoms_ = other.geoms_;
00070   fcl_objs_ = other.fcl_objs_;
00071 }
00072 
00073 void collision_detection::CollisionRobotIndustrial::getAttachedBodyObjects(const robot_state::AttachedBody *ab, std::vector<FCLGeometryConstPtr> &geoms) const
00074 {
00075   const std::vector<shapes::ShapeConstPtr> &shapes = ab->getShapes();
00076   for (std::size_t i = 0 ; i < shapes.size() ; ++i)
00077   {
00078     FCLGeometryConstPtr co = createCollisionGeometry(shapes[i], ab, i);
00079     if (co)
00080       geoms.push_back(co);
00081   }
00082 }
00083 
00084 void collision_detection::CollisionRobotIndustrial::constructFCLObject(const robot_state::RobotState &state, FCLObject &fcl_obj) const
00085 {
00086   fcl_obj.collision_objects_.reserve(geoms_.size());
00087   fcl::Transform3f tf;
00088 
00089   for (std::size_t i = 0 ; i < geoms_.size() ; ++i)
00090     if (geoms_[i] && geoms_[i]->collision_geometry_)
00091     {
00092       transform2fcl(state.getCollisionBodyTransform(geoms_[i]->collision_geometry_data_->ptr.link, geoms_[i]->collision_geometry_data_->shape_index), tf);
00093       fcl::CollisionObject *collObj = new fcl::CollisionObject(*fcl_objs_[i]);
00094       collObj->setTransform(tf);
00095       collObj->computeAABB();
00096       fcl_obj.collision_objects_.push_back(FCLCollisionObjectPtr(collObj));
00097     }
00098   
00099   // TODO: Implement a method for caching fcl::CollisionObject's for robot_state::AttachedBody's
00100   std::vector<const robot_state::AttachedBody*> ab;
00101   state.getAttachedBodies(ab);
00102   for (std::size_t j = 0 ; j < ab.size() ; ++j)
00103   {
00104     std::vector<FCLGeometryConstPtr> objs;
00105     getAttachedBodyObjects(ab[j], objs);
00106     const EigenSTL::vector_Affine3d &ab_t = ab[j]->getGlobalCollisionBodyTransforms();
00107     for (std::size_t k = 0 ; k < objs.size() ; ++k)
00108       if (objs[k]->collision_geometry_)
00109       {
00110         transform2fcl(ab_t[k], tf);
00111         fcl_obj.collision_objects_.push_back(FCLCollisionObjectPtr(new fcl::CollisionObject(objs[k]->collision_geometry_, tf)));
00112         // we copy the shared ptr to the CollisionGeometryData, as this is not stored by the class itself,
00113         // and would be destroyed when objs goes out of scope.
00114         fcl_obj.collision_geometry_.push_back(objs[k]);
00115       }
00116   }
00117 }
00118 
00119 void collision_detection::CollisionRobotIndustrial::allocSelfCollisionBroadPhase(const robot_state::RobotState &state, FCLManager &manager) const
00120 {
00121   fcl::DynamicAABBTreeCollisionManager* m = new fcl::DynamicAABBTreeCollisionManager();
00122   // m->tree_init_level = 2;
00123   manager.manager_.reset(m);
00124   constructFCLObject(state, manager.object_);
00125   manager.object_.registerTo(manager.manager_.get());
00126   // manager.manager_->update();
00127 }
00128 
00129 void collision_detection::CollisionRobotIndustrial::checkSelfCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state) const
00130 {
00131   checkSelfCollisionHelper(req, res, state, NULL);
00132 }
00133 
00134 void collision_detection::CollisionRobotIndustrial::checkSelfCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state,
00135                                                                 const AllowedCollisionMatrix &acm) const
00136 {
00137   checkSelfCollisionHelper(req, res, state, &acm);
00138 }
00139 
00140 void collision_detection::CollisionRobotIndustrial::checkSelfCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state1, const robot_state::RobotState &state2) const
00141 {
00142   logError("FCL continuous collision checking not yet implemented");
00143 }
00144 
00145 void collision_detection::CollisionRobotIndustrial::checkSelfCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state1, const robot_state::RobotState &state2, const AllowedCollisionMatrix &acm) const
00146 {
00147   logError("FCL continuous collision checking not yet implemented");
00148 }
00149 
00150 void collision_detection::CollisionRobotIndustrial::checkSelfCollisionHelper(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state,
00151                                                                              const AllowedCollisionMatrix *acm) const
00152 {
00153   FCLManager manager;
00154   allocSelfCollisionBroadPhase(state, manager);
00155   CollisionData cd(&req, &res, acm);
00156   cd.enableGroup(getRobotModel());
00157   manager.manager_->collide(&cd, &collisionCallback);
00158   if (req.distance)
00159   {
00160     DistanceRequest dreq(false, true, req.group_name, acm);
00161     DistanceResult dres;
00162 
00163     dreq.enableGroup(getRobotModel());
00164     distanceSelfHelper(dreq, dres, state);
00165     res.distance = dres.minimum_distance.min_distance;
00166   }
00167 }
00168 
00169 void collision_detection::CollisionRobotIndustrial::checkOtherCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state,
00170                                                                  const CollisionRobot &other_robot, const robot_state::RobotState &other_state) const
00171 {
00172   checkOtherCollisionHelper(req, res, state, other_robot, other_state, NULL);
00173 }
00174 
00175 void collision_detection::CollisionRobotIndustrial::checkOtherCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state,
00176                                                                  const CollisionRobot &other_robot, const robot_state::RobotState &other_state,
00177                                                                  const AllowedCollisionMatrix &acm) const
00178 {
00179   checkOtherCollisionHelper(req, res, state, other_robot, other_state, &acm);
00180 }
00181 
00182 void collision_detection::CollisionRobotIndustrial::checkOtherCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state1, const robot_state::RobotState &state2,
00183                                                                  const CollisionRobot &other_robot, const robot_state::RobotState &other_state1, const robot_state::RobotState &other_state2) const
00184 {
00185   logError("FCL continuous collision checking not yet implemented");
00186 }
00187 
00188 void collision_detection::CollisionRobotIndustrial::checkOtherCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state1, const robot_state::RobotState &state2,
00189                                                                  const CollisionRobot &other_robot, const robot_state::RobotState &other_state1, const robot_state::RobotState &other_state2,
00190                                                                  const AllowedCollisionMatrix &acm) const
00191 {
00192   logError("FCL continuous collision checking not yet implemented");
00193 }
00194 
00195 void collision_detection::CollisionRobotIndustrial::checkOtherCollisionHelper(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state,
00196                                                                        const CollisionRobot &other_robot, const robot_state::RobotState &other_state,
00197                                                                        const AllowedCollisionMatrix *acm) const
00198 {
00199   FCLManager manager;
00200   allocSelfCollisionBroadPhase(state, manager);
00201 
00202   const CollisionRobotIndustrial &fcl_rob = dynamic_cast<const CollisionRobotIndustrial&>(other_robot);
00203   FCLObject other_fcl_obj;
00204   fcl_rob.constructFCLObject(other_state, other_fcl_obj);
00205 
00206   CollisionData cd(&req, &res, acm);
00207   cd.enableGroup(getRobotModel());
00208   for (std::size_t i = 0 ; !cd.done_ && i < other_fcl_obj.collision_objects_.size() ; ++i)
00209     manager.manager_->collide(other_fcl_obj.collision_objects_[i].get(), &cd, &collisionCallback);
00210   if (req.distance)
00211     res.distance = distanceOtherHelper(state, other_robot, other_state, acm);
00212 }
00213 
00214 void collision_detection::CollisionRobotIndustrial::updatedPaddingOrScaling(const std::vector<std::string> &links)
00215 {
00216   std::size_t index;
00217   for (std::size_t i = 0 ; i < links.size() ; ++i)
00218   {
00219     const robot_model::LinkModel *lmodel = robot_model_->getLinkModel(links[i]);
00220     if (lmodel)
00221     {
00222       for (std::size_t j = 0 ; j < lmodel->getShapes().size() ; ++j)
00223       {
00224         FCLGeometryConstPtr g = createCollisionGeometry(lmodel->getShapes()[j], getLinkScale(lmodel->getName()), getLinkPadding(lmodel->getName()), lmodel, j);
00225         if (g)
00226         {
00227           index = lmodel->getFirstCollisionBodyTransformIndex() + j;
00228           geoms_[index] = g;
00229           fcl_objs_[index] = FCLCollisionObjectConstPtr(new fcl::CollisionObject(g->collision_geometry_));
00230         }
00231       }
00232     }
00233     else
00234       logError("Updating padding or scaling for unknown link: '%s'", links[i].c_str());
00235   }
00236 }
00237 
00238 double collision_detection::CollisionRobotIndustrial::distanceSelf(const robot_state::RobotState &state) const
00239 {
00240   return distanceSelfHelper(state, NULL);
00241 }
00242 
00243 double collision_detection::CollisionRobotIndustrial::distanceSelf(const robot_state::RobotState &state,
00244                                                             const AllowedCollisionMatrix &acm) const
00245 {
00246   return distanceSelfHelper(state, &acm);
00247 }
00248 
00249 double collision_detection::CollisionRobotIndustrial::distanceSelfHelper(const robot_state::RobotState &state,
00250                                                                   const AllowedCollisionMatrix *acm) const
00251 {
00252   FCLManager manager;
00253   allocSelfCollisionBroadPhase(state, manager);
00254 
00255   CollisionRequest req;
00256   CollisionResult res;
00257   CollisionData cd(&req, &res, acm);
00258   cd.enableGroup(getRobotModel());
00259 
00260   manager.manager_->distance(&cd, &distanceCallback);
00261 
00262   return res.distance;
00263 }
00264 
00265 double collision_detection::CollisionRobotIndustrial::distanceOther(const robot_state::RobotState &state,
00266                                                              const CollisionRobot &other_robot,
00267                                                              const robot_state::RobotState &other_state) const
00268 {
00269   return distanceOtherHelper(state, other_robot, other_state, NULL);
00270 }
00271 
00272 double collision_detection::CollisionRobotIndustrial::distanceOther(const robot_state::RobotState &state,
00273                                                              const CollisionRobot &other_robot,
00274                                                              const robot_state::RobotState &other_state,
00275                                                              const AllowedCollisionMatrix &acm) const
00276 {
00277   return distanceOtherHelper(state, other_robot, other_state, &acm);
00278 }
00279 
00280 double collision_detection::CollisionRobotIndustrial::distanceOtherHelper(const robot_state::RobotState &state,
00281                                                                    const CollisionRobot &other_robot,
00282                                                                    const robot_state::RobotState &other_state,
00283                                                                    const AllowedCollisionMatrix *acm) const
00284 {
00285   FCLManager manager;
00286   allocSelfCollisionBroadPhase(state, manager);
00287 
00288   const CollisionRobotIndustrial& fcl_rob = dynamic_cast<const CollisionRobotIndustrial&>(other_robot);
00289   FCLObject other_fcl_obj;
00290   fcl_rob.constructFCLObject(other_state, other_fcl_obj);
00291 
00292   CollisionRequest req;
00293   CollisionResult res;
00294   CollisionData cd(&req, &res, acm);
00295   cd.enableGroup(getRobotModel());
00296   for(std::size_t i = 0; !cd.done_ && i < other_fcl_obj.collision_objects_.size(); ++i)
00297     manager.manager_->distance(other_fcl_obj.collision_objects_[i].get(), &cd, &distanceCallback);
00298 
00299   return res.distance;
00300 }
00301 
00302 
00303 void collision_detection::CollisionRobotIndustrial::distanceSelf(const DistanceRequest &req, DistanceResult &res, const robot_state::RobotState &state) const
00304 {
00305   distanceSelfHelper(req, res, state);
00306 }
00307 
00308 void collision_detection::CollisionRobotIndustrial::distanceSelfHelper(const DistanceRequest &req, DistanceResult &res, const robot_state::RobotState &state) const
00309 {
00310   FCLManager manager;
00311   allocSelfCollisionBroadPhase(state, manager);
00312   DistanceData drd(&req, &res);
00313 
00314   manager.manager_->distance(&drd, &distanceDetailedCallback);
00315 }
00316 
00317 


industrial_collision_detection
Author(s): Levi Armstrong
autogenerated on Sat Jun 8 2019 19:23:38