btClipPolygon.h
Go to the documentation of this file.
00001 #ifndef BT_CLIP_POLYGON_H_INCLUDED
00002 #define BT_CLIP_POLYGON_H_INCLUDED
00003 
00007 /*
00008 This source file is part of GIMPACT Library.
00009 
00010 For the latest info, see http://gimpact.sourceforge.net/
00011 
00012 Copyright (c) 2007 Francisco Leon Najera. C.C. 80087371.
00013 email: projectileman@yahoo.com
00014 
00015 
00016 This software is provided 'as-is', without any express or implied warranty.
00017 In no event will the authors be held liable for any damages arising from the use of this software.
00018 Permission is granted to anyone to use this software for any purpose,
00019 including commercial applications, and to alter it and redistribute it freely,
00020 subject to the following restrictions:
00021 
00022 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
00023 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
00024 3. This notice may not be removed or altered from any source distribution.
00025 */
00026 
00027 #include "LinearMath/btTransform.h"
00028 #include "LinearMath/btGeometryUtil.h"
00029 
00030 
00031 SIMD_FORCE_INLINE btScalar bt_distance_point_plane(const btVector4 & plane,const btVector3 &point)
00032 {
00033         return point.dot(plane) - plane[3];
00034 }
00035 
00038 SIMD_FORCE_INLINE void bt_vec_blend(btVector3 &vr, const btVector3 &va,const btVector3 &vb, btScalar blend_factor)
00039 {
00040         vr = (1-blend_factor)*va + blend_factor*vb;
00041 }
00042 
00044 SIMD_FORCE_INLINE void bt_plane_clip_polygon_collect(
00045                                                 const btVector3 & point0,
00046                                                 const btVector3 & point1,
00047                                                 btScalar dist0,
00048                                                 btScalar dist1,
00049                                                 btVector3 * clipped,
00050                                                 int & clipped_count)
00051 {
00052         bool _prevclassif = (dist0>SIMD_EPSILON);
00053         bool _classif = (dist1>SIMD_EPSILON);
00054         if(_classif!=_prevclassif)
00055         {
00056                 btScalar blendfactor = -dist0/(dist1-dist0);
00057                 bt_vec_blend(clipped[clipped_count],point0,point1,blendfactor);
00058                 clipped_count++;
00059         }
00060         if(!_classif)
00061         {
00062                 clipped[clipped_count] = point1;
00063                 clipped_count++;
00064         }
00065 }
00066 
00067 
00069 
00072 SIMD_FORCE_INLINE int bt_plane_clip_polygon(
00073                                                 const btVector4 & plane,
00074                                                 const btVector3 * polygon_points,
00075                                                 int polygon_point_count,
00076                                                 btVector3 * clipped)
00077 {
00078     int clipped_count = 0;
00079 
00080 
00081     //clip first point
00082         btScalar firstdist = bt_distance_point_plane(plane,polygon_points[0]);;
00083         if(!(firstdist>SIMD_EPSILON))
00084         {
00085                 clipped[clipped_count] = polygon_points[0];
00086                 clipped_count++;
00087         }
00088 
00089         btScalar olddist = firstdist;
00090         for(int i=1;i<polygon_point_count;i++)
00091         {
00092                 btScalar dist = bt_distance_point_plane(plane,polygon_points[i]);
00093 
00094                 bt_plane_clip_polygon_collect(
00095                                                 polygon_points[i-1],polygon_points[i],
00096                                                 olddist,
00097                                                 dist,
00098                                                 clipped,
00099                                                 clipped_count);
00100 
00101 
00102                 olddist = dist;
00103         }
00104 
00105         //RETURN TO FIRST  point
00106 
00107         bt_plane_clip_polygon_collect(
00108                                         polygon_points[polygon_point_count-1],polygon_points[0],
00109                                         olddist,
00110                                         firstdist,
00111                                         clipped,
00112                                         clipped_count);
00113 
00114         return clipped_count;
00115 }
00116 
00118 
00122 SIMD_FORCE_INLINE int bt_plane_clip_triangle(
00123                                                 const btVector4 & plane,
00124                                                 const btVector3 & point0,
00125                                                 const btVector3 & point1,
00126                                                 const btVector3& point2,
00127                                                 btVector3 * clipped // an allocated array of 16 points at least
00128                                                 )
00129 {
00130     int clipped_count = 0;
00131 
00132     //clip first point0
00133         btScalar firstdist = bt_distance_point_plane(plane,point0);;
00134         if(!(firstdist>SIMD_EPSILON))
00135         {
00136                 clipped[clipped_count] = point0;
00137                 clipped_count++;
00138         }
00139 
00140         // point 1
00141         btScalar olddist = firstdist;
00142         btScalar dist = bt_distance_point_plane(plane,point1);
00143 
00144         bt_plane_clip_polygon_collect(
00145                                         point0,point1,
00146                                         olddist,
00147                                         dist,
00148                                         clipped,
00149                                         clipped_count);
00150 
00151         olddist = dist;
00152 
00153 
00154         // point 2
00155         dist = bt_distance_point_plane(plane,point2);
00156 
00157         bt_plane_clip_polygon_collect(
00158                                         point1,point2,
00159                                         olddist,
00160                                         dist,
00161                                         clipped,
00162                                         clipped_count);
00163         olddist = dist;
00164 
00165 
00166 
00167         //RETURN TO FIRST  point0
00168         bt_plane_clip_polygon_collect(
00169                                         point2,point0,
00170                                         olddist,
00171                                         firstdist,
00172                                         clipped,
00173                                         clipped_count);
00174 
00175         return clipped_count;
00176 }
00177 
00178 
00179 
00180 
00181 
00182 #endif // GIM_TRI_COLLISION_H_INCLUDED
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


bullet
Author(s): Erwin Coumans, ROS package maintained by Tully Foote
autogenerated on Wed Oct 31 2012 07:54:31