Simbody  3.3
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Groups Pages
ContactGeometry.h
Go to the documentation of this file.
1 #ifndef SimTK_SIMMATH_CONTACT_GEOMETRY_H_
2 #define SimTK_SIMMATH_CONTACT_GEOMETRY_H_
3 
4 /* -------------------------------------------------------------------------- *
5  * Simbody(tm): SimTKmath *
6  * -------------------------------------------------------------------------- *
7  * This is part of the SimTK biosimulation toolkit originating from *
8  * Simbios, the NIH National Center for Physics-Based Simulation of *
9  * Biological Structures at Stanford, funded under the NIH Roadmap for *
10  * Medical Research, grant U54 GM072970. See https://simtk.org/home/simbody. *
11  * *
12  * Portions copyright (c) 2008-12 Stanford University and the Authors. *
13  * Authors: Peter Eastman, Michael Sherman *
14  * Contributors: Ian Stavness, Andreas Scholz *
15  * *
16  * Licensed under the Apache License, Version 2.0 (the "License"); you may *
17  * not use this file except in compliance with the License. You may obtain a *
18  * copy of the License at http://www.apache.org/licenses/LICENSE-2.0. *
19  * *
20  * Unless required by applicable law or agreed to in writing, software *
21  * distributed under the License is distributed on an "AS IS" BASIS, *
22  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. *
23  * See the License for the specific language governing permissions and *
24  * limitations under the License. *
25  * -------------------------------------------------------------------------- */
26 
31 #include "SimTKcommon.h"
36 
37 #include <cassert>
38 
39 namespace SimTK {
40 
44 SimTK_DEFINE_UNIQUE_INDEX_TYPE(ContactGeometryTypeId);
45 
46 class ContactGeometryImpl;
47 class OBBTreeNodeImpl;
48 class OBBTree;
49 class Plane;
50 
51 
52 
53 //==============================================================================
54 // CONTACT GEOMETRY
55 //==============================================================================
111 public:
112 class HalfSpace;
113 class Cylinder;
114 class Sphere;
115 class Ellipsoid;
116 class SmoothHeightMap;
117 class TriangleMesh;
118 class Torus;
119 
120 // TODO
121 class Cone;
122 
124 ContactGeometry() : impl(0) {}
126 ContactGeometry(const ContactGeometry& src);
128 ContactGeometry& operator=(const ContactGeometry& src);
132 ~ContactGeometry();
133 
135 DecorativeGeometry createDecorativeGeometry() const;
136 
147 Vec3 findNearestPoint(const Vec3& position, bool& inside, UnitVec3& normal) const;
148 
163 Vec3 projectDownhillToNearestPoint(const Vec3& pointQ) const;
164 
229 bool trackSeparationFromLine(const Vec3& pointOnLine,
230  const UnitVec3& directionOfLine,
231  const Vec3& startingGuessForClosestPoint,
232  Vec3& newClosestPointOnSurface,
233  Vec3& closestPointOnLine,
234  Real& height) const;
235 
236 
237 
249 bool intersectsRay(const Vec3& origin, const UnitVec3& direction,
250  Real& distance, UnitVec3& normal) const;
251 
257 void getBoundingSphere(Vec3& center, Real& radius) const;
258 
262 bool isSmooth() const;
263 
280 void calcCurvature(const Vec3& point, Vec2& curvature,
281  Rotation& orientation) const;
282 
293 const Function& getImplicitFunction() const;
294 
300 Real calcSurfaceValue(const Vec3& point) const;
301 
312 UnitVec3 calcSurfaceUnitNormal(const Vec3& point) const;
313 
319 Vec3 calcSurfaceGradient(const Vec3& point) const;
320 
326 Mat33 calcSurfaceHessian(const Vec3& point) const;
327 
356 Real calcGaussianCurvature(const Vec3& gradient,
357  const Mat33& Hessian) const;
358 
362 Real calcGaussianCurvature(const Vec3& point) const {
363  return calcGaussianCurvature(calcSurfaceGradient(point),
364  calcSurfaceHessian(point));
365 }
366 
375 Real calcSurfaceCurvatureInDirection(const Vec3& point, const UnitVec3& direction) const;
376 
379 bool isConvex() const;
380 
386 Vec3 calcSupportPoint(UnitVec3 direction) const;
387 
390 ContactGeometryTypeId getTypeId() const;
391 
442 static Vec2 evalParametricCurvature(const Vec3& P, const UnitVec3& nn,
443  const Vec3& dPdu, const Vec3& dPdv,
444  const Vec3& d2Pdu2, const Vec3& d2Pdv2,
445  const Vec3& d2Pdudv,
446  Transform& X_EP);
447 
521 static void combineParaboloids(const Rotation& R_SP1, const Vec2& k1,
522  const UnitVec3& x2, const Vec2& k2,
523  Rotation& R_SP, Vec2& k);
524 
529 static void combineParaboloids(const Rotation& R_SP1, const Vec2& k1,
530  const UnitVec3& x2, const Vec2& k2,
531  Vec2& k);
532 
533 
547 void initGeodesic(const Vec3& xP, const Vec3& xQ, const Vec3& xSP,
548  const GeodesicOptions& options, Geodesic& geod) const;
549 
550 
593 // XXX if xP and xQ are the exact end-points of prevGeod; then geod = prevGeod;
594 void continueGeodesic(const Vec3& xP, const Vec3& xQ, const Geodesic& prevGeod,
595  const GeodesicOptions& options, Geodesic& geod) const;
596 
623 void makeStraightLineGeodesic(const Vec3& xP, const Vec3& xQ,
624  const UnitVec3& defaultDirectionIfNeeded,
625  const GeodesicOptions& options, Geodesic& geod) const;
626 
627 
637 // XXX what to do if tP is not in the tangent plane at P -- project it?
638 void shootGeodesicInDirectionUntilLengthReached
639  (const Vec3& xP, const UnitVec3& tP, const Real& terminatingLength,
640  const GeodesicOptions& options, Geodesic& geod) const;
641 
655 void calcGeodesicReverseSensitivity
656  (Geodesic& geodesic,
657  const Vec2& initSensitivity = Vec2(0,1)) const; // j, jdot at end point
658 
659 
669 // XXX what to do if tP is not in the tangent plane at P -- project it?
670 // XXX what to do if we don't hit the plane
671 void shootGeodesicInDirectionUntilPlaneHit(const Vec3& xP, const UnitVec3& tP,
672  const Plane& terminatingPlane, const GeodesicOptions& options,
673  Geodesic& geod) const;
674 
675 
678 void calcGeodesic(const Vec3& xP, const Vec3& xQ,
679  const Vec3& tPhint, const Vec3& tQhint, Geodesic& geod) const;
680 
683 void calcGeodesicUsingOrthogonalMethod(const Vec3& xP, const Vec3& xQ,
684  const Vec3& tPhint, Real lengthHint, Geodesic& geod) const;
685 
688 void calcGeodesicUsingOrthogonalMethod(const Vec3& xP, const Vec3& xQ,
689  Geodesic& geod) const
690 {
691  const Vec3 r_PQ = xQ - xP;
692  const Real lengthHint = r_PQ.norm();
693  const UnitVec3 n = calcSurfaceUnitNormal(xP);
694  // Project r_PQ into the tangent plane.
695  const Vec3 t_PQ = r_PQ - (~r_PQ*n)*n;
696  const Real tLength = t_PQ.norm();
697  const UnitVec3 tPhint =
698  tLength != 0 ? UnitVec3(t_PQ/tLength, true)
699  : n.perp(); // some arbitrary perpendicular to n
700  calcGeodesicUsingOrthogonalMethod(xP, xQ, Vec3(tPhint), lengthHint, geod);
701 }
702 
703 
711 Vec2 calcSplitGeodError(const Vec3& P, const Vec3& Q,
712  const UnitVec3& tP, const UnitVec3& tQ,
713  Geodesic* geod=0) const;
714 
715 
716 
727 // XXX what to do if tP is not in the tangent plane at P -- project it?
728 void shootGeodesicInDirectionUntilLengthReachedAnalytical
729  (const Vec3& xP, const UnitVec3& tP, const Real& terminatingLength,
730  const GeodesicOptions& options, Geodesic& geod) const;
731 
732 
743 // XXX what to do if tP is not in the tangent plane at P -- project it?
744 // XXX what to do if we don't hit the plane
745 void shootGeodesicInDirectionUntilPlaneHitAnalytical(const Vec3& xP, const UnitVec3& tP,
746  const Plane& terminatingPlane, const GeodesicOptions& options,
747  Geodesic& geod) const;
748 
749 
754 void calcGeodesicAnalytical(const Vec3& xP, const Vec3& xQ,
755  const Vec3& tPhint, const Vec3& tQhint, Geodesic& geod) const;
756 
765 Vec2 calcSplitGeodErrorAnalytical(const Vec3& P, const Vec3& Q,
766  const UnitVec3& tP, const UnitVec3& tQ,
767  Geodesic* geod=0) const;
768 
779 const Plane& getPlane() const;
782 void setPlane(const Plane& plane) const;
784 const Geodesic& getGeodP() const;
786 const Geodesic& getGeodQ() const;
787 const int getNumGeodesicsShot() const;
788 void addVizReporter(ScheduledEventReporter* reporter) const;
793 explicit ContactGeometry(ContactGeometryImpl* impl);
794 bool isOwnerHandle() const;
795 bool isEmptyHandle() const;
796 bool hasImpl() const {return impl != 0;}
798 const ContactGeometryImpl& getImpl() const {assert(impl); return *impl;}
800 ContactGeometryImpl& updImpl() {assert(impl); return *impl; }
801 
802 protected:
803 ContactGeometryImpl* impl;
804 };
805 
806 
807 
808 //==============================================================================
809 // HALF SPACE
810 //==============================================================================
814 public:
815 HalfSpace();
816 
818 static bool isInstance(const ContactGeometry& geo)
819 { return geo.getTypeId()==classTypeId(); }
821 static const HalfSpace& getAs(const ContactGeometry& geo)
822 { assert(isInstance(geo)); return static_cast<const HalfSpace&>(geo); }
825 { assert(isInstance(geo)); return static_cast<HalfSpace&>(geo); }
826 
828 static ContactGeometryTypeId classTypeId();
829 
830 class Impl;
831 const Impl& getImpl() const;
832 Impl& updImpl();
833 };
834 
835 
836 
837 //==============================================================================
838 // CYLINDER
839 //==============================================================================
844 public:
845 explicit Cylinder(Real radius);
846 Real getRadius() const;
847 void setRadius(Real radius);
848 
850 static bool isInstance(const ContactGeometry& geo)
851 { return geo.getTypeId()==classTypeId(); }
853 static const Cylinder& getAs(const ContactGeometry& geo)
854 { assert(isInstance(geo)); return static_cast<const Cylinder&>(geo); }
857 { assert(isInstance(geo)); return static_cast<Cylinder&>(geo); }
858 
860 static ContactGeometryTypeId classTypeId();
861 
862 class Impl;
863 const Impl& getImpl() const;
864 Impl& updImpl();
865 };
866 
867 
868 
869 //==============================================================================
870 // SPHERE
871 //==============================================================================
875 public:
876 explicit Sphere(Real radius);
877 Real getRadius() const;
878 void setRadius(Real radius);
879 
881 static bool isInstance(const ContactGeometry& geo)
882 { return geo.getTypeId()==classTypeId(); }
884 static const Sphere& getAs(const ContactGeometry& geo)
885 { assert(isInstance(geo)); return static_cast<const Sphere&>(geo); }
888 { assert(isInstance(geo)); return static_cast<Sphere&>(geo); }
889 
891 static ContactGeometryTypeId classTypeId();
892 
893 class Impl;
894 const Impl& getImpl() const;
895 Impl& updImpl();
896 };
897 
898 
899 
900 //==============================================================================
901 // ELLIPSOID
902 //==============================================================================
925 public:
929 explicit Ellipsoid(const Vec3& radii);
932 const Vec3& getRadii() const;
938 void setRadii(const Vec3& radii);
939 
945 const Vec3& getCurvatures() const;
946 
959 UnitVec3 findUnitNormalAtPoint(const Vec3& P) const;
960 
968 Vec3 findPointWithThisUnitNormal(const UnitVec3& n) const;
969 
978 Vec3 findPointInSameDirection(const Vec3& Q) const;
979 
1002 void findParaboloidAtPoint(const Vec3& Q, Transform& X_EP, Vec2& k) const;
1003 
1009 void findParaboloidAtPointWithNormal(const Vec3& Q, const UnitVec3& n,
1010  Transform& X_EP, Vec2& k) const;
1011 
1013 static bool isInstance(const ContactGeometry& geo)
1014 { return geo.getTypeId()==classTypeId(); }
1016 static const Ellipsoid& getAs(const ContactGeometry& geo)
1017 { assert(isInstance(geo)); return static_cast<const Ellipsoid&>(geo); }
1020 { assert(isInstance(geo)); return static_cast<Ellipsoid&>(geo); }
1021 
1023 static ContactGeometryTypeId classTypeId();
1024 
1025 class Impl;
1026 const Impl& getImpl() const;
1027 Impl& updImpl();
1028 };
1029 
1030 
1031 
1032 //==============================================================================
1033 // SMOOTH HEIGHT MAP
1034 //==============================================================================
1047 public:
1051 explicit SmoothHeightMap(const BicubicSurface& surface);
1052 
1055 const BicubicSurface& getBicubicSurface() const;
1056 
1059 const OBBTree& getOBBTree() const;
1060 
1062 static bool isInstance(const ContactGeometry& geo)
1063 { return geo.getTypeId()==classTypeId(); }
1065 static const SmoothHeightMap& getAs(const ContactGeometry& geo)
1066 { assert(isInstance(geo)); return static_cast<const SmoothHeightMap&>(geo); }
1069 { assert(isInstance(geo)); return static_cast<SmoothHeightMap&>(geo); }
1070 
1072 static ContactGeometryTypeId classTypeId();
1073 
1074 class Impl;
1075 const Impl& getImpl() const;
1076 Impl& updImpl();
1077 };
1078 
1079 
1080 
1081 //==============================================================================
1082 // TRIANGLE MESH
1083 //==============================================================================
1105 : public ContactGeometry {
1106 public:
1107 class OBBTreeNode;
1118 TriangleMesh(const ArrayViewConst_<Vec3>& vertices, const ArrayViewConst_<int>& faceIndices, bool smooth=false);
1127 explicit TriangleMesh(const PolygonalMesh& mesh, bool smooth=false);
1129 int getNumEdges() const;
1131 int getNumFaces() const;
1133 int getNumVertices() const;
1137 const Vec3& getVertexPosition(int index) const;
1143 int getFaceEdge(int face, int edge) const;
1148 int getFaceVertex(int face, int vertex) const;
1153 int getEdgeFace(int edge, int face) const;
1158 int getEdgeVertex(int edge, int vertex) const;
1163 void findVertexEdges(int vertex, Array_<int>& edges) const;
1166 const UnitVec3& getFaceNormal(int face) const;
1169 Real getFaceArea(int face) const;
1175 Vec3 findPoint(int face, const Vec2& uv) const;
1180 Vec3 findCentroid(int face) const;
1185 UnitVec3 findNormalAtPoint(int face, const Vec2& uv) const;
1196 Vec3 findNearestPoint(const Vec3& position, bool& inside, UnitVec3& normal) const;
1209 Vec3 findNearestPoint(const Vec3& position, bool& inside, int& face, Vec2& uv) const;
1210 
1220 Vec3 findNearestPointToFace(const Vec3& position, int face, Vec2& uv) const;
1221 
1222 
1234 bool intersectsRay(const Vec3& origin, const UnitVec3& direction, Real& distance, UnitVec3& normal) const;
1248 bool intersectsRay(const Vec3& origin, const UnitVec3& direction, Real& distance, int& face, Vec2& uv) const;
1251 OBBTreeNode getOBBTreeNode() const;
1252 
1255 PolygonalMesh createPolygonalMesh() const;
1256 
1258 static bool isInstance(const ContactGeometry& geo)
1259 { return geo.getTypeId()==classTypeId(); }
1261 static const TriangleMesh& getAs(const ContactGeometry& geo)
1262 { assert(isInstance(geo)); return static_cast<const TriangleMesh&>(geo); }
1265 { assert(isInstance(geo)); return static_cast<TriangleMesh&>(geo); }
1266 
1268 static ContactGeometryTypeId classTypeId();
1269 
1270 class Impl;
1271 const Impl& getImpl() const;
1272 Impl& updImpl();
1273 };
1274 
1275 
1276 
1277 //==============================================================================
1278 // TRIANGLE MESH :: OBB TREE NODE
1279 //==============================================================================
1285 public:
1286 OBBTreeNode(const OBBTreeNodeImpl& impl);
1289 const OrientedBoundingBox& getBounds() const;
1291 bool isLeafNode() const;
1294 const OBBTreeNode getFirstChildNode() const;
1297 const OBBTreeNode getSecondChildNode() const;
1300 const Array_<int>& getTriangles() const;
1304 int getNumTriangles() const;
1305 
1306 private:
1307 const OBBTreeNodeImpl* impl;
1308 };
1309 
1310 //==============================================================================
1311 // TORUS
1312 //==============================================================================
1319 public:
1320 Torus(Real torusRadius, Real tubeRadius);
1321 Real getTorusRadius() const;
1322 void setTorusRadius(Real radius);
1323 Real getTubeRadius() const;
1324 void setTubeRadius(Real radius);
1325 
1327 static bool isInstance(const ContactGeometry& geo)
1328 { return geo.getTypeId()==classTypeId(); }
1330 static const Torus& getAs(const ContactGeometry& geo)
1331 { assert(isInstance(geo)); return static_cast<const Torus&>(geo); }
1334 { assert(isInstance(geo)); return static_cast<Torus&>(geo); }
1335 
1337 static ContactGeometryTypeId classTypeId();
1338 
1339 class Impl;
1340 const Impl& getImpl() const;
1341 Impl& updImpl();
1342 };
1343 
1344 
1345 
1346 
1347 //==============================================================================
1348 // GEODESIC EVALUATOR helper classes
1349 //==============================================================================
1350 
1351 
1355 class Plane {
1356 public:
1357  Plane() : m_normal(1,0,0), m_offset(0) { }
1358  Plane(const Vec3& normal, const Real& offset)
1359  : m_normal(normal), m_offset(offset) { }
1360 
1361  Real getDistance(const Vec3& pt) const {
1362  return ~m_normal*pt - m_offset;
1363  }
1364 
1365  Vec3 getNormal() const {
1366  return m_normal;
1367  }
1368 
1369  Real getOffset() const {
1370  return m_offset;
1371  }
1372 
1373 private:
1374  Vec3 m_normal;
1375  Real m_offset;
1376 }; // class Plane
1377 
1378 
1384 public:
1386  : TriggeredEventHandler(Stage::Position) { }
1387 
1388  explicit GeodHitPlaneEvent(const Plane& aplane)
1389  : TriggeredEventHandler(Stage::Position) {
1390  plane = aplane;
1391  }
1392 
1393  // event is triggered if distance of geodesic endpoint to plane is zero
1394  Real getValue(const State& state) const {
1395  if (!enabled) {
1396  return 1;
1397  }
1398  Vec3 endpt(&state.getQ()[0]);
1399  Real dist = plane.getDistance(endpt);
1400 // std::cout << "dist = " << dist << std::endl;
1401  return dist;
1402  }
1403 
1404  // This method is called whenever this event occurs.
1405  void handleEvent(State& state, Real accuracy, bool& shouldTerminate) const {
1406  if (!enabled) {
1407  return;
1408  }
1409 
1410  // This should be triggered when geodesic endpoint to plane is zero.
1411  Vec3 endpt;
1412  const Vector& q = state.getQ();
1413  endpt[0] = q[0]; endpt[1] = q[1]; endpt[2] = q[2];
1414  Real dist = plane.getDistance(endpt);
1415 
1416 // ASSERT(std::abs(dist) < 0.01 );
1417  shouldTerminate = true;
1418 // std::cout << "hit plane!" << std::endl;
1419  }
1420 
1421  void setPlane(const Plane& aplane) const {
1422  plane = aplane;
1423  }
1424 
1425  const Plane& getPlane() const {
1426  return plane;
1427  }
1428 
1429  const void setEnabled(bool enabledFlag) {
1430  enabled = enabledFlag;
1431  }
1432 
1433  const bool isEnabled() {
1434  return enabled;
1435  }
1436 
1437 private:
1438  mutable Plane plane;
1439  bool enabled;
1440 
1441 }; // class GeodHitPlaneEvent
1442 
1447 public:
1448  PathDecorator(const Vector& x, const Vec3& O, const Vec3& I, const Vec3& color) :
1449  m_x(x), m_O(O), m_I(I), m_color(color) { }
1450 
1451  virtual void generateDecorations(const State& state,
1452  Array_<DecorativeGeometry>& geometry) {
1453 // m_system.realize(state, Stage::Position);
1454 
1455  Vec3 P, Q;
1456  P[0] = m_x[0]; P[1] = m_x[1]; P[2] = m_x[2];
1457  Q[0] = m_x[3]; Q[1] = m_x[4]; Q[2] = m_x[5];
1458 
1459  geometry.push_back(DecorativeSphere(Real(.05)).setColor(Black).setTransform(m_O));
1460  geometry.push_back(DecorativeSphere(Real(.05)).setColor(Black).setTransform(P));
1461  geometry.push_back(DecorativeSphere(Real(.05)).setColor(Black).setTransform(Q));
1462  geometry.push_back(DecorativeSphere(Real(.05)).setColor(Black).setTransform(m_I));
1463 
1464  geometry.push_back(DecorativeLine(m_O,P)
1465  .setColor(m_color)
1466  .setLineThickness(2));
1467  geometry.push_back(DecorativeLine(Q,m_I)
1468  .setColor(m_color)
1469  .setLineThickness(2));
1470 
1471  }
1472 
1473 private:
1474  const Vector& m_x; // x = ~[P Q]
1475  const Vec3& m_O;
1476  const Vec3& m_I;
1477  const Vec3& m_color;
1478  Rotation R_plane;
1479  Vec3 offset;
1480 }; // class DecorationGenerator
1481 
1482 
1487 public:
1488  PlaneDecorator(const Plane& plane, const Vec3& color) :
1489  m_plane(plane), m_color(color) { }
1490 
1491  virtual void generateDecorations(const State& state,
1492  Array_<DecorativeGeometry>& geometry) {
1493 // m_system.realize(state, Stage::Position);
1494 
1495  // draw plane
1496  R_plane.setRotationFromOneAxis(UnitVec3(m_plane.getNormal()),
1498  offset = 0;
1499  offset[0] = m_plane.getOffset();
1500  geometry.push_back(
1501  DecorativeBrick(Vec3(Real(.01),1,1))
1502  .setTransform(Transform(R_plane, R_plane*offset))
1503  .setColor(m_color)
1504  .setOpacity(Real(.2)));
1505  }
1506 
1507 private:
1508  const Plane& m_plane;
1509  const Vec3& m_color;
1510  Rotation R_plane;
1511  Vec3 offset;
1512 }; // class DecorationGenerator
1513 
1514 
1515 } // namespace SimTK
1516 
1517 #endif // SimTK_SIMMATH_CONTACT_GEOMETRY_H_
This class will create a smooth surface that approximates a two-argument function F(X...
Definition: BicubicSurface.h:158
ScheduledEventReporter is a subclass of EventReporter for events that occur at a particular time that...
Definition: EventReporter.h:72
UnitVec< P, 1 > perp() const
Return a new unit vector perpendicular to this one but otherwise arbitrary.
Definition: UnitVec.h:182
Plane(const Vec3 &normal, const Real &offset)
Definition: ContactGeometry.h:1358
This defines a rectangular solid centered at the origin and aligned with the local frame axes...
Definition: DecorativeGeometry.h:334
SimTK_DEFINE_UNIQUE_INDEX_TYPE(AssemblyConditionIndex)
A simple plane class.
Definition: ContactGeometry.h:1355
UnitVec< Real, 1 > UnitVec3
Definition: UnitVec.h:41
static Ellipsoid & updAs(ContactGeometry &geo)
Cast the supplied ContactGeometry object to a writable Ellipsoid.
Definition: ContactGeometry.h:1019
This class generates decoration for contact points and straight line path segments.
Definition: ContactGeometry.h:1446
static SmoothHeightMap & updAs(ContactGeometry &geo)
Cast the supplied ContactGeometry object to a writable SmoothHeightMap.
Definition: ContactGeometry.h:1068
This is a unique integer type for quickly identifying specific types of contact geometry for fast loo...
const void setEnabled(bool enabledFlag)
Definition: ContactGeometry.h:1429
Plane()
Definition: ContactGeometry.h:1357
GeodHitPlaneEvent(const Plane &aplane)
Definition: ContactGeometry.h:1388
static bool isInstance(const ContactGeometry &geo)
Return true if the supplied ContactGeometry object is an Ellipsoid.
Definition: ContactGeometry.h:1013
This ContactGeometry subclass represents a torus centered at the origin with the axial direction alig...
Definition: ContactGeometry.h:1318
const bool isEnabled()
Definition: ContactGeometry.h:1433
Definition: CoordinateAxis.h:196
This class is basically a glorified enumerated type, type-safe and range checked but permitting conve...
Definition: Stage.h:50
PathDecorator(const Vector &x, const Vec3 &O, const Vec3 &I, const Vec3 &color)
Definition: ContactGeometry.h:1448
This class stores a geodesic curve after it has been determined.
Definition: Geodesic.h:51
static HalfSpace & updAs(ContactGeometry &geo)
Cast the supplied ContactGeometry object to a writable halfspace.
Definition: ContactGeometry.h:824
This file defines the BicubicSurface class, and the BicubicFunction class that uses it to create a tw...
static bool isInstance(const ContactGeometry &geo)
Return true if the supplied ContactGeometry object is a halfspace.
Definition: ContactGeometry.h:818
This ContactGeometry subclass represents a smooth surface fit through a set of sampled points using b...
Definition: ContactGeometry.h:1045
ContactGeometryImpl * impl
Internal use only.
Definition: ContactGeometry.h:803
This class represents a rectangular box with arbitrary position and orientation.
Definition: OrientedBoundingBox.h:42
void handleEvent(State &state, Real accuracy, bool &shouldTerminate) const
This method is invoked to handle the event.
Definition: ContactGeometry.h:1405
virtual void generateDecorations(const State &state, Array_< DecorativeGeometry > &geometry)
This will be called every time a new State is about to be visualized.
Definition: ContactGeometry.h:1491
static bool isInstance(const ContactGeometry &geo)
Return true if the supplied ContactGeometry object is a cylinder.
Definition: ContactGeometry.h:850
PlaneDecorator(const Plane &plane, const Vec3 &color)
Definition: ContactGeometry.h:1488
static const TriangleMesh & getAs(const ContactGeometry &geo)
Cast the supplied ContactGeometry object to a const triangle mesh.
Definition: ContactGeometry.h:1261
Vec< 2 > Vec2
Definition: SmallMatrix.h:103
static const Sphere & getAs(const ContactGeometry &geo)
Cast the supplied ContactGeometry object to a const sphere.
Definition: ContactGeometry.h:884
ContactGeometryImpl & updImpl()
Internal use only.
Definition: ContactGeometry.h:800
This is the handle class for the hidden State implementation.
Definition: State.h:264
void calcGeodesicUsingOrthogonalMethod(const Vec3 &xP, const Vec3 &xQ, Geodesic &geod) const
This signature makes a guess at the initial direction and length and then calls the other signature...
Definition: ContactGeometry.h:688
static const Cylinder & getAs(const ContactGeometry &geo)
Cast the supplied ContactGeometry object to a const cylinder.
Definition: ContactGeometry.h:853
This class represents a node in the Oriented Bounding Box Tree for a TriangleMesh.
Definition: ContactGeometry.h:1284
Real calcGaussianCurvature(const Vec3 &point) const
This signature is for convenience; use the other one to save time if you already have the gradient an...
Definition: ContactGeometry.h:362
const Complex I
We only need one complex constant, i = sqrt(-1). For the rest just multiply the real constant by i...
Includes internal headers providing declarations for the basic SimTK Core classes, including Simmatrix.
A DecorationGenerator is used to define geometry that may change over the course of a simulation...
Definition: DecorationGenerator.h:45
static bool isInstance(const ContactGeometry &geo)
Return true if the supplied ContactGeometry object is a SmoothHeightMap.
Definition: ContactGeometry.h:1062
static Torus & updAs(ContactGeometry &geo)
Cast the supplied ContactGeometry object to a writable torus.
Definition: ContactGeometry.h:1333
This class generates decoration for a plane.
Definition: ContactGeometry.h:1486
This class stores options for calculating geodesics.
Definition: Geodesic.h:311
static Sphere & updAs(ContactGeometry &geo)
Cast the supplied ContactGeometry object to a writable sphere.
Definition: ContactGeometry.h:887
This ContactGeometry subclass represents an arbitrary shape described by a mesh of triangular faces...
Definition: ContactGeometry.h:1104
static const Ellipsoid & getAs(const ContactGeometry &geo)
Cast the supplied ContactGeometry object to a const Ellipsoid.
Definition: ContactGeometry.h:1016
static bool isInstance(const ContactGeometry &geo)
Return true if the supplied ContactGeometry object is a sphere.
Definition: ContactGeometry.h:881
static Cylinder & updAs(ContactGeometry &geo)
Cast the supplied ContactGeometry object to a writable cylinder.
Definition: ContactGeometry.h:856
A ContactGeometry object describes the shape of all or part of the boundary of a solid object...
Definition: ContactGeometry.h:110
const Plane & getPlane() const
Definition: ContactGeometry.h:1425
static const SmoothHeightMap & getAs(const ContactGeometry &geo)
Cast the supplied ContactGeometry object to a const SmoothHeightMap.
Definition: ContactGeometry.h:1065
Real getDistance(const Vec3 &pt) const
Definition: ContactGeometry.h:1361
This ContactGeometry subclass represents an object that occupies the entire half-space x>0...
Definition: ContactGeometry.h:813
static bool isInstance(const ContactGeometry &geo)
Return true if the supplied ContactGeometry object is a triangle mesh.
Definition: ContactGeometry.h:1258
This class provides a description of a mesh made of polygonal faces (not limited to triangles)...
Definition: PolygonalMesh.h:71
This is the header file that every Simmath compilation unit should include first. ...
This is the client-side interface to an implementation-independent representation of "Decorations" su...
Definition: DecorativeGeometry.h:86
This defines a sphere centered at the origin.
Definition: DecorativeGeometry.h:301
This Array_ helper class is the base class for ArrayView_ which is the base class for Array_; here we...
Definition: Array.h:48
This ContactGeometry subclass represents a sphere centered at the origin.
Definition: ContactGeometry.h:874
virtual void generateDecorations(const State &state, Array_< DecorativeGeometry > &geometry)
This will be called every time a new State is about to be visualized.
Definition: ContactGeometry.h:1451
TODO.
Definition: OBBTree.h:100
TriggeredEventHandler is a subclass of EventHandler for events that occur when some condition is sati...
Definition: EventHandler.h:109
Real getOffset() const
Definition: ContactGeometry.h:1369
static const Torus & getAs(const ContactGeometry &geo)
Cast the supplied ContactGeometry object to a const torus.
Definition: ContactGeometry.h:1330
Vec3 getNormal() const
Definition: ContactGeometry.h:1365
const Vector & getQ(SubsystemIndex) const
Per-subsystem access to the global shared variables.
This ContactGeometry subclass represents a cylinder centered at the origin, with radius r in the x-y ...
Definition: ContactGeometry.h:843
CNT< ScalarNormSq >::TSqrt norm() const
Definition: Vec.h:555
Vec< 3 > Vec3
Definition: SmallMatrix.h:104
bool hasImpl() const
Internal use only.
Definition: ContactGeometry.h:796
static TriangleMesh & updAs(ContactGeometry &geo)
Cast the supplied ContactGeometry object to a writable triangle mesh.
Definition: ContactGeometry.h:1264
void setPlane(const Plane &aplane) const
Definition: ContactGeometry.h:1421
static bool isInstance(const ContactGeometry &geo)
Return true if the supplied ContactGeometry object is a torus.
Definition: ContactGeometry.h:1327
ContactGeometry()
Base class default constructor creates an empty handle.
Definition: ContactGeometry.h:124
const ContactGeometryImpl & getImpl() const
Internal use only.
Definition: ContactGeometry.h:798
static const HalfSpace & getAs(const ContactGeometry &geo)
Cast the supplied ContactGeometry object to a const halfspace.
Definition: ContactGeometry.h:821
This class represents a small matrix whose size is known at compile time, containing elements of any ...
Definition: Mat.h:51
A line between two points.
Definition: DecorativeGeometry.h:254
Real getValue(const State &state) const
Get the value of the event trigger function for a State.
Definition: ContactGeometry.h:1394
void push_back(const T &value)
This method increases the size of the Array by one element at the end and initializes that element by...
Definition: Array.h:2329
This file defines the Geodesic class.
This ContactGeometry subclass represents an ellipsoid centered at the origin, with its principal axes...
Definition: ContactGeometry.h:924
A event handler to terminate integration when geodesic hits the plane.
Definition: ContactGeometry.h:1383
GeodHitPlaneEvent()
Definition: ContactGeometry.h:1385
#define SimTK_SIMMATH_EXPORT
Definition: SimTKmath/include/simmath/internal/common.h:64
Transform_< Real > Transform
Definition: Transform.h:44
Rotation_ & setRotationFromOneAxis(const UnitVec3P &uvec, const CoordinateAxis axis)
Calculate R_AB by knowing one of B's unit vector expressed in A.
ContactGeometryTypeId getTypeId() const
ContactTrackerSubsystem uses this id for fast identification of specific surface shapes.
const Vec3 Black
RGB=( 0, 0, 0)