klampt.model.robotinfo module
Registry of semantic properties for robots to help build generalized (non-robot-specific) code.
A robot typically consists of a set of parts, a base (either fixed or
moving), end effectors, a controller, and other assorted properties. The
RobotInfo
data structure will let you define these and store them
in a human-editable file format. This is also used for klampt_control
and
some Robot Interface Layer controllers (see
klampt.control.robotinterfaceutils.OmniRobotInterface
).
Grippers also come with a lot of semantic information, such as typical
approach directions, opening widths, synergies, etc. These should be stored in
a GripperInfo
structure. (So far, Klamp’t doesn’t have built-in
integration with grasp planning algorithms, but we hope to add more in the
future.)
- class klampt.model.robotinfo.RobotInfo(name, modelFile=None, baseType='fixed', parts=None, endEffectors=None, grippers=None, properties=None)[source]
Bases:
object
Stores common semantic properties for a robot.
- name
a string identifying this robot by name.
- Type:
str
- modelFile
a file pointing to the Klamp’t model (.urdf or .rob.)
- Type:
str, optional
- baseType
specifies whether the robot has a mobile or floating base. Possible values are:
‘fixed’: rigidly attached
‘floating’: floating in space (e.g., drone, legged robot)
‘differential’: differential drive base (properties[‘differential’] should hold more info)
‘dubins’: Dubins car base (properties[‘dubins’] should hold more info)
- Type:
str
- parts
a set of named parts. Each part consists of a list of link names or indices.
- Type:
dict str->list
- endEffectors
a set of named end effectors.
- Type:
dict str->EndEffectorInfo
- grippers
a set of named grippers.
- Type:
dict str->GripperInfo
- properties
a dict of named properties. Values must be JSON-loadable/savable.
- Type:
dict str->anything
- controllerFile
the file containing code for the Klampt RIL controller.
Should be a Python file (
/path/to/file.py
) or module (package.module) containing a functionmake(robotModel)
that returns aRobotInterfaceBase
.- Type:
str, optional
- controllerArgs
extra arguments that will be passed to the make() function.
- Type:
list, optional
- simulatorFile
the file containing code for simulation emulators for the robot. If not provided, the default robot simulator is used.
Should be a Python file (
/path/to/file.py
) or module (package.module) containing a functionmake(sim,robotIndex)
which returns a pair(controller, emulators)
.Here,
controller
is aRobotInterfaceBase
configured for the simulator (seeklampt.control.simrobotinterface
).emulators
is a list ofSensorEmulator
orActuatorEmulator
objects configured for use in aSimpleSimulator
.- Type:
str, optional
- calibrationFiles
a set of calibration files that will be loaded and imposed on the klamptModel when it is loaded. Using separate calibration files is more efficient than overwriting a .rob or .urdf file when the calibration changes.
Valid keys include:
[sensor name]: a JSON file giving any of the named sensor’s settings (typically, the transform T)
kinematics: a JSON file giving link parent transforms and joint axes. The file should have format:
{"link1":{"axis":VALUE,"Tparent":VALUE} ...}
- Type:
dict str->str
- resourceDir
the directory containing resources for this robot.
- Type:
str, optional
- filePaths
a list of paths where files will be searched.
- Type:
list of str
- robotModel
a cached robot model, loaded upon calling
klamptModel()
. If a robot is loaded externally (e.g., viaWorldModel
) you may set this member to avoid re- loading a model.- Type:
- all_robots = {}
- static load(fn)[source]
Loads / registers a RobotInfo from a JSON file previously saved to disk.
- Return type:
- klamptModel()[source]
Returns the Klamp’t RobotModel associated with this robot, either by the
robotModel
object or loading from the given filenameself.modelFile
.The results are cached so this can be called many times without a performance hit.
- Return type:
- configureKinematics(file)[source]
Loads a json calibration file from the given file name and configures the kinematic model.
- saveKinematicCalibration(file, update_calibration_attr=True)[source]
Saves the kinematic calibration to a file
- configureSensor(sensor)[source]
Configures a sensor with a calibration, if present.
The calibration file can be a JSON, YAML, or numpy file. If the sensor is a camera, the calibration file can be an intrinsics calibration.
- Return type:
- saveSensorCalibration(sensor, file, update_calibration_attr=True)[source]
Configures a sensor with a calibration, if present.
The calibration file can be a JSON, YAML, or numpy file. If the sensor is a camera, the calibration file can be an intrinsics calibration.
- controller()[source]
Returns a Robot Interface Layer object configured for use on the real robot. Requires
controllerFile
to be defined.- Return type:
- configureControllerEndEffectors(controller)[source]
Configures a Robot Interface Layer object with the appropriate end effector configuration.
Assumes the controller is initialized.
Returns a dictionary mapping end effectors to parts and a list of end effectors that are not associated with any part.
- Return type:
Tuple
[Dict
[str
,str
],List
[str
]]
- configureSimulator(sim, robotIndex=0)[source]
Configures a
SimpleSimulator
to emulate the robot’s behavior.- Parameters:
sim (SimpleSimulator) – the simulator to configure. It should have a world model set up to already have a matching robot’s model.
robotIndex (int or str) – the index of the robot model in the sim’s world.
- eeSolver(endEffector, target)[source]
Given a named end effector and a target point, transform, or set of parameters from config.setConfig(ikgoal) / config.getConfig(ikgoal), returns the IKSolver for the end effector and that target.
- Return type:
- toDriverIndices(items)[source]
Converts link names or indices to robot driver indices
- Return type:
List
[int
]
- listResources()[source]
Retrieves a list of all named resources, if resourceDir is set
- Return type:
List
[str
]
- class klampt.model.robotinfo.EndEffectorInfo(link, activeLinks, ikObjective=None)[source]
Bases:
object
Stores info about default end effectors and the method for Cartesian solving.
- link
the link on which the end effector “lives”.
- Type:
int or str
- activeLinks
the links that are driven by cartesian commands to this end effector.
- Type:
list of int or str
- ikObjective
the template IK objective giving the tool center point and objective type. If None, this will be left unspecified.
- Type:
IKObjective, optional
- class klampt.model.robotinfo.GripperInfo(name, baseLink, fingerLinks=None, fingerDrivers=None, type=None, center=None, primaryAxis=None, secondaryAxis=None, fingerLength=None, fingerWidth=None, fingerDepth=None, maximumSpan=None, minimumSpan=None, closedConfig=None, openConfig=None, gripperLinks=None, klamptModel=None, register=True)[source]
Bases:
object
Stores basic information describing a gripper and its mounting on a robot.
For a vacuum-type gripper,
center should be set to middle of the vacuum at a “tight” seal.
primaryAxis should be set to the outward direction from the vacuum.
maximumSpan should be set to the outer diameter of the vacuum seal
minimumSpan should be set to the minimum diameter of an object that a seal can form around
fingerLength should be set to the amount the vacuum should lower from an offset away from the object (the length of the vacuum seal)
For a parallel-jaw gripper,
center should be set to the deepest point within the gripper.
primaryAxis should be set to the “down” direction for a top-down grasp (away from the wrist, usually).
secondaryAxis should be set to the axis along which the fingers close / open (either sign is OK).
fingerLength should be set to the distance along primaryAxis from center to the tips of the gripper’s fingers.
fingerWidth should be set to the width of the fingers.
fingerDepth should be set to the thickness of the fingers along secondaryAxis
maximumSpan should be set to the fingers’ maximum separation.
minimumSpan should be set to the fingers’ minimum separation.
For a multi-finger gripper, these elements are less important, but can help with general heuristics.
center should be set to a point on the “palm”
primaryAxis should be set to a open direction away from the wrist.
secondaryAxis should be set to the axis along which the fingers close / open in a power grasp (either sign is OK).
fingerLength should be set to approximately the length of each finger.
fingerWidth should be set to approximately the width of each finger.
fingerDepth should be set to approximately the thickness of each finger.
maximumSpan should be set to the width of the largest object grippable.
minimumSpan should be set to the width of the smallest object grippable.
- name
the gripper name
- Type:
str
- baseLink
the index of the gripper’s base
- Type:
int or str
- fingerLinks
the moving indices of the gripper’s fingers.
- Type:
list of int
- fingerDrivers
the driver indices of the gripper’s fingers. Can also be a list of list of ints if each finger joint can be individually actuated.
- Type:
list of int
- type
Specifies the type of gripper. Can be ‘vacuum’, ‘parallel’, ‘wrapping’, or None (unknown)
- Type:
str, optional
- center
A central point on the “palm” of the gripper.
- Type:
list of 3 floats, optional
- primaryAxis
The local axis of the gripper that opposes the “typical” load. (Unit vector in the opposite direction of the load)
- Type:
list of 3 floats, optional
- secondaryAxis
The local axis of the gripper perpendicular to the primary that dictates the direction of the fingers opening and closing
- Type:
list of 3 floats, optional
- fingerLength,fingerWidth,fingerDepth
dimensions of the fingers.
- Type:
float, optional
- maximumSpan
the maximum opening span of the gripper.
- Type:
float, optional
- minimumSpan
the minimum opening span of the gripper.
- Type:
float, optional
- closedConfig
the “logical closed” gripper finger config.
- Type:
list of floats, optional
- openConfig
the “logical open” gripper finger config.
- Type:
list of floats, optional
- synergies
for multifingered hands, a set of “synergies” that are able to generate a full gripper configuration. If a synergy is a list of k Vectors, the synergy accepts k-1 parameters
p
in the range [0,1]^(k-1) and outputs an affine combination A[0]*p[0] + … + A[k-2]*p[k-2] + A[k-1].- Type:
dict str -> list of Vectors
- gripperLinks
the list of all links attached to the gripper, including non-actuated ones. If not provided, assumed to be the base link plus all descendant links on the klamptModel.
- Type:
list of int, optional
- klamptModel
the Klamp’t .rob or .urdf model to which this refers to. Note: this is not necessarily a model of just the gripper. To get just the gripper, use
self.getSubrobot()
.- Type:
str, optional
- all_grippers = {}
- static load(fn)[source]
Loads / registers a GripperInfo from a JSON file previously saved to disk.
- Return type:
- static mounted(gripper, klamptModel, baseLink, name=None, register=True)[source]
From a standalone gripper, return a GripperInfo such that the link indices are shifted onto a new robot model.
klamptModel should contain the arm as well as the gripper links, and baseLink should be the name or index of the gripper base on the model.
- partwayOpenConfig(amount)[source]
Returns a finger configuration partway open, with amount in the range [0 (closed),1 (fully open)].
- Return type:
Sequence
[float
]
- configToOpening(qfinger)[source]
Estimates how far qfinger is from closedConfig to openConfig. Only meaningful if qfinger is close to being along the straight C-space line between the two.
- Return type:
float
- evalSynergy(synergy_name, parameters)[source]
Maps from a set of parameters to a full gripper configuration according to the given synergy.
- Return type:
Sequence
[float
]
- configToSynergy(qfinger, synergy_name=None)[source]
Maps a finger config to the closest synergy parameters. If synergy_name is given, then this restricts the search to a single synergy.
Only works for affine synergies.
- Return type:
Tuple
[str
,Sequence
[float
]]
- widthToOpening(width)[source]
Returns an opening amount in the range 0 (closed) to 1 (open) such that the fingers have a given width between them.
- Return type:
float
- openingToWidth(opening)[source]
For a given opening amount in the range 0 (closed) to 1 (open) returns an approximation to the width between the fingers.
- Return type:
float
- setFingerConfig(qrobot, qfinger)[source]
Given a full robot config qrobot, returns a config but with the finger degrees of freedom fixed to qfinger.
- Return type:
Sequence
[float
]
- getFingerConfig(qrobot)[source]
Given a full robot config qrobot, returns a finger config.
- Return type:
Sequence
[float
]
- descendantLinks(robot)[source]
Returns all links under the base link. This may be different from fingerLinks if there are some frozen DOFs and you prefer to treat a finger configuration as only those DOFS for the active links.
- Return type:
List
[int
]
- getSubrobot(robot, all_descendants=True)[source]
Returns the SubRobotModel of the gripper given a RobotModel.
If some of the links belonging to the gripper are frozen and not part of the DOFs (i.e., part of fingerLinks), then they will be included in the SubRobotModel if all_descendants=True. This means there may be a discrepancy between the finger configuration and the sub-robot configuration.
Otherwise, they will be excluded and finger configurations will map one-to-one to the sub-robot.
- Return type:
- getGeometry(robot, qfinger=None, type='Group')[source]
Returns a Geometry of the gripper frozen at its configuration. If qfinger = None, the current configuration is used. Otherwise, qfinger is a finger configuration.
type can be ‘Group’ (most general and fastest) or ‘TriangleMesh’ (compatible with Jupyter notebook visualizer.)
- Return type:
- addToVis(robot=None, animate=True, base_xform=None)[source]
Adds the gripper to the klampt.vis scene.
- Return type:
None
- Parameters:
robot (RobotModel, optional) – if given, this gripper is a sub-robot of the given robot.
animate (bool) – if True, animates the opening and closing of the gripper.
base_xform (se3 element, optional) – if given and robot=False, poses the gripper base at this transform.