4 import pinocchio
as pin
5 from test_case
import PinocchioTestCase
10 self.
model = pin.buildSampleModelHumanoidRandom()
12 self.
model.getJointId(
"rarm2_joint")
13 if self.
model.existJointName(
"rarm2_joint")
14 else (self.
model.njoints - 1)
31 self.
q = pin.randomConfiguration(self.
model)
32 self.
v = np.random.rand(self.
model.nv)
33 self.
a = np.random.rand(self.
model.nv)
46 pin.computeForwardKinematicsDerivatives(model, data, q, v, a)
48 pin.getFrameVelocityDerivatives(model, data, self.
frame_idx, pin.WORLD)
49 pin.getFrameVelocityDerivatives(model, data, self.
frame_idx, pin.LOCAL)
50 pin.getFrameVelocityDerivatives(
51 model, data, self.
frame_idx, pin.LOCAL_WORLD_ALIGNED
54 pin.getFrameAccelerationDerivatives(model, data, self.
frame_idx, pin.WORLD)
55 pin.getFrameAccelerationDerivatives(model, data, self.
frame_idx, pin.LOCAL)
56 pin.getFrameAccelerationDerivatives(
57 model, data, self.
frame_idx, pin.LOCAL_WORLD_ALIGNED
61 if __name__ ==
"__main__":