geometric_shapes_utility.h
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 #ifndef FCL_GEOMETRIC_SHAPES_UTILITY_H
00039 #define FCL_GEOMETRIC_SHAPES_UTILITY_H
00040 
00041 #include <vector>
00042 #include "fcl/shape/geometric_shapes.h"
00043 #include "fcl/BV/BV.h"
00044 
00045 namespace fcl
00046 {
00047 
00049 namespace details
00050 {
00052 std::vector<Vec3f> getBoundVertices(const Box& box, const Transform3f& tf);
00053 std::vector<Vec3f> getBoundVertices(const Sphere& sphere, const Transform3f& tf);
00054 std::vector<Vec3f> getBoundVertices(const Capsule& capsule, const Transform3f& tf);
00055 std::vector<Vec3f> getBoundVertices(const Cone& cone, const Transform3f& tf);
00056 std::vector<Vec3f> getBoundVertices(const Cylinder& cylinder, const Transform3f& tf);
00057 std::vector<Vec3f> getBoundVertices(const Convex& convex, const Transform3f& tf);
00058 std::vector<Vec3f> getBoundVertices(const Triangle2& triangle, const Transform3f& tf);
00059 } 
00061 
00062 
00064 template<typename BV, typename S>
00065 void computeBV(const S& s, const Transform3f& tf, BV& bv)
00066 {
00067   std::vector<Vec3f> convex_bound_vertices = details::getBoundVertices(s, tf);
00068   fit(&convex_bound_vertices[0], (int)convex_bound_vertices.size(), bv);
00069 }
00070 
00071 template<>
00072 void computeBV<AABB, Box>(const Box& s, const Transform3f& tf, AABB& bv);
00073 
00074 template<>
00075 void computeBV<AABB, Sphere>(const Sphere& s, const Transform3f& tf, AABB& bv);
00076 
00077 template<>
00078 void computeBV<AABB, Capsule>(const Capsule& s, const Transform3f& tf, AABB& bv);
00079 
00080 template<>
00081 void computeBV<AABB, Cone>(const Cone& s, const Transform3f& tf, AABB& bv);
00082 
00083 template<>
00084 void computeBV<AABB, Cylinder>(const Cylinder& s, const Transform3f& tf, AABB& bv);
00085 
00086 template<>
00087 void computeBV<AABB, Convex>(const Convex& s, const Transform3f& tf, AABB& bv);
00088 
00089 template<>
00090 void computeBV<AABB, Triangle2>(const Triangle2& s, const Transform3f& tf, AABB& bv);
00091 
00092 template<>
00093 void computeBV<AABB, Halfspace>(const Halfspace& s, const Transform3f& tf, AABB& bv);
00094 
00095 template<>
00096 void computeBV<AABB, Plane>(const Plane& s, const Transform3f& tf, AABB& bv);
00097 
00098 
00099 
00100 template<>
00101 void computeBV<OBB, Box>(const Box& s, const Transform3f& tf, OBB& bv);
00102 
00103 template<>
00104 void computeBV<OBB, Sphere>(const Sphere& s, const Transform3f& tf, OBB& bv);
00105 
00106 template<>
00107 void computeBV<OBB, Capsule>(const Capsule& s, const Transform3f& tf, OBB& bv);
00108 
00109 template<>
00110 void computeBV<OBB, Cone>(const Cone& s, const Transform3f& tf, OBB& bv);
00111 
00112 template<>
00113 void computeBV<OBB, Cylinder>(const Cylinder& s, const Transform3f& tf, OBB& bv);
00114 
00115 template<>
00116 void computeBV<OBB, Convex>(const Convex& s, const Transform3f& tf, OBB& bv);
00117 
00118 template<>
00119 void computeBV<OBB, Halfspace>(const Halfspace& s, const Transform3f& tf, OBB& bv);
00120 
00121 template<>
00122 void computeBV<OBB, Plane>(const Plane& s, const Transform3f& tf, OBB& bv);
00123 
00124 
00125 template<>
00126 void computeBV<RSS, Plane>(const Plane& s, const Transform3f& tf, RSS& bv);
00127 
00128 template<>
00129 void computeBV<OBBRSS, Plane>(const Plane& s, const Transform3f& tf, OBBRSS& bv);
00130 
00131 template<>
00132 void computeBV<kIOS, Plane>(const Plane& s, const Transform3f& tf, kIOS& bv);
00133 
00134 template<>
00135 void computeBV<KDOP<16>, Plane>(const Plane& s, const Transform3f& tf, KDOP<16>& bv);
00136 
00137 template<>
00138 void computeBV<KDOP<18>, Plane>(const Plane& s, const Transform3f& tf, KDOP<18>& bv);
00139 
00140 template<>
00141 void computeBV<KDOP<24>, Plane>(const Plane& s, const Transform3f& tf, KDOP<24>& bv);
00142 
00143 
00145 void constructBox(const AABB& bv, Box& box, Transform3f& tf);
00146 
00147 void constructBox(const OBB& bv, Box& box, Transform3f& tf);
00148 
00149 void constructBox(const OBBRSS& bv, Box& box, Transform3f& tf);
00150 
00151 void constructBox(const kIOS& bv, Box& box, Transform3f& tf);
00152 
00153 void constructBox(const RSS& bv, Box& box, Transform3f& tf);
00154 
00155 void constructBox(const KDOP<16>& bv, Box& box, Transform3f& tf);
00156 
00157 void constructBox(const KDOP<18>& bv, Box& box, Transform3f& tf);
00158 
00159 void constructBox(const KDOP<24>& bv, Box& box, Transform3f& tf);
00160 
00161 void constructBox(const AABB& bv, const Transform3f& tf_bv, Box& box, Transform3f& tf);
00162 
00163 void constructBox(const OBB& bv, const Transform3f& tf_bv, Box& box, Transform3f& tf);
00164 
00165 void constructBox(const OBBRSS& bv, const Transform3f& tf_bv, Box& box, Transform3f& tf);
00166 
00167 void constructBox(const kIOS& bv, const Transform3f& tf_bv, Box& box, Transform3f& tf);
00168 
00169 void constructBox(const RSS& bv, const Transform3f& tf_bv, Box& box, Transform3f& tf);
00170 
00171 void constructBox(const KDOP<16>& bv, const Transform3f& tf_bv, Box& box, Transform3f& tf);
00172 
00173 void constructBox(const KDOP<18>& bv, const Transform3f& tf_bv, Box& box, Transform3f& tf);
00174 
00175 void constructBox(const KDOP<24>& bv, const Transform3f& tf_bv, Box& box, Transform3f& tf);
00176 
00177 Halfspace transform(const Halfspace& a, const Transform3f& tf);
00178 
00179 Plane transform(const Plane& a, const Transform3f& tf);
00180 
00181 }
00182 
00183 #endif
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


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