Simbody  3.4 (development)
ContactGeometry.h
Go to the documentation of this file.
00001 #ifndef SimTK_SIMMATH_CONTACT_GEOMETRY_H_
00002 #define SimTK_SIMMATH_CONTACT_GEOMETRY_H_
00003 
00004 /* -------------------------------------------------------------------------- *
00005  *                        Simbody(tm): SimTKmath                              *
00006  * -------------------------------------------------------------------------- *
00007  * This is part of the SimTK biosimulation toolkit originating from           *
00008  * Simbios, the NIH National Center for Physics-Based Simulation of           *
00009  * Biological Structures at Stanford, funded under the NIH Roadmap for        *
00010  * Medical Research, grant U54 GM072970. See https://simtk.org/home/simbody.  *
00011  *                                                                            *
00012  * Portions copyright (c) 2008-12 Stanford University and the Authors.        *
00013  * Authors: Peter Eastman, Michael Sherman                                    *
00014  * Contributors: Ian Stavness, Andreas Scholz                                                              *
00015  *                                                                            *
00016  * Licensed under the Apache License, Version 2.0 (the "License"); you may    *
00017  * not use this file except in compliance with the License. You may obtain a  *
00018  * copy of the License at http://www.apache.org/licenses/LICENSE-2.0.         *
00019  *                                                                            *
00020  * Unless required by applicable law or agreed to in writing, software        *
00021  * distributed under the License is distributed on an "AS IS" BASIS,          *
00022  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.   *
00023  * See the License for the specific language governing permissions and        *
00024  * limitations under the License.                                             *
00025  * -------------------------------------------------------------------------- */
00026 
00031 #include "SimTKcommon.h"
00032 #include "simmath/internal/common.h"
00033 #include "simmath/internal/OrientedBoundingBox.h"
00034 #include "simmath/internal/Geodesic.h"
00035 #include "simmath/internal/BicubicSurface.h"
00036 
00037 #include <cassert>
00038 
00039 namespace SimTK {
00040 
00044 SimTK_DEFINE_UNIQUE_INDEX_TYPE(ContactGeometryTypeId);
00045 
00046 class ContactGeometryImpl;
00047 class OBBTreeNodeImpl;
00048 class OBBTree;
00049 class Plane;
00050 
00051 
00052 
00053 //==============================================================================
00054 //                             CONTACT GEOMETRY
00055 //==============================================================================
00110 class SimTK_SIMMATH_EXPORT ContactGeometry {
00111 public:
00112 class HalfSpace;
00113 class Cylinder;
00114 class Sphere;
00115 class Ellipsoid;
00116 class SmoothHeightMap;
00117 class TriangleMesh;
00118 class Torus;
00119 
00120 // TODO
00121 class Cone;
00122 
00124 ContactGeometry() : impl(0) {}
00126 ContactGeometry(const ContactGeometry& src);
00128 ContactGeometry& operator=(const ContactGeometry& src);
00132 ~ContactGeometry();
00133 
00135 DecorativeGeometry createDecorativeGeometry() const;
00136 
00147 Vec3 findNearestPoint(const Vec3& position, bool& inside, UnitVec3& normal) const;
00148 
00163 Vec3 projectDownhillToNearestPoint(const Vec3& pointQ) const;
00164 
00229 bool trackSeparationFromLine(const Vec3& pointOnLine,
00230                              const UnitVec3& directionOfLine,
00231                              const Vec3& startingGuessForClosestPoint,
00232                              Vec3& newClosestPointOnSurface,
00233                              Vec3& closestPointOnLine,
00234                              Real& height) const;
00235 
00236 
00237 
00249 bool intersectsRay(const Vec3& origin, const UnitVec3& direction, 
00250                    Real& distance, UnitVec3& normal) const;
00251 
00257 void getBoundingSphere(Vec3& center, Real& radius) const;
00258 
00262 bool isSmooth() const;
00263 
00280 void calcCurvature(const Vec3& point, Vec2& curvature, 
00281                    Rotation& orientation) const;
00282 
00293 const Function& getImplicitFunction() const;
00294 
00300 Real calcSurfaceValue(const Vec3& point) const;
00301 
00312 UnitVec3 calcSurfaceUnitNormal(const Vec3& point) const;
00313 
00319 Vec3 calcSurfaceGradient(const Vec3& point) const;
00320 
00326 Mat33 calcSurfaceHessian(const Vec3& point) const;
00327 
00356 Real calcGaussianCurvature(const Vec3&  gradient,
00357                            const Mat33& Hessian) const;
00358 
00362 Real calcGaussianCurvature(const Vec3& point) const {
00363     return calcGaussianCurvature(calcSurfaceGradient(point),
00364                                  calcSurfaceHessian(point)); 
00365 }
00366 
00375 Real calcSurfaceCurvatureInDirection(const Vec3& point, const UnitVec3& direction) const;
00376 
00379 bool isConvex() const;
00380 
00386 Vec3 calcSupportPoint(UnitVec3 direction) const;
00387 
00390 ContactGeometryTypeId getTypeId() const;
00391 
00442 static Vec2 evalParametricCurvature(const Vec3& P, const UnitVec3& nn,
00443                                     const Vec3& dPdu, const Vec3& dPdv,
00444                                     const Vec3& d2Pdu2, const Vec3& d2Pdv2, 
00445                                     const Vec3& d2Pdudv,
00446                                     Transform& X_EP);
00447 
00521 static void combineParaboloids(const Rotation& R_SP1, const Vec2& k1,
00522                                const UnitVec3& x2, const Vec2& k2,
00523                                Rotation& R_SP, Vec2& k);
00524 
00529 static void combineParaboloids(const Rotation& R_SP1, const Vec2& k1,
00530                                const UnitVec3& x2, const Vec2& k2,
00531                                Vec2& k);
00532 
00533 
00547 void initGeodesic(const Vec3& xP, const Vec3& xQ, const Vec3& xSP,
00548         const GeodesicOptions& options, Geodesic& geod) const;
00549 
00550 
00593 // XXX if xP and xQ are the exact end-points of prevGeod; then geod = prevGeod;
00594 void continueGeodesic(const Vec3& xP, const Vec3& xQ, const Geodesic& prevGeod,
00595         const GeodesicOptions& options, Geodesic& geod) const;
00596 
00623 void makeStraightLineGeodesic(const Vec3& xP, const Vec3& xQ,
00624         const UnitVec3& defaultDirectionIfNeeded,
00625         const GeodesicOptions& options, Geodesic& geod) const;
00626 
00627 
00637 // XXX what to do if tP is not in the tangent plane at P -- project it?
00638 void shootGeodesicInDirectionUntilLengthReached
00639    (const Vec3& xP, const UnitVec3& tP, const Real& terminatingLength, 
00640     const GeodesicOptions& options, Geodesic& geod) const;
00641 
00655 void calcGeodesicReverseSensitivity
00656    (Geodesic& geodesic,
00657     const Vec2& initSensitivity = Vec2(0,1)) const; // j, jdot at end point
00658 
00659 
00669 // XXX what to do if tP is not in the tangent plane at P -- project it?
00670 // XXX what to do if we don't hit the plane
00671 void shootGeodesicInDirectionUntilPlaneHit(const Vec3& xP, const UnitVec3& tP,
00672         const Plane& terminatingPlane, const GeodesicOptions& options,
00673         Geodesic& geod) const;
00674 
00675 
00678 void calcGeodesic(const Vec3& xP, const Vec3& xQ,
00679         const Vec3& tPhint, const Vec3& tQhint, Geodesic& geod) const;
00680 
00683 void calcGeodesicUsingOrthogonalMethod(const Vec3& xP, const Vec3& xQ,
00684         const Vec3& tPhint, Real lengthHint, Geodesic& geod) const;
00685 
00688 void calcGeodesicUsingOrthogonalMethod(const Vec3& xP, const Vec3& xQ,
00689         Geodesic& geod) const
00690 {
00691     const Vec3 r_PQ = xQ - xP;
00692     const Real lengthHint = r_PQ.norm();
00693     const UnitVec3 n = calcSurfaceUnitNormal(xP);
00694     // Project r_PQ into the tangent plane.
00695     const Vec3 t_PQ = r_PQ - (~r_PQ*n)*n;
00696     const Real tLength = t_PQ.norm();
00697     const UnitVec3 tPhint =
00698         tLength != 0 ? UnitVec3(t_PQ/tLength, true)
00699                      : n.perp(); // some arbitrary perpendicular to n
00700     calcGeodesicUsingOrthogonalMethod(xP, xQ, Vec3(tPhint), lengthHint, geod);           
00701 }
00702 
00703 
00711 Vec2 calcSplitGeodError(const Vec3& P, const Vec3& Q,
00712                    const UnitVec3& tP, const UnitVec3& tQ,
00713                    Geodesic* geod=0) const;
00714 
00715 
00716 
00727 // XXX what to do if tP is not in the tangent plane at P -- project it?
00728 void shootGeodesicInDirectionUntilLengthReachedAnalytical
00729    (const Vec3& xP, const UnitVec3& tP, const Real& terminatingLength,
00730     const GeodesicOptions& options, Geodesic& geod) const;
00731 
00732 
00743 // XXX what to do if tP is not in the tangent plane at P -- project it?
00744 // XXX what to do if we don't hit the plane
00745 void shootGeodesicInDirectionUntilPlaneHitAnalytical(const Vec3& xP, const UnitVec3& tP,
00746         const Plane& terminatingPlane, const GeodesicOptions& options,
00747         Geodesic& geod) const;
00748 
00749 
00754 void calcGeodesicAnalytical(const Vec3& xP, const Vec3& xQ,
00755         const Vec3& tPhint, const Vec3& tQhint, Geodesic& geod) const;
00756 
00765 Vec2 calcSplitGeodErrorAnalytical(const Vec3& P, const Vec3& Q,
00766                    const UnitVec3& tP, const UnitVec3& tQ,
00767                    Geodesic* geod=0) const;
00768 
00779 const Plane& getPlane() const;
00782 void setPlane(const Plane& plane) const;
00784 const Geodesic& getGeodP() const;
00786 const Geodesic& getGeodQ() const;
00787 const int getNumGeodesicsShot() const;
00788 void addVizReporter(ScheduledEventReporter* reporter) const;
00793 explicit ContactGeometry(ContactGeometryImpl* impl); 
00794 bool isOwnerHandle() const;                          
00795 bool isEmptyHandle() const;                          
00796 bool hasImpl() const {return impl != 0;}             
00798 const ContactGeometryImpl& getImpl() const {assert(impl); return *impl;}
00800 ContactGeometryImpl& updImpl() {assert(impl); return *impl; }
00801 
00802 protected:
00803 ContactGeometryImpl* impl; 
00804 };
00805 
00806 
00807 
00808 //==============================================================================
00809 //                                 HALF SPACE
00810 //==============================================================================
00813 class SimTK_SIMMATH_EXPORT ContactGeometry::HalfSpace : public ContactGeometry {
00814 public:
00815 HalfSpace();
00816 
00818 static bool isInstance(const ContactGeometry& geo)
00819 {   return geo.getTypeId()==classTypeId(); }
00821 static const HalfSpace& getAs(const ContactGeometry& geo)
00822 {   assert(isInstance(geo)); return static_cast<const HalfSpace&>(geo); }
00824 static HalfSpace& updAs(ContactGeometry& geo)
00825 {   assert(isInstance(geo)); return static_cast<HalfSpace&>(geo); }
00826 
00828 static ContactGeometryTypeId classTypeId();
00829 
00830 class Impl; 
00831 const Impl& getImpl() const; 
00832 Impl& updImpl(); 
00833 };
00834 
00835 
00836 
00837 //==============================================================================
00838 //                                CYLINDER
00839 //==============================================================================
00843 class SimTK_SIMMATH_EXPORT ContactGeometry::Cylinder : public ContactGeometry {
00844 public:
00845 explicit Cylinder(Real radius);
00846 Real getRadius() const;
00847 void setRadius(Real radius);
00848 
00850 static bool isInstance(const ContactGeometry& geo)
00851 {   return geo.getTypeId()==classTypeId(); }
00853 static const Cylinder& getAs(const ContactGeometry& geo)
00854 {   assert(isInstance(geo)); return static_cast<const Cylinder&>(geo); }
00856 static Cylinder& updAs(ContactGeometry& geo)
00857 {   assert(isInstance(geo)); return static_cast<Cylinder&>(geo); }
00858 
00860 static ContactGeometryTypeId classTypeId();
00861 
00862 class Impl; 
00863 const Impl& getImpl() const; 
00864 Impl& updImpl(); 
00865 };
00866 
00867 
00868 
00869 //==============================================================================
00870 //                                  SPHERE
00871 //==============================================================================
00874 class SimTK_SIMMATH_EXPORT ContactGeometry::Sphere : public ContactGeometry {
00875 public:
00876 explicit Sphere(Real radius);
00877 Real getRadius() const;
00878 void setRadius(Real radius);
00879 
00881 static bool isInstance(const ContactGeometry& geo)
00882 {   return geo.getTypeId()==classTypeId(); }
00884 static const Sphere& getAs(const ContactGeometry& geo)
00885 {   assert(isInstance(geo)); return static_cast<const Sphere&>(geo); }
00887 static Sphere& updAs(ContactGeometry& geo)
00888 {   assert(isInstance(geo)); return static_cast<Sphere&>(geo); }
00889 
00891 static ContactGeometryTypeId classTypeId();
00892 
00893 class Impl; 
00894 const Impl& getImpl() const; 
00895 Impl& updImpl(); 
00896 };
00897 
00898 
00899 
00900 //==============================================================================
00901 //                                  ELLIPSOID
00902 //==============================================================================
00924 class SimTK_SIMMATH_EXPORT ContactGeometry::Ellipsoid : public ContactGeometry {
00925 public:
00929 explicit Ellipsoid(const Vec3& radii);
00932 const Vec3& getRadii() const;
00938 void setRadii(const Vec3& radii);
00939 
00945 const Vec3& getCurvatures() const;
00946 
00959 UnitVec3 findUnitNormalAtPoint(const Vec3& P) const;
00960 
00968 Vec3 findPointWithThisUnitNormal(const UnitVec3& n) const;
00969 
00978 Vec3 findPointInSameDirection(const Vec3& Q) const;
00979 
01002 void findParaboloidAtPoint(const Vec3& Q, Transform& X_EP, Vec2& k) const;
01003 
01009 void findParaboloidAtPointWithNormal(const Vec3& Q, const UnitVec3& n,
01010     Transform& X_EP, Vec2& k) const;
01011 
01013 static bool isInstance(const ContactGeometry& geo)
01014 {   return geo.getTypeId()==classTypeId(); }
01016 static const Ellipsoid& getAs(const ContactGeometry& geo)
01017 {   assert(isInstance(geo)); return static_cast<const Ellipsoid&>(geo); }
01019 static Ellipsoid& updAs(ContactGeometry& geo)
01020 {   assert(isInstance(geo)); return static_cast<Ellipsoid&>(geo); }
01021 
01023 static ContactGeometryTypeId classTypeId();
01024 
01025 class Impl; 
01026 const Impl& getImpl() const; 
01027 Impl& updImpl(); 
01028 };
01029 
01030 
01031 
01032 //==============================================================================
01033 //                            SMOOTH HEIGHT MAP
01034 //==============================================================================
01045 class SimTK_SIMMATH_EXPORT 
01046 ContactGeometry::SmoothHeightMap : public ContactGeometry {
01047 public:
01051 explicit SmoothHeightMap(const BicubicSurface& surface);
01052 
01055 const BicubicSurface& getBicubicSurface() const;
01056 
01059 const OBBTree& getOBBTree() const;
01060 
01062 static bool isInstance(const ContactGeometry& geo)
01063 {   return geo.getTypeId()==classTypeId(); }
01065 static const SmoothHeightMap& getAs(const ContactGeometry& geo)
01066 {   assert(isInstance(geo)); return static_cast<const SmoothHeightMap&>(geo); }
01068 static SmoothHeightMap& updAs(ContactGeometry& geo)
01069 {   assert(isInstance(geo)); return static_cast<SmoothHeightMap&>(geo); }
01070 
01072 static ContactGeometryTypeId classTypeId();
01073 
01074 class Impl; 
01075 const Impl& getImpl() const; 
01076 Impl& updImpl(); 
01077 };
01078 
01079 
01080 
01081 //==============================================================================
01082 //                              TRIANGLE MESH
01083 //==============================================================================
01104 class SimTK_SIMMATH_EXPORT ContactGeometry::TriangleMesh 
01105 :   public ContactGeometry {
01106 public:
01107 class OBBTreeNode;
01118 TriangleMesh(const ArrayViewConst_<Vec3>& vertices, const ArrayViewConst_<int>& faceIndices, bool smooth=false);
01127 explicit TriangleMesh(const PolygonalMesh& mesh, bool smooth=false);
01129 int getNumEdges() const;
01131 int getNumFaces() const;
01133 int getNumVertices() const;
01137 const Vec3& getVertexPosition(int index) const;
01143 int getFaceEdge(int face, int edge) const;
01148 int getFaceVertex(int face, int vertex) const;
01153 int getEdgeFace(int edge, int face) const;
01158 int getEdgeVertex(int edge, int vertex) const;
01163 void findVertexEdges(int vertex, Array_<int>& edges) const;
01166 const UnitVec3& getFaceNormal(int face) const;
01169 Real getFaceArea(int face) const;
01175 Vec3 findPoint(int face, const Vec2& uv) const;
01180 Vec3 findCentroid(int face) const;
01185 UnitVec3 findNormalAtPoint(int face, const Vec2& uv) const;
01196 Vec3 findNearestPoint(const Vec3& position, bool& inside, UnitVec3& normal) const;
01209 Vec3 findNearestPoint(const Vec3& position, bool& inside, int& face, Vec2& uv) const;
01210 
01220 Vec3 findNearestPointToFace(const Vec3& position, int face, Vec2& uv) const;
01221 
01222 
01234 bool intersectsRay(const Vec3& origin, const UnitVec3& direction, Real& distance, UnitVec3& normal) const;
01248 bool intersectsRay(const Vec3& origin, const UnitVec3& direction, Real& distance, int& face, Vec2& uv) const;
01251 OBBTreeNode getOBBTreeNode() const;
01252 
01255 PolygonalMesh createPolygonalMesh() const;
01256 
01258 static bool isInstance(const ContactGeometry& geo)
01259 {   return geo.getTypeId()==classTypeId(); }
01261 static const TriangleMesh& getAs(const ContactGeometry& geo)
01262 {   assert(isInstance(geo)); return static_cast<const TriangleMesh&>(geo); }
01264 static TriangleMesh& updAs(ContactGeometry& geo)
01265 {   assert(isInstance(geo)); return static_cast<TriangleMesh&>(geo); }
01266 
01268 static ContactGeometryTypeId classTypeId();
01269 
01270 class Impl; 
01271 const Impl& getImpl() const; 
01272 Impl& updImpl(); 
01273 };
01274 
01275 
01276 
01277 //==============================================================================
01278 //                       TRIANGLE MESH :: OBB TREE NODE
01279 //==============================================================================
01284 class SimTK_SIMMATH_EXPORT ContactGeometry::TriangleMesh::OBBTreeNode {
01285 public:
01286 OBBTreeNode(const OBBTreeNodeImpl& impl);
01289 const OrientedBoundingBox& getBounds() const;
01291 bool isLeafNode() const;
01294 const OBBTreeNode getFirstChildNode() const;
01297 const OBBTreeNode getSecondChildNode() const;
01300 const Array_<int>& getTriangles() const;
01304 int getNumTriangles() const;
01305 
01306 private:
01307 const OBBTreeNodeImpl* impl;
01308 };
01309 
01310 //==============================================================================
01311 //                                TORUS
01312 //==============================================================================
01318 class SimTK_SIMMATH_EXPORT ContactGeometry::Torus : public ContactGeometry {
01319 public:
01320 Torus(Real torusRadius, Real tubeRadius);
01321 Real getTorusRadius() const;
01322 void setTorusRadius(Real radius);
01323 Real getTubeRadius() const;
01324 void setTubeRadius(Real radius);
01325 
01327 static bool isInstance(const ContactGeometry& geo)
01328 {   return geo.getTypeId()==classTypeId(); }
01330 static const Torus& getAs(const ContactGeometry& geo)
01331 {   assert(isInstance(geo)); return static_cast<const Torus&>(geo); }
01333 static Torus& updAs(ContactGeometry& geo)
01334 {   assert(isInstance(geo)); return static_cast<Torus&>(geo); }
01335 
01337 static ContactGeometryTypeId classTypeId();
01338 
01339 class Impl; 
01340 const Impl& getImpl() const; 
01341 Impl& updImpl(); 
01342 };
01343 
01344 
01345 
01346 
01347 //==============================================================================
01348 //                     GEODESIC EVALUATOR helper classes
01349 //==============================================================================
01350 
01351 
01355 class Plane {
01356 public:
01357     Plane() : m_normal(1,0,0), m_offset(0) { }
01358     Plane(const Vec3& normal, const Real& offset)
01359     :   m_normal(normal), m_offset(offset) { }
01360 
01361     Real getDistance(const Vec3& pt) const {
01362         return ~m_normal*pt - m_offset;
01363     }
01364 
01365     Vec3 getNormal() const {
01366         return m_normal;
01367     }
01368 
01369     Real getOffset() const {
01370         return m_offset;
01371     }
01372 
01373 private:
01374     Vec3 m_normal;
01375     Real m_offset;
01376 }; // class Plane
01377 
01378 
01383 class GeodHitPlaneEvent : public TriggeredEventHandler {
01384 public:
01385     GeodHitPlaneEvent()
01386     :   TriggeredEventHandler(Stage::Position) { }
01387 
01388     explicit GeodHitPlaneEvent(const Plane& aplane)
01389     :   TriggeredEventHandler(Stage::Position) {
01390         plane = aplane;
01391     }
01392 
01393     // event is triggered if distance of geodesic endpoint to plane is zero
01394     Real getValue(const State& state) const {
01395         if (!enabled) {
01396             return 1;
01397         }
01398         Vec3 endpt(&state.getQ()[0]);
01399         Real dist =  plane.getDistance(endpt);
01400 //        std::cout << "dist = " << dist << std::endl;
01401         return dist;
01402     }
01403 
01404     // This method is called whenever this event occurs.
01405     void handleEvent(State& state, Real accuracy, bool& shouldTerminate) const {
01406         if (!enabled) {
01407             return;
01408         }
01409 
01410         // This should be triggered when geodesic endpoint to plane is zero.
01411         Vec3 endpt;
01412         const Vector& q = state.getQ();
01413         endpt[0] = q[0]; endpt[1] = q[1]; endpt[2] = q[2];
01414         Real dist = plane.getDistance(endpt);
01415 
01416 //        ASSERT(std::abs(dist) < 0.01 );
01417         shouldTerminate = true;
01418 //        std::cout << "hit plane!" << std::endl;
01419     }
01420 
01421     void setPlane(const Plane& aplane) const {
01422         plane = aplane;
01423     }
01424 
01425     const Plane& getPlane() const {
01426         return plane;
01427     }
01428 
01429     const void setEnabled(bool enabledFlag) {
01430         enabled = enabledFlag;
01431     }
01432 
01433     const bool isEnabled() {
01434         return enabled;
01435     }
01436 
01437 private:
01438     mutable Plane plane;
01439     bool enabled;
01440 
01441 }; // class GeodHitPlaneEvent
01442 
01446 class PathDecorator : public DecorationGenerator {
01447 public:
01448     PathDecorator(const Vector& x, const Vec3& O, const Vec3& I, const Vec3& color) :
01449             m_x(x), m_O(O), m_I(I), m_color(color) { }
01450 
01451     virtual void generateDecorations(const State& state,
01452             Array_<DecorativeGeometry>& geometry) {
01453 //        m_system.realize(state, Stage::Position);
01454 
01455         Vec3 P, Q;
01456         P[0] = m_x[0]; P[1] = m_x[1]; P[2] = m_x[2];
01457         Q[0] = m_x[3]; Q[1] = m_x[4]; Q[2] = m_x[5];
01458 
01459         geometry.push_back(DecorativeSphere(Real(.05)).setColor(Black).setTransform(m_O));
01460         geometry.push_back(DecorativeSphere(Real(.05)).setColor(Black).setTransform(P));
01461         geometry.push_back(DecorativeSphere(Real(.05)).setColor(Black).setTransform(Q));
01462         geometry.push_back(DecorativeSphere(Real(.05)).setColor(Black).setTransform(m_I));
01463 
01464         geometry.push_back(DecorativeLine(m_O,P)
01465                 .setColor(m_color)
01466                 .setLineThickness(2));
01467         geometry.push_back(DecorativeLine(Q,m_I)
01468                 .setColor(m_color)
01469                 .setLineThickness(2));
01470 
01471     }
01472 
01473 private:
01474     const Vector& m_x; // x = ~[P Q]
01475     const Vec3& m_O;
01476     const Vec3& m_I;
01477     const Vec3& m_color;
01478     Rotation R_plane;
01479     Vec3 offset;
01480 }; // class DecorationGenerator
01481 
01482 
01486 class PlaneDecorator : public DecorationGenerator {
01487 public:
01488     PlaneDecorator(const Plane& plane, const Vec3& color) :
01489             m_plane(plane), m_color(color) { }
01490 
01491     virtual void generateDecorations(const State& state,
01492             Array_<DecorativeGeometry>& geometry) {
01493 //        m_system.realize(state, Stage::Position);
01494 
01495         // draw plane
01496         R_plane.setRotationFromOneAxis(UnitVec3(m_plane.getNormal()),
01497                 CoordinateAxis::XCoordinateAxis());
01498         offset = 0;
01499         offset[0] = m_plane.getOffset();
01500         geometry.push_back(
01501                 DecorativeBrick(Vec3(Real(.01),1,1))
01502                 .setTransform(Transform(R_plane, R_plane*offset))
01503                 .setColor(m_color)
01504                 .setOpacity(Real(.2)));
01505     }
01506 
01507 private:
01508     const Plane& m_plane;
01509     const Vec3& m_color;
01510     Rotation R_plane;
01511     Vec3 offset;
01512 }; // class DecorationGenerator
01513 
01514 
01515 } // namespace SimTK
01516 
01517 #endif // SimTK_SIMMATH_CONTACT_GEOMETRY_H_
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines