diff --git a/src/main/java/us/ihmc/mecano/algorithms/CenterOfMassJacobian.java b/src/main/java/us/ihmc/mecano/algorithms/CenterOfMassJacobian.java index 3ebd009..18664c8 100644 --- a/src/main/java/us/ihmc/mecano/algorithms/CenterOfMassJacobian.java +++ b/src/main/java/us/ihmc/mecano/algorithms/CenterOfMassJacobian.java @@ -51,13 +51,9 @@ public class CenterOfMassJacobian implements ReferenceFrameHolder * expressed in the center of mass frame. */ private final ReferenceFrame rootFrame; - /** - * Defines the multi-body system to use with this calculator. - */ + /** Defines the multi-body system to use with this calculator. */ private final MultiBodySystemReadOnly input; - /** - * The root of the internal recursive algorithm. - */ + /** The root of the internal recursive algorithm. */ private final RecursionStep initialRecursionStep; /** * Only the first pass of this algorithm has to be recursive, the two other passes can be iterative @@ -65,36 +61,22 @@ public class CenterOfMassJacobian implements ReferenceFrameHolder */ private final RecursionStep[] recursionSteps; - /** - * The center of mass Jacobian. - */ + /** The center of mass Jacobian. */ private final DMatrixRMaj jacobianMatrix; - /** - * Matrix containing the velocities of the joints to consider. - */ + /** Matrix containing the velocities of the joints to consider. */ private final DMatrixRMaj jointVelocityMatrix; - /** - * Intermediate variable for garbage free operations. - */ + /** Intermediate variable for garbage free operations. */ private final DMatrixRMaj centerOfMassVelocityMatrix = new DMatrixRMaj(3, 1); - /** - * Intermediate variable to store one column of the Jacobian matrix. - */ + /** Intermediate variable to store one column of the Jacobian matrix. */ private final FixedFrameVector3DBasics jacobianColumn; - /** - * Intermediate variable to store the unit-twist of the parent joint. - */ + /** Intermediate variable to store the unit-twist of the parent joint. */ private final Twist jointUnitTwist = new Twist(); - /** - * The center of mass velocity. - */ + /** The center of mass velocity. */ private final FixedFrameVector3DBasics centerOfMassVelocity = MecanoFactories.newFixedFrameVector3DBasics(this); - /** - * Whether the Jacobian has been updated since the last call to {@link #reset()}. - */ + /** Whether the Jacobian has been updated since the last call to {@link #reset()}. */ private boolean isJacobianUpToDate = false; /** * Whether the center of mass velocity has been updated since the last call to {@link #reset()}. diff --git a/src/main/java/us/ihmc/mecano/algorithms/CentroidalMomentumCalculator.java b/src/main/java/us/ihmc/mecano/algorithms/CentroidalMomentumCalculator.java index 49f566f..0bb4f69 100644 --- a/src/main/java/us/ihmc/mecano/algorithms/CentroidalMomentumCalculator.java +++ b/src/main/java/us/ihmc/mecano/algorithms/CentroidalMomentumCalculator.java @@ -41,61 +41,35 @@ */ public class CentroidalMomentumCalculator implements ReferenceFrameHolder { - /** - * Defines the multi-body system to use with this calculator. - */ + /** Defines the multi-body system to use with this calculator. */ private final MultiBodySystemReadOnly input; - /** - * The center of mass centroidal momentum matrix. - */ + /** The center of mass centroidal momentum matrix. */ private final ReferenceFrame matrixFrame; - /** - * Array for each iteration of this algorithm. - */ + /** Array for each iteration of this algorithm. */ private final IterativeStep[] iterativeSteps; - /** - * Intermediate variable to store the unit-twist of the parent joint. - */ + /** Intermediate variable to store the unit-twist of the parent joint. */ private final Twist jointUnitTwist; - /** - * Intermediate variable for garbage free operations. - */ + /** Intermediate variable for garbage free operations. */ private final Twist intermediateUnitTwist; - /** - * Intermediate variable to store one column of the centroidal momentum matrix. - */ + /** Intermediate variable to store one column of the centroidal momentum matrix. */ private final Momentum unitMomentum; - /** - * Intermediate variable for garbage free operations. - */ + /** Intermediate variable for garbage free operations. */ private final Momentum intermediateMomentum; - /** - * The total momentum of the system. - */ + /** The total momentum of the system. */ private final FixedFrameMomentumBasics momentum; - /** - * The center of mass velocity. - */ + /** The center of mass velocity. */ private final FixedFrameVector3DBasics centerOfMassVelocity; - /** - * The centroidal momentum matrix. - */ + /** The centroidal momentum matrix. */ private final DMatrixRMaj centroidalMomentumMatrix; - /** - * Matrix containing the velocities of the joints to consider. - */ + /** Matrix containing the velocities of the joints to consider. */ private final DMatrixRMaj jointVelocityMatrix; - /** - * The total momentum of the system. - */ + /** The total momentum of the system. */ private final DMatrixRMaj momentumMatrix = new DMatrixRMaj(6, 1); - /** - * The total system mass. - */ + /** The total system mass. */ private double totalMass = 0.0; /** @@ -106,13 +80,9 @@ public class CentroidalMomentumCalculator implements ReferenceFrameHolder * Whether the joint velocity matrix has been updated since the last call to {@link #reset()}. */ private boolean isJointVelocityMatrixUpToDate = false; - /** - * Whether the momentum has been updated since the last call to {@link #reset()}. - */ + /** Whether the momentum has been updated since the last call to {@link #reset()}. */ private boolean isMomentumUpToDate = false; - /** - * Whether the total mass has been updated since the last call to {@link #reset()}. - */ + /** Whether the total mass has been updated since the last call to {@link #reset()}. */ private boolean isTotalMassUpToDate = false; /** * Whether the center of mass velocity has been updated since the last call to {@link #reset()}. @@ -524,7 +494,7 @@ public void passTwo() *
        * h = (∑i=0:n Ii) * T ≡ ∑i=0:n (Ii * T)
        * 
- *

+ * * where h is the resulting unit-momentum, Ii is the spatial inertia of * the ith body, and T is the unit-twist. * diff --git a/src/main/java/us/ihmc/mecano/algorithms/CentroidalMomentumRateCalculator.java b/src/main/java/us/ihmc/mecano/algorithms/CentroidalMomentumRateCalculator.java index 25bf2ce..8726c6a 100644 --- a/src/main/java/us/ihmc/mecano/algorithms/CentroidalMomentumRateCalculator.java +++ b/src/main/java/us/ihmc/mecano/algorithms/CentroidalMomentumRateCalculator.java @@ -36,7 +36,7 @@ * -- h = A * qDDot + | -- A | * qDot = A * qDDot + b * dt \ dt / * - *

+ * * where h is the system's momentum, qDot and qDDot are the joint * velocity and acceleration vectors, A is the centroidal momentum matrix, and b * represents the convective term that this calculator also compute and that can be obtained via @@ -51,17 +51,11 @@ */ public class CentroidalMomentumRateCalculator implements ReferenceFrameHolder { - /** - * Defines the multi-body system to use with this calculator. - */ + /** Defines the multi-body system to use with this calculator. */ private final MultiBodySystemReadOnly input; - /** - * The center of mass centroidal momentum matrix. - */ + /** The center of mass centroidal momentum matrix. */ private final ReferenceFrame matrixFrame; - /** - * The root of the internal recursive algorithm. - */ + /** The root of the internal recursive algorithm. */ private final RecursionStep initialRecursionStep; /** * Only the first pass of this algorithm has to be recursive, the rest can be iterative which can @@ -69,68 +63,42 @@ public class CentroidalMomentumRateCalculator implements ReferenceFrameHolder */ private final RecursionStep[] recursionSteps; private final Map rigidBodyToRecursionStepMap; - /** - * Intermediate variable to store the unit-twist of the parent joint. - */ + /** Intermediate variable to store the unit-twist of the parent joint. */ private final Twist jointUnitTwist; - /** - * Intermediate variable for garbage free operations. - */ + /** Intermediate variable for garbage free operations. */ private final Twist intermediateTwist; - /** - * Intermediate variable to store one column of the centroidal momentum matrix. - */ + /** Intermediate variable to store one column of the centroidal momentum matrix. */ private final Momentum unitMomentum; - /** - * Intermediate variable for garbage free operations. - */ + /** Intermediate variable for garbage free operations. */ private final Momentum intermediateMomentum; - /** - * The centroidal momentum matrix. - */ + /** The centroidal momentum matrix. */ private final DMatrixRMaj centroidalMomentumMatrix; /** * The convective term resulting from the Coriolis and centrifugal forces acting on the system. */ private final SpatialForce biasSpatialForce; - /** - * The total momentum of the system. - */ + /** The total momentum of the system. */ private final FixedFrameMomentumBasics momentum; - /** - * The total rate of change of momentum of the system. - */ + /** The total rate of change of momentum of the system. */ private final FixedFrameSpatialForceBasics momentumRate; - /** - * The center of mass velocity. - */ + /** The center of mass velocity. */ private final FixedFrameVector3DBasics centerOfMassVelocity; - /** - * The center of mass acceleration. - */ + /** The center of mass acceleration. */ private final FixedFrameVector3DBasics centerOfMassAcceleration; /** * The convective term resulting from the Coriolis and centrifugal forces acting on the system. */ private final DMatrixRMaj biasSpatialForceMatrix = new DMatrixRMaj(6, 1); - /** - * Matrix containing the velocities of the joints to consider. - */ + /** Matrix containing the velocities of the joints to consider. */ private final DMatrixRMaj jointVelocityMatrix; - /** - * Matrix containing the accelerations of the joints to consider. - */ + /** Matrix containing the accelerations of the joints to consider. */ private final DMatrixRMaj jointAccelerationMatrix; - /** - * The total momentum of the system. - */ + /** The total momentum of the system. */ private final DMatrixRMaj momentumMatrix = new DMatrixRMaj(6, 1); - /** - * The total system mass. - */ + /** The total system mass. */ private double totalMass = 0.0; /** @@ -145,17 +113,13 @@ public class CentroidalMomentumRateCalculator implements ReferenceFrameHolder * Whether the joint acceleration matrix has been updated since the last call to {@link #reset()}. */ private boolean isJointAccelerationMatrixUpToDate = false; - /** - * Whether the momentum has been updated since the last call to {@link #reset()}. - */ + /** Whether the momentum has been updated since the last call to {@link #reset()}. */ private boolean isMomentumUpToDate = false; /** * Whether the rate of change of momentum has been updated since the last call to {@link #reset()}. */ private boolean isMomentumRateUpToDate = false; - /** - * Whether the total mass has been updated since the last call to {@link #reset()}. - */ + /** Whether the total mass has been updated since the last call to {@link #reset()}. */ private boolean isTotalMassUpToDate = false; /** * Whether the center of mass velocity has been updated since the last call to {@link #reset()}. @@ -591,8 +555,8 @@ public DMatrixRMaj getBiasSpatialForceMatrix() /** * Computes the convective term while considering only a subset of the multi-body system. * - * @param jointSelection the only joints that are considered. - * @param biasSpatialForceToPack the matrix used to store the result. Modified. + * @param jointSelection the only joints that are considered. + * @param biasSpatialForceMatrixToPack the matrix used to store the result. Modified. * @return {@code true} if the convective term was successfully computed, {@code false} if not all * the joints could be found and the result is inaccurate. */ @@ -636,9 +600,7 @@ public ReferenceFrame getReferenceFrame() */ private class RecursionStep { - /** - * The rigid-body for which this recursion is. - */ + /** The rigid-body for which this recursion is. */ private final RigidBodyReadOnly rigidBody; /** * Body inertia: usually equal to {@code rigidBody.getInertial()}. However, if at least one child of @@ -655,9 +617,7 @@ private class RecursionStep * joint. */ private final DMatrixRMaj centroidalMomentumMatrixBlock; - /** - * The Coriolis and centrifugal accelerations for this rigid-body. - */ + /** The Coriolis and centrifugal accelerations for this rigid-body. */ private final SpatialAcceleration coriolisBodyAcceleration; /** * Intermediate variable to prevent repetitive calculation of a transform between this rigid-body's @@ -785,7 +745,7 @@ public void passTwo() *

        * h = (∑i=0:n Ii) * T ≡ ∑i=0:n (Ii * T)
        * 
- *

+ * * where h is the resulting unit-momentum, Ii is the spatial inertia of * the ith body, and T is the unit-twist. * diff --git a/src/main/java/us/ihmc/mecano/algorithms/CompositeRigidBodyMassMatrixCalculator.java b/src/main/java/us/ihmc/mecano/algorithms/CompositeRigidBodyMassMatrixCalculator.java index e29e393..bedb7ec 100644 --- a/src/main/java/us/ihmc/mecano/algorithms/CompositeRigidBodyMassMatrixCalculator.java +++ b/src/main/java/us/ihmc/mecano/algorithms/CompositeRigidBodyMassMatrixCalculator.java @@ -47,7 +47,7 @@ *

  * τ = H(q) qDDot + C(q, qDot) qDot + G(q) + ∑i Ji Wi, ext
  * 
- *

+ * * where τ, q, qDot, and qDDot are the joint effort, * configuration, velocity, and acceleration vectors, H is the joint-space inertia matrix * or also called here mass matrix, C is the Coriolis and centrifugal matrix, G @@ -70,7 +70,7 @@ * -- = A * qDDot + -- * qDot = A * qDDot + b * dt dt * - *

+ * * where h is the system's momentum and A is the centroidal momentum matrix, the * term introduce b represents the convective term. *

@@ -85,37 +85,25 @@ */ public class CompositeRigidBodyMassMatrixCalculator { - /** - * Defines the multi-body system to use with this calculator. - */ + /** Defines the multi-body system to use with this calculator. */ private final MultiBodySystemReadOnly input; - /** - * The root of the internal recursive algorithm. - */ + /** The root of the internal recursive algorithm. */ private final CompositeRigidBodyInertia rootCompositeInertia; /** * Array of all the recursion steps but the root. This allows to efficiently iterate through when * computing the centroidal momentum matrix. */ private final CompositeRigidBodyInertia[] compositeInertias; - /** - * The mass matrix of the system. - */ + /** The mass matrix of the system. */ private final DMatrixRMaj massMatrix; private final DMatrixRMaj coriolisMatrix; - /** - * Intermediate variable to store the child inertia. - */ + /** Intermediate variable to store the child inertia. */ private final SpatialInertia childInertia = new SpatialInertia(); - /** - * Intermediate variable to store the child factorized inertia. - */ + /** Intermediate variable to store the child factorized inertia. */ private final FactorizedBodyInertia childFactorizedInertia = new FactorizedBodyInertia(); - /** - * Intermediate variable for garbage free operations. - */ + /** Intermediate variable for garbage free operations. */ private final Twist intermediateTwist = new Twist(); /** * Intermediate variable to store the wrench resulting from Coriolis and centrifugal accelerations. @@ -134,9 +122,7 @@ public class CompositeRigidBodyMassMatrixCalculator */ private final DMatrixRMaj centroidalConvectiveTermMatrix = new DMatrixRMaj(6, 1); - /** - * Frame in which the centroidal momentum matrix and its convective term are to be calculated. - */ + /** Frame in which the centroidal momentum matrix and its convective term are to be calculated. */ private ReferenceFrame centroidalMomentumFrame; /** * The centroidal momentum matrix represents the map from joint velocity space to momentum space. @@ -483,13 +469,9 @@ private class CompositeRigidBodyInertia */ private final int[] jointIndices; - /** - * Spatial inertia representing the subtree starting off this rigid-body. - */ + /** Spatial inertia representing the subtree starting off this rigid-body. */ private final SpatialInertia compositeInertia; - /** - * Spatial factorized inertia representing the subtree starting off this rigid-body. - */ + /** Spatial factorized inertia representing the subtree starting off this rigid-body. */ private final FactorizedBodyInertia compositeFactorizedInertia; /** @@ -498,18 +480,12 @@ private class CompositeRigidBodyInertia */ private final Momentum[] F1, F2, F3; private final DMatrixRMaj motionSubspaceDot; - /** - * This parent joint unit-twists. - */ + /** This parent joint unit-twists. */ private final Twist[] unitTwists; - /** - * The time-derivative of this parent joint unit-twists. - */ + /** The time-derivative of this parent joint unit-twists. */ private final SpatialAcceleration[] unitTwistDots; - /** - * The Coriolis and centrifugal accelerations for this rigid-body. - */ + /** The Coriolis and centrifugal accelerations for this rigid-body. */ private final SpatialAcceleration coriolisBodyAcceleration; /** * Transform from {@code this.getFrameAfterJoint()} to {@code parent.getFrameAfterJoint()} used to diff --git a/src/main/java/us/ihmc/mecano/algorithms/ForwardDynamicsCalculator.java b/src/main/java/us/ihmc/mecano/algorithms/ForwardDynamicsCalculator.java index a326f27..38866d7 100644 --- a/src/main/java/us/ihmc/mecano/algorithms/ForwardDynamicsCalculator.java +++ b/src/main/java/us/ihmc/mecano/algorithms/ForwardDynamicsCalculator.java @@ -56,22 +56,14 @@ public enum JointSourceMode ACCELERATION_SOURCE; } - /** - * Defines the multi-body system to use with this calculator. - */ + /** Defines the multi-body system to use with this calculator. */ private final MultiBodySystemReadOnly input; - /** - * The root of the internal recursive algorithm. - */ + /** The root of the internal recursive algorithm. */ private final ArticulatedBodyRecursionStep initialRecursionStep; - /** - * Map to quickly retrieve information for each rigid-body. - */ + /** Map to quickly retrieve information for each rigid-body. */ private final Map rigidBodyToRecursionStepMap = new LinkedHashMap<>(); - /** - * For iterating over each rigid-body quickly. - */ + /** For iterating over each rigid-body quickly. */ private final ArticulatedBodyRecursionStep[] articulatedBodyRecursionSteps; private boolean isJointTauOutputDirty = true; @@ -738,9 +730,7 @@ public RigidBodyAccelerationProvider getAccelerationProvider(boolean considerVel return considerVelocities ? accelerationProvider : zeroVelocityAccelerationProvider; } - /** - * Intermediate result used for garbage free operations. - */ + /** Intermediate result used for garbage free operations. */ private final SpatialForce jointForceFromChild = new SpatialForce(); /** @@ -798,7 +788,7 @@ class ArticulatedBodyRecursionStep * = IA - U ( ST U )-1 UT * = IA - IA S ( ST IA S )-1 ST IA * - *

+ * * where IA is this handle's articulated-body inertia, and S is the * parent joint motion subspace. */ @@ -827,7 +817,7 @@ class ArticulatedBodyRecursionStep *

        * U = IA S
        * 
- *

+ * * where IA is this handle's articulated-body inertia, and S is the * parent joint motion subspace. */ @@ -839,7 +829,7 @@ class ArticulatedBodyRecursionStep * D = ST U * = ST IA S * - *

+ * * where IA is this handle's articulated-body inertia, and S is the * parent joint motion subspace. */ @@ -851,7 +841,7 @@ class ArticulatedBodyRecursionStep * D-1 = ( ST U )-1 * = ( ST IA S )-1 * - *

+ * * where IA is this handle's articulated-body inertia, and S is the * parent joint motion subspace. */ @@ -863,7 +853,7 @@ class ArticulatedBodyRecursionStep * U D-1 = U ( ST U )-1 * = IA S ( ST IA S )-1 * - *

+ * * where IA is this handle's articulated-body inertia, and S is the * parent joint motion subspace. */ @@ -875,7 +865,7 @@ class ArticulatedBodyRecursionStep * U D-1 UT = U ( ST U )-1 UT * = IA S ( ST IA S )-1 ST IA * - *

+ * * where IA is this handle's articulated-body inertia, and S is the * parent joint motion subspace. */ @@ -891,7 +881,7 @@ class ArticulatedBodyRecursionStep *

        * u = τ - ST pA
        * 
- *

+ * * where τ is the N-by-1 vector representing the joint effort, N being the number of * DoFs for this joint, S is the joint motion subspace, and pA some * bias forces exerted on this joint. @@ -903,7 +893,7 @@ class ArticulatedBodyRecursionStep *

        * c = v × ( S qDot )
        * 
- *

+ * * where v is the twist of this body, S the joint motion subspace, and * qDot the N-by-1 vector for this joint velocity, with N being the number of DoFs for this * joint. @@ -916,7 +906,7 @@ class ArticulatedBodyRecursionStep * pa = pA + Ia c + U D-1 u * = pA + Ia c + IA S ( ST IA S )-1 ( τ - ST pA ) * - *

+ * * where pA are the bias forces acting on this joint, Ia is * the apparent articulated-body inertia for the parent, S is the joint motion subspace, * IA this handle's articulated-body inertia, τ this joint effort, diff --git a/src/main/java/us/ihmc/mecano/algorithms/InverseDynamicsCalculator.java b/src/main/java/us/ihmc/mecano/algorithms/InverseDynamicsCalculator.java index aeab976..4a6a732 100644 --- a/src/main/java/us/ihmc/mecano/algorithms/InverseDynamicsCalculator.java +++ b/src/main/java/us/ihmc/mecano/algorithms/InverseDynamicsCalculator.java @@ -40,39 +40,23 @@ public class InverseDynamicsCalculator private static final boolean DEFAULT_CONSIDER_ACCELERATIONS = true; private static final boolean DEFAULT_CONSIDER_CORIOLIS = true; - /** - * Defines the multi-body system to use with this calculator. - */ + /** Defines the multi-body system to use with this calculator. */ private final MultiBodySystemReadOnly input; - /** - * The root of the internal recursive algorithm. - */ + /** The root of the internal recursive algorithm. */ final RecursionStep initialRecursionStep; - /** - * Map to quickly retrieve information for each rigid-body. - */ + /** Map to quickly retrieve information for each rigid-body. */ final Map rigidBodyToRecursionStepMap = new LinkedHashMap<>(); - /** - * Map to quickly retrieve information for each joint. - */ + /** Map to quickly retrieve information for each joint. */ private final Map jointToRecursionStepMap = new LinkedHashMap<>(); - /** - * The input of this algorithm: the acceleration matrix for all the joints to consider. - */ + /** The input of this algorithm: the acceleration matrix for all the joints to consider. */ private final DMatrixRMaj allJointAccelerationMatrix; - /** - * The output of this algorithm: the effort matrix for all the joints to consider. - */ + /** The output of this algorithm: the effort matrix for all the joints to consider. */ private final DMatrixRMaj allJointTauMatrix; - /** - * Whether the effort resulting from the joint accelerations should be considered. - */ + /** Whether the effort resulting from the joint accelerations should be considered. */ private boolean considerJointAccelerations = DEFAULT_CONSIDER_ACCELERATIONS; - /** - * Whether the effort resulting from the Coriolis and centrifugal forces should be considered. - */ + /** Whether the effort resulting from the Coriolis and centrifugal forces should be considered. */ private boolean considerCoriolisAndCentrifugalForces = DEFAULT_CONSIDER_CORIOLIS; /** * Extension of this algorithm into an acceleration provider that be used instead of a @@ -97,10 +81,10 @@ public class InverseDynamicsCalculator * @deprecated Use the following code snippet instead: * *

-    *                                                                                                                               InverseDynamicsCalculator calculator = new InverseDynamicsCalculator(rootBody);
-    *                                                                                                                               calculator.setConsiderCoriolisAndCentrifugalForces(considerCoriolisAndCentrifugalForces);
-    *                                                                                                                               calculator.setConsiderJointAccelerations(considerJointAccelerations);
-    *                                                                                                                               
+ * InverseDynamicsCalculator calculator = new InverseDynamicsCalculator(rootBody); + * calculator.setConsiderCoriolisAndCentrifugalForces(considerCoriolisAndCentrifugalForces); + * calculator.setConsiderJointAccelerations(considerJointAccelerations); + * */ @Deprecated public InverseDynamicsCalculator(RigidBodyReadOnly rootBody, boolean considerCoriolisAndCentrifugalForces, boolean considerJointAccelerations) @@ -127,10 +111,10 @@ public InverseDynamicsCalculator(RigidBodyReadOnly rootBody, boolean considerCor * @deprecated Use the following code snippet instead: * *
-    *                                                                                                                               InverseDynamicsCalculator calculator = new InverseDynamicsCalculator(input);
-    *                                                                                                                               calculator.setConsiderCoriolisAndCentrifugalForces(considerCoriolisAndCentrifugalForces);
-    *                                                                                                                               calculator.setConsiderJointAccelerations(considerJointAccelerations);
-    *                                                                                                                               
+ * InverseDynamicsCalculator calculator = new InverseDynamicsCalculator(input); + * calculator.setConsiderCoriolisAndCentrifugalForces(considerCoriolisAndCentrifugalForces); + * calculator.setConsiderJointAccelerations(considerJointAccelerations); + * */ @Deprecated public InverseDynamicsCalculator(MultiBodySystemReadOnly input, boolean considerCoriolisAndCentrifugalForces, boolean considerJointAccelerations) @@ -167,10 +151,10 @@ public InverseDynamicsCalculator(MultiBodySystemReadOnly input, boolean consider * @deprecated Use the following code snippet instead: * *
-    *                                                                                                                               InverseDynamicsCalculator calculator = new InverseDynamicsCalculator(input, considerIgnoredSubtreesInertia);
-    *                                                                                                                               calculator.setConsiderCoriolisAndCentrifugalForces(considerCoriolisAndCentrifugalForces);
-    *                                                                                                                               calculator.setConsiderJointAccelerations(considerJointAccelerations);
-    *                                                                                                                               
+ * InverseDynamicsCalculator calculator = new InverseDynamicsCalculator(input, considerIgnoredSubtreesInertia); + * calculator.setConsiderCoriolisAndCentrifugalForces(considerCoriolisAndCentrifugalForces); + * calculator.setConsiderJointAccelerations(considerJointAccelerations); + * */ @Deprecated public InverseDynamicsCalculator(MultiBodySystemReadOnly input, @@ -712,9 +696,7 @@ default String getSimpleNameForParent() } } - /** - * Intermediate result used for garbage free operations. - */ + /** Intermediate result used for garbage free operations. */ private final SpatialForce jointForceFromChild = new SpatialForce(); /** diff --git a/src/main/java/us/ihmc/mecano/algorithms/JointTorqueRegressorCalculator.java b/src/main/java/us/ihmc/mecano/algorithms/JointTorqueRegressorCalculator.java index e86ee59..99a3e1c 100644 --- a/src/main/java/us/ihmc/mecano/algorithms/JointTorqueRegressorCalculator.java +++ b/src/main/java/us/ihmc/mecano/algorithms/JointTorqueRegressorCalculator.java @@ -304,9 +304,7 @@ public enum SpatialInertiaBasisOption { M, MCOM_X, MCOM_Y, MCOM_Z, I_XX, I_XY, I_XZ, I_YY, I_YZ, I_ZZ; - /** - * Utility method to get all the basis options, for use in loops. - */ + /** Utility method to get all the basis options, for use in loops. */ public static final SpatialInertiaBasisOption[] values = values(); /** diff --git a/src/main/java/us/ihmc/mecano/algorithms/MultiBodyGravityGradientCalculator.java b/src/main/java/us/ihmc/mecano/algorithms/MultiBodyGravityGradientCalculator.java index cac1b2d..2a8c638 100644 --- a/src/main/java/us/ihmc/mecano/algorithms/MultiBodyGravityGradientCalculator.java +++ b/src/main/java/us/ihmc/mecano/algorithms/MultiBodyGravityGradientCalculator.java @@ -47,26 +47,18 @@ */ public class MultiBodyGravityGradientCalculator { - /** - * Defines the multi-body system to use with this calculator. - */ + /** Defines the multi-body system to use with this calculator. */ private final MultiBodySystemReadOnly input; /** * Output of this algorithm: joint efforts due to gravity and external wrenches for all the joint to * consider. */ private final DMatrixRMaj tauMatrix; - /** - * Output of this algorithm: gradient of the {@link #tauMatrix}. - */ + /** Output of this algorithm: gradient of the {@link #tauMatrix}. */ private final DMatrixRMaj tauGradientMatrix; - /** - * The root of the internal recursive algorithm. - */ + /** The root of the internal recursive algorithm. */ private final AlgorithmStep initialStep; - /** - * Map to quickly retrieve information for each rigid-body. - */ + /** Map to quickly retrieve information for each rigid-body. */ private final Map rigidBodyToAlgorithmStepMap = new LinkedHashMap<>(); /** @@ -321,23 +313,15 @@ public DMatrixRMaj getTauGradientMatrix() return tauGradientMatrix; } - /** - * Intermediate variable used to compute {@link AlgorithmStep#subTreeExternalSpatialForce}. - */ + /** Intermediate variable used to compute {@link AlgorithmStep#subTreeExternalSpatialForce}. */ private final SpatialForce childExternalSpatialForce = new SpatialForce(); - /** - * Intermediate variable used to compute {@link AlgorithmStep#subTreeCoM}. - */ + /** Intermediate variable used to compute {@link AlgorithmStep#subTreeCoM}. */ private final FramePoint3D childCoM = new FramePoint3D(); - /** - * This class represents a single step for this algorithm. - */ + /** This class represents a single step for this algorithm. */ private class AlgorithmStep { - /** - * The rigid-body for which this step is for. - */ + /** The rigid-body for which this step is for. */ private final RigidBodyReadOnly rigidBody; /** * Body inertia: usually equal to {@code rigidBody.getInertial()}. However, if at least one child of @@ -345,17 +329,11 @@ private class AlgorithmStep * attached to the ignored joint. */ private final SpatialInertia bodyInertia; - /** - * The corresponding matrix indices for each of this step's joint degree of freedom. - */ + /** The corresponding matrix indices for each of this step's joint degree of freedom. */ private final int[] jointIndices; - /** - * The algorithm step for the parent of this step's rigid-body. - */ + /** The algorithm step for the parent of this step's rigid-body. */ private final AlgorithmStep parent; - /** - * The algorithm steps for the children of this step's rigid-body. - */ + /** The algorithm steps for the children of this step's rigid-body. */ private final List children = new ArrayList<>(); /** @@ -378,17 +356,11 @@ private class AlgorithmStep */ private boolean hasSubTreeExternalWrench = false; - /** - * The total mass of the subtree starting at this step. - */ + /** The total mass of the subtree starting at this step. */ private double subTreeMass; - /** - * The total center of mass of the subtree starting at this step. - */ + /** The total center of mass of the subtree starting at this step. */ private final FramePoint3D subTreeCoM = new FramePoint3D(); - /** - * The sum of external wrenches applied to the subtree starting at this step. - */ + /** The sum of external wrenches applied to the subtree starting at this step. */ private final SpatialForce subTreeExternalSpatialForce = new SpatialForce(); /** * The resulting force due to gravity on the subtree at the sutree's center of mass expressed in @@ -512,9 +484,7 @@ public void passOne() subTreeCoM.scale(1.0 / subTreeMass); } - /** - * From leaves to root, compute the elements of the gradient matrix. - */ + /** From leaves to root, compute the elements of the gradient matrix. */ public void passTwo() { for (int i = 0; i < children.size(); i++)