hpp-manipulation-corba  4.9.0
Corba server for manipulation planning
manipulation.robot.Robot Class Reference

Load and handle a composite robot for manipulation planning. More...

Inheritance diagram for manipulation.robot.Robot:
Collaboration diagram for manipulation.robot.Robot:

Public Member Functions

def __init__ (self, compositeName=None, robotName=None, rootJointType=None, load=True, client=None)
 Constructor. More...
 
def loadModel (self, robotName, rootJointType)
 Virtual function to load the robot model. More...
 
def insertRobotModel (self, robotName, rootJointType, urdfName, srdfName)
 Load robot model and insert it in the device. More...
 
def insertRobotModelOnFrame (self, robotName, frameName, rootJointType, urdfName, srdfName)
 Insert robot model as a child of a frame of the Device. More...
 
def insertRobotModelFromString (self, robotName, rootJointType, urdfString, srdfString)
 Same as Robot.insertRobotModel. More...
 
def insertRobotSRDFModel (self, robotName, packageName, modelName, srdfSuffix)
 Load a SRDF for the robot. More...
 
def insertHumanoidModel (self, robotName, rootJointType, urdfName, srdfName)
 Load humanoid robot model and insert it in the device. More...
 
def insertHumanoidModelFromString (self, robotName, rootJointType, urdfString, srdfString)
 Same as Robot.insertHumanoidModel. More...
 
def loadHumanoidModel (self, robotName, rootJointType, urdfName, srdfName)
 
def loadEnvironmentModel (self, urdfName, srdfName, envName)
 Load environment model and store in local map. More...
 
Joints
def setRootJointPosition (self, robotName, position)
 Set the position of root joint of a robot in world frame. More...
 
Bodies
def getGripperPositionInJoint (self, gripperName)
 Return the joint name in which a gripper is and the position relatively to the joint. More...
 
def getHandlePositionInJoint (self, handleName)
 Return the joint name in which a handle is and the position relatively to the joint. More...
 

Public Attributes

 rootJointType
 
 load
 
 robotNames
 

Detailed Description

Load and handle a composite robot for manipulation planning.

A composite robot is a kinematic chain composed of several sub-kinematic chains rooted at an anchor joint.

Constructor & Destructor Documentation

◆ __init__()

def manipulation.robot.Robot.__init__ (   self,
  compositeName = None,
  robotName = None,
  rootJointType = None,
  load = True,
  client = None 
)

Constructor.

Parameters
robotNamename of the first robot that is loaded now,
rootJointTypetype of root joint among ("freeflyer", "planar", "anchor"),
loadwhether to actually load urdf files. Set to no if you only want to initialize a corba client to an already initialized problem.

Member Function Documentation

◆ getGripperPositionInJoint()

def manipulation.robot.Robot.getGripperPositionInJoint (   self,
  gripperName 
)

Return the joint name in which a gripper is and the position relatively to the joint.

◆ getHandlePositionInJoint()

def manipulation.robot.Robot.getHandlePositionInJoint (   self,
  handleName 
)

Return the joint name in which a handle is and the position relatively to the joint.

◆ insertHumanoidModel()

def manipulation.robot.Robot.insertHumanoidModel (   self,
  robotName,
  rootJointType,
  urdfName,
  srdfName 
)

Load humanoid robot model and insert it in the device.

Parameters
robotNamekey of the robot in hpp::manipulation::ProblemSolver object map (see hpp::manipulation::ProblemSolver::addRobot)
rootJointTypetype of root joint among "anchor", "freeflyer", "planar",
urdfNamename of the urdf file
srdfNamename of the srdf file

◆ insertHumanoidModelFromString()

def manipulation.robot.Robot.insertHumanoidModelFromString (   self,
  robotName,
  rootJointType,
  urdfString,
  srdfString 
)

Same as Robot.insertHumanoidModel.

Parameters
urdfStringXML string of the URDF,
srdfStringXML string of the SRDF

◆ insertRobotModel()

def manipulation.robot.Robot.insertRobotModel (   self,
  robotName,
  rootJointType,
  urdfName,
  srdfName 
)

Load robot model and insert it in the device.

Parameters
robotNamekey of the robot in hpp::manipulation::ProblemSolver object map (see hpp::manipulation::ProblemSolver::addRobot)
rootJointTypetype of root joint among "anchor", "freeflyer", "planar",
urdfNamename of the urdf file
srdfNamename of the srdf file

◆ insertRobotModelFromString()

def manipulation.robot.Robot.insertRobotModelFromString (   self,
  robotName,
  rootJointType,
  urdfString,
  srdfString 
)

Same as Robot.insertRobotModel.

Parameters
urdfStringXML string of the URDF,
srdfStringXML string of the SRDF

◆ insertRobotModelOnFrame()

def manipulation.robot.Robot.insertRobotModelOnFrame (   self,
  robotName,
  frameName,
  rootJointType,
  urdfName,
  srdfName 
)

Insert robot model as a child of a frame of the Device.

Parameters
robotNamekey of the robot in ProblemSolver object map (see hpp::manipulation::ProblemSolver::addRobot)
frameNamename of the existing frame that will the root of the added robot,
rootJointTypetype of root joint among "anchor", "freeflyer", "planar",
urdfNamename of the urdf file
srdfNamename of the srdf file

◆ insertRobotSRDFModel()

def manipulation.robot.Robot.insertRobotSRDFModel (   self,
  robotName,
  packageName,
  modelName,
  srdfSuffix 
)

Load a SRDF for the robot.

Several SRDF can thus be loaded for the same robot

Parameters
robotNamekey of the robot in hpp::manipulation::Device object map (see hpp::manipulation::Device)
packageNameName of the ROS package containing the model,
modelNameName of the package containing the model
srdfSuffixsuffix for srdf file,

The ros url are built as follows:

  • "package://${packageName}/srdf/${modelName}${srdfSuffix}.srdf"

◆ loadEnvironmentModel()

def manipulation.robot.Robot.loadEnvironmentModel (   self,
  urdfName,
  srdfName,
  envName 
)

Load environment model and store in local map.

Contact surfaces are build from the corresping srdf file. See hpp-manipulation-urdf for more details about contact surface specifications.

Parameters
envNamekey of the object in ProblemSolver object map (see hpp::manipulation::ProblemSolver::addRobot)
urdfNamename of the urdf file,
srdfNamename of the srdf file.

◆ loadHumanoidModel()

def manipulation.robot.Robot.loadHumanoidModel (   self,
  robotName,
  rootJointType,
  urdfName,
  srdfName 
)

◆ loadModel()

def manipulation.robot.Robot.loadModel (   self,
  robotName,
  rootJointType 
)

Virtual function to load the robot model.

◆ setRootJointPosition()

def manipulation.robot.Robot.setRootJointPosition (   self,
  robotName,
  position 
)

Set the position of root joint of a robot in world frame.

Parameters
robotNamekey of the robot in ProblemSolver object map.
positionconstant position of the root joint in world frame in initial configuration.

Member Data Documentation

◆ load

manipulation.robot.Robot.load

◆ robotNames

manipulation.robot.Robot.robotNames

◆ rootJointType

manipulation.robot.Robot.rootJointType

The documentation for this class was generated from the following file: