Commit cf0dbc3a authored by Sreekanth Arikatla's avatar Sreekanth Arikatla

Merge branch 'minorCleanUp' into 'master'

Minor clean up

See merge request !350
parents 1ec0fe1d eecca310
Pipeline #142261 passed with stage
in 0 seconds
......@@ -128,10 +128,6 @@ main()
scene->addLight(colorLight);
scene->addSceneObject(deformableObj);
// print UPS
/*auto ups = std::make_shared<UPSCounter>();
apiutils::printUPS(sdk->getSceneManager(scene), ups);*/
scene->getCamera()->setFocalPoint(0, -5, 5);
scene->getCamera()->setPosition(-15., -5.0, 15.0);
......
......@@ -136,7 +136,7 @@ generateFluid(const std::shared_ptr<Scene>& scene, const double particleRadius)
// Create a fluids object
auto fluidObj = std::make_shared<SPHObject>("Sphere");
// Create a visiual model
// Create a visual model
auto fluidVisualModel = std::make_shared<VisualModel>(fluidGeometry);
auto fluidMaterial = std::make_shared<RenderMaterial>();
fluidMaterial->setColor(Color::Blue);
......@@ -152,14 +152,14 @@ generateFluid(const std::shared_ptr<Scene>& scene, const double particleRadius)
sphParams->m_bNormalizeDensity = true;
if (SCENE_ID == 2) // highly viscous fluid
{
sphParams->m_RatioKernelOverParticleRadius = 6.0;
sphParams->m_ViscosityFluid = 0.5;
sphParams->m_SurfaceTensionStiffness = 5.0;
sphParams->m_kernelOverParticleRadiusRatio = 6.0;
sphParams->m_viscosityCoeff = 0.5;
sphParams->m_surfaceTensionStiffness = 5.0;
}
if (SCENE_ID == 3) // bunny-shaped fluid
{
sphParams->m_BoundaryFriction = 0.3;
sphParams->m_frictionBoundary= 0.3;
}
sphModel->configure(sphParams);
......
......@@ -95,7 +95,7 @@ BoneDrillingCH::erodeBone()
if (m_nodalDensity[cd.nodeIdx] <= 0.)
{
// TODO: Unused variable, maybe used in furture?
/// \todo Unused variable, maybe used in furture?
// lock.lock();
// m_erodedNodes.push_back(cd.nodeId);
// lock.unlock();
......
......@@ -89,7 +89,7 @@ private:
std::vector<double> m_nodalDensity; ///> Density of the bone
double m_initialBoneDensity = 1.0; ///> Density of the bone before the start of the drilling process
// std::vector<size_t> m_erodedNodes; // TODO: Unused variable
// std::vector<size_t> m_erodedNodes; /// \todo Unused variable
std::vector<bool> m_nodeRemovalStatus; ///> Keeps track of the removal status of the node
std::vector<std::vector<size_t>> m_nodalCardinalSet; ///> Keeps track of the removal status of the node
......
......@@ -144,6 +144,6 @@ PBDCollisionHandling::generatePBDConstraints()
m_PBDConstraints.push_back(c);
}
//TODO: generating PbdPointTriangleConstraint from the VTColData should be added
//\todo generating PbdPointTriangleConstraint from the VTColData should be added
}
}
......@@ -42,7 +42,7 @@ SPHCollisionHandling::processCollisionData()
LOG_IF(FATAL, (!SPHModel)) << "SPH model was not initialized";
#endif
const auto boundaryFriction = m_SPHObject->getSPHModel()->getParameters()->m_BoundaryFriction;
const auto boundaryFriction = m_SPHObject->getSPHModel()->getParameters()->m_frictionBoundary;
#if defined(DEBUG) || defined(_DEBUG) || !defined(NDEBUG)
LOG_IF(FATAL, (boundaryFriction<0.0 || boundaryFriction>1.0))
<< "Invalid boundary friction coefficient (value must be in [0, 1])";
......
......@@ -33,7 +33,7 @@ PbdConstantDensityConstraint::initConstraint(PbdModel& model, const double)
// constraint parameters
// Refer: Miller, et al 2003 "Particle-Based Fluid Simulation for Interactive Applications."
// TODO: Check if these numbers can be variable
/// \todo Check if these numbers can be variable
m_wPoly6Coeff = 315.0 / (64.0 * PI * pow(m_maxDist, 9));
m_wSpikyCoeff = 15.0 / (PI * pow(m_maxDist, 6));
......
......@@ -21,7 +21,7 @@
#pragma once
// TODO: Remove this in TBB 2019 Update 4: https://github.com/intel/tbb/blob/tbb_2019/CHANGES#L117
/// \todo Remove this in TBB 2019 Update 4: https://github.com/intel/tbb/blob/tbb_2019/CHANGES#L117
#define TBB_PREVIEW_GLOBAL_CONTROL 1
#include <tbb/tbb.h>
......
......@@ -23,6 +23,8 @@
#include <iostream>
/// \todo remove nameless union/struct in the future
#pragma warning(disable : 4201)
namespace imstk
{
///
......@@ -102,4 +104,5 @@ struct Color
static Color Orange;
static Color Yellow;
};
#pragma warning(default : 4201)
}
......@@ -30,7 +30,7 @@ namespace imstk
///
/// \struct stdSink
///
/// \brief
/// \brief A standard sink that prints the message to a standard output
///
struct stdSink
{
......
......@@ -101,12 +101,14 @@ public:
/// \brief Check if cell index in dimension d is valid (d = 0/1/2 => x/y/z dimension)
///
template<int d>
bool isValidCellIndex(const int idx) const { return idx >= 0 && static_cast<unsigned int>(idx) < m_Resolution[d]; }
bool isValidCellIndex(const int idx) const
{ return idx >= 0 && static_cast<unsigned int>(idx) < m_Resolution[d]; }
///
/// \brief Check if 3D cell indices are valid
///
bool isValidCellIndices(const int i, const int j, const int k) const { return isValidCellIndex<0>(i) && isValidCellIndex<1>(j) && isValidCellIndex<2>(k); }
bool isValidCellIndices(const int i, const int j, const int k) const
{ return isValidCellIndex<0>(i) && isValidCellIndex<1>(j) && isValidCellIndex<2>(k); }
///
/// \brief Get the 3D index (cell_x, cell_y, cell_z) of the cell containing the given positions
......@@ -136,53 +138,77 @@ public:
/// \brief Get data in a cell
/// \param A position in space
///
CellData& getCellData(const Vec3r& ppos) { return m_CellData[getCellLinearizedIndex < unsigned int > (ppos)]; }
CellData& getCellData(const Vec3r& ppos)
{
return m_CellData[getCellLinearizedIndex < unsigned int > (ppos)];
}
///
/// \brief Get data in a cell
/// \param A position in space
///
const CellData& getCellData(const Vec3r& ppos) const { return m_CellData[getCellLinearizedIndex < unsigned int > (ppos)]; }
const CellData& getCellData(const Vec3r& ppos) const
{ return m_CellData[getCellLinearizedIndex < unsigned int > (ppos)]; }
///
/// \brief Get data in a cell
/// \param A linearized index of cell
///
CellData& getCellData(size_t linearizedIdx) { assert(linearizedIdx < m_CellData.size()); return m_CellData[linearizedIdx]; }
CellData& getCellData(size_t linearizedIdx)
{
assert(linearizedIdx < m_CellData.size());
return m_CellData[linearizedIdx];
}
///
/// \brief Get data in a cell
/// \param A linearized index of cell
///
const CellData& getCellData(size_t linearizedIdx) const { assert(linearizedIdx < m_CellData.size()); return m_CellData[linearizedIdx]; }
const CellData& getCellData(size_t linearizedIdx) const
{
assert(linearizedIdx < m_CellData.size());
return m_CellData[linearizedIdx];
}
///
/// \brief Get data in a cell
/// \param 3D index of a cell
///
template<class IndexType>
CellData& getCellData(const std::array<IndexType, 3>& cellIdx) { return m_CellData[getCellLinearizedIndex(cellIdx[0], cellIdx[1], cellIdx[2])]; }
CellData& getCellData(const std::array<IndexType, 3>& cellIdx)
{
return m_CellData[getCellLinearizedIndex(cellIdx[0], cellIdx[1], cellIdx[2])];
}
///
/// \brief Get data in a cell
/// \param 3D index of a cell
///
template<class IndexType>
const CellData& getCellData(const std::array<IndexType, 3>& cellIdx) const { return m_CellData[getCellLinearizedIndex(cellIdx[0], cellIdx[1], cellIdx[2])]; }
const CellData& getCellData(const std::array<IndexType, 3>& cellIdx) const
{
return m_CellData[getCellLinearizedIndex(cellIdx[0], cellIdx[1], cellIdx[2])];
}
///
/// \brief Get data in a cell
/// \param 3D index of a cell
///
template<class IndexType>
CellData& getCellData(const IndexType i, const IndexType j, const IndexType k) { return m_CellData[getCellLinearizedIndex(i, j, k)]; }
CellData& getCellData(const IndexType i, const IndexType j, const IndexType k)
{
return m_CellData[getCellLinearizedIndex(i, j, k)];
}
///
/// \brief Get data in a cell
/// \param 3D index of a cell
///
template<class IndexType>
const CellData& getCellData(const IndexType i, const IndexType j, const IndexType k) const { return m_CellData[getCellLinearizedIndex(i, j, k)]; }
const CellData& getCellData(const IndexType i, const IndexType j, const IndexType k) const
{
return m_CellData[getCellLinearizedIndex(i, j, k)];
}
///
/// \brief Apply a function to all cell data
......
......@@ -23,4 +23,4 @@ imstk_add_library( DynamicalModels
#-----------------------------------------------------------------------------
if( iMSTK_BUILD_TESTING )
add_subdirectory( Testing )
endif()
endif()
\ No newline at end of file
#-----------------------------------------------------------------------------
# Create target
#-----------------------------------------------------------------------------
include(imstkAddLibrary)
imstk_add_library( ForceModel
DEPENDS
Core
VegaFEM::massSpringSystem
VegaFEM::corotationalLinearFEM
VegaFEM::isotropicHyperelasticFEM
VegaFEM::forceModel
VegaFEM::stvk
VegaFEM::graph
VegaFEM::volumetricMesh
)
#-----------------------------------------------------------------------------
# Testing
#-----------------------------------------------------------------------------
if( iMSTK_BUILD_TESTING )
add_subdirectory( Testing )
endif()
......@@ -31,7 +31,7 @@
namespace imstk
{
// TODO: Move to appropriate place
/// \todo Move to appropriate place
enum class ForceModelType
{
StVK,
......@@ -45,7 +45,7 @@ enum class ForceModelType
none
};
// TODO: Move to appropriate place
/// \todo Move to appropriate place
enum class HyperElasticMaterialType
{
StVK,
......@@ -91,10 +91,10 @@ enum class HyperElasticMaterialType
/// numberOfThreads Number of threads spawned by the force model
/// [default = 0]
///
/// TODO: Convert this to input through JSON format
/// \todo Convert this to input through JSON format
class ForceModelConfig
{
// TODO: Do this in a better way
/// \todo Do this in a better way
struct customOptionsList
{
char femMethod[256];
......
......@@ -36,8 +36,6 @@ enum class DynamicalModelType
elastoDynamics,
positionBasedDynamics,
SPH,
NavierStokes,
HeatEquation,
none
};
......
......@@ -250,7 +250,7 @@ FEMDeformableBodyModel::initializeMassMatrix(const bool saveToDisk /*= false*/)
this->initializeEigenMatrixFromVegaMatrix(*vegaMatrix, m_M);
// TODO: Add option to save mass matrix to file
/// \todo Add option to save mass matrix to file
return true;
}
......
......@@ -393,7 +393,8 @@ PbdModel::initializeConstantDensityConstraint(const double stiffness)
&& m_mesh->getType() != Geometry::Type::HexahedralMesh
&& m_mesh->getType() != Geometry::Type::PointSet)
{
LOG(WARNING) << "Constant constraint should come with a mesh"; //TODO: Really only need a point cloud, so may need to change this.
//\todo Really only need a point cloud, so may need to change this.
LOG(WARNING) << "Constant constraint should come with a mesh!";
return false;
}
......
......@@ -432,7 +432,8 @@ protected:
} // end namespace SPH
///
/// \brief Struct contains SPH kernels for time integration, using different kernel for different purposes
/// \brief Class contains SPH kernels for time integration,
/// using different kernel for different purposes
///
class SPHSimulationKernels
{
......
......@@ -31,7 +31,7 @@ namespace imstk
{
///
/// \class SPHModelConfig
/// \brief Parameters for SPH simulation
/// \brief Class that holds the SPH model parameters
///
class SPHModelConfig
{
......@@ -41,65 +41,49 @@ private:
public:
SPHModelConfig(const Real particleRadius);
////////////////////////////////////////////////////////////////////////////////
// TODO: Move this to solver or time integrator in the future
Real m_MinTimestep = Real(1e-6);
Real m_MaxTimestep = Real(1e-3);
/// \todo Move this to solver or time integrator in the future
Real m_minTimestep = Real(1e-6);
Real m_maxTimestep = Real(1e-3);
Real m_CFLFactor = Real(1.0);
////////////////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////////////////////
// particle parameters
Real m_ParticleRadius = Real(0);
Real m_ParticleRadiusSqr = Real(0);
////////////////////////////////////////////////////////////////////////////////
Real m_particleRadius = Real(0);
Real m_particleRadiusSqr = Real(0); ///> \note derived quantity
////////////////////////////////////////////////////////////////////////////////
// material parameters
Real m_RestDensity = Real(1000.0);
Real m_RestDensitySqr = Real(1000000.0);
Real m_RestDensityInv = Real(1.0 / 1000.0);
Real m_ParticleMass = Real(1);
Real m_ParticleMassScale = Real(0.95); // scale particle mass to a smaller value to maintain stability
Real m_restDensity = Real(1000.0);
Real m_restDensitySqr = Real(1000000.0); ///> \note derived quantity
Real m_restDensityInv = Real(1.0 / 1000.0); ///> \note derived quantity
Real m_particleMass = Real(1);
Real m_particleMassScale = Real(0.95); ///> scale particle mass to a smaller value to maintain stability
bool m_bNormalizeDensity = false;
bool m_bDensityWithBoundary = false;
////////////////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////////////////////
// pressure
Real m_PressureStiffness = Real(50000.0);
////////////////////////////////////////////////////////////////////////////////
Real m_pressureStiffness = Real(50000.0);
////////////////////////////////////////////////////////////////////////////////
// viscosity and surface tension/cohesion
Real m_ViscosityFluid = Real(1e-2);
Real m_ViscosityBoundary = Real(1e-5);
Real m_SurfaceTensionStiffness = Real(1);
Real m_BoundaryFriction = Real(0.1);
////////////////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////////////////////
// kernel data
Real m_RatioKernelOverParticleRadius = Real(4.0);
Real m_KernelRadius;
Real m_KernelRadiusSqr;
////////////////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////////////////////
Real m_viscosityCoeff = Real(1e-2);
Real m_viscosityBoundary = Real(1e-5);
Real m_surfaceTensionStiffness = Real(1);
Real m_frictionBoundary = Real(0.1);
// kernel properties
Real m_kernelOverParticleRadiusRatio = Real(4.0);
Real m_kernelRadius; ///> \note derived quantity
Real m_kernelRadiusSqr; ///> \note derived quantity
// gravity
Vec3r m_Gravity = Vec3r(0, -9.81, 0);
////////////////////////////////////////////////////////////////////////////////
Vec3r m_gravity = Vec3r(0, -9.81, 0);
////////////////////////////////////////////////////////////////////////////////
// neighbor search
NeighborSearch::Method m_NeighborSearchMethod = NeighborSearch::Method::UniformGridBasedSearch;
////////////////////////////////////////////////////////////////////////////////
};
///
/// \class SPHModel
/// \brief SPH simulation model
/// \brief SPH fluid model
///
class SPHModel : public DynamicalModel<SPHKinematicState>
{
......@@ -117,12 +101,12 @@ public:
///
/// \brief Set simulation parameters
///
void configure(const std::shared_ptr<SPHModelConfig>& params) { m_Parameters = params; }
void configure(const std::shared_ptr<SPHModelConfig>& params) { m_modelParameters = params; }
///
/// \brief Set the geometry (particle positions)
///
void setModelGeometry(const std::shared_ptr<PointSet>& geo) { m_Geometry = geo; }
void setModelGeometry(const std::shared_ptr<PointSet>& geo) { m_geometry = geo; }
///
/// \brief Initialize the dynamical model
......@@ -137,44 +121,61 @@ public:
///
/// \brief Update positions of point set geometry
///
virtual void updatePhysicsGeometry() override { assert(m_Geometry); m_Geometry->setVertexPositions(this->m_currentState->getPositions()); }
virtual void updatePhysicsGeometry() override
{ assert(m_geometry); m_geometry->setVertexPositions(this->m_currentState->getPositions()); }
///
/// \brief Reset the current state to the initial state
///
virtual void resetToInitialState() override { this->m_currentState->setState(this->m_initialState); }
virtual void resetToInitialState() override
{ this->m_currentState->setState(this->m_initialState); }
///
/// \brief Get the simulation parameters
///
const std::shared_ptr<SPHModelConfig>& getParameters() const { assert(m_Parameters); return m_Parameters; }
const std::shared_ptr<SPHModelConfig>& getParameters() const
{ assert(m_modelParameters); return m_modelParameters; }
///
/// \brief Get the kinematics particle data (positions + velocities)
///
SPHKinematicState& getKinematicsState() { assert(this->m_currentState); return *this->m_currentState; }
const SPHKinematicState& getKinematicsState() const { assert(this->m_currentState); return *this->m_currentState; }
SPHKinematicState& getKinematicsState()
{
assert(this->m_currentState);
return *this->m_currentState;
}
const SPHKinematicState& getKinematicsState() const
{
assert(this->m_currentState);
return *this->m_currentState;
}
///
/// \brief Get particle simulation data
///
SPHSimulationState& getState() { return m_SimulationState; }
const SPHSimulationState& getState() const { return m_SimulationState; }
SPHSimulationState& getState() { return m_simulationState; }
const SPHSimulationState& getState() const { return m_simulationState; }
///
/// \brief Set the default time step size, valid only if using a fixed time step for integration
/// \brief Set the default time step size,
/// valid only if using a fixed time step for integration
///
virtual void setTimeStep(const double timeStep) override { setDefaultTimeStep(static_cast<Real>(timeStep)); }
virtual void setTimeStep(const double timeStep) override
{ setDefaultTimeStep(static_cast<Real>(timeStep)); }
///
/// \brief Set the default time step size, valid only if using a fixed time step for integration
/// \brief Set the default time step size,
/// valid only if using a fixed time step for integration
///
void setDefaultTimeStep(const Real timeStep) { m_DefaultDt = static_cast<Real>(timeStep); }
void setDefaultTimeStep(const Real timeStep)
{ m_defaultDt = static_cast<Real>(timeStep); }
///
/// \brief Returns the time step size
///
virtual double getTimeStep() const override { return static_cast<double>(m_dt); }
virtual double getTimeStep() const override
{ return static_cast<double>(m_dt); }
///
/// \brief Do one time step simulation
......@@ -203,7 +204,8 @@ private:
void computeNeighborRelativePositions();
///
/// \brief Collect the densities of neighbor particles, called after all density computation (after density normalizaton, if applicable)
/// \brief Collect the densities of neighbor particles,
/// called after all density computation (after density normalization, if applicable)
///
void collectNeighborDensity();
......@@ -234,6 +236,8 @@ private:
///
/// \brief Compute surface tension and update velocities
/// Compute surface tension using Akinci et at. 2013 model
/// (Versatile Surface Tension and Adhesion for SPH Fluids)
///
void computeSurfaceTension();
......@@ -242,14 +246,14 @@ private:
///
void moveParticles(const Real timestep);
std::shared_ptr<PointSet> m_Geometry;
SPHSimulationState m_SimulationState;
std::shared_ptr<PointSet> m_geometry;
SPHSimulationState m_simulationState;
Real m_dt; ///> time step size
Real m_DefaultDt; ///> default time step size
Real m_defaultDt; ///> default time step size
SPHSimulationKernels m_Kernels; // must be initialized during model initialization
std::shared_ptr<SPHModelConfig> m_Parameters; // must be set before simulation
std::shared_ptr<NeighborSearch> m_NeighborSearcher; // must be initialized during model initialization
SPHSimulationKernels m_kernels; ///> SPH kernels (must be initialized during model initialization)
std::shared_ptr<SPHModelConfig> m_modelParameters; ///> SPH Model parameters (must be set before simulation)
std::shared_ptr<NeighborSearch> m_neighborSearcher; ///> Neighbor Search (must be initialized during model initialization)
};
} // end namespace imstk
......@@ -140,7 +140,7 @@ public:
///
/// \brief Rewire the node order and triangle connectivity to optimize for memory layout
/// The intended use is for large meshes that doesn't fit into CPU/GPU memory.
/// TODO: Further optimization to find a 1-d uninterrupted sub-graph at each iteration.
/// \todo Further optimization to find a 1-d uninterrupted sub-graph at each iteration.
///
void optimizeForDataLocality();
......@@ -202,7 +202,8 @@ public:
///
/// \brief Set load factor
/// \param loadFactor the maximum number of vertices; a multiple of the original vertex count
/// \param loadFactor the maximum number of vertices
/// a multiple of the original vertex count
///
virtual void setLoadFactor(double loadFactor) override;
......
......@@ -69,7 +69,7 @@ protected:
VolumetricMesh(Geometry::Type type, const std::string name = std::string("")) : PointSet(type, name) {}
std::shared_ptr<SurfaceMesh> m_attachedSurfaceMesh = nullptr; ///> Attached surface mesh
std::shared_ptr<vega::VolumetricMesh> m_attachedVegaMesh = nullptr; ///> Attached vega mesh
std::shared_ptr<SurfaceMesh> m_attachedSurfaceMesh; ///> Attached surface mesh
std::shared_ptr<vega::VolumetricMesh> m_attachedVegaMesh; ///> Attached vega mesh
};
} // imstk
......@@ -55,9 +55,10 @@ public:
static std::shared_ptr<imstk::VolumetricMesh> read(const std::string& filePath, const MeshFileType meshType);
protected:
//
// \brief Possible element types in a MSH file format as mentioned at http://www.manpagez.com/info/gmsh/gmsh-2.2.6/gmsh_63.php
//
///
/// \brief Possible element types in a MSH file format
/// as mentioned at http://www.manpagez.com/info/gmsh/gmsh-2.2.6/gmsh_63.php
///
enum ElemType
{
line=1,
......
......@@ -95,7 +95,7 @@ VTKTetrahedralMeshRenderDelegate::updateDataSource()
if (geometry->getTopologyChangedFlag())
{
m_mappedVertexArray->Modified(); // TODO: only modify if vertices change
m_mappedVertexArray->Modified(); /// \todo only modify if vertices change
// Copy cells
auto& maskedTets = std::dynamic_pointer_cast<TetrahedralMesh>(geometry)->getRemovedTetrahedra();
......
......@@ -40,7 +40,7 @@ vtkStandardNewMacro(vtkCapsuleSource);
//----------------------------------------------------------------------------
// Construct sphere with radius=0.5 and default resolution 8 in both Phi
// and Theta directions. Theta ranges from (0,360) and phi (0,180) degrees.
// \todo
/// \todo
vtkCapsuleSource::vtkCapsuleSource(int res)
{
res = res < 8 ? 8 : res;
......
......@@ -61,7 +61,7 @@ CollisionGraph::addInteractionPair(CollidingObjectPtr A,
return intPair;
}
//TODO: Refactor -> PBD only
//\todo Refactor -> PBD only
void
CollisionGraph::addInteractionPair(std::shared_ptr<PbdInteractionPair> pair)
{
......
......@@ -66,7 +66,7 @@ public:
CollisionHandling::Type CHAType,
CollisionHandling::Type CHBType);
//TODO: Refactor -> PBD only
//\todo Refactor -> PBD only
InteractionPairPtr addInteractionPair(CollidingObjectPtr A,
CollidingObjectPtr B,
CollisionDetectionPtr CD,
......@@ -99,7 +99,7 @@ public:
const std::unordered_map<CollidingObjectPtr, std::vector<InteractionPairPtr>>& getInteractionPairMap() const;
protected:
std::vector<std::shared_ptr<PbdInteractionPair>> m_interactionPbdPairList; //TODO: Refactor -> PBD only
std::vector<std::shared_ptr<PbdInteractionPair>> m_interactionPbdPairList; //\todo Refactor -> PBD only
std::vector<InteractionPairPtr> m_interactionPairList; ///< All interaction pairs in the collision graph
std::unordered_map<CollidingObjectPtr, std::vector<InteractionPairPtr>> m_interactionPairMap; ///< Map of interaction pairs per colliding object
......
......@@ -28,7 +28,7 @@
namespace imstk
{
// TODO: Complete this
/// \todo Complete this
class RigidBodyState
{
public:
......
......@@ -115,7 +115,7 @@ OpenVRCommand::Execute(
// grip button
if (eventId == vtkCommand::MiddleButtonPressEvent)
{
// TODO: Take a screenshot
/// \todo Take a screenshot
this->AbortFlagOn();
}
......
......@@ -86,7 +86,7 @@ DirectLinearSolver<Matrixd>::solve(Vectord& x)
{
if (!m_linearSystem)
{
// TODO: Log this
/// \todo Log this
return;
}
......
......@@ -145,7 +145,7 @@ NewtonSolver::updateJacobian(const Vectord& x)
auto& b = m_nonLinearSystem->m_F(x, m_isSemiImplicit);
auto linearSystem = std::make_shared<LinearSolverType::LinearSystemType>(A, b);
//linearSystem->setLinearProjectors(m_nonLinearSystem->getLinearProjectors()); // TODO: Left for near future reference. Clear in future.
//linearSystem->setLinearProjectors(m_nonLinearSystem->getLinearProjectors()); /// \todo Left for near future reference. Clear in future.
m_linearSolver->setSystem(linearSystem);
return b.dot(b);
......@@ -160,7 +160,7 @@ NewtonSolver::updateForcingTerm(const double ratio, const double stopTolerance,
// Save guard to prevent the forcing term to become too small for far away iterates