btIDebugDraw.h
Go to the documentation of this file.
00001 /*
00002 Bullet Continuous Collision Detection and Physics Library
00003 Copyright (c) 2003-2009 Erwin Coumans  http://bulletphysics.org
00004 
00005 This software is provided 'as-is', without any express or implied warranty.
00006 In no event will the authors be held liable for any damages arising from the use of this software.
00007 Permission is granted to anyone to use this software for any purpose, 
00008 including commercial applications, and to alter it and redistribute it freely, 
00009 subject to the following restrictions:
00010 
00011 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.
00012 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
00013 3. This notice may not be removed or altered from any source distribution.
00014 */
00015 
00016 
00017 #ifndef BT_IDEBUG_DRAW__H
00018 #define BT_IDEBUG_DRAW__H
00019 
00020 #include "btVector3.h"
00021 #include "btTransform.h"
00022 
00023 
00028 class   btIDebugDraw
00029 {
00030         public:
00031 
00032         enum    DebugDrawModes
00033         {
00034                 DBG_NoDebug=0,
00035                 DBG_DrawWireframe = 1,
00036                 DBG_DrawAabb=2,
00037                 DBG_DrawFeaturesText=4,
00038                 DBG_DrawContactPoints=8,
00039                 DBG_NoDeactivation=16,
00040                 DBG_NoHelpText = 32,
00041                 DBG_DrawText=64,
00042                 DBG_ProfileTimings = 128,
00043                 DBG_EnableSatComparison = 256,
00044                 DBG_DisableBulletLCP = 512,
00045                 DBG_EnableCCD = 1024,
00046                 DBG_DrawConstraints = (1 << 11),
00047                 DBG_DrawConstraintLimits = (1 << 12),
00048                 DBG_FastWireframe = (1<<13),
00049                 DBG_MAX_DEBUG_DRAW_MODE
00050         };
00051 
00052         virtual ~btIDebugDraw() {};
00053 
00054         virtual void    drawLine(const btVector3& from,const btVector3& to,const btVector3& color)=0;
00055                 
00056         virtual void    drawLine(const btVector3& from,const btVector3& to, const btVector3& fromColor, const btVector3& toColor)
00057         {
00058         (void) toColor;
00059                 drawLine (from, to, fromColor);
00060         }
00061 
00062         virtual void    drawSphere(btScalar radius, const btTransform& transform, const btVector3& color)
00063         {
00064                 btVector3 start = transform.getOrigin();
00065 
00066                 const btVector3 xoffs = transform.getBasis() * btVector3(radius,0,0);
00067                 const btVector3 yoffs = transform.getBasis() * btVector3(0,radius,0);
00068                 const btVector3 zoffs = transform.getBasis() * btVector3(0,0,radius);
00069 
00070                 // XY 
00071                 drawLine(start-xoffs, start+yoffs, color);
00072                 drawLine(start+yoffs, start+xoffs, color);
00073                 drawLine(start+xoffs, start-yoffs, color);
00074                 drawLine(start-yoffs, start-xoffs, color);
00075 
00076                 // XZ
00077                 drawLine(start-xoffs, start+zoffs, color);
00078                 drawLine(start+zoffs, start+xoffs, color);
00079                 drawLine(start+xoffs, start-zoffs, color);
00080                 drawLine(start-zoffs, start-xoffs, color);
00081 
00082                 // YZ
00083                 drawLine(start-yoffs, start+zoffs, color);
00084                 drawLine(start+zoffs, start+yoffs, color);
00085                 drawLine(start+yoffs, start-zoffs, color);
00086                 drawLine(start-zoffs, start-yoffs, color);
00087         }
00088         
00089         virtual void    drawSphere (const btVector3& p, btScalar radius, const btVector3& color)
00090         {
00091                 btTransform tr;
00092                 tr.setIdentity();
00093                 tr.setOrigin(p);
00094                 drawSphere(radius,tr,color);
00095         }
00096         
00097         virtual void    drawTriangle(const btVector3& v0,const btVector3& v1,const btVector3& v2,const btVector3& /*n0*/,const btVector3& /*n1*/,const btVector3& /*n2*/,const btVector3& color, btScalar alpha)
00098         {
00099                 drawTriangle(v0,v1,v2,color,alpha);
00100         }
00101         virtual void    drawTriangle(const btVector3& v0,const btVector3& v1,const btVector3& v2,const btVector3& color, btScalar /*alpha*/)
00102         {
00103                 drawLine(v0,v1,color);
00104                 drawLine(v1,v2,color);
00105                 drawLine(v2,v0,color);
00106         }
00107 
00108         virtual void    drawContactPoint(const btVector3& PointOnB,const btVector3& normalOnB,btScalar distance,int lifeTime,const btVector3& color)=0;
00109 
00110         virtual void    reportErrorWarning(const char* warningString) = 0;
00111 
00112         virtual void    draw3dText(const btVector3& location,const char* textString) = 0;
00113         
00114         virtual void    setDebugMode(int debugMode) =0;
00115         
00116         virtual int             getDebugMode() const = 0;
00117 
00118         virtual void drawAabb(const btVector3& from,const btVector3& to,const btVector3& color)
00119         {
00120 
00121                 btVector3 halfExtents = (to-from)* 0.5f;
00122                 btVector3 center = (to+from) *0.5f;
00123                 int i,j;
00124 
00125                 btVector3 edgecoord(1.f,1.f,1.f),pa,pb;
00126                 for (i=0;i<4;i++)
00127                 {
00128                         for (j=0;j<3;j++)
00129                         {
00130                                 pa = btVector3(edgecoord[0]*halfExtents[0], edgecoord[1]*halfExtents[1],                
00131                                         edgecoord[2]*halfExtents[2]);
00132                                 pa+=center;
00133 
00134                                 int othercoord = j%3;
00135                                 edgecoord[othercoord]*=-1.f;
00136                                 pb = btVector3(edgecoord[0]*halfExtents[0], edgecoord[1]*halfExtents[1],        
00137                                         edgecoord[2]*halfExtents[2]);
00138                                 pb+=center;
00139 
00140                                 drawLine(pa,pb,color);
00141                         }
00142                         edgecoord = btVector3(-1.f,-1.f,-1.f);
00143                         if (i<3)
00144                                 edgecoord[i]*=-1.f;
00145                 }
00146         }
00147         virtual void drawTransform(const btTransform& transform, btScalar orthoLen)
00148         {
00149                 btVector3 start = transform.getOrigin();
00150                 drawLine(start, start+transform.getBasis() * btVector3(orthoLen, 0, 0), btVector3(0.7f,0,0));
00151                 drawLine(start, start+transform.getBasis() * btVector3(0, orthoLen, 0), btVector3(0,0.7f,0));
00152                 drawLine(start, start+transform.getBasis() * btVector3(0, 0, orthoLen), btVector3(0,0,0.7f));
00153         }
00154 
00155         virtual void drawArc(const btVector3& center, const btVector3& normal, const btVector3& axis, btScalar radiusA, btScalar radiusB, btScalar minAngle, btScalar maxAngle, 
00156                                 const btVector3& color, bool drawSect, btScalar stepDegrees = btScalar(10.f))
00157         {
00158                 const btVector3& vx = axis;
00159                 btVector3 vy = normal.cross(axis);
00160                 btScalar step = stepDegrees * SIMD_RADS_PER_DEG;
00161                 int nSteps = (int)((maxAngle - minAngle) / step);
00162                 if(!nSteps) nSteps = 1;
00163                 btVector3 prev = center + radiusA * vx * btCos(minAngle) + radiusB * vy * btSin(minAngle);
00164                 if(drawSect)
00165                 {
00166                         drawLine(center, prev, color);
00167                 }
00168                 for(int i = 1; i <= nSteps; i++)
00169                 {
00170                         btScalar angle = minAngle + (maxAngle - minAngle) * btScalar(i) / btScalar(nSteps);
00171                         btVector3 next = center + radiusA * vx * btCos(angle) + radiusB * vy * btSin(angle);
00172                         drawLine(prev, next, color);
00173                         prev = next;
00174                 }
00175                 if(drawSect)
00176                 {
00177                         drawLine(center, prev, color);
00178                 }
00179         }
00180         virtual void drawSpherePatch(const btVector3& center, const btVector3& up, const btVector3& axis, btScalar radius, 
00181                 btScalar minTh, btScalar maxTh, btScalar minPs, btScalar maxPs, const btVector3& color, btScalar stepDegrees = btScalar(10.f))
00182         {
00183                 btVector3 vA[74];
00184                 btVector3 vB[74];
00185                 btVector3 *pvA = vA, *pvB = vB, *pT;
00186                 btVector3 npole = center + up * radius;
00187                 btVector3 spole = center - up * radius;
00188                 btVector3 arcStart;
00189                 btScalar step = stepDegrees * SIMD_RADS_PER_DEG;
00190                 const btVector3& kv = up;
00191                 const btVector3& iv = axis;
00192                 btVector3 jv = kv.cross(iv);
00193                 bool drawN = false;
00194                 bool drawS = false;
00195                 if(minTh <= -SIMD_HALF_PI)
00196                 {
00197                         minTh = -SIMD_HALF_PI + step;
00198                         drawN = true;
00199                 }
00200                 if(maxTh >= SIMD_HALF_PI)
00201                 {
00202                         maxTh = SIMD_HALF_PI - step;
00203                         drawS = true;
00204                 }
00205                 if(minTh > maxTh)
00206                 {
00207                         minTh = -SIMD_HALF_PI + step;
00208                         maxTh =  SIMD_HALF_PI - step;
00209                         drawN = drawS = true;
00210                 }
00211                 int n_hor = (int)((maxTh - minTh) / step) + 1;
00212                 if(n_hor < 2) n_hor = 2;
00213                 btScalar step_h = (maxTh - minTh) / btScalar(n_hor - 1);
00214                 bool isClosed = false;
00215                 if(minPs > maxPs)
00216                 {
00217                         minPs = -SIMD_PI + step;
00218                         maxPs =  SIMD_PI;
00219                         isClosed = true;
00220                 }
00221                 else if((maxPs - minPs) >= SIMD_PI * btScalar(2.f))
00222                 {
00223                         isClosed = true;
00224                 }
00225                 else
00226                 {
00227                         isClosed = false;
00228                 }
00229                 int n_vert = (int)((maxPs - minPs) / step) + 1;
00230                 if(n_vert < 2) n_vert = 2;
00231                 btScalar step_v = (maxPs - minPs) / btScalar(n_vert - 1);
00232                 for(int i = 0; i < n_hor; i++)
00233                 {
00234                         btScalar th = minTh + btScalar(i) * step_h;
00235                         btScalar sth = radius * btSin(th);
00236                         btScalar cth = radius * btCos(th);
00237                         for(int j = 0; j < n_vert; j++)
00238                         {
00239                                 btScalar psi = minPs + btScalar(j) * step_v;
00240                                 btScalar sps = btSin(psi);
00241                                 btScalar cps = btCos(psi);
00242                                 pvB[j] = center + cth * cps * iv + cth * sps * jv + sth * kv;
00243                                 if(i)
00244                                 {
00245                                         drawLine(pvA[j], pvB[j], color);
00246                                 }
00247                                 else if(drawS)
00248                                 {
00249                                         drawLine(spole, pvB[j], color);
00250                                 }
00251                                 if(j)
00252                                 {
00253                                         drawLine(pvB[j-1], pvB[j], color);
00254                                 }
00255                                 else
00256                                 {
00257                                         arcStart = pvB[j];
00258                                 }
00259                                 if((i == (n_hor - 1)) && drawN)
00260                                 {
00261                                         drawLine(npole, pvB[j], color);
00262                                 }
00263                                 if(isClosed)
00264                                 {
00265                                         if(j == (n_vert-1))
00266                                         {
00267                                                 drawLine(arcStart, pvB[j], color);
00268                                         }
00269                                 }
00270                                 else
00271                                 {
00272                                         if(((!i) || (i == (n_hor-1))) && ((!j) || (j == (n_vert-1))))
00273                                         {
00274                                                 drawLine(center, pvB[j], color);
00275                                         }
00276                                 }
00277                         }
00278                         pT = pvA; pvA = pvB; pvB = pT;
00279                 }
00280         }
00281         
00282         virtual void drawBox(const btVector3& bbMin, const btVector3& bbMax, const btVector3& color)
00283         {
00284                 drawLine(btVector3(bbMin[0], bbMin[1], bbMin[2]), btVector3(bbMax[0], bbMin[1], bbMin[2]), color);
00285                 drawLine(btVector3(bbMax[0], bbMin[1], bbMin[2]), btVector3(bbMax[0], bbMax[1], bbMin[2]), color);
00286                 drawLine(btVector3(bbMax[0], bbMax[1], bbMin[2]), btVector3(bbMin[0], bbMax[1], bbMin[2]), color);
00287                 drawLine(btVector3(bbMin[0], bbMax[1], bbMin[2]), btVector3(bbMin[0], bbMin[1], bbMin[2]), color);
00288                 drawLine(btVector3(bbMin[0], bbMin[1], bbMin[2]), btVector3(bbMin[0], bbMin[1], bbMax[2]), color);
00289                 drawLine(btVector3(bbMax[0], bbMin[1], bbMin[2]), btVector3(bbMax[0], bbMin[1], bbMax[2]), color);
00290                 drawLine(btVector3(bbMax[0], bbMax[1], bbMin[2]), btVector3(bbMax[0], bbMax[1], bbMax[2]), color);
00291                 drawLine(btVector3(bbMin[0], bbMax[1], bbMin[2]), btVector3(bbMin[0], bbMax[1], bbMax[2]), color);
00292                 drawLine(btVector3(bbMin[0], bbMin[1], bbMax[2]), btVector3(bbMax[0], bbMin[1], bbMax[2]), color);
00293                 drawLine(btVector3(bbMax[0], bbMin[1], bbMax[2]), btVector3(bbMax[0], bbMax[1], bbMax[2]), color);
00294                 drawLine(btVector3(bbMax[0], bbMax[1], bbMax[2]), btVector3(bbMin[0], bbMax[1], bbMax[2]), color);
00295                 drawLine(btVector3(bbMin[0], bbMax[1], bbMax[2]), btVector3(bbMin[0], bbMin[1], bbMax[2]), color);
00296         }
00297         virtual void drawBox(const btVector3& bbMin, const btVector3& bbMax, const btTransform& trans, const btVector3& color)
00298         {
00299                 drawLine(trans * btVector3(bbMin[0], bbMin[1], bbMin[2]), trans * btVector3(bbMax[0], bbMin[1], bbMin[2]), color);
00300                 drawLine(trans * btVector3(bbMax[0], bbMin[1], bbMin[2]), trans * btVector3(bbMax[0], bbMax[1], bbMin[2]), color);
00301                 drawLine(trans * btVector3(bbMax[0], bbMax[1], bbMin[2]), trans * btVector3(bbMin[0], bbMax[1], bbMin[2]), color);
00302                 drawLine(trans * btVector3(bbMin[0], bbMax[1], bbMin[2]), trans * btVector3(bbMin[0], bbMin[1], bbMin[2]), color);
00303                 drawLine(trans * btVector3(bbMin[0], bbMin[1], bbMin[2]), trans * btVector3(bbMin[0], bbMin[1], bbMax[2]), color);
00304                 drawLine(trans * btVector3(bbMax[0], bbMin[1], bbMin[2]), trans * btVector3(bbMax[0], bbMin[1], bbMax[2]), color);
00305                 drawLine(trans * btVector3(bbMax[0], bbMax[1], bbMin[2]), trans * btVector3(bbMax[0], bbMax[1], bbMax[2]), color);
00306                 drawLine(trans * btVector3(bbMin[0], bbMax[1], bbMin[2]), trans * btVector3(bbMin[0], bbMax[1], bbMax[2]), color);
00307                 drawLine(trans * btVector3(bbMin[0], bbMin[1], bbMax[2]), trans * btVector3(bbMax[0], bbMin[1], bbMax[2]), color);
00308                 drawLine(trans * btVector3(bbMax[0], bbMin[1], bbMax[2]), trans * btVector3(bbMax[0], bbMax[1], bbMax[2]), color);
00309                 drawLine(trans * btVector3(bbMax[0], bbMax[1], bbMax[2]), trans * btVector3(bbMin[0], bbMax[1], bbMax[2]), color);
00310                 drawLine(trans * btVector3(bbMin[0], bbMax[1], bbMax[2]), trans * btVector3(bbMin[0], bbMin[1], bbMax[2]), color);
00311         }
00312 
00313         virtual void drawCapsule(btScalar radius, btScalar halfHeight, int upAxis, const btTransform& transform, const btVector3& color)
00314         {
00315                 btVector3 capStart(0.f,0.f,0.f);
00316                 capStart[upAxis] = -halfHeight;
00317 
00318                 btVector3 capEnd(0.f,0.f,0.f);
00319                 capEnd[upAxis] = halfHeight;
00320 
00321                 // Draw the ends
00322                 {
00323 
00324                         btTransform childTransform = transform;
00325                         childTransform.getOrigin() = transform * capStart;
00326                         drawSphere(radius, childTransform, color);
00327                 }
00328 
00329                 {
00330                         btTransform childTransform = transform;
00331                         childTransform.getOrigin() = transform * capEnd;
00332                         drawSphere(radius, childTransform, color);
00333                 }
00334 
00335                 // Draw some additional lines
00336                 btVector3 start = transform.getOrigin();
00337 
00338                 capStart[(upAxis+1)%3] = radius;
00339                 capEnd[(upAxis+1)%3] = radius;
00340                 drawLine(start+transform.getBasis() * capStart,start+transform.getBasis() * capEnd, color);
00341                 capStart[(upAxis+1)%3] = -radius;
00342                 capEnd[(upAxis+1)%3] = -radius;
00343                 drawLine(start+transform.getBasis() * capStart,start+transform.getBasis() * capEnd, color);
00344 
00345                 capStart[(upAxis+1)%3] = 0.f;
00346                 capEnd[(upAxis+1)%3] = 0.f;
00347 
00348                 capStart[(upAxis+2)%3] = radius;
00349                 capEnd[(upAxis+2)%3] = radius;
00350                 drawLine(start+transform.getBasis() * capStart,start+transform.getBasis() * capEnd, color);
00351                 capStart[(upAxis+2)%3] = -radius;
00352                 capEnd[(upAxis+2)%3] = -radius;
00353                 drawLine(start+transform.getBasis() * capStart,start+transform.getBasis() * capEnd, color);
00354         }
00355 
00356         virtual void drawCylinder(btScalar radius, btScalar halfHeight, int upAxis, const btTransform& transform, const btVector3& color)
00357         {
00358                 btVector3 start = transform.getOrigin();
00359                 btVector3       offsetHeight(0,0,0);
00360                 offsetHeight[upAxis] = halfHeight;
00361                 btVector3       offsetRadius(0,0,0);
00362                 offsetRadius[(upAxis+1)%3] = radius;
00363                 drawLine(start+transform.getBasis() * (offsetHeight+offsetRadius),start+transform.getBasis() * (-offsetHeight+offsetRadius),color);
00364                 drawLine(start+transform.getBasis() * (offsetHeight-offsetRadius),start+transform.getBasis() * (-offsetHeight-offsetRadius),color);
00365 
00366                 // Drawing top and bottom caps of the cylinder
00367                 btVector3 yaxis(0,0,0);
00368                 yaxis[upAxis] = btScalar(1.0);
00369                 btVector3 xaxis(0,0,0);
00370                 xaxis[(upAxis+1)%3] = btScalar(1.0);
00371                 drawArc(start-transform.getBasis()*(offsetHeight),transform.getBasis()*yaxis,transform.getBasis()*xaxis,radius,radius,0,SIMD_2_PI,color,false,btScalar(10.0));
00372                 drawArc(start+transform.getBasis()*(offsetHeight),transform.getBasis()*yaxis,transform.getBasis()*xaxis,radius,radius,0,SIMD_2_PI,color,false,btScalar(10.0));
00373         }
00374 
00375         virtual void drawCone(btScalar radius, btScalar height, int upAxis, const btTransform& transform, const btVector3& color)
00376         {
00377 
00378                 btVector3 start = transform.getOrigin();
00379 
00380                 btVector3       offsetHeight(0,0,0);
00381                 offsetHeight[upAxis] = height * btScalar(0.5);
00382                 btVector3       offsetRadius(0,0,0);
00383                 offsetRadius[(upAxis+1)%3] = radius;
00384                 btVector3       offset2Radius(0,0,0);
00385                 offset2Radius[(upAxis+2)%3] = radius;
00386 
00387                 drawLine(start+transform.getBasis() * (offsetHeight),start+transform.getBasis() * (-offsetHeight+offsetRadius),color);
00388                 drawLine(start+transform.getBasis() * (offsetHeight),start+transform.getBasis() * (-offsetHeight-offsetRadius),color);
00389                 drawLine(start+transform.getBasis() * (offsetHeight),start+transform.getBasis() * (-offsetHeight+offset2Radius),color);
00390                 drawLine(start+transform.getBasis() * (offsetHeight),start+transform.getBasis() * (-offsetHeight-offset2Radius),color);
00391 
00392                 // Drawing the base of the cone
00393                 btVector3 yaxis(0,0,0);
00394                 yaxis[upAxis] = btScalar(1.0);
00395                 btVector3 xaxis(0,0,0);
00396                 xaxis[(upAxis+1)%3] = btScalar(1.0);
00397                 drawArc(start-transform.getBasis()*(offsetHeight),transform.getBasis()*yaxis,transform.getBasis()*xaxis,radius,radius,0,SIMD_2_PI,color,false,10.0);
00398         }
00399 
00400         virtual void drawPlane(const btVector3& planeNormal, btScalar planeConst, const btTransform& transform, const btVector3& color)
00401         {
00402                 btVector3 planeOrigin = planeNormal * planeConst;
00403                 btVector3 vec0,vec1;
00404                 btPlaneSpace1(planeNormal,vec0,vec1);
00405                 btScalar vecLen = 100.f;
00406                 btVector3 pt0 = planeOrigin + vec0*vecLen;
00407                 btVector3 pt1 = planeOrigin - vec0*vecLen;
00408                 btVector3 pt2 = planeOrigin + vec1*vecLen;
00409                 btVector3 pt3 = planeOrigin - vec1*vecLen;
00410                 drawLine(transform*pt0,transform*pt1,color);
00411                 drawLine(transform*pt2,transform*pt3,color);
00412         }
00413 };
00414 
00415 
00416 #endif //BT_IDEBUG_DRAW__H
00417 
 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