Skip to content

Commit

Permalink
[all] Update data comments (#4751)
Browse files Browse the repository at this point in the history
* simply apply the doxygenDataComments script

* manual post-process

* Fix data comment from online documentation info

* Last fixes between online documentation and the C++ description

* apply one last time the script to apply changes done in inl to the header files

* Apply suggestions from code review

* Apply suggestions from code review

Co-authored-by: Alex Bilger <alxbilger@users.noreply.github.com>

* apply changes to headers

* cosmetic change

* fix compilation due to disappearing d_ on data name

---------

Co-authored-by: Alex Bilger <alxbilger@users.noreply.github.com>
Co-authored-by: Paul Baksic <30337881+bakpaul@users.noreply.github.com>
  • Loading branch information
3 people committed Jun 5, 2024
1 parent 0235ec3 commit 459f806
Show file tree
Hide file tree
Showing 221 changed files with 547 additions and 548 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -218,7 +218,7 @@ ConstraintAnimationLoop::ConstraintAnimationLoop() :
, d_tol( initData(&d_tol, 0.00001_sreal, "tolerance", "Tolerance of the Gauss-Seidel"))
, d_maxIt( initData(&d_maxIt, 1000, "maxIterations", "Maximum number of iterations of the Gauss-Seidel"))
, d_doCollisionsFirst(initData(&d_doCollisionsFirst, false, "doCollisionsFirst","Compute the collisions first (to support penality-based contacts)"))
, d_doubleBuffer( initData(&d_doubleBuffer, false, "doubleBuffer","Buffer the constraint problem in a doublebuffer to be accessible with an other thread"))
, d_doubleBuffer( initData(&d_doubleBuffer, false, "doubleBuffer","Double the buffer dedicated to the constraint problem to make it accessible to another thread"))
, d_scaleTolerance( initData(&d_scaleTolerance, true, "scaleTolerance","Scale the error tolerance with the number of constraints"))
, d_allVerified( initData(&d_allVerified, false, "allVerified","All contraints must be verified (each constraint's error < tolerance)"))
, d_sor( initData(&d_sor, 1.0_sreal, "sor","Successive Over Relaxation parameter (0-2)"))
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -112,7 +112,7 @@ class SOFA_COMPONENT_ANIMATIONLOOP_API ConstraintAnimationLoop : public sofa::si
Data<SReal> d_tol; ///< Tolerance of the Gauss-Seidel
Data<int> d_maxIt; ///< Maximum number of iterations of the Gauss-Seidel
Data<bool> d_doCollisionsFirst; ///< Compute the collisions first (to support penality-based contacts)
Data<bool> d_doubleBuffer; ///< Buffer the constraint problem in a SReal buffer to be accessible with an other thread
Data<bool> d_doubleBuffer; ///< Double the buffer dedicated to the constraint problem to make it accessible to another thread
Data<bool> d_scaleTolerance; ///< Scale the error tolerance with the number of constraints
Data<bool> d_allVerified; ///< All contraints must be verified (each constraint's error < tolerance)
Data<SReal> d_sor; ///< Successive Over Relaxation parameter (0-2)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -48,8 +48,8 @@ class SOFA_COMPONENT_ANIMATIONLOOP_API FreeMotionAnimationLoop : public sofa::si

Data<bool> d_solveVelocityConstraintFirst; ///< solve separately velocity constraint violations before position constraint violations
Data<bool> d_threadSafeVisitor; ///< If true, do not use realloc and free visitors in fwdInteractionForceField.
Data<bool> d_parallelCollisionDetectionAndFreeMotion; ///<If true, executes free motion and collision detection in parallel
Data<bool> d_parallelODESolving; ///<If true, executes all free motions in parallel
Data<bool> d_parallelCollisionDetectionAndFreeMotion; ///< If true, executes free motion step and collision detection step in parallel.
Data<bool> d_parallelODESolving; ///< If true, solves all the ODEs in parallel during the free motion step.

protected:
FreeMotionAnimationLoop();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ class SOFA_COMPONENT_COLLISION_DETECTION_ALGORITHM_API BruteForceBroadPhase : pu
SOFA_ATTRIBUTE_DEPRECATED__RENAME_DATA_IN_COLLISION_DETECTION_ALGORITHM()
Data<type::fixed_array<sofa::type::Vec3, 2> > box;

Data<type::fixed_array<sofa::type::Vec3, 2> > d_box;
Data<type::fixed_array<sofa::type::Vec3, 2> > d_box; ///< if not empty, objects that do not intersect this bounding-box will be ignored


public:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ namespace sofa::component::collision::detection::intersection
using namespace sofa::component::collision::geometry;

BaseProximityIntersection::BaseProximityIntersection()
: d_alarmDistance(initData(&d_alarmDistance, 1.0_sreal, "alarmDistance", "Proximity detection distance"))
: d_alarmDistance(initData(&d_alarmDistance, 1.0_sreal, "alarmDistance", "Distance above which the intersection computations ignores the promixity pair. This distance can also be used in some broad phase algorithms to reduce the search area"))
, d_contactDistance(initData(&d_contactDistance, 0.5_sreal, "contactDistance", "Distance below which a contact is created"))
{
d_alarmDistance.setRequired(true);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ class SOFA_COMPONENT_COLLISION_DETECTION_INTERSECTION_API BaseProximityIntersect
Data<SReal> contactDistance;


Data<SReal> d_alarmDistance; ///< Proximity detection distance
Data<SReal> d_alarmDistance; ///< Distance above which the intersection computations ignores the promixity pair. This distance can also be used in some broad phase algorithms to reduce the search area
Data<SReal> d_contactDistance; ///< Distance below which a contact is created
protected:
BaseProximityIntersection();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -55,14 +55,12 @@ LocalMinDistance::LocalMinDistance()
, d_filterIntersection(initData(&d_filterIntersection, true, "filterIntersection", "Activate LMD filter"))
, d_angleCone(initData(&d_angleCone, 0.0, "angleCone", "Filtering cone extension angle"))
, d_coneFactor(initData(&d_coneFactor, 0.5, "coneFactor", "Factor for filtering cone angle computation"))
, d_useLMDFilters(initData(&d_useLMDFilters, false, "useLMDFilters", "Use external cone computation (Work in Progress)"))
, d_useLMDFilters(initData(&d_useLMDFilters, false, "useLMDFilters", "Use external cone computation"))
{
filterIntersection.setParent(&d_filterIntersection);
angleCone.setParent(&d_angleCone);
coneFactor.setParent(&d_coneFactor);
useLMDFilters.setParent(&d_useLMDFilters);


}

void LocalMinDistance::init()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,7 @@ class SOFA_COMPONENT_COLLISION_DETECTION_INTERSECTION_API LocalMinDistance : pub
Data<bool> d_filterIntersection; ///< Activate LMD filter
Data<double> d_angleCone; ///< Filtering cone extension angle
Data<double> d_coneFactor; ///< Factor for filtering cone angle computation
Data<bool> d_useLMDFilters; ///< Use external cone computation (Work in Progress)
Data<bool> d_useLMDFilters; ///< Use external cone computation

protected:
LocalMinDistance();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,6 @@ MinProximityIntersection::MinProximityIntersection()
useLinePoint.setParent(&d_useLinePoint);
useLineLine.setParent(&d_useLineLine);
useSurfaceNormals.setParent(&d_useSurfaceNormals);

}

void MinProximityIntersection::init()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -145,7 +145,7 @@ public :
Data<bool> bothSide;


Data<bool> d_bothSide; ///< to activate collision on both-side of the both side of the line model (when surface normals are defined on these lines)
Data<bool> d_bothSide; ///< activate collision on both side of the line model (when surface normals are defined on these lines)

/// Pre-construction check method called by ObjectFactory.
/// Check that DataTypes matches the MechanicalState.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -105,7 +105,7 @@ class PointCollisionModel : public core::CollisionModel
Data<bool> bothSide;


Data<bool> d_bothSide; ///< to activate collision on both side of the point model (when surface normals are defined on these points)
Data<bool> d_bothSide; ///< activate collision on both side of the point model (when surface normals are defined on these points)

/// Pre-construction check method called by ObjectFactory.
/// Check that DataTypes matches the MechanicalState.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -99,7 +99,7 @@ class SOFA_COMPONENT_COLLISION_GEOMETRY_API RayCollisionModel : public core::Col



Data<SReal> d_defaultLength;
Data<SReal> d_defaultLength; ///< The default length for all rays in this collision model

std::set<response::contact::BaseRayContact*> contacts;
core::behavior::MechanicalState<defaulttype::Vec3Types>* mstate;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -165,7 +165,7 @@ class SphereCollisionModel : public core::CollisionModel
Data<SReal> defaultRadius;

Data< VecReal > d_radius; ///< Radius of each sphere
Data< SReal > d_defaultRadius; ///< Default Radius
Data< SReal > d_defaultRadius; ///< Default radius
Data< bool > d_showImpostors; ///< Draw spheres as impostors instead of "real" spheres


Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ namespace sofa::component::collision::geometry
template<class DataTypes>
SphereCollisionModel<DataTypes>::SphereCollisionModel()
: d_radius(initData(&d_radius, "listRadius", "Radius of each sphere"))
, d_defaultRadius(initData(&d_defaultRadius, (SReal)(1.0), "radius", "Default Radius"))
, d_defaultRadius(initData(&d_defaultRadius, (SReal)(1.0), "radius", "Default radius"))
, d_showImpostors(initData(&d_showImpostors, true, "showImpostors", "Draw spheres as impostors instead of \"real\" spheres"))
, mstate(nullptr)
{
Expand All @@ -47,7 +47,7 @@ SphereCollisionModel<DataTypes>::SphereCollisionModel()
template<class DataTypes>
SphereCollisionModel<DataTypes>::SphereCollisionModel(core::behavior::MechanicalState<DataTypes>* _mstate )
: d_radius(initData(&d_radius, "listRadius", "Radius of each sphere"))
, d_defaultRadius(initData(&d_defaultRadius, (SReal)(1.0), "radius", "Default Radius. (default=1.0)"))
, d_defaultRadius(initData(&d_defaultRadius, (SReal)(1.0), "radius", "Default radius"))
, d_showImpostors(initData(&d_showImpostors, true, "showImpostors", "Draw spheres as impostors instead of \"real\" spheres"))
, mstate(_mstate)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -135,7 +135,7 @@ class TriangleCollisionModel : public core::CollisionModel

enum { NBARY = 2 };

Data<bool> d_bothSide; ///< to activate collision on both side of the triangle model
Data<bool> d_bothSide; ///< activate collision on both side of the triangle model
Data<bool> d_computeNormals; ///< set to false to disable computation of triangles normal
Data<bool> d_useCurvature; ///< use the curvature of the mesh to avoid some self-intersection test

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ public :


Data<sofa::helper::OptionsGroup> d_response; ///< contact response class
Data<std::string> d_responseParams; ///< contact response parameters (syntax: name1=value1 Data<std::string> responseParams;name2=value2 Data<std::string> responseParams;...)
Data<std::string> d_responseParams; ///< contact response parameters (syntax: name1=value1&name2=value2&...)

/// outputsVec fixes the reproducibility problems by storing contacts in the collision detection saved order
/// if not given, it is still working but with eventual reproducibility problems
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ class SOFA_COMPONENT_CONSTRAINT_LAGRANGIAN_CORRECTION_API GenericConstraintCorre

SingleLink<GenericConstraintCorrection, sofa::core::behavior::LinearSolver, BaseLink::FLAG_STOREPATH | BaseLink::FLAG_STRONGLINK> l_linearSolver; ///< Link towards the linear solver used to compute the compliance matrix, requiring the inverse of the linear system matrix
SingleLink<GenericConstraintCorrection, sofa::core::behavior::OdeSolver, BaseLink::FLAG_STOREPATH | BaseLink::FLAG_STRONGLINK> l_ODESolver; ///< Link towards the ODE solver used to recover the integration factors
Data< SReal > d_complianceFactor; ///< Factor applied to the position factor and velocity factor used to calculate compliance matrix.
Data< SReal > d_complianceFactor; ///< Factor applied to the position factor and velocity factor used to calculate compliance matrix

protected:
GenericConstraintCorrection();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -119,7 +119,7 @@ class UncoupledConstraintCorrection : public sofa::core::behavior::ConstraintCor
SOFA_ATTRIBUTE_DEPRECATED__RENAME_DATA_IN_CONSTRAINT_LAGRANGIAN_CORRECTION()
Data<bool> f_verbose;

core::topology::PointData< VecReal > d_compliance; ///< Rigid compliance value: 1st value for translations, 6 others for upper-triangular part of symmetric 3x3 rotation compliance matrix
core::topology::PointData< VecReal > d_compliance; ///< Compliance value on each dof. If Rigid compliance (7 values): 1st value for translations, 6 others for upper-triangular part of symmetric 3x3 rotation compliance matrix

Data< Real > d_defaultCompliance; ///< Default compliance value for new dof or if all should have the same (in which case compliance vector should be empty)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -102,7 +102,7 @@ inline sofa::defaulttype::RigidDeriv<3, Real> UncoupledConstraintCorrection_comp
template<class DataTypes>
UncoupledConstraintCorrection<DataTypes>::UncoupledConstraintCorrection(sofa::core::behavior::MechanicalState<DataTypes> *mm)
: Inherit(mm)
, d_compliance(initData(&d_compliance, "compliance", "compliance value on each dof. If Rigid compliance (7 values): 1st value for translations, 6 others for upper-triangular part of symmetric 3x3 rotation compliance matrix"))
, d_compliance(initData(&d_compliance, "compliance", "Compliance value on each dof. If Rigid compliance (7 values): 1st value for translations, 6 others for upper-triangular part of symmetric 3x3 rotation compliance matrix"))
, d_defaultCompliance(initData(&d_defaultCompliance, (Real)0.00001, "defaultCompliance", "Default compliance value for new dof or if all should have the same (in which case compliance vector should be empty)"))
, d_verbose(initData(&d_verbose, false, "verbose", "Dump the constraint matrix at each iteration") )
, d_correctionVelocityFactor(initData(&d_correctionVelocityFactor, (Real)1.0, "correctionVelocityFactor", "Factor applied to the constraint forces when correcting the velocities"))
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -113,7 +113,7 @@ class BilateralLagrangianConstraint : public PairInteractionConstraint<DataTypes
VecCoord initialDifference;

Data<double> d_numericalTolerance; ///< a real value specifying the tolerance during the constraint solving. (default=0.0001
Data<bool> d_activate; ///< bool to control constraint activation
Data<bool> d_activate; ///< control constraint activation (true by default)
Data<bool> d_keepOrientDiff; ///< keep the initial difference in orientation (only for rigids)


Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,9 +41,9 @@ using sofa::type::Vec;
template<class DataTypes>
BilateralLagrangianConstraint<DataTypes>::BilateralLagrangianConstraint(MechanicalState* object1, MechanicalState* object2)
: Inherit(object1, object2)
, d_m1(initData(&d_m1, "first_point", "index of the constraint on the first model"))
, d_m2(initData(&d_m2, "second_point", "index of the constraint on the second model"))
, d_restVector(initData(&d_restVector, "rest_vector", "Relative position to maintain between attached points (optional)"))
, d_m1(initData(&d_m1, "first_point","index of the constraint on the first model (object1)"))
, d_m2(initData(&d_m2, "second_point","index of the constraint on the second model (object2)"))
, d_restVector(initData(&d_restVector, "rest_vector","Relative position to maintain between attached points (optional)"))
, d_numericalTolerance(initData(&d_numericalTolerance, 0.0001, "numericalTolerance",
"a real value specifying the tolerance during the constraint solving. (optional, default=0.0001)") )
, d_activate( initData(&d_activate, true, "activate", "control constraint activation (true by default)"))
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ class FixedLagrangianConstraint : public core::behavior::Constraint<DataTypes>
sofa::type::vector<Deriv> m_prevForces;

SetIndex d_indices;
Data<bool> d_fixAll;
Data<bool> d_fixAll; ///< If true, fix all points

FixedLagrangianConstraint(MechanicalState* object = nullptr);
virtual ~FixedLagrangianConstraint() {}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ class SlidingLagrangianConstraint : public core::behavior::PairInteractionConstr
Data<int> d_m1; ///< index of the spliding point on the first model
Data<int> d_m2a; ///< index of one end of the sliding axis
Data<int> d_m2b; ///< index of the other end of the sliding axis
Data<Deriv> d_force; ///< interaction force
Data<Deriv> d_force; ///< force (impulse) used to solve the constraint

Real m_dist; // constraint violation
Real m_thirdConstraint; // 0 if A<proj<B, -1 if proj<A, 1 if B<proj
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ class SOFA_COMPONENT_CONSTRAINT_LAGRANGIAN_SOLVER_API GenericConstraintSolver :
ConstraintProblem* getConstraintProblem() override;
void lockConstraintProblem(sofa::core::objectmodel::BaseObject* from, ConstraintProblem* p1, ConstraintProblem* p2 = nullptr) override;

Data< sofa::helper::OptionsGroup > d_resolutionMethod; ///< Method used to solve the constraint problem, among: \"ProjectedGaussSeidel\", \"UnbuiltGaussSeidel\" or \"for NonsmoothNonlinearConjugateGradient\"
Data< sofa::helper::OptionsGroup > d_resolutionMethod; ///< Method used to solve the constraint problem, among: "ProjectedGaussSeidel", "UnbuiltGaussSeidel" or "for NonsmoothNonlinearConjugateGradient"

SOFA_ATTRIBUTE_DEPRECATED__RENAME_DATA_IN_CONSTRAINT_LAGRANGIAN_SOLVER()
Data<int> maxIt;
Expand Down Expand Up @@ -110,8 +110,8 @@ class SOFA_COMPONENT_CONSTRAINT_LAGRANGIAN_SOLVER_API GenericConstraintSolver :
Data<SReal> d_sor; ///< Successive Over Relaxation parameter (0-2)
Data<bool> d_scaleTolerance; ///< Scale the error tolerance with the number of constraints
Data<bool> d_allVerified; ///< All contraints must be verified (each constraint's error < tolerance)
Data<int> d_newtonIterations; ///< Maximum iteration number of Newton (for the NNCG solver only)
Data<bool> d_multithreading; ///< Compliances built concurrently
Data<int> d_newtonIterations; ///< Maximum iteration number of Newton (for the NonsmoothNonlinearConjugateGradient solver only)
Data<bool> d_multithreading; ///< Build compliances concurrently
Data<bool> d_computeGraphs; ///< Compute graphs of errors and forces during resolution
Data<std::map < std::string, sofa::type::vector<SReal> > > d_graphErrors; ///< Sum of the constraints' errors at each iteration
Data<std::map < std::string, sofa::type::vector<SReal> > > d_graphConstraints; ///< Graph of each constraint's error at the end of the resolution
Expand All @@ -123,7 +123,7 @@ class SOFA_COMPONENT_CONSTRAINT_LAGRANGIAN_SOLVER_API GenericConstraintSolver :
Data<int> d_currentIterations; ///< OUTPUT: current number of constraint groups
Data<SReal> d_currentError; ///< OUTPUT: current error
Data<bool> d_reverseAccumulateOrder; ///< True to accumulate constraints from nodes in reversed order (can be necessary when using multi-mappings or interaction constraints not following the node hierarchy)
Data<type::vector< SReal >> d_constraintForces; ///< OUTPUT: The Data constraintForces is used to provide the intensities of constraint forces in the simulation. The user can easily check the constraint forces from the GenericConstraint component interface.
Data<type::vector< SReal >> d_constraintForces; ///< OUTPUT: constraint forces (stored only if computeConstraintForces=True)
Data<bool> d_computeConstraintForces; ///< The indices of the constraintForces to store in the constraintForce data field.

sofa::core::MultiVecDerivId getLambda() const override;
Expand Down
Loading

0 comments on commit 459f806

Please sign in to comment.