iMSTK
Interactive Medical Simulation Toolkit
All Classes Namespaces Functions Variables Typedefs Enumerations Enumerator Friends Pages
Namespaces | Classes | Typedefs | Enumerations | Functions | Variables
imstk Namespace Reference

Compound Geometry. More...

Namespaces

 GeometryUtils
 Contains a set of free functions for processing geometry also contains a set of conversion and coupling functions for VTK.
 

Classes

class  AbstractCellMesh
 Provides non templated base for cell based meshes. More...
 
class  AbstractDataArray
 This class serves as the base class of DataArray, for typeless use. More...
 
class  AbstractDynamicalModel
 Abstract class for mathematical model of the physics governing the dynamic object. More...
 
class  AbstractVTKViewer
 Subclasses viewer for the VTK rendering back-end. More...
 
class  AnalyticalGeometry
 Base class for any analytical geometrical representation. More...
 
class  AnimationModel
 Contains geometric and animation render information. More...
 
class  AnimationObject
 TODO. More...
 
class  AppendMesh
 This filter appends two SurfaceMeshes, no topological connections are made. More...
 
class  ArcNeedle
 
class  AssertionFailure
 
class  AssertMessage
 
class  AssimpMeshIO
 Assimp reader for surface meshes. More...
 
class  AxesModel
 Defines an axes that should be rendered. More...
 
class  BackwardEuler
 Backward Euler time integration. More...
 
class  Behaviour
 A Behaviour represents a single component system A template is used here for UpdateInfo to keep the ComponentModel library more general and separable. UpdateInfo could be anything you need from outside to update the component, this would generally be your own struct or just a single primitive such as double timestep. More...
 
class  BidirectionalPlaneToSphereCD
 Plane to sphere collision detection Generates point-direction contact data. More...
 
class  BoneDrillingCH
 Implements bone drilling collision handling. More...
 
class  Burnable
 Defines the behaviour to allow a Pbd Object to be burned. This object creates the state data on the mesh to store both the damage state that controls when a cell gets deleted and state data for visualization. This is currently defined as [0,1] where 0 is no damage and value >= 1 deletes the cell. The visual data is purely for visualization, and can be used as the user desires. The model that changes the state is defined by the burning object. More...
 
class  Burner
 Defines the behaviour to allow a tool to burn a pbdObject. This is done by storing state on the mesh that defines the damage from burning and the visual change caused by cauterization. These are currently normalized from [0,1] where 1 is the maximum damage. Once the damage reaches 1, the cell is deleted on the next visual update. More...
 
class  ButtonEvent
 
class  CacheOutput
 
class  Camera
 Produces a perpsective transformation matrix. More...
 
class  CameraController
 Directly controls a camera given the device client pose, could be unsmooth depending on device. Rigid body should be preferred for smoothness. More...
 
class  Capsule
 Capsule geometry, default configuration is centered at origin with length running up and down the y axes. The length refers to the length of the cylinder. More...
 
class  CapsuleToCapsuleCD
 Capsule to Capsule collision detection. More...
 
class  CCDAlgorithm
 Base class for all Continuous Collision Detection (CCD) classes. A continuous collision detection algorithm typically requires geometries in two timesteps (previous, current) for continuous analysis between the two. CCDAlgorithm classes follow the same logic as CollisionDetectionAlgorithm. This base class for CCD algorithms enforces the implementation of a function (UpdatePreviousTimestepGeometry) to cache/store previous state of the colliding geometries. More...
 
class  CDObjectFactory
 Manages and generates the CollisionDetectionAlgorithms. More...
 
struct  CellIndexElement
 Represents a cell by a single cell id OR by N vertex ids. Which case can be determined by the idCount. More...
 
class  CellMesh
 Abstract template base class for all meshes that have homogenous cell types. This class allows templated access to cells. A cell in iMSTK could be a line, triangle, quad, tetrahedron, hexahedron, ... It is a group of vertices that form an element of a larger mesh. More...
 
class  CellPicker
 Picks cells of geomToPick via those that that are intersecting pickingGeom. More...
 
struct  CellVertexElement
 Represents a cell by its vertex values Possible cells may be: point, edge, triangle, quad, or tetrahedron Maximum 4 vertices (tetrahedron is maximum cell it could represent) More...
 
class  CleanMesh
 This filter can merge duplicate points and cells, it only works with LineMesh and SurfaceMesh. It accepts a tolerance as a fraction of the length of bounding box of the input data or an absolute tolerance. More...
 
class  ClosedSurfaceMeshToCapsuleCD
 Closed SurfaceMesh to Capsule collision detection Generates point-triangle. More...
 
class  ClosedSurfaceMeshToMeshCD
 Closed mesh to mesh collision with brute force strategy. It can handle closed SurfaceMesh vs PointSet, LineMesh, & SurfaceMesh. Note: This CD method cannot yet automatically determine the closed SurfaceMesh given two unordered inputs. Ensure the second input/B is the closed SurfaceMesh. More...
 
class  CollidingObject
 A SceneObject with a geometry for collision. More...
 
class  CollisionData
 Describes the contact manifold between two geometries. More...
 
class  CollisionDataDebugModel
 Class for visualizing CollisionData. Give it collision data and add it to the scene This class intentionally does not automatically update it provides debugUpdate which may be called by the user when appropriate (for debug purposes) More...
 
class  CollisionDetectionAlgorithm
 Base class for all collision detection classes. CollisionDetection classes produce CollisionData between two geometries A and B. CollisionData has two sides. That is, the contact information to resolve collision for geometry A and the contact info to resolve geometry B. More...
 
struct  CollisionElement
 Union of collision elements. We use a union to avoid polymorphism. There may be many elements and accessing them needs to be quick. Additionally the union keeps them more compact and allows one to keep them on the stack. More...
 
class  CollisionHandling
 Base class for all collision handling classes. More...
 
class  CollisionInteraction
 Abstract class for defining collision interactions between objects. More...
 
struct  Color
 Color in RGB space. More...
 
class  ColorFunction
 A regularly/structured table of colors to lookup by value. More...
 
class  Command
 Stores everything needed to invoke an event A call may not be present, in which case invoke doesn't do anything. More...
 
class  Component
 Represents a part of an entity, involved in a system. The component system is doubly linked meaning the Entity contains a shared_ptr to Component while the Component keeps a weak_ptr to Entity. Components are able to not exist on an entity as the entity parent is not garunteed to exist. The initialize call cannot be issue'd without a valid entity. More...
 
class  CompositeImplicitGeometry
 
class  CompoundCD
 Collision detection that supports a geometry consisting of multiple subgeometries. For the actual calcualation the information gets passed to the appropriate shape/subshape CD algorithm. Currently Does not support adding/removing a shape during runtime. More...
 
class  CompoundGeometry
 
class  ConjugateGradient
 Conjugate gradient sparse linear solver for Spd matrices. More...
 
class  ConnectiveStrandGenerator
 This filter takes in two surface meshes and generates a LineMesh that connectes the faces of the two meshes. Internally the strands are generated such that only faces with normals pointing in opposite direction are used. This cuts down on penetration. This is expected to be used to generate connective tissue with the ProximitySurfaceSelectoror any other method to select a subset of a surface mesh to connect. More...
 
class  ConsoleModule
 The console thread can run separately or in sync to provide keyboard events from the console they should be handled on another thread. More...
 
class  ControllerForceText
 Displays virtual coupling force text in the top right. More...
 
class  CorotationalFemForceModel
 Force model for corotational based finite elements formulation. More...
 
class  CpuTimer
 CPU timer. More...
 
struct  CutData
 
class  Cylinder
 Cylinder geometry, default configuration is at origin with length running up the y axes. More...
 
class  DataArray
 Simple dynamic array implementation that also supports event posting and viewing/facade. More...
 
class  DataTracker
 Store time based data to write to a file. More...
 
class  DebugGeometryModel
 Class for quickly rendering and showing various primivites such as line segments, triangles, arrows, points. More...
 
class  DeviceClient
 The device client's represents the device and provides an interface to acquire data from a device. It posts events the device may have as well as provides the state. More...
 
class  DeviceControl
 While the DeviceClient provides quantities from the device, the control defines what to do with those quantities. More...
 
class  DeviceManager
 Abstract class for DeviceManagers which must return a DeviceClient for which it manages. More...
 
class  DeviceManagerFactory
 Manages and generates the DeviceManager's. More...
 
class  DirectionalLight
 A directional light has no position or range. The focal point is the direction. More...
 
class  DirectLinearSolver
 Dense direct solvers. Solves a dense system of equations using Cholesky decomposition. More...
 
class  DirectLinearSolver< Matrixd >
 
class  DirectLinearSolver< SparseMatrixd >
 Sparse direct solvers. Solves a sparse system of equations using a sparse LU decomposition. More...
 
class  DummyClient
 Allows setting the pose of the device from external caller without a real device connected. More...
 
class  DynamicalModel
 Base class for mathematical model of the physics governing the dynamic object. More...
 
class  DynamicObject
 Base class for scene objects that move and/or deform. More...
 
class  EdgeEdgeCCDState
 
struct  EdgePair
 Hash together a pair of edges. More...
 
class  EmbeddingConstraint
 Constrains a rigid body line segment defined via p and q to a "puncture" point defined via barycentric coordinates on a triangle. More...
 
struct  EmptyElement
 
class  Entity
 Top-level class for entities. Entities contain a collection of components which define how to be used in a system. More...
 
class  Event
 Base class for events which contain a type, priority, and data priority defaults to 0 and uses a greater than comparator. Negatives are allowed. More...
 
class  EventObject
 EventObject is the base class for all objects in iMSTK that can receive and emit events. It supports direct and queued observer functions. Direct observers receive events immediately on the same thread This can either be posted on an object or be a function pointer Queued observers receive events within their queue which they can process whenever they like. These can be connected with the connect/queuedConnect/disconnect functions Lambda recievers cannot be disconnected unless all receivers to a signal are removed. More...
 
class  ExtractEdges
 This filter extracts the edges of a SurfaceMesh producing a LineMesh. More...
 
class  FastMarch
 
class  FeDeformableObject
 Scene objects that can deform. More...
 
class  FeDeformBodyState
 This class stores the state of the unknown field variable in vectorized form. More...
 
class  FemDeformableBodyModel
 Mathematical model of the physics governing the dynamic deformable object. More...
 
struct  FemModelConfig
 Parameters for finite element model. More...
 
class  FpsTxtCounter
 Displays visual and physics framerates through dependent TextVisualModel. More...
 
class  GaussSeidel
 Gauss-Seidel sparse linear solver. More...
 
class  Geometry
 Base class for any geometrical representation. More...
 
class  GeometryAlgorithm
 Abstract base class for geometry algorithms. GeometryAlgorithms take N input geometries and produce N output geometries. Subclasses should implement requestUpdate to do algorithm logic. Subclasses may also setInputPortReq to require an input to be a certain type. More...
 
class  GeometryMap
 Base class for any geometric map. More...
 
class  Graph
 class to represent a graph object More...
 
struct  GraspedData
 Info needed to add a constraint for the grasped object Garunteed to be a PbdObject. More...
 
struct  GrasperData
 GrasperData is either a ray, a grasping geometry, or another PbdObject (rigid) More...
 
class  GridBasedNeighborSearch
 Class for searching neighbors using regular grid. More...
 
class  HaplyDeviceClient
 Subclass of DeviceClient for haply, currently implemented only for the Inverse3. Warning: This code is based off an early version of the Haply Hardware API. More...
 
class  HaplyDeviceManager
 Devices manager using Haply, only supports Inverse3 right now Warning: This code is based off an early version of the Haply Hardware API. More...
 
class  HexahedralMesh
 Hexahedral mesh class. More...
 
class  IblProbe
 Image-based lighting probe. More...
 
class  ImageData
 Class to represent 1, 2, or 3D image data (i.e. structured points) More...
 
class  ImageDistanceTransform
 This filter generates a signed or unsigned distance transform from a binary mask. More...
 
class  ImageGradient
 This filter computes the gradient or magnitude using sobels kernel over an image. More...
 
class  ImageResample
 Trilinearly Resamples a 3d image to different dimensions. More...
 
class  ImageReslice
 Resamples an image using a transform. More...
 
struct  ImplicitFunctionBackwardGradient
 Gradient given by backward finite differences. More...
 
struct  ImplicitFunctionCentralGradient
 Gradient given by central finite differences. More...
 
struct  ImplicitFunctionForwardGradient
 Gradient given by forward finite differences. More...
 
struct  ImplicitFunctionGradient
 Base struct for gradient functors. More...
 
class  ImplicitGeometry
 Class that can represent the geometry of multiple implicit geometries as boolean functions One may supply it with multiple implicit geometries and the operation they would like. More...
 
class  ImplicitGeometryToImageData
 This filter rasterizes an implicit function to image of specified dimensions and bounds. More...
 
class  ImplicitGeometryToPointSetCCD
 ImplicitGeometry to PointSet continous collision detection. This CD method marches along the displacement of the points in the pointset to converge on the zero crossing of the implicit geometry. This particular version is suited for levelsets not SDFs as it caches the history of the contact to avoid sampling the implicit geometry anywhere but at the surface (it will also work for SDFs, though better alterations/modifications of this exist for SDFs) More...
 
class  ImplicitGeometryToPointSetCD
 ImplicitGeometry to PointSet collision detection. This generates PointDirection collision data via signed distance sampling and central finite differences. More...
 
struct  ImplicitStructuredCurvature
 Curvature given in structured coordinates. More...
 
class  imstkNew
 std::shared_ptr<T> obj = std::make_shared<T>(); equivalent, convenience class for STL shared allocations. Cannot be used in overloaded polymorphic calls More...
 
class  InternalForceModel
 Base class for internal force model within the following context. More...
 
class  IsometricMap
 A maps that lets the child follow the parent transform. More...
 
class  IsotropicHyperelasticFeForceModel
 Force model for the isotropic hyperelastic material. More...
 
class  IterativeLinearSolver
 Base class for iterative linear solvers. More...
 
class  Jacobi
 Jacobi sparse linear solver. More...
 
class  KeyboardControl
 
class  KeyboardDeviceClient
 This class provides the keyboard state it also posts events. More...
 
class  KeyboardSceneControl
 This implements keyboard controls to control a scene manager and viewer it may operate with both sceneManager and viewer, or only one or the other. warning: This control may pause a thread. Thus it is a bad idea to process it on the thread you're pausing, as you then could not resume. More...
 
class  KeyEvent
 Provides the information of a key event (press, release, & which key) More...
 
class  LambdaBehaviour
 A SceneBehaviour that can update via a lambda function. More...
 
class  LaparoscopicToolController
 Two-jawed laparoscopic tool controlled by external device The tool is composed of three scene objects: pivot, lower jaw and upper jaw The jaws open-close based on the buttons at present. This has to be replaced by potentiometer tracking in future. More...
 
class  LevelSetCH
 Applies impulses to the leveset given point direction collision data propotional to the force on the rigid object. More...
 
class  LevelSetDeformableObject
 Base class for scene objects that move and/or deform under position based dynamics formulation, implements the PbdModel and PbdSolver. More...
 
class  LevelSetModel
 This class implements a generic level set model, it requires both a forward and backward finite differencing method. More...
 
struct  LevelSetModelConfig
 
class  Light
 Abstract base class for lights. More...
 
class  LinearFemForceModel
 Force model for linear finite element formulation. More...
 
class  LinearProjectionConstraint
 Linear projection constraint. More...
 
class  LinearSolver
 Base class for linear solvers. More...
 
class  LinearSystem
 Represents the linear system of the form $ Ax = b $. More...
 
class  LineMesh
 Base class for all volume mesh types. More...
 
class  LineMeshCut
 This filter cuts the lines of a LineMesh into smaller lines using input cutting geometry Only supports convex shaped cutting, ie: An edge can't be split twice. More...
 
class  LineMeshToCapsuleCD
 LineMesh to Capsule collision detection Generates point-edge and point-point CD data By default only generates contact data for the pointset. More...
 
class  LineMeshToLineMeshCCD
 LineMesh to LineMesh continous collision detection. This CCD method can process self collision as well. Self collision mode is indicated to the algorithm by providing geometryA (input 0) == geometryB (input 1). More...
 
class  LineMeshToSphereCD
 LineMesh to Sphere collision detection Generates point-edge and point-point CD data By default only generates contact data for the pointset. More...
 
class  LocalMarchingCubes
 This filter extracts a contour SurfaceMesh from an image given an isovalue. Users should prefer imstkFlyingEdges over this unless sparse/local processing is needed. More...
 
class  LoggerG3
 
class  LoggerSynchronous
 
class  LogMessageBase
 
class  LogOutput
 
class  LooseOctree
 Class LooseOctree, where each tree node has a loose boundary which is exactly twice big as its exact, tight boundary During tree update, a primitive is moved around from node to node If removed from a node, the primitive is moving up to find the lowest node that tightly contains it, then it is inserted again from top-down, to a lowest level possible, stopping at a node that loosely contains it Pointer variables in tree and tree node are all raw pointers, not smart pointers, for fast operations. More...
 
class  MeshCut
 Base abstract class for discrete cut algorithms. More...
 
class  MeshIO
 Mesh data IO. More...
 
struct  MeshSide
 Packs the info needed to add a constraint to a side by reference (this way dynamic casting & dereferencing is not being done in tight loops) More...
 
class  Module
 Base class for imstk module system. A module defines something that is updated, and can be paused/resumed. It cannot start or stop Update loops are defined externally by a driver so they may be replaced. More...
 
class  ModuleDriver
 Defines the control of modules. More...
 
class  MouseControl
 This is the base class for mouse based controls It can be constructed and observed or subclassed and overridden to implement controls. More...
 
class  MouseDeviceClient
 
class  MouseEvent
 Provides the information of a mouse event, this includes button presses/releases and scrolling. More...
 
class  MouseSceneControl
 Controls the camera using trackball controls Left click rotate, middle click pan. More...
 
class  MshMeshIO
 Can read/return LineMesh, SurfaceMesh, TetrahedralMesh, or HexahedralMesh from given .msh file. Can only read homogenous elements. More...
 
class  Needle
 Base for all needles in imstk it supports global puncture state, per object puncture state, and per id/cell puncture state. More...
 
class  NeedleInteraction
 Defines interaction between NeedleObject and PbdObject. More...
 
class  NeedlePbdCH
 Handles penetration constraints for the needle and the thread by creating a set of puncture points that are used to find the nearest segment on either the needle or the thread and constraining the tissue to the needle, or the thread to the tissue. This class assumes the mesh is not cut or otherwise modified during runtime. WARNING: This class currently assumes a tetrahedral mesh for the physics mesh of the punctureable pbdObject and a triangle mesh for the collision geometry of that object. More...
 
struct  NeighborInfo
 The helper struct to store relative positions and densities of neighbor particlcles. More...
 
class  NeighborSearch
 A wrapper class for Grid-based and spatial-hashing neighbor search. More...
 
class  NewmarkBeta
 Newmark-beta time integration. More...
 
class  NewtonSolver
 Newton method. This version of the newton method is based on the work by Tim Kelly and others at NC State University. The algorithm is globally convergent in the sense that for any initial iterate the iteration either converge to a root of F or fails. Global convergence is achieved using a line search sub-process and the Armijo rule. More...
 
class  NonLinearSolver
 Base class for non-linear solvers. More...
 
class  NonLinearSystem
 Base class for a multi-variable nonlinear system. More...
 
struct  NormalGroup
 Helper class for indentifying duplicate points. More...
 
class  NullOutput
 
class  ObjectControllerGhost
 A behaviour that renders a second copy of the controlled object at a lower opacity in the physical position as opposed to the original rendered at the virtual. More...
 
class  ObjectFactory
 Generic Factory class that can take objects with constructor parameters. More...
 
class  ObjectIO
 ObjectIO provides SceneObject reading capabilities It is used to read complex visual objects or animated objects. More...
 
class  OctreeDebugModel
 OctreeDebugModel for debug visualizing an octree. More...
 
class  OctreeNode
 The OctreeNode class. More...
 
struct  OctreeNodeBlock
 The OctreeNodeBlock struct This is a data structure to store a memory block of 8 tree node at a time Using a block of 8 nodes at a time can reduce node allocation/merging/slitting overhead. More...
 
struct  OctreePrimitive
 The OctreePrimitive struct For each octree primitive (point/triangle/analytical geometry), store its relevant data. More...
 
class  OpenHapticDeviceClient
 Subclass of DeviceClient for phantom omni Holds and updates the data sync or on its own thread Holder of data. More...
 
class  OpenHapticDeviceManager
 Devices manager using HDAPI. More...
 
class  OpenVRDeviceClient
 This class provides quantities for the specified VR device The devices creation is tied to the viewer. It is only acquirable from a VR viewer and exists on the viewers thread. More...
 
class  OrientedBox
 OrientedBox geometry, specified with extents (half lengths) More...
 
class  PbdAngularConstraint
 Applies rotational correction only. More...
 
class  PbdAngularDistanceConstraint
 Constraints one orientation to be relative by a given angular distance/offset to another orientation. More...
 
class  PbdAngularHingeConstraint
 Constraint a single oriented particle along an axes of rotation Aligns oriented particles up axes to hinge axes. More...
 
class  PbdAreaConstraint
 Area constraint for triangular face. More...
 
struct  PbdAreaConstraintFunctor
 PbdAreaConstraintFunctor generates constraints per cell of a SurfaceMesh. More...
 
class  PbdBaryPointToPointConstraint
 Constrains two points from two separate cells/elements given via barycentric coordinates to be coincident. More...
 
class  PbdBendConstraint
 Bend constraint between two segments. Maintains angle between the two segments in the initial configuration given. More...
 
struct  PbdBendConstraintFunctor
 PbdBendConstraintFunctor generates constraints per cell of a LineMesh. More...
 
struct  PbdBody
 Represents a pbd body in the model. This is a data only object. It does no function. PbdBody can be of different types. The types effect what properties it has. More...
 
class  PbdBodyConstraintFunctor
 Abstract PbdConstraintFunctor that assumes usage of a singular body & geometry. More...
 
class  PbdBodyToBodyDistanceConstraint
 Constrain two locally defined points on each body by a given distance. More...
 
class  PbdBodyToBodyNormalConstraint
 
struct  PbdCHTableKey
 Used as a key in a function table to decide how to handle resulting collision. More...
 
class  PbdCollisionConstraint
 The PbdCollisionConstraint implements two sided collision. This allows the usage of differing stiffness for each side which can be useful during solve. Due to differences in definition, collisions do not use XPBD. Only PBD. They are assumed perfectly rigid even though stiffness is modifiable. Given enough iterations in the solve, it will converge to perfectly rigid. More...
 
class  PbdCollisionHandling
 Implements PBD based collision handling. Given an input PbdObject and CollisionData it creates & adds constraints in the PbdModel to be solved in order to resolve the collision. More...
 
