hpp-manipulation-corba
4.9.0
Corba server for manipulation planning
|
Load and handle a composite robot for manipulation planning. More...
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 | |
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.
robotName | name of the first robot that is loaded now, |
rootJointType | type of root joint among ("freeflyer", "planar", "anchor"), |
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.
robotName | key of the robot in hpp::manipulation::ProblemSolver object map (see hpp::manipulation::ProblemSolver::addRobot) |
rootJointType | type of root joint among "anchor", "freeflyer", "planar", |
urdfName | name of the urdf file |
srdfName | name of the srdf file |
def manipulation.robot.Robot.insertHumanoidModelFromString | ( | self, | |
robotName, | |||
rootJointType, | |||
urdfString, | |||
srdfString | |||
) |
Same as Robot.insertHumanoidModel.
urdfString | XML string of the URDF, |
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.
robotName | key of the robot in hpp::manipulation::ProblemSolver object map (see hpp::manipulation::ProblemSolver::addRobot) |
rootJointType | type of root joint among "anchor", "freeflyer", "planar", |
urdfName | name of the urdf file |
srdfName | name of the srdf file |
def manipulation.robot.Robot.insertRobotModelFromString | ( | self, | |
robotName, | |||
rootJointType, | |||
urdfString, | |||
srdfString | |||
) |
Same as Robot.insertRobotModel.
urdfString | XML string of the URDF, |
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.
robotName | key of the robot in ProblemSolver object map (see hpp::manipulation::ProblemSolver::addRobot) |
frameName | name of the existing frame that will the root of the added robot, |
rootJointType | type of root joint among "anchor", "freeflyer", "planar", |
urdfName | name of the urdf file |
srdfName | name of the srdf file |
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
robotName | key of the robot in hpp::manipulation::Device object map (see hpp::manipulation::Device) |
packageName | Name of the ROS package containing the model, |
modelName | Name of the package containing the model |
srdfSuffix | suffix for srdf file, |
The ros url are built as follows:
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.
envName | key of the object in ProblemSolver object map (see hpp::manipulation::ProblemSolver::addRobot) |
urdfName | name of the urdf file, |
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.
robotName | key of the robot in ProblemSolver object map. |
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 |