Skip to content
Snippets Groups Projects
Commit ed267f7b authored by Pierre Fernbach's avatar Pierre Fernbach
Browse files

fix indentation in rbprmBuilder.py : always 2 spaces

parent daa7768e
No related branches found
No related tags found
No related merge requests found
...@@ -25,285 +25,285 @@ import hpp.gepetto.blender.exportmotion as em ...@@ -25,285 +25,285 @@ import hpp.gepetto.blender.exportmotion as em
# A RbprmDevice robot is a dual representation of a robots. One robot describes the # A RbprmDevice robot is a dual representation of a robots. One robot describes the
# trunk of the robot, and a set of robots describe the range of motion of each limb of the robot. # trunk of the robot, and a set of robots describe the range of motion of each limb of the robot.
class Builder (object): class Builder (object):
## Constructor ## Constructor
def __init__ (self, load = True): def __init__ (self, load = True):
self.tf_root = "base_link" self.tf_root = "base_link"
self.rootJointType = dict() self.rootJointType = dict()
self.client = BasicClient () # client of hpp.corbaserver.robot self.client = BasicClient ()
self.clientRbprm = RbprmClient () # client of hpp.corbaserver.rbprm.rbprmBuilder self.clientRbprm = RbprmClient ()
self.load = load self.load = load
## Virtual function to load the robot model. ## Virtual function to load the robot model.
# #
# \param urdfName urdf description of the robot trunk, # \param urdfName urdf description of the robot trunk,
# \param urdfNameroms either a string, or an array of strings, indicating the urdf of the different roms to add. # \param urdfNameroms either a string, or an array of strings, indicating the urdf of the different roms to add.
# \param rootJointType type of root joint among ("freeflyer", "planar", # \param rootJointType type of root joint among ("freeflyer", "planar",
# "anchor"), # "anchor"),
# \param meshPackageName name of the meshpackage from where the robot mesh will be loaded # \param meshPackageName name of the meshpackage from where the robot mesh will be loaded
# \param packageName name of the package from where the robot will be loaded # \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 urdfSuffix optional suffix for the urdf of the robot package
# \param srdfSuffix optional suffix for the srdf 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): def loadModel (self, urdfName, urdfNameroms, rootJointType, meshPackageName, packageName, urdfSuffix, srdfSuffix):
if(isinstance(urdfNameroms, list)): if(isinstance(urdfNameroms, list)):
for urdfNamerom in urdfNameroms: for urdfNamerom in urdfNameroms:
self.clientRbprm.rbprm.loadRobotRomModel(urdfNamerom, rootJointType, packageName, urdfNamerom, urdfSuffix, srdfSuffix) self.clientRbprm.rbprm.loadRobotRomModel(urdfNamerom, rootJointType, packageName, urdfNamerom, urdfSuffix, srdfSuffix)
else: else:
self.clientRbprm.rbprm.loadRobotRomModel(urdfNameroms, rootJointType, packageName, urdfNameroms, urdfSuffix, srdfSuffix) self.clientRbprm.rbprm.loadRobotRomModel(urdfNameroms, rootJointType, packageName, urdfNameroms, urdfSuffix, srdfSuffix)
self.clientRbprm.rbprm.initNewProblemSolver() self.clientRbprm.rbprm.initNewProblemSolver()
self.clientRbprm.rbprm.loadRobotCompleteModel(urdfName, rootJointType, packageName, urdfName, urdfSuffix, srdfSuffix) self.clientRbprm.rbprm.loadRobotCompleteModel(urdfName, rootJointType, packageName, urdfName, urdfSuffix, srdfSuffix)
self.name = urdfName self.name = urdfName
self.displayName = urdfName self.displayName = urdfName
self.tf_root = "base_link" self.tf_root = "base_link"
self.rootJointType = rootJointType self.rootJointType = rootJointType
self.jointNames = self.client.robot.getJointNames () self.jointNames = self.client.robot.getJointNames ()
self.allJointNames = self.client.robot.getAllJointNames () self.allJointNames = self.client.robot.getAllJointNames ()
self.client.robot.meshPackageName = meshPackageName self.client.robot.meshPackageName = meshPackageName
self.meshPackageName = meshPackageName self.meshPackageName = meshPackageName
self.rankInConfiguration = dict () self.rankInConfiguration = dict ()
self.rankInVelocity = dict () self.rankInVelocity = dict ()
self.packageName = packageName self.packageName = packageName
self.urdfName = urdfName self.urdfName = urdfName
self.urdfSuffix = urdfSuffix self.urdfSuffix = urdfSuffix
self.srdfSuffix = srdfSuffix self.srdfSuffix = srdfSuffix
rankInConfiguration = rankInVelocity = 0 rankInConfiguration = rankInVelocity = 0
for j in self.jointNames: for j in self.jointNames:
self.rankInConfiguration [j] = rankInConfiguration self.rankInConfiguration [j] = rankInConfiguration
rankInConfiguration += self.client.robot.getJointConfigSize (j) rankInConfiguration += self.client.robot.getJointConfigSize (j)
self.rankInVelocity [j] = rankInVelocity self.rankInVelocity [j] = rankInVelocity
rankInVelocity += self.client.robot.getJointNumberDof (j) rankInVelocity += self.client.robot.getJointNumberDof (j)
## Init RbprmShooter ## Init RbprmShooter
#
def initshooter (self):
return self.clientRbprm.rbprm.initshooter ()
## Sets limits on robot orientation, described according to Euler's ZYX rotation order
#
# \param bounds 6D vector with the lower and upperBound for each rotation axis in sequence
def boundSO3 (self, bounds):
return self.clientRbprm.rbprm.boundSO3 (bounds)
## Specifies a preferred affordance for a given rom.
# This constrains the planner to accept a rom configuration only if
# it collides with a surface the normal of which has these properties.
#
# \param rom name of the rome,
# \param affordances list of affordance names
def setAffordanceFilter (self, rom, affordances):
return self.clientRbprm.rbprm.setAffordanceFilter (rom, affordances)
## Specifies a rom constraint for the planner.
# A configuration will be valid if and only if the considered rom collides
# with the environment.
#
# \param romFilter array of roms indicated by name, which determine the constraint.
def setFilter (self, romFilter):
return self.clientRbprm.rbprm.setFilter (romFilter)
## Export a computed path for blender
# #
def initshooter (self): # \param problem the problem associated with the path computed for the robot
return self.clientRbprm.rbprm.initshooter () # \param stepsize increment along the path
# \param pathId if of the considered path
## Sets limits on robot orientation, described according to Euler's ZYX rotation order # \param filename name of the output file where to save the output
# def exportPath (self, viewer, problem, pathId, stepsize, filename):
# \param bounds 6D vector with the lower and upperBound for each rotation axis in sequence em.exportPath(viewer, self.client.robot, problem, pathId, stepsize, filename)
def boundSO3 (self, bounds):
return self.clientRbprm.rbprm.boundSO3 (bounds) ## \name Degrees of freedom
# \{
## Specifies a preferred affordance for a given rom.
# This constrains the planner to accept a rom configuration only if ## Get size of configuration
# it collides with a surface the normal of which has these properties. # \return size of configuration
# def getConfigSize (self):
# \param rom name of the rome, return self.client.robot.getConfigSize ()
# \param affordances list of affordance names
def setAffordanceFilter (self, rom, affordances): # Get size of velocity
return self.clientRbprm.rbprm.setAffordanceFilter (rom, affordances) # \return size of velocity
def getNumberDof (self):
## Specifies a rom constraint for the planner. return self.client.robot.getNumberDof ()
# A configuration will be valid if and only if the considered rom collides ## \}
# with the environment.
# ## \name Joints
# \param romFilter array of roms indicated by name, which determine the constraint. #\{
def setFilter (self, romFilter):
return self.clientRbprm.rbprm.setFilter (romFilter) ## Get joint names in the same order as in the configuration.
def getJointNames (self):
## Export a computed path for blender return self.client.robot.getJointNames ()
#
# \param problem the problem associated with the path computed for the robot ## Get joint names in the same order as in the configuration.
# \param stepsize increment along the path def getAllJointNames (self):
# \param pathId if of the considered path return self.client.robot.getAllJointNames ()
# \param filename name of the output file where to save the output
def exportPath (self, viewer, problem, pathId, stepsize, filename): ## Get joint position.
em.exportPath(viewer, self.client.robot, problem, pathId, stepsize, filename) def getJointPosition (self, jointName):
return self.client.robot.getJointPosition (jointName)
## \name Degrees of freedom
# \{ ## Set static position of joint in its parent frame
def setJointPosition (self, jointName, position):
## Get size of configuration return self.client.robot.setJointPosition (jointName, position)
# \return size of configuration
def getConfigSize (self): ## Get joint number degrees of freedom.
return self.client.robot.getConfigSize () def getJointNumberDof (self, jointName):
return self.client.robot.getJointNumberDof (jointName)
# Get size of velocity
# \return size of velocity ## Get joint number config size.
def getNumberDof (self): def getJointConfigSize (self, jointName):
return self.client.robot.getNumberDof () return self.client.robot.getJointConfigSize (jointName)
## \}
## set bounds for the joint
## \name Joints def setJointBounds (self, jointName, inJointBound):
#\{ return self.client.robot.setJointBounds (jointName, inJointBound)
## Get joint names in the same order as in the configuration. ## Set bounds on the translation part of the freeflyer joint.
def getJointNames (self): #
return self.client.robot.getJointNames () # Valid only if the robot has a freeflyer joint.
def setTranslationBounds (self, xmin, xmax, ymin, ymax, zmin, zmax):
## Get joint names in the same order as in the configuration. self.client.robot.setJointBounds \
def getAllJointNames (self): (self.displayName + "base_joint_x", [xmin, xmax])
return self.client.robot.getAllJointNames () self.client.robot.setJointBounds \
(self.displayName + "base_joint_y", [ymin, ymax])
## Get joint position. self.client.robot.setJointBounds \
def getJointPosition (self, jointName): (self.displayName + "base_joint_z", [zmin, zmax])
return self.client.robot.getJointPosition (jointName)
## Get link position in joint frame
## Set static position of joint in its parent frame #
def setJointPosition (self, jointName, position): # Joints are oriented in a different way as in urdf standard since
return self.client.robot.setJointPosition (jointName, position) # rotation and uni-dimensional translation joints act around or along
# their x-axis. This method returns the position of the urdf link in
## Get joint number degrees of freedom. # world frame.
def getJointNumberDof (self, jointName): #
return self.client.robot.getJointNumberDof (jointName) # \param jointName name of the joint
# \return position of the link in world frame.
## Get joint number config size. def getLinkPosition (self, jointName):
def getJointConfigSize (self, jointName): return self.client.robot.getLinkPosition (jointName)
return self.client.robot.getJointConfigSize (jointName)
## Get link name
## set bounds for the joint #
def setJointBounds (self, jointName, inJointBound): # \param jointName name of the joint,
return self.client.robot.setJointBounds (jointName, inJointBound) # \return name of the link.
def getLinkName (self, jointName):
## Set bounds on the translation part of the freeflyer joint. return self.client.robot.getLinkName (jointName)
#
# Valid only if the robot has a freeflyer joint. def getLinkNames (self, jointName):
def setTranslationBounds (self, xmin, xmax, ymin, ymax, zmin, zmax): return self.client.robot.getLinkNames (jointName)
self.client.robot.setJointBounds \ ## \}
(self.displayName + "base_joint_x", [xmin, xmax])
self.client.robot.setJointBounds \ ## \name Access to current configuration
(self.displayName + "base_joint_y", [ymin, ymax]) #\{
self.client.robot.setJointBounds \
(self.displayName + "base_joint_z", [zmin, zmax]) ## Set current configuration of composite robot
#
## Get link position in joint frame # \param q configuration of the composite robot
# def setCurrentConfig (self, q):
# Joints are oriented in a different way as in urdf standard since self.client.robot.setCurrentConfig (q)
# rotation and uni-dimensional translation joints act around or along
# their x-axis. This method returns the position of the urdf link in ## Get current configuration of composite robot
# world frame. #
# # \return configuration of the composite robot
# \param jointName name of the joint def getCurrentConfig (self):
# \return position of the link in world frame. return self.client.robot.getCurrentConfig ()
def getLinkPosition (self, jointName):
return self.client.robot.getLinkPosition (jointName) ## Shoot random configuration
# \return dofArray Array of degrees of freedom.
## Get link name def shootRandomConfig(self):
# return self.client.robot.shootRandomConfig ()
# \param jointName name of the joint,
# \return name of the link. ## \}
def getLinkName (self, jointName):
return self.client.robot.getLinkName (jointName) ## \name Bodies
# \{
def getLinkNames (self, jointName):
return self.client.robot.getLinkNames (jointName) ## Get the list of objects attached to a joint.
## \} # \param inJointName name of the joint.
# \return list of names of CollisionObject attached to the body.
## \name Access to current configuration def getJointInnerObjects (self, jointName):
#\{ return self.client.robot.getJointInnerObjects (jointName)
## Set current configuration of composite robot
# ## Get list of collision objects tested with the body attached to a joint
# \param q configuration of the composite robot # \param inJointName name of the joint.
def setCurrentConfig (self, q): # \return list of names of CollisionObject
self.client.robot.setCurrentConfig (q) def getJointOuterObjects (self, jointName):
return self.client.robot.getJointOuterObjects (jointName)
## Get current configuration of composite robot
# ## Get position of robot object
# \return configuration of the composite robot # \param objectName name of the object.
def getCurrentConfig (self): # \return transformation as a hpp.Transform object
return self.client.robot.getCurrentConfig () def getObjectPosition (self, objectName):
return Transform (self.client.robot.getObjectPosition
## Shoot random configuration (objectName))
# \return dofArray Array of degrees of freedom.
def shootRandomConfig(self): ## \brief Remove an obstacle from outer objects of a joint body
return self.client.robot.shootRandomConfig () #
# \param objectName name of the object to remove,
## \} # \param jointName name of the joint owning the body,
# \param collision whether collision with object should be computed,
## \name Bodies # \param distance whether distance to object should be computed.
# \{ def removeObstacleFromJoint (self, objectName, jointName, collision,
distance):
## Get the list of objects attached to a joint. return self.client.obstacle.removeObstacleFromJoint \
# \param inJointName name of the joint. (objectName, jointName, collision, distance)
# \return list of names of CollisionObject attached to the body.
def getJointInnerObjects (self, jointName):
return self.client.robot.getJointInnerObjects (jointName) ## \}
## \name Collision checking and distance computation
## Get list of collision objects tested with the body attached to a joint # \{
# \param inJointName name of the joint.
# \return list of names of CollisionObject ## Test collision with obstacles and auto-collision.
def getJointOuterObjects (self, jointName): #
return self.client.robot.getJointOuterObjects (jointName) # Check whether current configuration of robot is valid by calling
# CkwsDevice::collisionTest ().
## Get position of robot object # \return whether configuration is valid
# \param objectName name of the object. # \note Deprecated. Use isConfigValid instead.
# \return transformation as a hpp.Transform object def collisionTest (self):
def getObjectPosition (self, objectName): print "Deprecated. Use isConfigValid instead"
return Transform (self.client.robot.getObjectPosition return self.client.robot.collisionTest ()
(objectName))
## Check the validity of a configuration.
## \brief Remove an obstacle from outer objects of a joint body #
# # Check whether a configuration of robot is valid.
# \param objectName name of the object to remove, # \param cfg a configuration
# \param jointName name of the joint owning the body, # \return whether configuration is valid
# \param collision whether collision with object should be computed, def isConfigValid (self, cfg):
# \param distance whether distance to object should be computed. return self.client.robot.isConfigValid (cfg)
def removeObstacleFromJoint (self, objectName, jointName, collision,
distance): ## Compute distances between bodies and obstacles
return self.client.obstacle.removeObstacleFromJoint \ #
(objectName, jointName, collision, distance) # \return list of distances,
# \return names of the objects belonging to a body
# \return names of the objects tested with inner objects,
## \} # \return closest points on the body,
# \return closest points on the obstacles
## \name Collision checking and distance computation # \note outer objects for a body can also be inner objects of another
# \{ # body.
def distancesToCollision (self):
## Test collision with obstacles and auto-collision. return self.client.robot.distancesToCollision ()
# ## \}
# Check whether current configuration of robot is valid by calling
# CkwsDevice::collisionTest (). ## \}
# \return whether configuration is valid ## \name Mass and inertia
# \note Deprecated. Use isConfigValid instead. # \{
def collisionTest (self):
print "Deprecated. Use isConfigValid instead" ## Get mass of robot
return self.client.robot.collisionTest () def getMass (self):
return self.client.robot.getMass ()
## Check the validity of a configuration.
# ## Get position of center of mass
# Check whether a configuration of robot is valid. def getCenterOfMass (self):
# \param cfg a configuration return self.client.robot.getCenterOfMass ()
# \return whether configuration is valid ## Get Jacobian of the center of mass
def isConfigValid (self, cfg): def getJacobianCenterOfMass (self):
return self.client.robot.isConfigValid (cfg) return self.client.robot.getJacobianCenterOfMass ()
##\}
## Compute distances between bodies and obstacles
# ## Get the dimension of the extra configuration space
# \return list of distances, def getDimensionExtraConfigSpace(self):
# \return names of the objects belonging to a body return self.client.robot.getDimensionExtraConfigSpace()
# \return names of the objects tested with inner objects,
# \return closest points on the body, ## Convert a direction vector to a quaternion (use Eigen::Quaterniond::FromTwoVectors with Z vector)
# \return closest points on the obstacles # \param u the vector director
# \note outer objects for a body can also be inner objects of another def quaternionFromVector(self,vector):
# body. return self.client.robot.quaternionFromVector(vector)
def distancesToCollision (self):
return self.client.robot.distancesToCollision ()
## \}
## \}
## \name Mass and inertia
# \{
## Get mass of robot
def getMass (self):
return self.client.robot.getMass ()
## Get position of center of mass
def getCenterOfMass (self):
return self.client.robot.getCenterOfMass ()
## Get Jacobian of the center of mass
def getJacobianCenterOfMass (self):
return self.client.robot.getJacobianCenterOfMass ()
##\}
## Get the dimension of the extra configuration space
def getDimensionExtraConfigSpace(self):
return self.client.robot.getDimensionExtraConfigSpace()
## Convert a direction vector to a quaternion (use Eigen::Quaterniond::FromTwoVectors with Z vector)
# \param u the vector director
def quaternionFromVector(self,vector):
return self.client.robot.quaternionFromVector(vector)
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment