def test_com_motion_above_feet_WB(self): cs = ContactSequence() cs.loadFromBinary(str(PATH / "com_motion_above_feet_WB.cs")) self.assertEqual(cs.size(), 1) self.assertTrue(cs.haveConsistentContacts()) self.assertTrue(cs.haveTimings()) self.assertTrue(cs.haveCentroidalValues()) self.assertTrue(cs.haveCentroidalTrajectories()) self.assertTrue(cs.haveJointsTrajectories()) self.assertTrue(cs.haveJointsDerivativesTrajectories()) self.assertTrue(cs.haveContactForcesTrajectories()) self.assertTrue(cs.haveZMPtrajectories()) checkCS(self, cs, wholeBody=True)
def test_walk_20cm_quasistatic_WB(self): cs = ContactSequence() cs.loadFromBinary(str(PATH / "walk_20cm_quasistatic_WB.cs")) self.assertEqual(cs.size(), 23) self.assertTrue(cs.haveConsistentContacts()) self.assertTrue(cs.haveTimings()) self.assertTrue(cs.haveCentroidalValues()) self.assertTrue(cs.haveCentroidalTrajectories()) self.assertTrue(cs.haveEffectorsTrajectories(1e-1)) self.assertTrue(cs.haveJointsTrajectories()) self.assertTrue(cs.haveJointsDerivativesTrajectories()) self.assertTrue(cs.haveContactForcesTrajectories()) self.assertTrue(cs.haveZMPtrajectories()) self.assertTrue(cs.haveFriction()) self.assertTrue(cs.haveContactModelDefined()) checkCS(self, cs, quasistatic=True, effector=True, wholeBody=True)