traversal_node_setup.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, Inc. 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 
00038 #include "fcl/traversal/traversal_node_setup.h"
00039 
00040 namespace fcl
00041 {
00042 
00043 
00044 namespace details
00045 {
00046 template<typename BV, typename OrientedNode>
00047 static inline bool setupMeshCollisionOrientedNode(OrientedNode& node,
00048                                                   const BVHModel<BV>& model1, const Transform3f& tf1,
00049                                                   const BVHModel<BV>& model2, const Transform3f& tf2,
00050                                                   const CollisionRequest& request,
00051                                                   CollisionResult& result)
00052 {
00053   if(model1.getModelType() != BVH_MODEL_TRIANGLES || model2.getModelType() != BVH_MODEL_TRIANGLES)
00054     return false;
00055 
00056   node.vertices1 = model1.vertices;
00057   node.vertices2 = model2.vertices;
00058 
00059   node.tri_indices1 = model1.tri_indices;
00060   node.tri_indices2 = model2.tri_indices;
00061 
00062   node.model1 = &model1;
00063   node.tf1 = tf1;
00064   node.model2 = &model2;
00065   node.tf2 = tf2;
00066 
00067   node.request = request;
00068   node.result = &result;
00069 
00070   node.cost_density = model1.cost_density * model2.cost_density;
00071 
00072   relativeTransform(tf1.getRotation(), tf1.getTranslation(), tf2.getRotation(), tf2.getTranslation(), node.R, node.T);
00073 
00074   return true;
00075 }
00076 
00077 }
00078 
00079 
00080 bool initialize(MeshCollisionTraversalNodeOBB& node,
00081                 const BVHModel<OBB>& model1, const Transform3f& tf1,
00082                 const BVHModel<OBB>& model2, const Transform3f& tf2,
00083                 const CollisionRequest& request,
00084                 CollisionResult& result)
00085 {
00086   return details::setupMeshCollisionOrientedNode(node, model1, tf1, model2, tf2, request, result);
00087 }
00088 
00089 
00090 bool initialize(MeshCollisionTraversalNodeRSS& node,
00091                 const BVHModel<RSS>& model1, const Transform3f& tf1,
00092                 const BVHModel<RSS>& model2, const Transform3f& tf2,
00093                 const CollisionRequest& request,
00094                 CollisionResult& result)
00095 {
00096   return details::setupMeshCollisionOrientedNode(node, model1, tf1, model2, tf2, request, result);
00097 }
00098 
00099 
00100 bool initialize(MeshCollisionTraversalNodekIOS& node,
00101                 const BVHModel<kIOS>& model1, const Transform3f& tf1,
00102                 const BVHModel<kIOS>& model2, const Transform3f& tf2,
00103                 const CollisionRequest& request,
00104                 CollisionResult& result)
00105 {
00106   return details::setupMeshCollisionOrientedNode(node, model1, tf1, model2, tf2, request, result);
00107 }
00108 
00109 bool initialize(MeshCollisionTraversalNodeOBBRSS& node,
00110                 const BVHModel<OBBRSS>& model1, const Transform3f& tf1,
00111                 const BVHModel<OBBRSS>& model2, const Transform3f& tf2,
00112                 const CollisionRequest& request,
00113                 CollisionResult& result)
00114 {
00115   return details::setupMeshCollisionOrientedNode(node, model1, tf1, model2, tf2, request, result);
00116 }
00117 
00118 
00119 namespace details
00120 {
00121 template<typename BV, typename OrientedNode>
00122 static inline bool setupMeshDistanceOrientedNode(OrientedNode& node,
00123                                                  const BVHModel<BV>& model1, const Transform3f& tf1,
00124                                                  const BVHModel<BV>& model2, const Transform3f& tf2,
00125                                                  const DistanceRequest& request,
00126                                                  DistanceResult& result)
00127 {
00128   if(model1.getModelType() != BVH_MODEL_TRIANGLES || model2.getModelType() != BVH_MODEL_TRIANGLES)
00129     return false;
00130 
00131   node.request = request;
00132   node.result = &result;
00133 
00134   node.model1 = &model1;
00135   node.tf1 = tf1;
00136   node.model2 = &model2;
00137   node.tf2 = tf2;
00138 
00139   node.vertices1 = model1.vertices;
00140   node.vertices2 = model2.vertices;
00141 
00142   node.tri_indices1 = model1.tri_indices;
00143   node.tri_indices2 = model2.tri_indices;
00144 
00145   relativeTransform(tf1.getRotation(), tf1.getTranslation(), tf2.getRotation(), tf2.getTranslation(), node.R, node.T);
00146 
00147   return true;
00148 }
00149 
00150 
00151 }
00152 
00153 bool initialize(MeshDistanceTraversalNodeRSS& node,
00154                 const BVHModel<RSS>& model1, const Transform3f& tf1,
00155                 const BVHModel<RSS>& model2, const Transform3f& tf2,
00156                 const DistanceRequest& request,
00157                 DistanceResult& result)
00158 {
00159   return details::setupMeshDistanceOrientedNode(node, model1, tf1, model2, tf2, request, result);
00160 }
00161 
00162 
00163 bool initialize(MeshDistanceTraversalNodekIOS& node,
00164                 const BVHModel<kIOS>& model1, const Transform3f& tf1,
00165                 const BVHModel<kIOS>& model2, const Transform3f& tf2,
00166                 const DistanceRequest& request,
00167                 DistanceResult& result)
00168 {
00169   return details::setupMeshDistanceOrientedNode(node, model1, tf1, model2, tf2, request, result);
00170 }
00171 
00172 bool initialize(MeshDistanceTraversalNodeOBBRSS& node,
00173                 const BVHModel<OBBRSS>& model1, const Transform3f& tf1,
00174                 const BVHModel<OBBRSS>& model2, const Transform3f& tf2,
00175                 const DistanceRequest& request,
00176                 DistanceResult& result)
00177 {
00178   return details::setupMeshDistanceOrientedNode(node, model1, tf1, model2, tf2, request, result);
00179 }
00180 
00181 
00182 }
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


fcl
Author(s): Jia Pan
autogenerated on Tue Jan 15 2013 16:05:31