Unverified Commit d4499855 authored by Fernbach Pierre's avatar Fernbach Pierre Committed by GitHub
Browse files

Merge pull request #53 from JasonChmn/devel

Add parameter for context in rbprm builder and fullbody
parents 0bcd5c3f 7915d9c4
......@@ -26,9 +26,12 @@ from hpp.corbaserver.robot import Robot
# trunk of the robot, and a set of robots describe the range of motion of each limb of the robot.
class Builder(Robot):
# # Constructor
def __init__(self, load=True):
def __init__(self, load=True, clientRbprm=None):
self.tf_root = "base_link"
self.clientRbprm = RbprmClient()
if clientRbprm is None:
self.clientRbprm = RbprmClient()
else:
self.clientRbprm = clientRbprm
self.load = load
# # Virtual function to load the robot model.
......@@ -41,8 +44,8 @@ class Builder(Robot):
# \param packageName name of the package from where the robot will be loaded
# \param urdfSuffix optional suffix for the urdf of the robot package
# \param srdfSuffix optional suffix for the srdf of the robot package
def loadModel(self, urdfName, urdfNameroms, rootJointType, meshPackageName, packageName, urdfSuffix, srdfSuffix):
Robot.__init__(self, urdfName, rootJointType, False)
def loadModel(self, urdfName, urdfNameroms, rootJointType, meshPackageName, packageName, urdfSuffix, srdfSuffix, client=None):
Robot.__init__(self, urdfName, rootJointType, False, client=client)
if (isinstance(urdfNameroms, list)):
for urdfNamerom in urdfNameroms:
self.clientRbprm.rbprm.loadRobotRomModel(urdfNamerom, rootJointType, packageName, urdfNamerom,
......
......@@ -28,9 +28,12 @@ from numpy import array, matrix
# trunk of the robot, one for the range of motion
class FullBody(Robot):
# # Constructor
def __init__(self, load=True):
def __init__(self, load=True, clientRbprm=None):
self.tf_root = "base_link"
self.clientRbprm = RbprmClient()
if clientRbprm == None:
self.clientRbprm = RbprmClient()
else:
self.clientRbprm = clientRbprm
self.load = load
self.limbNames = []
......@@ -43,8 +46,8 @@ class FullBody(Robot):
# \param packageName name of the package from where the robot will be loaded
# \param urdfSuffix optional suffix for the urdf of the robot package
# \param srdfSuffix optional suffix for the srdf of the robot package
def loadFullBodyModel(self, urdfName, rootJointType, meshPackageName, packageName, urdfSuffix, srdfSuffix):
Robot.__init__(self, urdfName, rootJointType, False)
def loadFullBodyModel(self, urdfName, rootJointType, meshPackageName, packageName, urdfSuffix, srdfSuffix, client=None):
Robot.__init__(self, urdfName, rootJointType, False, client)
self.clientRbprm.rbprm.loadFullBodyRobot(urdfName, rootJointType, packageName, urdfName, urdfSuffix,
srdfSuffix,
self.client.problem.getSelected("problem")[0])
......
Markdown is supported
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment