hpp-manipulation-corba
4.15.1
Corba server for manipulation planning
|
Public Member Functions | |
def | __init__ (self, compositeName=None, robotName=None, rootJointType=None, load=True, client=None) |
def | loadModel (self, robotName, rootJointType) |
def | insertRobotModel (self, robotName, rootJointType, urdfName, srdfName) |
def | insertRobotModelOnFrame (self, robotName, frameName, rootJointType, urdfName, srdfName) |
def | insertRobotModelFromString (self, robotName, rootJointType, urdfString, srdfString, frame="universe") |
def | insertRobotSRDFModel (self, robotName, srdfPath) |
def | insertHumanoidModel (self, robotName, rootJointType, urdfName, srdfName) |
def | insertHumanoidModelFromString (self, robotName, rootJointType, urdfString, srdfString) |
def | loadHumanoidModel (self, robotName, rootJointType, urdfName, srdfName) |
def | loadEnvironmentModel (self, urdfName, srdfName, envName) |
def | setRootJointPosition (self, robotName, position) |
def | getGripperPositionInJoint (self, gripperName) |
def | getHandlePositionInJoint (self, handleName) |
Public Attributes | |
rootJointType | |
load | |
robotNames | |
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.
def manipulation.robot.Robot.__init__ | ( | self, | |
compositeName = None , |
|||
robotName = None , |
|||
rootJointType = None , |
|||
load = True , |
|||
client = None |
|||
) |
Constructor \\param robotName name of the first robot that is loaded now, \\param rootJointType type of root joint among ("freeflyer", "planar", "anchor"), \\param load whether to actually load urdf files. Set to no if you only want to initialize a corba client to an already initialized problem.
def manipulation.robot.Robot.getGripperPositionInJoint | ( | self, | |
gripperName | |||
) |
Return the joint name in which a gripper is and the position relatively to the joint
def manipulation.robot.Robot.getHandlePositionInJoint | ( | self, | |
handleName | |||
) |
Return the joint name in which a handle is and the position relatively to the joint
def manipulation.robot.Robot.insertHumanoidModel | ( | self, | |
robotName, | |||
rootJointType, | |||
urdfName, | |||
srdfName | |||
) |
Load humanoid robot model and insert it in the device \\param robotName key of the robot in hpp::manipulation::ProblemSolver object map (see hpp::manipulation::ProblemSolver::addRobot) \\param rootJointType type of root joint among "anchor", "freeflyer", "planar", \\param urdfName name of the urdf file \\param srdfName name of the srdf file
def manipulation.robot.Robot.insertHumanoidModelFromString | ( | self, | |
robotName, | |||
rootJointType, | |||
urdfString, | |||
srdfString | |||
) |
Same as Robot.insertHumanoidModel \\param urdfString XML string of the URDF, \\param srdfString XML string of the SRDF
def manipulation.robot.Robot.insertRobotModel | ( | self, | |
robotName, | |||
rootJointType, | |||
urdfName, | |||
srdfName | |||
) |
Load robot model and insert it in the device \\param robotName key of the robot in hpp::manipulation::ProblemSolver object map (see hpp::manipulation::ProblemSolver::addRobot) \\param rootJointType type of root joint among "anchor", "freeflyer", "planar", \\param urdfName name of the urdf file \\param srdfName name of the srdf file
def manipulation.robot.Robot.insertRobotModelFromString | ( | self, | |
robotName, | |||
rootJointType, | |||
urdfString, | |||
srdfString, | |||
frame = "universe" |
|||
) |
Same as Robot.insertRobotModel \\param urdfString XML string of the URDF, \\param srdfString XML string of the SRDF
def manipulation.robot.Robot.insertRobotModelOnFrame | ( | self, | |
robotName, | |||
frameName, | |||
rootJointType, | |||
urdfName, | |||
srdfName | |||
) |
Insert robot model as a child of a frame of the Device \\param robotName key of the robot in ProblemSolver object map (see hpp::manipulation::ProblemSolver::addRobot) \\param frameName name of the existing frame that will the root of the added robot, \\param rootJointType type of root joint among "anchor", "freeflyer", "planar", \\param urdfName name of the urdf file \\param srdfName name of the srdf file
def manipulation.robot.Robot.insertRobotSRDFModel | ( | self, | |
robotName, | |||
srdfPath | |||
) |
Load a SRDF for the robot. Several SRDF can thus be loaded for the same robot \\param robotName key of the robot in hpp::manipulation::Device object map (see hpp::manipulation::Device) \\param srdfPath path to srdf file (can start with "package://")
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. \\param envName key of the object in ProblemSolver object map (see hpp::manipulation::ProblemSolver::addRobot) \\param urdfName name of the urdf file, \\param srdfName name of the srdf file.
def manipulation.robot.Robot.loadHumanoidModel | ( | self, | |
robotName, | |||
rootJointType, | |||
urdfName, | |||
srdfName | |||
) |
def manipulation.robot.Robot.loadModel | ( | self, | |
robotName, | |||
rootJointType | |||
) |
Virtual function to load the robot model.
def manipulation.robot.Robot.setRootJointPosition | ( | self, | |
robotName, | |||
position | |||
) |
Set the position of root joint of a robot in world frame \\param robotName key of the robot in ProblemSolver object map. \\param position constant position of the root joint in world frame in initial configuration.
manipulation.robot.Robot.load |
manipulation.robot.Robot.robotNames |
manipulation.robot.Robot.rootJointType |