|
||||||||||
PREV CLASS NEXT CLASS | FRAMES NO FRAMES | |||||||||
SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD |
java.lang.Objectus.ihmc.utilities.screwTheory.GeometricJacobian
public class GeometricJacobian
Constructor Summary | |
---|---|
GeometricJacobian(InverseDynamicsJoint[] joints,
ReferenceFrame jacobianFrame)
|
|
GeometricJacobian(InverseDynamicsJoint joint,
java.util.List<Twist> unitTwists,
ReferenceFrame jacobianFrame)
|
|
GeometricJacobian(InverseDynamicsJoint joint,
ReferenceFrame jacobianFrame)
|
|
GeometricJacobian(RigidBody ancestor,
RigidBody descendant,
ReferenceFrame jacobianFrame)
|
Method Summary | |
---|---|
void |
changeFrame(ReferenceFrame jacobianFrame)
|
void |
compute()
Computes the Jacobian. |
org.ejml.data.DenseMatrix64F |
computeJointTorques(Wrench wrench)
returns the joint torque vector that corresponds to the given wrench |
double |
det()
|
RigidBody |
getBase()
|
ReferenceFrame |
getBaseFrame()
|
RigidBody |
getEndEffector()
|
ReferenceFrame |
getEndEffectorFrame()
|
double |
getJacobianEntry(int row,
int column)
Returns one entry from the Jacobian matrix. |
ReferenceFrame |
getJacobianFrame()
|
org.ejml.data.DenseMatrix64F |
getJacobianMatrix()
Returns a reference to the underlying Matrix object. |
InverseDynamicsJoint[] |
getJointsInOrder()
|
int |
getNumberOfColumns()
|
java.lang.String |
getShortInfo()
|
void |
packTwist(Twist twistToPack,
org.ejml.data.DenseMatrix64F jointVelocities)
packs the twist that corresponds to the given joint velocity vector |
java.lang.String |
toString()
|
Methods inherited from class java.lang.Object |
---|
equals, getClass, hashCode, notify, notifyAll, wait, wait, wait |
Constructor Detail |
---|
public GeometricJacobian(InverseDynamicsJoint joint, java.util.List<Twist> unitTwists, ReferenceFrame jacobianFrame)
public GeometricJacobian(RigidBody ancestor, RigidBody descendant, ReferenceFrame jacobianFrame)
public GeometricJacobian(InverseDynamicsJoint[] joints, ReferenceFrame jacobianFrame)
public GeometricJacobian(InverseDynamicsJoint joint, ReferenceFrame jacobianFrame)
Method Detail |
---|
public void compute()
public void changeFrame(ReferenceFrame jacobianFrame)
public void packTwist(Twist twistToPack, org.ejml.data.DenseMatrix64F jointVelocities)
jointVelocities
- the joint velocity vector;
should have the same ordering as the unitRelativeTwistsInBodyFrame that were passed in during construction,
should be a column vectorpublic org.ejml.data.DenseMatrix64F computeJointTorques(Wrench wrench)
wrench
- the resulting wrench at the end effector.
The wrench should be expressed in this Jacobian's jacobianFrame and its 'onWhat' frame should be this Jacobian's endEffectorFrame
public org.ejml.data.DenseMatrix64F getJacobianMatrix()
public double det()
public double getJacobianEntry(int row, int column)
row
- the desired row of the Jacobiancolumn
- the desired column of the Jacobian
public int getNumberOfColumns()
public ReferenceFrame getJacobianFrame()
public InverseDynamicsJoint[] getJointsInOrder()
public RigidBody getBase()
public RigidBody getEndEffector()
public ReferenceFrame getBaseFrame()
public ReferenceFrame getEndEffectorFrame()
public java.lang.String toString()
toString
in class java.lang.Object
public java.lang.String getShortInfo()
|
||||||||||
PREV CLASS NEXT CLASS | FRAMES NO FRAMES | |||||||||
SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD |