diff --git a/robots/a1_description/urdf/a1.urdf b/robots/a1_description/urdf/a1.urdf index 34bc79f9de364b9a7249634747fe605897c39843..f690ee750791716c8e8ae02186bd00c68a03c6ca 100644 --- a/robots/a1_description/urdf/a1.urdf +++ b/robots/a1_description/urdf/a1.urdf @@ -129,6 +129,11 @@ <cylinder length="0.032" radius="0.041"/> </geometry> </collision> + <inertial> + <mass value="0"/> + <origin rpy="0 0 0" xyz="0 0 0"/> + <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> + </inertial> </link> <joint name="FR_thigh_joint" type="revolute"> <origin rpy="0 0 0" xyz="0 -0.0838 0"/> @@ -251,6 +256,11 @@ <cylinder length="0.032" radius="0.041"/> </geometry> </collision> + <inertial> + <mass value="0"/> + <origin rpy="0 0 0" xyz="0 0 0"/> + <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> + </inertial> </link> <joint name="FL_thigh_joint" type="revolute"> <origin rpy="0 0 0" xyz="0 0.0838 0"/> @@ -373,6 +383,11 @@ <cylinder length="0.032" radius="0.041"/> </geometry> </collision> + <inertial> + <mass value="0"/> + <origin rpy="0 0 0" xyz="0 0 0"/> + <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> + </inertial> </link> <joint name="RR_thigh_joint" type="revolute"> <origin rpy="0 0 0" xyz="0 -0.0838 0"/> @@ -495,6 +510,11 @@ <cylinder length="0.032" radius="0.041"/> </geometry> </collision> + <inertial> + <mass value="0"/> + <origin rpy="0 0 0" xyz="0 0 0"/> + <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> + </inertial> </link> <joint name="RL_thigh_joint" type="revolute"> <origin rpy="0 0 0" xyz="0 0.0838 0"/> diff --git a/unittest/test_load.py b/unittest/test_load.py index e76b00cc049e47e0b71d8cc9349224eaf4dee413..233d5bfe7ee816d8f4b23015c778aa6388f37e83 100755 --- a/unittest/test_load.py +++ b/unittest/test_load.py @@ -93,7 +93,7 @@ class RobotTestCase(unittest.TestCase): self.check('solo12', 19, 18) def test_finger_edu(self): - self.check('finger_edu', 3, 3) + self.check('finger_edu', 3, 3, one_kg_bodies=['finger_base_link']) def test_talos(self): self.check('talos', 39, 38)