From c26b717d4affeffbbef779e6f84e9e2e7516e8e3 Mon Sep 17 00:00:00 2001
From: Fernbach Pierre <pFernbach@users.noreply.github.com>
Date: Tue, 15 Sep 2020 15:55:01 +0200
Subject: [PATCH] Fix Hyq srdf (disable collision pairs)

---
 robots/hyq_description/srdf/hyq.srdf | 50 ++++++++++++++++++++++++++--
 1 file changed, 48 insertions(+), 2 deletions(-)

diff --git a/robots/hyq_description/srdf/hyq.srdf b/robots/hyq_description/srdf/hyq.srdf
index a811e61..93f38e1 100644
--- a/robots/hyq_description/srdf/hyq.srdf
+++ b/robots/hyq_description/srdf/hyq.srdf
@@ -96,8 +96,24 @@
         <joint name="rh_hfe_joint" value="-0.75" />
         <joint name="rh_kfe_joint" value="1.5" />
     </group_state>
-
-    <disable_collisions link1="lf_hipassembly" link2="lf_upperleg" reason="Adjacent" />
+    
+    <disable_collisions link1="lf_hipassembly" link2="trunk" reason="Adjacent"/>
+    <disable_collisions link1="lh_hipassembly" link2="trunk" reason="Adjacent"/>
+    <disable_collisions link1="rf_hipassembly" link2="trunk" reason="Adjacent"/>
+    <disable_collisions link1="rh_hipassembly" link2="trunk" reason="Adjacent"/>
+    <disable_collisions link1="lf_hipassembly" link2="lf_upperleg" reason="Adjacent"/>
+    <disable_collisions link1="lh_hipassembly" link2="lh_upperleg" reason="Adjacent"/>
+    <disable_collisions link1="rf_hipassembly" link2="rf_upperleg" reason="Adjacent"/>
+    <disable_collisions link1="rh_hipassembly" link2="rh_upperleg" reason="Adjacent"/>
+    <disable_collisions link1="lf_lowerleg" link2="lf_upperleg" reason="Adjacent"/>
+    <disable_collisions link1="lh_lowerleg" link2="lh_upperleg" reason="Adjacent"/>
+    <disable_collisions link1="rf_lowerleg" link2="rf_upperleg" reason="Adjacent"/>
+    <disable_collisions link1="rh_lowerleg" link2="rh_upperleg" reason="Adjacent"/>
+    <disable_collisions link1="lf_lowerleg" link2="lf_foot" reason="Adjacent"/>
+    <disable_collisions link1="lh_lowerleg" link2="lh_foot" reason="Adjacent"/>
+    <disable_collisions link1="rf_lowerleg" link2="rf_foot" reason="Adjacent"/>
+    <disable_collisions link1="rh_lowerleg" link2="rh_foot" reason="Adjacent"/>
+    
     <disable_collisions link1="lf_hipassembly" link2="lf_lowerleg" reason="Never" />
     <disable_collisions link1="lf_hipassembly" link2="rf_hipassembly" reason="Never" />
     <disable_collisions link1="lf_hipassembly" link2="rf_upperleg" reason="Never" />
@@ -108,5 +124,35 @@
     <disable_collisions link1="lf_hipassembly" link2="rh_hipassembly" reason="Never" />
     <disable_collisions link1="lf_hipassembly" link2="rh_upperleg" reason="Never" />
     <disable_collisions link1="lf_hipassembly" link2="rh_lowerleg" reason="Never" />
+    
+    <disable_collisions link1="rf_hipassembly" link2="rf_lowerleg" reason="Never" />
+    <disable_collisions link1="rf_hipassembly" link2="lf_upperleg" reason="Never" />
+    <disable_collisions link1="rf_hipassembly" link2="lf_lowerleg" reason="Never" />
+    <disable_collisions link1="rf_hipassembly" link2="lh_hipassembly" reason="Never" />
+    <disable_collisions link1="rf_hipassembly" link2="lh_upperleg" reason="Never" />
+    <disable_collisions link1="rf_hipassembly" link2="lh_lowerleg" reason="Never" />
+    <disable_collisions link1="rf_hipassembly" link2="rh_hipassembly" reason="Never" />
+    <disable_collisions link1="rf_hipassembly" link2="rh_upperleg" reason="Never" />
+    <disable_collisions link1="rf_hipassembly" link2="rh_lowerleg" reason="Never" />
+    
+    <disable_collisions link1="lh_hipassembly" link2="lh_lowerleg" reason="Never" />
+    <disable_collisions link1="lh_hipassembly" link2="rf_hipassembly" reason="Never" />
+    <disable_collisions link1="lh_hipassembly" link2="rf_upperleg" reason="Never" />
+    <disable_collisions link1="lh_hipassembly" link2="rf_lowerleg" reason="Never" />
+    <disable_collisions link1="lh_hipassembly" link2="lf_upperleg" reason="Never" />
+    <disable_collisions link1="lh_hipassembly" link2="lf_lowerleg" reason="Never" />
+    <disable_collisions link1="lh_hipassembly" link2="rh_hipassembly" reason="Never" />
+    <disable_collisions link1="lh_hipassembly" link2="rh_upperleg" reason="Never" />
+    <disable_collisions link1="lh_hipassembly" link2="rh_lowerleg" reason="Never" />
+    
+    <disable_collisions link1="rh_hipassembly" link2="rh_lowerleg" reason="Never" />
+    <disable_collisions link1="rh_hipassembly" link2="rf_hipassembly" reason="Never" />
+    <disable_collisions link1="rh_hipassembly" link2="rf_upperleg" reason="Never" />
+    <disable_collisions link1="rh_hipassembly" link2="rf_lowerleg" reason="Never" />
+    <disable_collisions link1="rh_hipassembly" link2="lh_hipassembly" reason="Never" />
+    <disable_collisions link1="rh_hipassembly" link2="lh_upperleg" reason="Never" />
+    <disable_collisions link1="rh_hipassembly" link2="lh_lowerleg" reason="Never" />
+    <disable_collisions link1="rh_hipassembly" link2="lf_upperleg" reason="Never" />
+    <disable_collisions link1="rh_hipassembly" link2="lf_lowerleg" reason="Never" />
 
 </robot>
-- 
GitLab