Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

go1: fix inertia of fake camera links for pybullet #158

Merged
merged 2 commits into from
Feb 13, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
35 changes: 35 additions & 0 deletions robots/go1_description/urdf/go1.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -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> -->
Expand Down Expand Up @@ -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> -->
Expand Down Expand Up @@ -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> -->
Expand Down Expand Up @@ -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> -->
Expand Down Expand Up @@ -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> -->
Expand Down Expand Up @@ -1690,13 +1715,23 @@
<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"/>
<parent link="camera_right"/>
<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"/>
Expand Down
8 changes: 4 additions & 4 deletions unittest/test_load.py
Original file line number Diff line number Diff line change
Expand Up @@ -11,13 +11,13 @@


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):
Expand Down Expand Up @@ -96,10 +96,10 @@ def test_panda(self):
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)
Expand Down