10 from example_robot_data
import load_full
14 def check(self, name, expected_nq, expected_nv, one_kg_bodies=[]):
15 """Helper function for the real tests"""
16 robot, _, urdf, _ =
load_full(name, display=
False, verbose=
True)
17 self.assertEqual(robot.model.nq, expected_nq)
18 self.assertEqual(robot.model.nv, expected_nv)
19 self.assertTrue(hasattr(robot,
"q0"))
20 self.assertTrue(hasattr(robot,
"urdf"))
25 client_id = pybullet.connect(pybullet.DIRECT)
26 robot_id = pybullet.loadURDF(urdf, physicsClientId=client_id)
27 for joint_id
in range(pybullet.getNumJoints(robot_id, client_id)):
28 dynamics = pybullet.getDynamicsInfo(robot_id, joint_id, client_id)
30 joint = pybullet.getJointInfo(robot_id, joint_id, client_id)
33 self.assertIn(joint[12].decode(), one_kg_bodies)
34 pybullet.disconnect(client_id)
37 self.
check(
"b1", 19, 18)
40 self.
check(
"go1", 19, 18)
43 self.
check(
"a1", 19, 18)
46 self.
check(
"anymal", 19, 18)
49 self.
check(
"anymal_c", 19, 18)
52 self.
check(
"anymal_kinova", 25, 24)
55 self.
check(
"baxter", 19, 19)
59 self.
check(
"cassie", 29, 28)
63 pin_version = tuple(int(i)
for i
in pinocchio.__version__.split(
"."))
64 self.assertLess(pin_version, (2, 9, 1))
67 self.
check(
"double_pendulum", 2, 2)
70 self.
check(
"double_pendulum_continuous", 4, 2)
73 self.
check(
"double_pendulum_simple", 2, 2)
76 self.
check(
"asr_twodof", 2, 2, one_kg_bodies=[
"ground"])
79 self.
check(
"hector", 7, 6)
82 self.
check(
"hyq", 19, 18)
85 self.
check(
"icub", 39, 38)
88 self.
check(
"icub_reduced", 36, 35)
91 self.
check(
"iris", 7, 6)
94 self.
check(
"kinova", 9, 6)
97 self.
check(
"panda", 9, 9)
100 self.
check(
"allegro_right_hand", 16, 16)
103 self.
check(
"allegro_left_hand", 16, 16)
106 self.
check(
"quadruped", 15, 14)
109 self.
check(
"romeo", 62, 61)
113 "simple_humanoid", 36, 35, one_kg_bodies=[
"LARM_LINK3",
"RARM_LINK3"]
118 "simple_humanoid_classical",
121 one_kg_bodies=[
"LARM_LINK3",
"RARM_LINK3"],
125 self.
check(
"bolt", 13, 12)
128 self.
check(
"solo8", 15, 14)
131 self.
check(
"solo12", 19, 18)
134 self.
check(
"finger_edu", 3, 3, one_kg_bodies=[
"finger_base_link"])
137 self.
check(
"talos", 39, 38)
140 self.
check(
"laikago", 19, 18)
143 self.
check(
"talos_box", 39, 38)
146 self.
check(
"talos_full", 51, 50)
149 self.
check(
"talos_full_box", 51, 50)
152 self.
check(
"talos_arm", 7, 7)
155 self.
check(
"talos_legs", 19, 18)
158 self.
check(
"tiago", 50, 48)
161 self.
check(
"tiago_dual", 111, 101)
164 self.
check(
"tiago_no_hand", 14, 12)
167 self.
check(
"ur3", 6, 6)
170 self.
check(
"ur3_gripper", 6, 6)
173 self.
check(
"ur3_limited", 6, 6)
176 self.
check(
"ur5", 6, 6)
179 self.
check(
"ur5_gripper", 6, 6)
182 self.
check(
"ur5_limited", 6, 6)
185 self.
check(
"ur10", 6, 6)
188 self.
check(
"ur10_limited", 6, 6)
191 if __name__ ==
"__main__":