From aed0b464ed0b9d947fa6bfddc9a584e69d3ad732 Mon Sep 17 00:00:00 2001
From: Rohan Budhiraja <proyan@users.noreply.github.com>
Date: Thu, 24 Jan 2019 13:18:34 +0100
Subject: [PATCH] [srdf] add rotor parameters (only the template) to the srdf

---
 srdf/talos.srdf | 35 +++++++++++++++++++++++++++++++++++
 1 file changed, 35 insertions(+)

diff --git a/srdf/talos.srdf b/srdf/talos.srdf
index 5ec30cb..331da50 100644
--- a/srdf/talos.srdf
+++ b/srdf/talos.srdf
@@ -161,6 +161,41 @@
         <joint name="torso_2_joint" value="0.006761" />
     </group_state>
 
+    
+    <rotor_params>
+        <joint name="arm_left_1_joint" mass="1e-5" gear_ratio="100."  />
+        <joint name="arm_left_2_joint" mass="1e-5" gear_ratio="100." />
+        <joint name="arm_left_3_joint" mass="1e-5" gear_ratio="100." />
+        <joint name="arm_left_4_joint" mass="1e-5" gear_ratio="100." />
+        <joint name="arm_left_5_joint" mass="1e-5" gear_ratio="100." />
+        <joint name="arm_left_6_joint" mass="1e-5" gear_ratio="100." />
+        <joint name="arm_left_7_joint" mass="1e-5" gear_ratio="100." />
+        <joint name="arm_right_1_joint" mass="1e-5" gear_ratio="100." />
+        <joint name="arm_right_2_joint" mass="1e-5" gear_ratio="100." />
+        <joint name="arm_right_3_joint" mass="1e-5" gear_ratio="100." />
+        <joint name="arm_right_4_joint" mass="1e-5" gear_ratio="100." />
+        <joint name="arm_right_5_joint" mass="1e-5" gear_ratio="100." />
+        <joint name="arm_right_6_joint" mass="1e-5" gear_ratio="100." />
+        <joint name="arm_right_7_joint" mass="1e-5" gear_ratio="100." />
+        <joint name="head_1_joint" mass="1e-5" gear_ratio="100." />
+        <joint name="head_2_joint" mass="1e-5" gear_ratio="100." />
+        <joint name="leg_left_1_joint" mass="1e-5" gear_ratio="100." />
+        <joint name="leg_left_2_joint" mass="1e-5" gear_ratio="100." />
+        <joint name="leg_left_3_joint" mass="1e-5" gear_ratio="100." />
+        <joint name="leg_left_4_joint" mass="1e-5" gear_ratio="100." />
+        <joint name="leg_left_5_joint" mass="1e-5" gear_ratio="100." />
+        <joint name="leg_left_6_joint" mass="1e-5" gear_ratio="100." />
+        <joint name="leg_right_1_joint" mass="1e-5" gear_ratio="100." />
+        <joint name="leg_right_2_joint" mass="1e-5" gear_ratio="100."  />
+        <joint name="leg_right_3_joint" mass="1e-5" gear_ratio="100." />
+        <joint name="leg_right_4_joint" mass="1e-5" gear_ratio="100." />
+        <joint name="leg_right_5_joint" mass="1e-5" gear_ratio="100." />
+        <joint name="leg_right_6_joint" mass="1e-5" gear_ratio="100." />
+        <joint name="torso_1_joint" mass="1e-5" gear_ratio="100." />
+        <joint name="torso_2_joint" mass="1e-5" gear_ratio="100." />
+   </rotor_params>
+    
+
   <!--
    Talos Specificities.
      foot height = y axis
-- 
GitLab