From 36325d3a51bee9c109815896645c99877ba6f53b Mon Sep 17 00:00:00 2001
From: pFernbach <pierre.fernbach@gmail.com>
Date: Wed, 13 Feb 2019 14:02:19 +0100
Subject: [PATCH] adapt ref config to extradof in foot (z)

---
 src/hpp/corbaserver/rbprm/anymal/robot.py | 28 +++++++++++------------
 1 file changed, 14 insertions(+), 14 deletions(-)

diff --git a/src/hpp/corbaserver/rbprm/anymal/robot.py b/src/hpp/corbaserver/rbprm/anymal/robot.py
index ddfc0d1..6394bf9 100644
--- a/src/hpp/corbaserver/rbprm/anymal/robot.py
+++ b/src/hpp/corbaserver/rbprm/anymal/robot.py
@@ -24,33 +24,33 @@ class Robot (Parent):
     ##
     #  Information to retrieve urdf and srdf files.
 
-    packageName = "anymal_boxy_description"
-    meshPackageName = "anymal_boxy_description"
+    packageName = "anymal_description"
+    meshPackageName = "anymal_description"
     rootJointType = "freeflyer"
-    urdfName = "anymal_reachability"
-    urdfSuffix = ""
-    srdfSuffix = ""
+    urdfName = "anymal"
+    urdfSuffix = "_reachability"
+    srdfSuffix = "_reachability"
 
     ## Information about the names of thes joints defining the limbs of the robot
     rLegId = 'RFleg'
     rleg = 'RF_HAA'
-    rfoot = 'RF_CONTACT_2'
+    rfoot = 'RF_ADAPTER_TO_FOOT'
     lLegId = 'LFleg'
     lleg = 'LF_HAA'
-    lfoot = 'LF_CONTACT_2'
+    lfoot = 'LF_ADAPTER_TO_FOOT'
     lArmId = 'LHleg'
     larm = 'LH_HAA'
-    lhand = 'LH_CONTACT_2'
+    lhand = 'LH_ADAPTER_TO_FOOT'
     rArmId = 'RHleg'
     rarm = 'RH_HAA'
-    rhand = 'RH_CONTACT_2'
+    rhand = 'RH_ADAPTER_TO_FOOT'
 
 
     referenceConfig =[0.,0.,0.444, 0.,0.,0.,1., # FF
-        0.04, 0.74, -1.08,0.34,-0.04,
-        0.04, -0.74, 1.08,-0.34,-0.04,
-        -0.04, 0.74, -1.08,0.34,0.04, 
-        -0.04, -0.74, 1.08,-0.34,0.04
+        0.04, 0.74, -1.08,0.34,-0.04,0.,
+        0.04, -0.74, 1.08,-0.34,-0.04,0.,
+        -0.04, 0.74, -1.08,0.34,0.04, 0.,
+        -0.04, -0.74, 1.08,-0.34,0.04,0.
         ]
     
     # informations required to generate the limbs databases the limbs : 
@@ -101,7 +101,7 @@ class Robot (Parent):
     def loadAllLimbs(self,heuristic, analysis = None, nbSamples = nbSamples, octreeSize = octreeSize):
         for id in self.limbs_names:
             eff = self.dict_limb_joint[id]
-            self.addLimb(id,self.dict_limb_rootJoint[id],eff,self.dict_offset[eff].translation.T.tolist(),self.dict_normal[eff],self.dict_size[eff][0],self.dict_size[eff][1],nbSamples,heuristic,octreeSize,self.cType,kinematicConstraintsPath=self.kinematicConstraintsPath+self.dict_limb_rootJoint[id]+"_com_constraints.obj",kinematicConstraintsMin=self.minDist)
+            self.addLimb(id,self.dict_limb_rootJoint[id],eff,self.dict_offset[eff].translation.T.tolist()[0],self.dict_normal[eff],self.dict_size[eff][0]/2.,self.dict_size[eff][1]/2.,nbSamples,heuristic,octreeSize,self.cType,kinematicConstraintsPath=self.kinematicConstraintsPath+self.dict_limb_rootJoint[id]+"_com_constraints.obj",kinematicConstraintsMin=self.minDist)
             if analysis :
                 self.runLimbSampleAnalysis(id, analysis, True)
         
-- 
GitLab