/** * Creates a new calculator for the subtree that starts off the given {@code rootBody}. * * @param rootBody the start of subtree for which the centroidal momentum matrix is to be computed. * Not modified. * @param matrixFrame the frame in which the centroidal momentum matrix is to be expressed. */ public CentroidalMomentumCalculator(RigidBodyReadOnly rootBody, ReferenceFrame matrixFrame) { this(MultiBodySystemReadOnly.toMultiBodySystemInput(rootBody), matrixFrame); }
/** * Creates a new calculator for the subtree that starts off the given {@code rootBody}. * * @param rootBody the start of subtree for which the mass matrix is to be computed. Not modified. */ public CompositeRigidBodyMassMatrixCalculator(RigidBodyReadOnly rootBody) { this(MultiBodySystemReadOnly.toMultiBodySystemInput(rootBody)); }
/** * Creates a new calculator for the subtree that starts off the given {@code rootBody}. * * @param rootBody the start of subtree for which the center of mass Jacobian is to be computed. Not * modified. * @param jacobianFrame the frame in which the center of mass Jacobian is to be expressed. */ public CenterOfMassJacobian(RigidBodyReadOnly rootBody, ReferenceFrame jacobianFrame) { this(MultiBodySystemReadOnly.toMultiBodySystemInput(rootBody), jacobianFrame); }
/** * Creates a new calculator for the subtree that starts off the given {@code rootBody}. * * @param rootBody the start of subtree for which the centroidal momentum matrix and bias force is * to be computed. Not modified. * @param matrixFrame the frame in which the centroidal momentum matrix is to be expressed. */ public CentroidalMomentumRateCalculator(RigidBodyReadOnly rootBody, ReferenceFrame matrixFrame) { this(MultiBodySystemReadOnly.toMultiBodySystemInput(rootBody), matrixFrame); }
/** * Creates a new calculator for the subtree that starts off the given {@code rootBody}. * * @param rootBody the start of subtree for which the mass matrix is to be computed. Not modified. * @param centroidalMomentumFrame the reference frame in which the centroidal momentum matrix and * convective term are to be computed. Only needed when this calculator is used to * calculate the centroidal momentum matrix and convective term. */ public CompositeRigidBodyMassMatrixCalculator(RigidBodyReadOnly rootBody, ReferenceFrame centroidalMomentumFrame) { this(MultiBodySystemReadOnly.toMultiBodySystemInput(rootBody), centroidalMomentumFrame); }
/** * Creates a new calculator for the subtree that starts off the given {@code rootBody}. * * @param rootBody the start of subtree for which the center of mass is to be computed. Not * modified. * @param referenceFrame the frame in which the center of mass is to be expressed. */ public CenterOfMassCalculator(RigidBodyReadOnly rootBody, ReferenceFrame referenceFrame) { this(MultiBodySystemReadOnly.toMultiBodySystemInput(rootBody), referenceFrame); }
/** * Creates a new calculator for the subtree that starts off the given {@code rootBody}. * <p> * A new reference frame at the center of mass is created, the Jacobian is expressed in that * reference frame. The center of mass frame can then be retrieved using * {@link #getReferenceFrame()}. * </p> * * @param rootBody the start of subtree for which the center of mass Jacobian is to be computed. Not * modified. * @param centerOfMassFrameName the name for the new frame at the center of mass. */ public CenterOfMassJacobian(RigidBodyReadOnly rootBody, String centerOfMassFrameName) { this(MultiBodySystemReadOnly.toMultiBodySystemInput(rootBody), centerOfMassFrameName); }
/** * Creates a calculator for computing the joint accelerations for all the descendants of the given * {@code rootBody}. * <p> * Do not forgot to set the gravitational acceleration so this calculator can properly account for * it. * </p> * * @param rootBody the supporting body of the subtree to be evaluated by this calculator. Not * modified. */ public ForwardDynamicsCalculator(RigidBodyReadOnly rootBody) { this(MultiBodySystemReadOnly.toMultiBodySystemInput(rootBody)); }
/** * Creates a calculator for computing the joint efforts for all the descendants of the given * {@code rootBody}. * <p> * Do not forgot to set the gravitational acceleration so this calculator can properly account for * it. * </p> * * @param rootBody the supporting body of the subtree to be evaluated by this calculator. Not * modified. * @param considerCoriolisAndCentrifugalForces whether the effort resulting from the Coriolis and * centrifugal forces should be considered. * @param considerJointAccelerations whether the effort resulting from the joint accelerations * should be considered. */ public InverseDynamicsCalculator(RigidBodyReadOnly rootBody, boolean considerCoriolisAndCentrifugalForces, boolean considerJointAccelerations) { this(MultiBodySystemReadOnly.toMultiBodySystemInput(rootBody), considerCoriolisAndCentrifugalForces, considerJointAccelerations); }
/** * Creates a new input from the given {@code rootBody}. The resulting input will consider all the * joints composing the subtree starting off the given body. * * @param rootBody the support body to the subtree to consider. Not modified. * @return the new input. */ public static MultiBodySystemReadOnly toMultiBodySystemInput(RigidBodyReadOnly rootBody) { return toMultiBodySystemInput(rootBody, Collections.emptyList()); }
/** * Creates a new input from the given {@code rootBody}. The resulting input will consider all the * joints composing the subtree starting off the given body less the given joints to ignore and * their respective descendants. * * @param rootBody the support body to the subtree to consider. Not modified. * @param jointsToIgnore the array of joints to ignore. Not modified. * @return the new input. */ public static MultiBodySystemReadOnly toMultiBodySystemInput(RigidBodyReadOnly rootBody, JointReadOnly[] jointsToIgnore) { return toMultiBodySystemInput(rootBody, Arrays.asList(jointsToIgnore)); }
/** * Creates a new input from the given joints to consider. * <p> * The resulting root body and joints to ignore are automatically evaluated. * </p> * * @param jointsToConsider the joints to consider. Not modified. * @return the new input. */ public static MultiBodySystemReadOnly toMultiBodySystemInput(JointReadOnly[] jointsToConsider) { return toMultiBodySystemInput(Arrays.asList(jointsToConsider)); }