diff --git a/robots/go1_description/urdf/go1.urdf b/robots/go1_description/urdf/go1.urdf index 92b652c6ca17073b7561aaeee2322958bdccbb0e..17ecaf66abe6346defdaaac8ae94e17f7b2f72f6 100644 --- a/robots/go1_description/urdf/go1.urdf +++ b/robots/go1_description/urdf/go1.urdf @@ -1344,6 +1344,11 @@ <child link="camera_optical_face"/> </joint> <link name="camera_optical_face"> + <inertial> + <origin xyz="0 0 0" rpy="0 0 0" /> + <mass value="0" /> + <inertia ixx="0" iyy="0" izz="0" ixy="0" ixz="0" iyz="0" /> + </inertial> </link> <gazebo reference="camera_face"> <!-- <material>Gazebo/Black</material> --> @@ -1418,6 +1423,11 @@ <child link="camera_optical_chin"/> </joint> <link name="camera_optical_chin"> + <inertial> + <origin xyz="0 0 0" rpy="0 0 0" /> + <mass value="0" /> + <inertia ixx="0" iyy="0" izz="0" ixy="0" ixz="0" iyz="0" /> + </inertial> </link> <gazebo reference="camera_chin"> <!-- <material>Gazebo/Black</material> --> @@ -1492,6 +1502,11 @@ <child link="camera_optical_left"/> </joint> <link name="camera_optical_left"> + <inertial> + <origin xyz="0 0 0" rpy="0 0 0" /> + <mass value="0" /> + <inertia ixx="0" iyy="0" izz="0" ixy="0" ixz="0" iyz="0" /> + </inertial> </link> <gazebo reference="camera_left"> <!-- <material>Gazebo/Black</material> --> @@ -1566,6 +1581,11 @@ <child link="camera_optical_right"/> </joint> <link name="camera_optical_right"> + <inertial> + <origin xyz="0 0 0" rpy="0 0 0" /> + <mass value="0" /> + <inertia ixx="0" iyy="0" izz="0" ixy="0" ixz="0" iyz="0" /> + </inertial> </link> <gazebo reference="camera_right"> <!-- <material>Gazebo/Black</material> --> @@ -1640,6 +1660,11 @@ <child link="camera_optical_rearDown"/> </joint> <link name="camera_optical_rearDown"> + <inertial> + <origin xyz="0 0 0" rpy="0 0 0" /> + <mass value="0" /> + <inertia ixx="0" iyy="0" izz="0" ixy="0" ixz="0" iyz="0" /> + </inertial> </link> <gazebo reference="camera_rearDown"> <!-- <material>Gazebo/Black</material> --> @@ -1690,6 +1715,11 @@ <child link="camera_laserscan_link_left"/> </joint> <link name="camera_laserscan_link_left"> + <inertial> + <origin xyz="0 0 0" rpy="0 0 0" /> + <mass value="0" /> + <inertia ixx="0" iyy="0" izz="0" ixy="0" ixz="0" iyz="0" /> + </inertial> </link> <joint name="camera_laserscan_joint_right" type="fixed"> <origin rpy="0 0.2618 0" xyz="0 0 0"/> @@ -1697,6 +1727,11 @@ <child link="camera_laserscan_link_right"/> </joint> <link name="camera_laserscan_link_right"> + <inertial> + <origin xyz="0 0 0" rpy="0 0 0" /> + <mass value="0" /> + <inertia ixx="0" iyy="0" izz="0" ixy="0" ixz="0" iyz="0" /> + </inertial> </link> <joint name="ultraSound_joint_left" type="fixed"> <origin rpy="0 0.2618 1.5707963267948966" xyz="-0.0535 0.0826 0.00868"/> diff --git a/unittest/test_load.py b/unittest/test_load.py index b29fb1ae62c36d5026e3df3ea624f6712cef1a0d..3560d05d635f91bb9875d13c4fc1cee435139f13 100755 --- a/unittest/test_load.py +++ b/unittest/test_load.py @@ -11,13 +11,13 @@ from example_robot_data import load_full class RobotTestCase(unittest.TestCase): - def check(self, name, expected_nq, expected_nv, one_kg_bodies=[], mass=True): + def check(self, name, expected_nq, expected_nv, one_kg_bodies=[]): """Helper function for the real tests""" robot, _, urdf, _ = load_full(name, display=False) self.assertEqual(robot.model.nq, expected_nq) self.assertEqual(robot.model.nv, expected_nv) self.assertTrue(hasattr(robot, "q0")) - if pybullet and mass: + if pybullet: self.check_pybullet(urdf, one_kg_bodies) def check_pybullet(self, urdf, one_kg_bodies): @@ -96,10 +96,10 @@ class RobotTestCase(unittest.TestCase): self.check("panda", 9, 9) def test_allegro_right(self): - self.check("allegro_right_hand", 16, 16, mass=False) + self.check("allegro_right_hand", 16, 16) def test_allegro_left(self): - self.check("allegro_left_hand", 16, 16, mass=False) + self.check("allegro_left_hand", 16, 16) def test_romeo(self): self.check("romeo", 62, 61)