btContactProcessing.h
Go to the documentation of this file.
00001 #ifndef BT_CONTACT_H_INCLUDED
00002 #define BT_CONTACT_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/btAlignedObjectArray.h"
00029 #include "btTriangleShapeEx.h"
00030 
00031 
00032 
00036 #define NORMAL_CONTACT_AVERAGE 1
00037 
00038 #define CONTACT_DIFF_EPSILON 0.00001f
00039 
00042 class GIM_CONTACT
00043 {
00044 public:
00045     btVector3 m_point;
00046     btVector3 m_normal;
00047     btScalar m_depth;//Positive value indicates interpenetration
00048     btScalar m_distance;//Padding not for use
00049     int m_feature1;//Face number
00050     int m_feature2;//Face number
00051 public:
00052     GIM_CONTACT()
00053     {
00054     }
00055 
00056     GIM_CONTACT(const GIM_CONTACT & contact):
00057                                 m_point(contact.m_point),
00058                                 m_normal(contact.m_normal),
00059                                 m_depth(contact.m_depth),
00060                                 m_feature1(contact.m_feature1),
00061                                 m_feature2(contact.m_feature2)
00062     {
00063     }
00064 
00065     GIM_CONTACT(const btVector3 &point,const btVector3 & normal,
00066                                 btScalar depth, int feature1, int feature2):
00067                                 m_point(point),
00068                                 m_normal(normal),
00069                                 m_depth(depth),
00070                                 m_feature1(feature1),
00071                                 m_feature2(feature2)
00072     {
00073     }
00074 
00076     SIMD_FORCE_INLINE unsigned int calc_key_contact() const
00077     {
00078         int _coords[] = {
00079                 (int)(m_point[0]*1000.0f+1.0f),
00080                 (int)(m_point[1]*1333.0f),
00081                 (int)(m_point[2]*2133.0f+3.0f)};
00082                 unsigned int _hash=0;
00083                 unsigned int *_uitmp = (unsigned int *)(&_coords[0]);
00084                 _hash = *_uitmp;
00085                 _uitmp++;
00086                 _hash += (*_uitmp)<<4;
00087                 _uitmp++;
00088                 _hash += (*_uitmp)<<8;
00089                 return _hash;
00090     }
00091 
00092     SIMD_FORCE_INLINE void interpolate_normals( btVector3 * normals,int normal_count)
00093     {
00094         btVector3 vec_sum(m_normal);
00095                 for(int i=0;i<normal_count;i++)
00096                 {
00097                         vec_sum += normals[i];
00098                 }
00099 
00100                 btScalar vec_sum_len = vec_sum.length2();
00101                 if(vec_sum_len <CONTACT_DIFF_EPSILON) return;
00102 
00103                 //GIM_INV_SQRT(vec_sum_len,vec_sum_len); // 1/sqrt(vec_sum_len)
00104 
00105                 m_normal = vec_sum/btSqrt(vec_sum_len);
00106     }
00107 
00108 };
00109 
00110 
00111 class btContactArray:public btAlignedObjectArray<GIM_CONTACT>
00112 {
00113 public:
00114         btContactArray()
00115         {
00116                 reserve(64);
00117         }
00118 
00119         SIMD_FORCE_INLINE void push_contact(
00120                 const btVector3 &point,const btVector3 & normal,
00121                 btScalar depth, int feature1, int feature2)
00122         {
00123                 push_back( GIM_CONTACT(point,normal,depth,feature1,feature2) );
00124         }
00125 
00126         SIMD_FORCE_INLINE void push_triangle_contacts(
00127                 const GIM_TRIANGLE_CONTACT & tricontact,
00128                 int feature1,int feature2)
00129         {
00130                 for(int i = 0;i<tricontact.m_point_count ;i++ )
00131                 {
00132                         push_contact(
00133                                 tricontact.m_points[i],
00134                                 tricontact.m_separating_normal,
00135                                 tricontact.m_penetration_depth,feature1,feature2);
00136                 }
00137         }
00138 
00139         void merge_contacts(const btContactArray & contacts, bool normal_contact_average = true);
00140 
00141         void merge_contacts_unique(const btContactArray & contacts);
00142 };
00143 
00144 
00145 #endif // GIM_CONTACT_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