class  PbdConnectiveTissueConstraintGenerator
 
class  PbdConstantDensityConstraint
 Implements the constant density constraint to simulate fluids. This constraint is global and applied to all vertices passed in during projection. More...
 
struct  PbdConstantDensityConstraintFunctor
 PbdConstantDensityConstraintFunctor generates a global constant density constraint for an entire PointSet. More...
 
class  PbdConstraint
 Base Constraint class for Position based dynamics constraints. More...
 
class  PbdConstraintContainer
 Container for pbd constraints. More...
 
struct  PbdConstraintFunctor
 PbdConstraintFunctor take input geometry and produce constraints. It exists to allow extensible constraint generation. Any number of constraints could be generated by a functor for a single geometry with any number of parameters. More...
 
class  PbdConstraintFunctorLambda
 PbdConstraintFunctor that can be forwarded out to a function pointer. More...
 
class  PbdContactConstraint
 A constraint on a rigid body that defines rotationl correction through dx applied at a local position r on the body. More...
 
class  PbdDihedralConstraint
 Angular constraint between two triangular faces. More...
 
struct  PbdDihedralConstraintFunctor
 PbdDihedralConstraintFunctor generates constraints per pair of triangle neighbors in a SurfaceMesh. More...
 
class  PbdDistanceConstraint
 Distance constraints between two nodal points. More...
 
struct  PbdDistanceConstraintFunctor
 PbdDistanceConstraintFunctor generates constraints between the edges of the input TetrahedralMesh, SurfaceMesh, or LineMesh. More...
 
class  PbdEdgeEdgeCCDConstraint
 Pushes an edge "outside" the other edge. More...
 
class  PbdEdgeEdgeConstraint
 Resolves an edge given by two pbd particles to coincide with another edge. More...
 
class  PbdEdgeToBodyConstraint
 Resolves a point on body to an edge with linear and angular movement. More...
 
class  PbdFemConstraint
 The PbdFemConstraint class for constraint as the elastic energy computed by linear shape functions with tetrahedral mesh. We provide several model for elastic energy including: Linear, Co-rotation, St Venant-Kirchhof and NeoHookean. More...
 
struct  PbdFemConstraintConfig
 Either mu/lambda used, may be computed from youngs modulus and poissons ratio. More...
 
class  PbdFemTetConstraint
 The FEMTetConstraint class class for constraint as the elastic energy computed by linear shape functions with tetrahedral mesh. More...
 
struct  PbdFemTetConstraintFunctor
 PbdFemTetConstraintFunctor generates constraints per cell of a TetrahedralMesh. More...
 
class  PbdInflatableDistanceConstraint
 
struct  PbdInflatableDistanceConstraintFunctor
 
class  PbdInflatableVolumeConstraint
 
struct  PbdInflatableVolumeConstraintFunctor
 
class  PbdModel
 This class implements the position based dynamics model. The PbdModel is a constraint based model that iteratively solves constraints to simulate the dynamics of a body. PbdModel supports SurfaceMesh, LineMesh, or TetrahedralMesh. PointSet is also supported for PBD fluids. More...
 
class  PbdModelConfig
 Gives parameters for PBD simulation. More...
 
class  PbdObject
 Base class for scene objects that move and/or deform under position based dynamics formulation, implements the PbdModel and PbdSolver. More...
 
class  PbdObjectCellRemoval
 This class defines a method of removing cells and their associated constraints from a Pbd object. Can update the visual and collision representation when using a tetrahedral mesh as physics object Does not support updating visual and collision representation when the physics mesh is a LineMesh or a SurfaceMesh AND they differ. Note: The two modes for visual meshes exist to support generating new texture coordinates, when reusing a vertex from a visual mesh the vertex should already have uv coordinates assigned to it. Assigning new ones may break the current look of the object as the vertex may still be in use. With the VisualSeparateVertices mode, new vertices will be generated for newly exposed surface. This allows the user to assign new uv coordinates to those new points. More...
 
class  PbdObjectCollision
 This class defines a collision interaction between two PbdObjects or PbdObject & CollidingObject. More...
 
class  PbdObjectController
 This class uses the provided device to control the provided rigid object via virtual coupling. That is, it applies forces+torques to the rigid body that will help move it to desired position/orientation. It has linear and angular spring scales as well as damping You may also use force smoothening for the force applied back on the device. More...
 
class  PbdObjectCutting
 This class defines a cutting interaction between a PbdObject and a CollidingObject. PbdObjectCutting::apply can be used to perform a discrete cut given the current states of both objects. More...
 
class  PbdObjectGrasping
 This class defines grasping of a PbdObject via different picking methods. Where grasping is define as grabbing & attaching of a PbdObject's mesh to points. More...
 
class  PbdObjectStitching
 This class defines stitching of a PbdObject via different picking methods. Ray based stitching is default. More...
 
class  PbdPointEdgeConstraint
 
class  PbdPointPointConstraint
 This constraint resolves two vertices to each other. More...
 
class  PbdPointTriangleConstraint
 The PbdPointTriangleConstraint moves a point to a triangle, and the triangle to the point. More...
 
class  PbdRigidBaryPointToPointConstraint
 
class  PbdRigidLineToPointConstraint
 This class constrains a rigid line to a fixed point. More...
 
class  PbdRigidObjectCollision
 This class defines a collision interaction between a first order PbdObject and second order RigidObject2. This will induce response in both models. More...
 
class  PbdRigidObjectGrasping
 
