Skip to content

Commit

Permalink
Reducing diff due to formatting.
Browse files Browse the repository at this point in the history
  • Loading branch information
SylvainBertrand committed Jan 10, 2024
1 parent f6c9e4b commit c0946a8
Show file tree
Hide file tree
Showing 8 changed files with 114 additions and 286 deletions.
36 changes: 9 additions & 27 deletions src/main/java/us/ihmc/mecano/algorithms/CenterOfMassJacobian.java
Original file line number Diff line number Diff line change
Expand Up @@ -51,50 +51,32 @@ 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
* which can provide a slight performance improvement.
*/
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()}.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;

/**
Expand All @@ -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()}.
Expand Down Expand Up @@ -524,7 +494,7 @@ public void passTwo()
* <pre>
* h = (&sum;<sub>i=0:n</sub> I<sub>i</sub>) * T &equiv; &sum;<sub>i=0:n</sub> (I<sub>i</sub> * T)
* </pre>
* <p>
*
* where <tt>h</tt> is the resulting unit-momentum, <tt>I<sub>i</sub></tt> is the spatial inertia of
* the i<sup>th</sup> body, and <tt>T</tt> is the unit-twist.
*
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@
* -- h = A * qDDot + | -- A | * qDot = A * qDDot + b
* dt \ dt /
* </pre>
* <p>
*
* where <tt>h</tt> is the system's momentum, <tt>qDot</tt> and <tt>qDDot</tt> are the joint
* velocity and acceleration vectors, <tt>A</tt> is the centroidal momentum matrix, and <tt>b</tt>
* represents the convective term that this calculator also compute and that can be obtained via
Expand All @@ -51,86 +51,54 @@
*/
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
* provide a slight performance improvement.
*/
private final RecursionStep[] recursionSteps;
private final Map<RigidBodyReadOnly, RecursionStep> 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;

/**
Expand All @@ -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()}.
Expand Down Expand Up @@ -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.
*/
Expand Down Expand Up @@ -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
Expand All @@ -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
Expand Down Expand Up @@ -785,7 +745,7 @@ public void passTwo()
* <pre>
* h = (&sum;<sub>i=0:n</sub> I<sub>i</sub>) * T &equiv; &sum;<sub>i=0:n</sub> (I<sub>i</sub> * T)
* </pre>
* <p>
*
* where <tt>h</tt> is the resulting unit-momentum, <tt>I<sub>i</sub></tt> is the spatial inertia of
* the i<sup>th</sup> body, and <tt>T</tt> is the unit-twist.
*
Expand Down
Loading

0 comments on commit c0946a8

Please sign in to comment.