diff --git a/src/hpp/corbaserver/rbprm/anymal/robot.py b/src/hpp/corbaserver/rbprm/anymal/robot.py
index b89b40961d02020c38cdb6860cf9f44f497d3472..a5eff853ab067b05fae88260a832c84598d731f9 100644
--- a/src/hpp/corbaserver/rbprm/anymal/robot.py
+++ b/src/hpp/corbaserver/rbprm/anymal/robot.py
@@ -23,7 +23,7 @@ import numpy as np
 class Robot (Parent):
     ##
     #  Information to retrieve urdf and srdf files.
-
+    name = "anymal"
     packageName = "anymal_data"
     meshPackageName = "anymal_data"
     rootJointType = "freeflyer"
@@ -129,12 +129,10 @@ class Robot (Parent):
 
     kneeIds = {"LF":9,"LH":12,"RF":15,"RH":18}
 
-    def __init__ (self, name = None,load = True):
-        Parent.__init__ (self,load)
-        if load:
-            self.loadFullBodyModel(self.urdfName, self.rootJointType, self.meshPackageName, self.packageName, self.urdfSuffix, self.srdfSuffix)
-        if name != None:
+    def __init__(self, name=None, load=True, client=None, clientRbprm=None):
+        if name is not None:
             self.name = name
+        Parent.__init__(self, self.name, self.rootJointType, load, client, None, clientRbprm)
         # save original bounds of the urdf for futur reset
         self.LF_HAA_bounds = self.getJointBounds('LF_HAA')
         self.LF_HFE_bounds = self.getJointBounds('LF_HFE')