class  PbdSolver
 Position Based Dynamics solver This solver can solve both partitioned constraints (unordered_set of vector'd constraints) in parallel and sequentially on vector'd constraints. It requires a set of constraints, positions, and invMasses. More...
 
class  PbdState
 Provides interface for accessing particles from a 2d array of PbdBody,Particles. More...
 
class  PbdTriangleToBodyConstraint
 Resolves a point on body to a triangle with linear and angular movement. More...
 
class  PbdVertexToBodyConstraint
 
class  PbdVolumeConstraint
 Volume constraint for tetrahedral element. More...
 
struct  PbdVolumeConstraintFunctor
 PbdVolumeConstraintFunctor generates constraints per cell of a TetrahedralMesh. More...
 
class  PenaltyCH
 Implements penalty collision handling between Fem and Rigid models. More...
 
class  PerformanceGraph
 Displays task graph node durations of a scene as overlay on the screen. More...
 
struct  PickData
 PickData provides ids to indicate what was picked These may be optionally used to indicate the selection. More...
 
class  PickingAlgorithm
 Abstract functor for picking/selecting of geometry. Differs from collision in that the picking criteria can follow different logic (ray, nearest, various exclusion criteria, etc). Some pickers utilize CollisionDetectionAlgorithms for intersection tests. More...
 
class  Plane
 Represents and infinite plane, width can be used for visual purposes. More...
 
struct  PointDirectionElement
 Direclty gives a point-direction contact as its collision data. More...
 
struct  PointEntry
 
struct  PointIndexDirectionElement
 Direclty gives a point-direction contact as its collision data, point given by index. More...
 
class  PointLight
 A point light has a position, and it's range is determined by it's intensity. More...
 
class  PointPicker
 Picks points on elements of geomToPick via those that that are intersecting the provided ray. More...
 
class  PointSet
 Base class for all geometries represented by discrete points and elements The pointsets follow a pipeline: More...
 
struct  PointSetData
 
class  PointSetToCapsuleCD
 PointSet to Capsule collision detection. Generates point-direction contact data. By default only generates contact data for the pointset. More...
 
class  PointSetToCylinderCD
 PointSet to Cylinder collision detection. Generates point-direction contact data. By default only generates contact data for the pointset. More...
 
class  PointSetToOrientedBoxCD
 PointSet to OrientedBox collision detection. Generates point-direction contact data. By default only generates contact data for the pointset. More...
 
class  PointSetToPlaneCD
 PointSet to unidirectional plane collision detection Generates point-direction contact data. By default only generates contact data for the pointset. More...
 
class  PointSetToSphereCD
 PointSet to sphere collision detection Generates point-direction contact data. By default only generates contact data for the pointset. More...
 
class  PointToTetMap
 Computes and applies the PointSet-Tetrahedra map. Vertices of the child geometry are deformed according to the deformation of the tetrahedron they are located in. If they are not within one, nearest tet is used. More...
 
class  PointwiseMap
 PointwiseMap can compute & apply a mapping between parent and child PointSet geometries. More...
 
class  PortHoleInteraction
 Defines the behaviour to constrain a PbdObject LineMesh or Capsule to a fixed port hole location. More...
 
class  ProgrammableClient
 Allows setting the pose of the device from external caller without a real device connected. More...
 
class  ProjectedGaussSeidelSolver
 Solves a linear system using the projected gauss seidel method. Only good for diagonally dominant systems, must have elements on diagonals though. The initial guess (start) is always zero, convergence value may be specified with epsilon, relaxation decreases the step size (useful when may rows exist in A) More...
 
class  ProximitySurfaceSelector
 This filter takes in two surface meshes and generates two surface meshes that are subsets of the two input meshes. The new surface meshes are made of faces of the two meshes that fall within a distance (m_proximity) of each other. More...
 
class  Puncturable
 Place this on an object to make it puncturable by a needle. This allows puncturables to know they've been punctured without needing to be aware of the needle. The Puncturable supports multiple local ids. More...
 
struct  Puncture
 The puncture itself is composed of a state and extra non-essential user data. More...
 
struct  PunctureIdEq
 The entity and tissue id should be reversible. More...
 
struct  PunctureIdHash
 The entity and tissue id should be reversible. More...
 
class  QuadricDecimate
 
class  RbdConstraint
 Abstract class for rigid body constraints. A RbdConstraint should mainly provide a constraint jacobian. It provides a constraint gradient for both linear and angular (each column). This gradient should vanish as the constraint scalar approaches 0. More...
 
class  RbdContactConstraint
 A hard rigid body constraint to prevent intersection. More...
 
class  RbdDistanceConstraint
 A rigid body constraint to keep objects at a specified distance from each other given two local points on the bodies. More...
 
class  RbdFrictionConstraint
 A rigid body constraint to apply friction. More...
 
class  ReducedFeDeformableObject
 
class  ReducedStVK
 
struct  ReducedStVKConfig
 
class  RenderDelegateObjectFactory
 Manages and generates the VTKRenderdelegates for all VisualModels. More...
 
class  Renderer
 Rendering window manager and contains user API to configure the rendering with various backends. More...
 
struct  RendererConfig
 
class  RenderMaterial
 Serves no function, just a database for render properties, emits events for others to observe its changes. More...
 
struct  RenderParticle
 Particle data. More...
 
class  RenderParticleEmitter
 Animation method for rendering particles Common use cases include smoke and fire. More...
 
struct  RenderParticleKeyFrame
 Keyframe for particle animation. More...
 
class  RenderParticles
 Particles for rendering. More...
 
struct  RigidBody
 Serves as a handle to the body. More...
 
class  RigidBodyCH
 Creates rigid body contact and frictional constraints given collision data then adds them to the rigid body model, if rigid objects use differing models, one-way contacts are added to both. If only one rigid object is given, one-ways are used. More...
 
class  RigidBodyModel2
 This class implements a constraint based rigid body linear system with pgs solver. More...
 
struct  RigidBodyModel2Config
 
class  RigidBodyState2
 Kinematic state of rigid bodies within a system. More...
 
class  RigidObject2
 Scene objects that are governed by rigid body dynamics under the RigidBodyModel2. More...
 
class  RigidObjectCollision
 
class  RigidObjectController
 This class uses the provided device to control the provided rigid object via virtual coupling. That is, it applies forces+torques to the rigid body that will help move it to desired position/orientation. It has linear and angular spring scales has well as dampening You may also use force smoothening for the force applied back on the device. More...
 
class  RigidObjectLevelSetCollision
 This class defines a collision interaction pipeline between a RigidObject and LevelSetDeformableObject. More...
 
class  Scene
 A collection of SceneObjects and interactions. More...
 
struct  SceneConfig
 
class  SceneControlText
 This implements a text on screen that will notify the user of the current state of the simulation. ie: If paused or not. It can be toggled on and off. More...
 
class  SceneManager
 Scene manager module manages multiple scenes and runs the active one. More...
 
class  SceneObject
 Base class for all scene objects. A scene object can optionally be visible and collide with other scene objects. A object of the class is static. More...
 
class  SceneObjectController
 This class implements once tracking controller controlling one scene object. More...
 
class  ScreenCaptureUtility
 Utility class to manage screen capture. More...
 
class  SelectEnclosedPoints
 
class  SequentialTaskGraphController
 This class executes a TaskGraph by first topologically sorting them (Kahn's algorithm) then sequentially running them. More...
 
class  SharedObjectRegistrar
 Templated class that can add to the object factory with objects that will be generated via std::make_shared More...
 
class  SignedDistanceField
 Structured field of signed distances implemented with ImageData The SDF differs in that when you scale an image via its spacing the distance samples are then wrong. Here you can isotropically scale as you wish. More...
 
class  SimulationManager
 Defines a sequential substepping approach to driving the modules and rendering. The user provides a desired timestep and as it runs it accumulates time. It then determines how many simulation steps before every render (simply accumulated time / timestep = substeps). The remainder is divided out over the substeps. This is the preferred driver. todo: Timestep smoothening. More...
 
class  SolverBase
 Base class for solvers. More...
 
class  SOR
 Successive Over Relaxation (SOR) sparse linear solver. More...
 
class  SpatialHashTable
 Abstract class for spatial hash tables. More...
 
class  SpatialHashTableSeparateChaining
 Implementation of SpatialHashTable using separate chaining. More...
 
class  SphBoundaryConditions
 
class  SphCollisionHandling
 The SphCollisionHandling consumes PointIndexDirection contact data to resolve positions and correct velocities of SPH particles. It does not correct pressures/densities. More...
 
class  Sphere
 Represents a sphere via its position & radius. More...
 
class  SphereToCapsuleCD
 Sphere to Capsule collision detection. More...
 
class  SphereToCylinderCD
 Sphere-Cylinder collision detection Generates point-direction contact data. By default generates contact data for both sides. More...
 
class  SphereToSphereCD
 Sphere to sphere collision detection Generates point-direction contact data. By default generates contact data for both sides. More...
 
class  SphModel
 
class  SphModelConfig
 Class that holds the SPH model parameters. More...
 
class  SphObject
 Base class for scene objects that move and/or deform under smooth particle hydrodynamics. More...
 
class  SphObjectCollision
 This class defines where collision should happen between SphObject and CollidingObject pipelines. More...
 
class  SphSimulationKernels
 Class contains SPH kernels for time integration, using different kernel for different purposes. More...
 
class  SphState
 Simulation states of SPH particles. More...
 
class  SpotLight
 
struct  SSAOConfig
 
struct  stdSink
 A standard sink that prints the message to a standard output. More...
 
class  StopWatch
 Stop Watch utility class. More...
 
class  StraightNeedle
 Definition of straight, single segment needle. More...
 
class  StreamOutput
 
struct  StructuredBackwardGradient
 Gradient given by backward finite differences. More...
 
struct  StructuredCentralGradient
 Gradient given by central finite differences. More...
 
struct  StructuredForwardGradient
 Gradient given by forward finite differences. More...
 
class  StvkForceModel
 
class  SurfaceMesh
 Represents a set of triangles & vertices via an array of Vec3d double vertices & Vec3i integer indices. More...
 
class  SurfaceMeshCut
 This filter cuts the triangles of a SurfaceMesh into smaller triangles using input cutting geometry. More...
 
class  SurfaceMeshDistanceTransform
 This filter computes exact signed distance fields using octrees and pseudonormal computations. One might need to adjust the tolerance depending on dataset scale. The bounds for the image can be set in the filter, when none are set the bounding box of the mesh is used, the margin. When providing your own bounds a box larger than the original object might be necessary depending on shape. More...
 
class  SurfaceMeshFlyingEdges
 This filter extracts a single isocontour from an imstkImageData. More...
 
class  SurfaceMeshImageMask
 
class  SurfaceMeshSmoothen
 This filter smoothes the input SurfaceMesh currently only laplacian smoothing is provided. More...
 
class  SurfaceMeshSubdivide
 
class  SurfaceMeshTextureProject
 This filter projects vertex texture attributes from one SurfaceMesh to another by finding the closest point on the source mesh and interpolating the results. This could later be expanded to arbitrary vertex attributes. More...
 
class  SurfaceMeshToCapsuleCD
 SurfaceMesh to Capsule collision detection Generates vertex-triangle, point-edge, and point-point CD data. More...
 
class  SurfaceMeshToSphereCD
 SurfaceMesh to Sphere collision detection Generates vertex-triangle, point-edge, and point-point CD data By default only generates contact data for the pointset. More...
 
class  SurfaceMeshToSurfaceMeshCD
 Collision detection for surface meshes. More...
 
struct  SurfMeshData
 
class  TaskGraph
 Base class for TaskGraph, a collection of TaskNode's. Maintains nodes, adjacencyList, and invAdjacencyList. More...
 
class  TaskGraphController
 Base class for TaskGraph controllers which are responsible for executing the TaskGraph. More...
 
class  TaskGraphVizWriter
 Writes a TaskGraph to an svg file. Produces unique node names from duplicates with postfix. Can also color by node compute time and highlight the critical path. More...
 
class  TaskNode
 Base class for TaskGraph nodes. More...
 
class  TbbTaskGraphController
 This class runs an input TaskGraph in parallel using tbb tasks. More...
 
class  Tearable
 Defines the behaviour to allow a mesh to seperate based on strain in a given cell. This class approximates strain using the constraint value in from the PBD solver. This is well defined for line meshes, but the behavior may not be what is expected for surface or tet meshes. More...
 
class  TetrahedralMesh
 Represents a set of tetrahedrons & vertices via an array of Vec3d double vertices & Vec4i integer indices. More...
 
class  TetraToLineMeshCD
 Computes intersection points along a line mesh on the faces of the tetrahedrons. More...
 
class  TetraToPointSetCD
 Computes if points lie in tetrahedrons using spatial hashing Generates tetra-point contact data. By default only generates contact data for both sides. More...
 
class  Texture
 A texture can be defined by file reference or ImageData input. More...
 
class  TextureDelegate
 iMSTK texture delegate abstract class More...
 
class  TextureManager
 The TextureManager provides delegates for textures, it will create new ones and cache old ones. More...
 
class  TextVisualModel
 Renders text to the screen. More...
 
class  TimeIntegrator
 This class defines the time integrators of various types. It only sets the rules of how the velocity (or equivalent) and acceleration (or equivalent) of the present time in terms of positions (or equivalent) from previous time steps. More...
 
class  TrackingDeviceControl
 Base class for all DeviceControls that track something in space (position and orientation) More...
 
class  TriangleToTetMap
 SurfaceToTetrahedralMap serves as a PointwiseMap but also maps tets to triangle faces. More...
 
struct  TriCell
 Utility for triangle comparison. More...
 
class  UnidirectionalPlaneToCapsuleCD
 Plane to capsule collision detection Generates point-direction contact data. By default only generates contact data for the sphere. More...
 
class  UnidirectionalPlaneToSphereCD
 Plane to sphere collision detection Generates point-direction contact data. By default only generates contact data for the sphere. More...
 
class  UniformSpatialGrid
 Class for handling data in 3D grid. More...
 
class  UPSCounter
 Utility class to count updates per second. More...
 
class  VecDataArray
 Simple dynamic array implementation that also supports event posting and viewing/facade. More...
 
class  VegaMeshIO
 Contains utility classes that convert vega volume mesh to volume mesh and vice-versa. More...
 
class  VertexLabelVisualModel
 Given a PointSet geometry it will render labels for each vertex with numberings. More...
 
class  VertexPicker
 Picks vertices of geomToPick via those that that are intersecting pickingGeom. More...
 
class  Viewer
 Base class for viewer that manages render window and the renderers Creates backend-specific renderers on a per-scene basis. Contains user API to configure the rendering with various backends. More...
 
struct  ViewerConfig
 
class  VisualModel
 Contains geometric, material, and render information. More...
 
class  VolumeRenderMaterial
 
class  VolumeRenderMaterialPresets
 TODO. More...
 
class  VolumetricMesh
 Base class for all volume mesh types. More...
 
class  VRPNDeviceClient
 This class is the receiver of the updates sent by the vrpn_server. More...
 
class  VRPNDeviceManager
 connects to the vrpn.exe server and lets iMSTK attach devices to the server More...
 
class  VTKAxesRenderDelegate
 Delegates rendering of Axes to VTK from VisualModel. More...
 
class  VTKCapsuleRenderDelegate
 Delegates rendering of capsules to VTK from VisualModel. More...
 
class  VTKCylinderRenderDelegate
 Delegates rendering of Cylinders to VTK from VisualModel. More...
 
class  VTKFluidRenderDelegate
 Delegates rendering of Fluid to VTK from VisualModel. More...
 
class  VTKHexahedralMeshRenderDelegate
 Delegates rendering of HexahedralMesh to VTK from VisualModel. More...
 
class  VTKImageDataRenderDelegate
 Delegates rendering of ImageData to VTK (via volume rendering) from VisualModel. More...
 
class  VTKInteractorStyle
 Interactor styles forward their controls to imstk objects. More...
 
class  VTKLineMeshRenderDelegate
 Delegates rendering of LineMesh to VTK from VisualModel. More...
 
class  VTKMeshIO
 Implements VTK read and write functions. More...
 
class  VTKOpenVRViewer
 
class  VTKOrientedCubeRenderDelegate
 Delegates rendering of OrientedBox to VTK from VisualModel. More...
 
class  VTKPlaneRenderDelegate
 Delegates rendering of Plane to VTK from VisualModel. More...
 
class  VTKPointSetRenderDelegate
 Delegates rendering of PointSet to VTK from VisualModel. More...
 
class  VTKPolyDataRenderDelegate
 Abstract base class for PolyData-based RenderDelegates. More...
 
class  VTKRenderDelegate
 Base class for VTK render delegates. More...
 
class  VTKRenderer
 Wraps a vtkRenderer. More...
 
class  VTKScreenCaptureUtility
 Utility class to manage screen capture through VTK. More...
 
class  VTKSphereRenderDelegate
 Delegates rendering of Sphere to VTK from VisualModel. More...
 
class  VTKSurfaceMeshRenderDelegate
 Delegates rendering of SurfaceMesh to VTK from VisualModel. More...
 
class  VTKSurfaceNormalRenderDelegate
 Delegates rendering of SurfaceMesh to VTK as normals per triangle center from VisualModel. More...
 
class  VTKTetrahedralMeshRenderDelegate
 Delegates rendering of TetrahedralMesh to VTK from VisualModel. More...
 
class  VTKTextRenderDelegate
 Delegates rendering of text to VTK from TextVisualModel. More...
 
class  VTKTextureDelegate
 couples a imstk texture to a VTK texture More...
 
class  VTKVertexLabelRenderDelegate
 Delegates rendering of text per PointSet vertex to VTK from VisualModel. More...
 
class  VTKViewer
 Subclasses viewer for the VTK rendering back-end Creates vtk renderer for each scene. Forwards mouse and keyboard events to the vtk renderwindow. More...
 
class  VTKVolumeRenderDelegate
 Abstract base class for volume-based RenderDelegates. More...
 

Typedefs

template<typename T >
using CDObjectRegistrar = SharedObjectRegistrar< CollisionDetectionAlgorithm, T >
 Auto registration class. More...
 
using Logger = LoggerG3
 
using FileSinkHandle = g3::SinkHandle< g3::FileSink >
 
using StdoutSinkHandle = g3::SinkHandle< stdSink >
 
using Vec2f = Eigen::Matrix< float, 2, 1 >
 
using Vec2d = Eigen::Matrix< double, 2, 1 >
 
using Vec2i = Eigen::Matrix< int, 2, 1 >
 
using StdVectorOfVec2f = std::vector< Vec2f, Eigen::aligned_allocator< Vec2f > >
 
using StdVectorOfVec2d = std::vector< Vec2d, Eigen::aligned_allocator< Vec2d > >
 
using Vec3f = Eigen::Matrix< float, 3, 1 >
 
using Vec3d = Eigen::Matrix< double, 3, 1 >
 
using Vec3i = Eigen::Matrix< int, 3, 1 >
 
using StdVectorOfVec3f = std::vector< Vec3f, Eigen::aligned_allocator< Vec3f > >
 
using StdVectorOfVec3d = std::vector< Vec3d, Eigen::aligned_allocator< Vec3d > >
 
using Vec4f = Eigen::Matrix< float, 4, 1 >
 
using Vec4d = Eigen::Matrix< double, 4, 1 >
 
using Vec4i = Eigen::Matrix< int, 4, 1 >
 
using StdVectorOfVec4f = std::vector< Vec4f, Eigen::aligned_allocator< Vec4f > >
 
using StdVectorOfVec4d = std::vector< Vec4d, Eigen::aligned_allocator< Vec4d > >
 
using Vec6f = Eigen::Matrix< float, 6, 1 >
 
using Vec6d = Eigen::Matrix< double, 6, 1 >
 
using Vec6i = Eigen::Matrix< int, 6, 1 >
 
using Vec8i = Eigen::Matrix< int, 8, 1 >
 
using Vectorf = Eigen::VectorXf
 
using Vectord = Eigen::VectorXd
 
using StdVectorOfVectorf = std::vector< Vectorf, Eigen::aligned_allocator< Vectorf > >
 
using StdVectorOfVectord = std::vector< Vectord, Eigen::aligned_allocator< Vectord > >
 
using Quatf = Eigen::Quaternion< float >
 
using Quatd = Eigen::Quaternion< double >
 
using StdVectorOfQuatf = std::vector< Quatf, Eigen::aligned_allocator< Quatf > >
 
using StdVectorOfQuatd = std::vector< Quatd, Eigen::aligned_allocator< Quatd > >
 
using Rotf = Eigen::AngleAxisf
 
using Rotd = Eigen::AngleAxisd
 
using Mat3f = Eigen::Matrix< float, 3, 3 >
 
using Mat3d = Eigen::Matrix< double, 3, 3 >
 
using StdVectorOfMat3d = std::vector< Mat3d, Eigen::aligned_allocator< Mat3d > >
 
using Mat4f = Eigen::Matrix< float, 4, 4 >
 
using Mat4d = Eigen::Matrix< double, 4, 4 >
 
using Matrixf = Eigen::Matrix< float, Eigen::Dynamic, Eigen::Dynamic >
 A dynamic size matrix of floats.
 
using Matrixd = Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic >
 A dynamic size matrix of doubles.
 
using SparseMatrixf = Eigen::SparseMatrix< float, Eigen::RowMajor >
 
using SparseMatrixd = Eigen::SparseMatrix< double, Eigen::RowMajor >
 
using RigidTransform3f = Eigen::Isometry3f
 
using RigidTransform3d = Eigen::Isometry3d
 
using AffineTransform3f = Eigen::Affine3f
 
using AffineTransform3d = Eigen::Affine3d
 
using ModuleDriverStatus = int
 
typedef unsigned char ScalarTypeId
 
using CellTypeId = unsigned char
 
using TaskNodeVector = std::vector< std::shared_ptr< TaskNode > >
 
using TaskNodeList = std::list< std::shared_ptr< TaskNode > >
 
using TaskNodeSet = std::unordered_set< std::shared_ptr< TaskNode > >
 
using TaskNodeAdjList = std::unordered_map< std::shared_ptr< TaskNode >, TaskNodeSet >
 
using TaskNodeNameMap = std::unordered_map< std::shared_ptr< TaskNode >, std::string >
 
using SceneBehaviour = Behaviour< double >
 
using EntityID = std::uint32_t
 
using PbdParticleId = std::pair< int, int >
 Index pair that refers to a particle in a PbdState. Index 0 is the body id, Index 1 is the particle id.
 
using DeviceType = int
 
using ButtonStateType = int
 
template<typename T >
using DeviceManagerRegistrar = SharedObjectRegistrar< DeviceManager, T >
 Auto registration class. More...
 
using KeyStateType = int
 
using MouseActionType = int
 
using MouseButtonType = int
 
using VRPNDeviceType = int
 
using PunctureId = std::tuple< int, int, int >
 Punctures are identified via three ints. The needle id, the puncturable id, and a local id that allows multi punctures on the needle,puncture pair. This could be a cell (face) id, vertex id, or an index into some other structure.
 
using PunctureMap = std::unordered_map< PunctureId, std::shared_ptr< Puncture >, PunctureIdHash, PunctureIdEq >
 
template<typename T >
using RenderDelegateRegistrar = SharedObjectRegistrar< VTKRenderDelegate, T >
 class for automatically registering a delegate More...
 

Enumerations

enum  CollisionElementType {
  Empty, CellVertex, CellIndex, PointDirection,
  PointIndexDirection
}
 
enum  PbdContactCase {
  Vertex, Edge, Triangle, Body,
  Primitive, None
}
 
enum  OctreePrimitiveType { Point = 0, Triangle, Analytical, NumPrimitiveTypes }
 The OctreePrimitiveType enum Type of primitive stored in the octree. More...
 
enum  FeMethodType { StVK, Corotational, Linear, Invertible }
 
enum  HyperElasticMaterialType { StVK, NeoHookean, MooneyRivlin, none }
 
enum  DynamicalModelType {
  RigidBodyDynamics, ElastoDynamics, PositionBasedDynamics, SmoothedParticleHydrodynamics,
  Physiology, None
}
 Type of the time dependent mathematical model.
 
enum  TimeSteppingType { RealTime, Fixed }
 Type of the update of the state of the body.
 
enum  SegmentCutType { NONE = 0, EDGE = 1 }
 
enum  TriCutType {
  NONE = 0, EDGE, VERT, EDGE_EDGE,
  EDGE_VERT, VERT_VERT
}
 
enum  MeshFileType {
  UNKNOWN, VTK, VTU, VTP,
  STL, PLY, OBJ, DAE,
  FBX, _3DS, VEG, MSH,
  NRRD, DCM, NII, MHD,
  JPG, PNG, BMP
}
 Enumeration the mesh file type.
 

Functions

 IMSTK_REGISTER_COLLISION_DETECTION (BidirectionalPlaneToSphereCD)
 
 IMSTK_REGISTER_COLLISION_DETECTION (CapsuleToCapsuleCD)
 
 IMSTK_REGISTER_COLLISION_DETECTION (ClosedSurfaceMeshToCapsuleCD)
 
 IMSTK_REGISTER_COLLISION_DETECTION (ClosedSurfaceMeshToMeshCD)
 
 IMSTK_REGISTER_COLLISION_DETECTION (ImplicitGeometryToPointSetCD)
 
 IMSTK_REGISTER_COLLISION_DETECTION (ImplicitGeometryToPointSetCCD)
 
 IMSTK_REGISTER_COLLISION_DETECTION (LineMeshToLineMeshCCD)
 
 IMSTK_REGISTER_COLLISION_DETECTION (LineMeshToSphereCD)
 
 IMSTK_REGISTER_COLLISION_DETECTION (LineMeshToCapsuleCD)
 
 IMSTK_REGISTER_COLLISION_DETECTION (PointSetToCapsuleCD)
 
 IMSTK_REGISTER_COLLISION_DETECTION (PointSetToCylinderCD)
 
 IMSTK_REGISTER_COLLISION_DETECTION (PointSetToPlaneCD)
 
 IMSTK_REGISTER_COLLISION_DETECTION (PointSetToSphereCD)
 
 IMSTK_REGISTER_COLLISION_DETECTION (PointSetToOrientedBoxCD)
 
 IMSTK_REGISTER_COLLISION_DETECTION (SphereToCapsuleCD)
 
 IMSTK_REGISTER_COLLISION_DETECTION (SphereToCylinderCD)
 
 IMSTK_REGISTER_COLLISION_DETECTION (SphereToSphereCD)
 
 IMSTK_REGISTER_COLLISION_DETECTION (SurfaceMeshToSurfaceMeshCD)
 
 IMSTK_REGISTER_COLLISION_DETECTION (SurfaceMeshToCapsuleCD)
 
 IMSTK_REGISTER_COLLISION_DETECTION (SurfaceMeshToSphereCD)
 
 IMSTK_REGISTER_COLLISION_DETECTION (TetraToPointSetCD)
 
 IMSTK_REGISTER_COLLISION_DETECTION (TetraToLineMeshCD)
 
 IMSTK_REGISTER_COLLISION_DETECTION (UnidirectionalPlaneToSphereCD)
 
 IMSTK_REGISTER_COLLISION_DETECTION (UnidirectionalPlaneToCapsuleCD)
 
 IMSTK_REGISTER_COLLISION_DETECTION (CompoundCD)
 
std::ostream & operator<< (std::ostream &os, const PbdCHTableKey &key)
 
bool isColorRangeCorrect (double c)
 
std::ostream & operator<< (std::ostream &os, const Color &c)
 
Color operator* (const Color &color_lhs, const Color &color_rhs)
 Multiplication operators.
 
Color operator* (const Color &color_lhs, const double intensity_rhs)
 
Color operator*= (const Color &color_lhs, const Color &color_rhs)
 
Color operator*= (const Color &color_lhs, const double intensity_rhs)
 
Color operator+ (const Color &color_lhs, const Color &color_rhs)
 Addition operators.
 
Color operator+ (const Color &color_lhs, const double intensity_rhs)
 
Color operator+= (const Color &color_lhs, const Color &color_rhs)
 
Color operator+= (const Color &color_lhs, const double intensity_rhs)
 
Color operator- (const Color &color_lhs, const Color &color_rhs)
 Subtraction operators.
 
Color operator- (const Color &color_lhs, const double intensity_rhs)
 
Color operator-= (const Color &color_lhs, const Color &color_rhs)
 
Color operator-= (const Color &color_lhs, const double intensity_rhs)
 
bool operator== (const Color &color_lhs, const Color &color_rhs)
 Comparison operator.
 
bool operator!= (const Color &color_lhs, const Color &color_rhs)
 
std::ostream & operator<< (std::ostream &os, const HaplyDeviceClient::DeviceInfo &info)
 
void mcSubImage (std::shared_ptr< ImageData > imageData, std::shared_ptr< SurfaceMesh > outputSurf, const Vec3i &start, const Vec3i &end, const double isoValue)
 
template<class Base , class Target >
std::function< bool(Base *)> makeTypeCheck ()
 
PunctureId getPunctureId (std::shared_ptr< Needle > needle, std::shared_ptr< Puncturable > puncturable, const int supportId=-1)
 Get puncture id between needle and puncturable.
 
std::string getCDType (const CollidingObject &obj1, const CollidingObject &obj2)
 
std::shared_ptr< PbdObjectaddConnectiveTissueConstraints (std::shared_ptr< LineMesh > connectiveLineMesh, std::shared_ptr< PbdObject > objA, std::shared_ptr< PbdObject > objB, std::shared_ptr< PbdModel > model, double mass, double distStiffness)
 
std::shared_ptr< PbdObjectmakeConnectiveTissue (std::shared_ptr< PbdObject > objA, std::shared_ptr< PbdObject > objB, std::shared_ptr< PbdModel > model, double maxDist, double strandsPerFace, int segmentsPerStrand, std::shared_ptr< ProximitySurfaceSelector > proxSelector, double mass, double distStiffness, double allowedAngleDeviation)
 
std::shared_ptr< imstk::PbdObjectmakeConnectiveTissue (std::shared_ptr< PbdObject > objA, std::shared_ptr< PbdObject > objB, std::shared_ptr< PbdModel > model, double maxDist, double strandsPerFace, int segmentsPerStrand, double mass, double distStiffness, double allowedAngleDeviation)
 
 vtkStandardNewMacro (VTKInteractorStyle)
 

Variables

const VRPNDeviceType VRPNAnalog = 0x1
 
const VRPNDeviceType VRPNButton = 0x2
 
const VRPNDeviceType VRPNTracker = 0x4
 
const VRPNDeviceType VRPNForce = 0x8
 
RenderDelegateRegistrar< VTKAxesRenderDelegate_imstk_registerrenderdelegate_axes ("AxesModel")
 
RenderDelegateRegistrar< VTKFluidRenderDelegate_imstk_registerrenderdelegate_fluid ("Fluid")
 
RenderDelegateRegistrar< VTKSurfaceNormalRenderDelegate_imstk_registerrenderdelegate_surfacenormals ("SurfaceNormals")
 

Detailed Description

Compound Geometry.

Todo:
remove nameless union/struct in the future

Typedef Documentation

◆ CDObjectRegistrar

Auto registration class.

Template Parameters
Ttype of the class to register

Definition at line 53 of file imstkCDObjectFactory.h.

◆ DeviceManagerRegistrar

template<typename T >
using imstk::DeviceManagerRegistrar = typedef SharedObjectRegistrar<DeviceManager, T>

Auto registration class.

Template Parameters
Ttype of the class to register

Definition at line 58 of file imstkDeviceManagerFactory.h.

◆ RenderDelegateRegistrar

template<typename T >
using imstk::RenderDelegateRegistrar = typedef SharedObjectRegistrar<VTKRenderDelegate, T>

class for automatically registering a delegate

Template Parameters
Ttype of the delegate object to register

Definition at line 58 of file imstkRenderDelegateObjectFactory.h.

Enumeration Type Documentation

◆ HyperElasticMaterialType

Todo:
Move to appropriate place

Definition at line 25 of file imstkInternalForceModelTypes.h.

◆ OctreePrimitiveType

The OctreePrimitiveType enum Type of primitive stored in the octree.

Todo:
Add line primitive to geometry

Definition at line 31 of file imstkLooseOctree.h.

Function Documentation

◆ makeTypeCheck()

template<class Base , class Target >
std::function<bool(Base*)> imstk::makeTypeCheck ( )

Returns a function that for instances with common Base classes determines whether it is of the Target type

Definition at line 24 of file imstkGeometryAlgorithm.h.

Variable Documentation

◆ _imstk_registerrenderdelegate_axes

RenderDelegateRegistrar<VTKAxesRenderDelegate> imstk::_imstk_registerrenderdelegate_axes("AxesModel")

Note, these do not refer to geometry classes