From d31a33da387463f56a47586319a2006671a0921a Mon Sep 17 00:00:00 2001
From: Justin Beri <18635834+justinberi@users.noreply.github.com>
Date: Thu, 31 Mar 2022 17:25:36 +1000
Subject: [PATCH] Add simplified double pendulum (#118)

* Add simplified double pendulum

* Add description to urdf, loader and unittest

* Fix format

* Fix format for unittest

* double pendudum: update credits

Co-authored-by: Justin Beri <justin [dot] beri [at] csiro [dot] au>
Co-authored-by: Justin Beri <justin.beri at hdr.qut.edu.au>
Co-authored-by: Guilhem Saurel <guilhem.saurel@laas.fr>
---
 python/example_robot_data/robots_loader.py    |   5 +
 robots/double_pendulum_description/README.md  |   3 +
 .../urdf/double_pendulum_simple.urdf          | 176 ++++++++++++++++++
 unittest/test_load.py                         |   3 +
 4 files changed, 187 insertions(+)
 create mode 100644 robots/double_pendulum_description/urdf/double_pendulum_simple.urdf

diff --git a/python/example_robot_data/robots_loader.py b/python/example_robot_data/robots_loader.py
index 4f6af75..3d89e65 100644
--- a/python/example_robot_data/robots_loader.py
+++ b/python/example_robot_data/robots_loader.py
@@ -495,6 +495,10 @@ class DoublePendulumContinuousLoader(DoublePendulumLoader):
     urdf_filename = "double_pendulum_continuous.urdf"
 
 
+class DoublePendulumSimpleLoader(DoublePendulumLoader):
+    urdf_filename = "double_pendulum_simple.urdf"
+
+
 def loadDoublePendulum():
     warnings.warn(_depr_msg('loadDoublePendulum()', 'double_pendulum'), FutureWarning, 2)
     return DoublePendulumLoader().robot
@@ -545,6 +549,7 @@ ROBOTS = {
     'cassie': CassieLoader,
     'double_pendulum': DoublePendulumLoader,
     'double_pendulum_continuous': DoublePendulumContinuousLoader,
+    'double_pendulum_simple': DoublePendulumSimpleLoader,
     'hector': HectorLoader,
     'hyq': HyQLoader,
     'icub': ICubLoader,
diff --git a/robots/double_pendulum_description/README.md b/robots/double_pendulum_description/README.md
index 32e239b..1aa58a1 100644
--- a/robots/double_pendulum_description/README.md
+++ b/robots/double_pendulum_description/README.md
@@ -1,4 +1,7 @@
 # Double Pendulum
 
 upstream: None. Original work from [@PepMS](https://github.com/PepMS).
+Extended by [@ManifoldFR](https://github.com/ManifoldFR) for the continous variant, and
+[@justinberi](https://github.com/justinberi) for the simplified (without mesh) variant.
+
 license: BSD
diff --git a/robots/double_pendulum_description/urdf/double_pendulum_simple.urdf b/robots/double_pendulum_description/urdf/double_pendulum_simple.urdf
new file mode 100644
index 0000000..3751d0c
--- /dev/null
+++ b/robots/double_pendulum_description/urdf/double_pendulum_simple.urdf
@@ -0,0 +1,176 @@
+<?xml version="1.0" encoding="utf-8"?>
+<!--Thus URDF was modified from `double_pendulum.urdf to avoid mehses.
+    Modifications by Justin Beri (https://github.com/justinberi) -->
+<robot
+  name="2dof_planar">
+  <link
+    name="base_link">
+    <inertial>
+      <origin
+        xyz="0 0 0"
+        rpy="0 0 0" />
+      <mass
+        value="0.1" />
+      <inertia
+        ixx="1"
+        ixy="0"
+        ixz="0"
+        iyy="1"
+        iyz="0"
+        izz="1" />
+    </inertial>
+    <visual>
+      <origin
+        xyz="0 0 0"
+        rpy="0 0 0" />
+      <geometry>
+        <box size="0.05 0.05 0.05"/>
+      </geometry>
+      <material
+        name="">
+        <color
+          rgba="1 0 0 1" />
+      </material>
+    </visual>
+    <collision>
+      <origin
+        xyz="0 0 0"
+        rpy="0 0 0" />
+      <geometry>
+        <box size="0.05 0.05 0.05"/>
+      </geometry>
+    </collision>
+  </link>
+  <link
+    name="link1">
+    <inertial>
+      <origin
+        xyz="0 0 0.05"
+        rpy="0 0 0" />
+      <mass
+        value="0.2" />
+      <inertia
+        ixx="0.000177083"
+        ixy="0"
+        ixz="0"
+        iyy="0.000177083"
+        iyz="0"
+        izz="0.000020833" />
+    </inertial>
+    <visual>
+      <origin
+        xyz="0 0 0.05"
+        rpy="0 0 0" />
+      <geometry>
+        <box size="0.025 0.025 0.1"/>
+      </geometry>
+      <material
+        name="">
+        <color
+          rgba="0 1 0 1" />
+      </material>
+    </visual>
+    <collision>
+      <origin
+        xyz="0 0 0.05"
+        rpy="0 0 0" />
+      <geometry>
+        <box size="0.025 0.025 0.1"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint
+    name="joint1"
+    type="revolute">
+    <origin
+      xyz="0.025 0 0"
+      rpy="0 0 0" />
+    <parent
+      link="base_link" />
+    <child
+      link="link1" />
+    <axis
+      xyz="1 0 0" />
+    <limit
+      lower="0"
+      upper="0"
+      effort="0"
+      velocity="0" />
+    <dynamics
+      damping="0.05" />
+  </joint>
+  <link
+    name="link2">
+    <inertial>
+      <origin
+        xyz="0 0 0.1"
+        rpy="0 0 0" />
+      <mass
+        value="0.3" />
+      <inertia
+        ixx="0.001015625"
+        ixy="0"
+        ixz="0"
+        iyy="0.001015625"
+        iyz="0"
+        izz="0.002" />
+    </inertial>
+    <visual>
+      <origin
+        xyz="0 0 0.1"
+        rpy="0 0 0" />
+      <geometry>
+        <box size="0.025 0.025 0.2"/>
+      </geometry>
+      <material
+        name="">
+        <color
+          rgba="0 0 1 1" />
+      </material>
+    </visual>
+    <collision>
+      <origin
+        xyz="0 0 0.1"
+        rpy="0 0 0" />
+      <geometry>
+        <box size="0.025 0.025 0.2"/>
+      </geometry>
+    </collision>
+  </link>
+  <joint
+    name="joint2"
+    type="revolute">
+    <origin
+      xyz="0.0125 0 0.1"
+      rpy="0 0 0" />
+    <parent
+      link="link1" />
+    <child
+      link="link2" />
+    <axis
+      xyz="1 0 0" />
+    <limit
+      lower="0"
+      upper="0"
+      effort="0"
+      velocity="0" />
+    <dynamics
+      damping="0.05" />
+  </joint>
+
+  <!-- For the end effector -->
+  <link name="link3">
+    <inertial>
+    <mass value="0.0"/>
+    <origin rpy="0 0 0" xyz="0 0 0"/>
+    <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
+    </inertial>
+  </link>
+  <joint name="joint3" type="fixed">
+    <origin xyz="0 0 0.2" rpy="0 0 0" />
+    <parent link="link2" />
+    <child link="link3" />
+    <axis xyz="1 0 0" />
+  </joint>
+
+</robot>
diff --git a/unittest/test_load.py b/unittest/test_load.py
index f01bdd8..b4f166f 100755
--- a/unittest/test_load.py
+++ b/unittest/test_load.py
@@ -57,6 +57,9 @@ class RobotTestCase(unittest.TestCase):
     def test_double_pendulum_continuous(self):
         self.check('double_pendulum_continuous', 4, 2)
 
+    def test_double_pendulum_simple(self):
+        self.check('double_pendulum_simple', 2, 2)
+
     def test_asr(self):
         self.check('asr_twodof', 2, 2, one_kg_bodies=['ground'])
 
-- 
GitLab