klampt.robotsim (core classes) module

The robotsim module contains all of the core classes and functions from the C++ API. These are imported into the main klampt namespace.

Note: The C++ API is converted from SWIG, so the documentation may be a little rough. The first lines of the documentation for overloaded SWIG functions may describe the signature for each function overload. For example, klampt.WorldModel.add() contains the listing:

add (name,robot): RobotModel
add (name,obj): RigidObjectModel
add (name,terrain): TerrainModel

Parameters: * name (str) –
            * robot (RobotModel, optional) –
            * obj (RigidObjectModel, optional) –
            * terrain (TerrainModel, optional) –

The colon followed by a type descriptor, : Type, gives the type of the return value. This means that if the second argument is a RobotModel, the first overload is matched, and the return value is a klampt.RobotModel.

Modeling robots and worlds

Imported into the main klampt package.

WorldModel(*args)

The main world class, containing robots, rigid objects, and static environment geometry.

RobotModel()

A model of a dynamic and kinematic robot.

RobotModelLink()

A reference to a link of a RobotModel.

RobotModelDriver()

A reference to a driver of a RobotModel.

RigidObjectModel()

A rigid movable object.

TerrainModel()

Static environment geometry.

Mass()

Stores mass information for a rigid body or robot link.

ContactParameters()

Stores contact parameters for an entity.

set_random_seed(seed)

Sets the random seed used by the motion planner.

destroy()

destroys internal data structures

Modeling geometries

Imported into the main klampt package.

Geometry3D(*args)

The three-D geometry container used throughout Klampt.

Appearance(*args)

Geometry appearance information.

GeometricPrimitive()

A geometric primitive.

TriangleMesh()

A 3D indexed triangle mesh class.

PointCloud()

A 3D point cloud class.

VolumeGrid()

An axis-aligned volumetric grid, typically a signed distance transform with > 0 indicating outside and < 0 indicating inside.

ConvexHull()

Stores a set of points to be set into a ConvexHull type.

DistanceQuerySettings()

Configures the _ext distance queries of Geometry3D.

DistanceQueryResult()

The result from a "fancy" distance query of Geometry3D.

ContactQueryResult()

The result from a contact query of Geometry3D.

Inverse kinematics

Imported into the main klampt package.

IKObjective(*args)

A class defining an inverse kinematic target.

IKSolver(*args)

An inverse kinematics solver based on the Newton-Raphson technique.

GeneralizedIKObjective(*args)

An inverse kinematics target for matching points between two robots and/or objects.

GeneralizedIKSolver(world)

An inverse kinematics solver between multiple robots and/or objects.

Simulation

Imported into the main klampt package.

Simulator(model)

A dynamics simulator for a WorldModel.

SimBody()

A reference to a rigid body inside a Simulator (either a RigidObjectModel, TerrainModel, or a link of a RobotModel).

SimJoint()

An interface to ODE's hinge and slider joints.

SimRobotController()

A controller for a simulated robot.

SimRobotSensor(robot, sensor)

A sensor on a simulated robot.

Equilibrium testing

See also the aliases in the klampt.model.contact module.

com_equilibrium(*args)

Tests whether the given COM com is stable for the given contacts and the given external force fext.

com_equilibrium_2d(*args)

Tests whether the given COM com is stable for the given contacts and the given external force fext.

equilibrium_torques(*args)

Solves for the torques / forces that keep the robot balanced against gravity.

force_closure(*args)

Returns true if the list of contact points has force closure.

force_closure_2d(*args)

Returns true if the list of 2D contact points has force closure.

set_friction_cone_approximation_edges(numEdges)

Globally sets the number of edges used in the friction cone approximation.

support_polygon(*args)

Calculates the support polygon for a given set of contacts and a downward external force (0,0,-g).

support_polygon_2d(*args)

Calculates the support polygon (interval) for a given set of contacts and a downward external force (0,-g).

Input/Output

Imported into the klampt.io package

subscribe_to_stream(*args)

Subscribes a Geometry3D to a stream.

detach_from_stream(protocol, name)

Unsubscribes from a stream previously subscribed to via SubscribeToStream()

process_streams(*args)

Does some processing on stream subscriptions.

wait_for_stream(protocol, name, timeout)

Waits up to timeout seconds for an update on the given stream.

threejs_get_scene(arg1)

Exports the WorldModel to a JSON string ready for use in Three.js.

threejs_get_transforms(arg1)

Exports the WorldModel to a JSON string ready for use in Three.js.

Visualization

For use in GLWidgetPlugin.

Widget()

WidgetSet()

ObjectPoser(object)

param object:

RobotPoser(robot)

param robot:

PointPoser()

TransformPoser()

Viewport()

Module contents

Classes:

WorldModel(*args)

The main world class, containing robots, rigid objects, and static environment geometry.

RobotModel()

A model of a dynamic and kinematic robot.

RobotModelLink()

A reference to a link of a RobotModel.

RigidObjectModel()

A rigid movable object.

TerrainModel()

Static environment geometry.

Mass()

Stores mass information for a rigid body or robot link.

ContactParameters()

Stores contact parameters for an entity.

SimRobotController()

A controller for a simulated robot.

SimRobotSensor(robot, sensor)

A sensor on a simulated robot.

SimBody()

A reference to a rigid body inside a Simulator (either a RigidObjectModel, TerrainModel, or a link of a RobotModel).

SimJoint()

An interface to ODE's hinge and slider joints.

Simulator(model)

A dynamics simulator for a WorldModel.

Geometry3D(*args)

The three-D geometry container used throughout Klampt.

Appearance(*args)

Geometry appearance information.

DistanceQuerySettings()

Configures the _ext distance queries of Geometry3D.

DistanceQueryResult()

The result from a "fancy" distance query of Geometry3D.

ContactQueryResult()

The result from a contact query of Geometry3D.

TriangleMesh()

A 3D indexed triangle mesh class.

PointCloud()

A 3D point cloud class.

GeometricPrimitive()

A geometric primitive.

ConvexHull()

Stores a set of points to be set into a ConvexHull type.

VolumeGrid()

An axis-aligned volumetric grid, typically a signed distance transform with > 0 indicating outside and < 0 indicating inside.

IKObjective(*args)

A class defining an inverse kinematic target.

IKSolver(*args)

An inverse kinematics solver based on the Newton-Raphson technique.

GeneralizedIKObjective(*args)

An inverse kinematics target for matching points between two robots and/or objects.

GeneralizedIKSolver(world)

An inverse kinematics solver between multiple robots and/or objects.

AABBPoser()

BoxPoser()

ObjectPoser(object)

param object:

PointPoser()

RobotModelDriver()

A reference to a driver of a RobotModel.

RobotPoser(robot)

param robot:

SpherePoser()

SwigPyIterator(*args, **kwargs)

TransformPoser()

Viewport()

Widget()

WidgetSet()

stringMap(*args)

Functions:

DetachFromStream(*args, **kwargs)

Deprecated in a future version of Klampt.

ProcessStreams(*args, **kwargs)

Deprecated in a future version of Klampt.

SampleTransform(obj)

Deprecated.

SubscribeToStream(*args, **kwargs)

Deprecated in a future version of Klampt.

ThreeJSGetScene(*args, **kwargs)

Deprecated in a future version of Klampt.

ThreeJSGetTransforms(*args, **kwargs)

Deprecated in a future version of Klampt.

WaitForStream(*args, **kwargs)

Deprecated in a future version of Klampt.

comEquilibrium(*args, **kwargs)

Deprecated in a future version of Klampt.

comEquilibrium2D(*args, **kwargs)

Deprecated in a future version of Klampt.

com_equilibrium(*args)

Tests whether the given COM com is stable for the given contacts and the given external force fext.

com_equilibrium_2d(*args)

Tests whether the given COM com is stable for the given contacts and the given external force fext.

destroy()

destroys internal data structures

detach_from_stream(protocol, name)

Unsubscribes from a stream previously subscribed to via SubscribeToStream()

doubleArray_frompointer(t)

rtype:

doubleArray

equilibriumTorques(*args, **kwargs)

Deprecated in a future version of Klampt.

equilibrium_torques(*args)

Solves for the torques / forces that keep the robot balanced against gravity.

floatArray_frompointer(t)

rtype:

floatArray

forceClosure(*args, **kwargs)

Deprecated in a future version of Klampt.

forceClosure2D(*args, **kwargs)

Deprecated in a future version of Klampt.

force_closure(*args)

Returns true if the list of contact points has force closure.

force_closure_2d(*args)

Returns true if the list of 2D contact points has force closure.

intArray_frompointer(t)

rtype:

intArray

process_streams(*args)

Does some processing on stream subscriptions.

setFrictionConeApproximationEdges(*args, ...)

Deprecated in a future version of Klampt.

setRandomSeed(*args, **kwargs)

Deprecated in a future version of Klampt.

set_friction_cone_approximation_edges(numEdges)

Globally sets the number of edges used in the friction cone approximation.

set_random_seed(seed)

Sets the random seed used by the motion planner.

subscribe_to_stream(*args)

Subscribes a Geometry3D to a stream.

supportPolygon(*args, **kwargs)

Deprecated in a future version of Klampt.

supportPolygon2D(*args, **kwargs)

Deprecated in a future version of Klampt.

support_polygon(*args)

Calculates the support polygon for a given set of contacts and a downward external force (0,0,-g).

support_polygon_2d(*args)

Calculates the support polygon (interval) for a given set of contacts and a downward external force (0,-g).

threejs_get_scene(arg1)

Exports the WorldModel to a JSON string ready for use in Three.js.

threejs_get_transforms(arg1)

Exports the WorldModel to a JSON string ready for use in Three.js.

wait_for_stream(protocol, name, timeout)

Waits up to timeout seconds for an update on the given stream.

class klampt.WorldModel(*args)[source]

Bases: object

The main world class, containing robots, rigid objects, and static environment geometry.

Every robot/robot link/terrain/rigid object is given a unique ID in the world. This is potentially a source of confusion because some functions take IDs and some take indices. Only the WorldModel and Simulator classes use IDs when the argument has ‘id’ as a suffix, e.g., geometry(), appearance(), Simulator.inContact(). All other functions use indices, e.g. robot(0), terrain(0), etc.

To get an object’s ID, you can see the value returned by loadElement and/or object.getID(). states.

To save/restore the state of the model, you must manually maintain copies of the states of whichever objects you wish to save/restore.

C++ includes: robotmodel.h

Creates a WorldModel.

__init__ (): WorldModel

__init__ (ptrRobotWorld): WorldModel

__init__ (w): WorldModel

__init__ (fn): WorldModel

Parameters:
  • ptrRobotWorld (void *, optional) –

  • w (WorldModel, optional) –

  • fn (str, optional) –

  • Given no arguments, creates a new world.

  • Given another WorldModel instance, creates a reference to an existing world. (To create a copy, use the copy() method.)

  • Given a string, loads from a file. A PyException is raised on failure.

  • Given a pointer to a C++ RobotWorld structure, a reference to that structure is returned. (This is advanced usage, seen only when interfacing C++ and Python code)

Attributes:

thisown

The membership flag

index

index : int

Methods:

copy()

Creates a copy of the world model.

readFile(fn)

Reads from a world XML file.

loadFile(fn)

Alias of readFile.

saveFile(fn[, elementDir])

Saves to a world XML file.

numRobots()

Returns the number of robots.

numRobotLinks(robot)

Returns the number of links on the given robot.

numRigidObjects()

Returns the number of rigid objects.

numTerrains()

Returns the number of terrains.

numIDs()

Returns the total number of world ids.

robot(*args)

Returns a RobotModel in the world by index or name.

robotLink(*args)

Returns a RobotModelLink of some RobotModel in the world by index or name.

rigidObject(*args)

Returns a RigidObjectModel in the world by index or name.

terrain(*args)

Returns a TerrainModel in the world by index or name.

makeRobot(name)

Creates a new empty robot.

makeRigidObject(name)

Creates a new empty rigid object.

makeTerrain(name)

Creates a new empty terrain.

loadRobot(fn)

Loads a robot from a .rob or .urdf file.

loadRigidObject(fn)

Loads a rigid object from a .obj or a mesh file.

loadTerrain(fn)

Loads a rigid object from a mesh file.

loadElement(fn)

Loads some element from a file, automatically detecting its type.

add(*args)

Adds a copy of the given robot, rigid object, or terrain to this world, either from this WorldModel or another.

remove(*args)

Removes a robot, rigid object, or terrain from the world.

getName(id)

Retrieves the name for a given element ID.

geometry(id)

Retrieves a geometry for a given element ID.

appearance(id)

Retrieves an appearance for a given element ID.

drawGL()

Draws the entire world using OpenGL.

enableGeometryLoading(enabled)

If geometry loading is set to false, then only the kinematics are loaded from disk, and no geometry / visualization / collision detection structures will be loaded.

enableInitCollisions(enabled)

If collision detection is set to true, then collision acceleration data structures will be automatically initialized, with debugging information.

property thisown

The membership flag

copy()[source]

Creates a copy of the world model. Note that geometries and appearances are shared, so this is very quick.

Return type:

WorldModel

readFile(fn)[source]

Reads from a world XML file.

Return type:

bool

Parameters:

fn (str) –

Returns:

True if successful, False if failed.

loadFile(fn)[source]

Alias of readFile.

Return type:

bool

Parameters:

fn (str) –

saveFile(fn, elementDir=None)[source]

Saves to a world XML file. If elementDir is provided, then robots, terrains, etc. will be saved there. Otherwise they will be saved to a folder with the same base name as fn (without the trailing .xml)

Return type:

bool

Parameters:
  • fn (str) –

  • elementDir (str, optional) – default value None

numRobots()[source]

Returns the number of robots.

Return type:

int

Returns the number of links on the given robot.

Return type:

int

Parameters:

robot (int) –

numRigidObjects()[source]

Returns the number of rigid objects.

Return type:

int

numTerrains()[source]

Returns the number of terrains.

Return type:

int

numIDs()[source]

Returns the total number of world ids.

Return type:

int

robot(*args)[source]

Returns a RobotModel in the world by index or name.

robot (index): RobotModel

robot (name): RobotModel

Return type:

RobotModel

Parameters:
  • index (int, optional) –

  • name (str, optional) –

Returns:

Return type:

RobotModel

Returns a RobotModelLink of some RobotModel in the world by index or name.

robotLink (robot,index): RobotModelLink

robotLink (robot,name): RobotModelLink

Return type:

RobotModelLink

Parameters:
  • robot (str or int) –

  • index (int, optional) –

  • name (str, optional) –

Returns:

Return type:

RobotModelLink

rigidObject(*args)[source]

Returns a RigidObjectModel in the world by index or name.

rigidObject (index): RigidObjectModel

rigidObject (name): RigidObjectModel

Return type:

RigidObjectModel

Parameters:
  • index (int, optional) –

  • name (str, optional) –

Returns:

Return type:

RigidObjectModel

terrain(*args)[source]

Returns a TerrainModel in the world by index or name.

terrain (index): TerrainModel

terrain (name): TerrainModel

Return type:

TerrainModel

Parameters:
  • index (int, optional) –

  • name (str, optional) –

Returns:

Return type:

TerrainModel

makeRobot(name)[source]

Creates a new empty robot. (Not terribly useful now since you can’t resize the number of links yet)

Return type:

RobotModel

Parameters:

name (str) –

makeRigidObject(name)[source]

Creates a new empty rigid object.

Return type:

RigidObjectModel

Parameters:

name (str) –

makeTerrain(name)[source]

Creates a new empty terrain.

Return type:

TerrainModel

Parameters:

name (str) –

loadRobot(fn)[source]

Loads a robot from a .rob or .urdf file. An empty robot is returned if loading fails.

Return type:

RobotModel

Parameters:

fn (str) –

loadRigidObject(fn)[source]

Loads a rigid object from a .obj or a mesh file. An empty rigid object is returned if loading fails.

Return type:

RigidObjectModel

Parameters:

fn (str) –

loadTerrain(fn)[source]

Loads a rigid object from a mesh file. An empty terrain is returned if loading fails.

Return type:

TerrainModel

Parameters:

fn (str) –

loadElement(fn)[source]

Loads some element from a file, automatically detecting its type. Meshes are interpreted as terrains.

Return type:

int

Parameters:

fn (str) –

Returns:

The element’s ID, or -1 if loading failed.

add(*args)[source]

Adds a copy of the given robot, rigid object, or terrain to this world, either from this WorldModel or another.

add (name,robot): RobotModel

add (name,obj): RigidObjectModel

add (name,terrain): TerrainModel

Return type:

TerrainModel

Parameters:
Returns:

Return type:

(TerrainModel or RobotModel or RigidObjectModel)

remove(*args)[source]

Removes a robot, rigid object, or terrain from the world. It must be in this world or an exception is raised.

remove (robot)

remove (object)

remove (terrain)

Return type:

None

Parameters:

Important

All other RobotModel, RigidObjectModel, or TerrainModel references will be invalidated.

getName(id)[source]

Retrieves the name for a given element ID.

Return type:

str

Parameters:

id (int) –

geometry(id)[source]

Retrieves a geometry for a given element ID.

Return type:

Geometry3D

Parameters:

id (int) –

appearance(id)[source]

Retrieves an appearance for a given element ID.

Return type:

Appearance

Parameters:

id (int) –

drawGL()[source]

Draws the entire world using OpenGL.

Return type:

None

enableGeometryLoading(enabled)[source]

If geometry loading is set to false, then only the kinematics are loaded from disk, and no geometry / visualization / collision detection structures will be loaded. Useful for quick scripts that just use kinematics / dynamics of a robot.

Return type:

None

Parameters:

enabled (bool) –

enableInitCollisions(enabled)[source]

If collision detection is set to true, then collision acceleration data structures will be automatically initialized, with debugging information. Useful for scripts that do planning and for which collision initialization may take a long time.

Return type:

None

Parameters:

enabled (bool) –

Note that even when this flag is off, the collision acceleration data structures will indeed be initialized the first time that geometry collision, distance, or ray-casting routines are called.

property index

index : int

class klampt.RobotModel[source]

Bases: object

A model of a dynamic and kinematic robot.

Stores both constant information, like the reference placement of the links, joint limits, velocity limits, etc, as well as a current configuration and current velocity which are state-dependent. Several functions depend on the robot’s current configuration and/or velocity. To update that, use the setConfig() and setVelocity() functions. setConfig() also update’s the robot’s link transforms via forward kinematics. You may also use setDOFPosition and setDOFVelocity for individual changes, but these are more expensive because each call updates all of the affected the link transforms.

It is important to understand that changing the configuration of the model doesn’t actually send a command to the physical / simulated robot. Moreover, the model does not automatically get updated when the physical / simulated robot moves. In essence, the model maintains temporary storage for performing kinematics, dynamics, and planning computations, as well as for visualization.

The state of the robot is retrieved using getConfig/getVelocity calls, and is set using setConfig/setVelocity. Because many routines change the robot’s configuration, like IK and motion planning, a common design pattern is to save/restore the configuration as follows:

q = robot.getConfig()
do some stuff that may touch the robot's configuration...
robot.setConfig(q)

The model maintains configuration/velocity/acceleration/torque limits. However, these are not enforced by the model, so you can happily set configurations outside the limits. Valid commands must rather be enforced by the planner / controller / simulator.

As elsewhere in Klampt, the mapping between links and drivers is not one-to one. A driver is essentially an actuator and transmission, and for most links a link is driven by a unique driver (e.g., a motor and gearbox). However, there do exist certain cases in which a link is not driven at all (e.g., the 6 virtual links of a floating-base robot), or multiple links are driven by a single actuator (e.g., a parallel-bar mechanism or a compliant hand). There are also unusual drivers that introduce underactuated dynamics into the system, such as a differential drive or Dubin’s car mobile base. Care must be taken when sending commands to motor controllers (e.g., Klampt Robot Interface Layer), which often work in the actuator space rather than joint space. (See configToDrivers(), configFromDrivers(), velocityToDrivers(), velocityFromDrivers()).

C++ includes: robotmodel.h

Attributes:

thisown

The membership flag

world

world : int

index

index : int

robot

robot : p.Klampt::RobotModel

dirty_dynamics

dirty_dynamics : bool

name

id

Returns the ID of the robot in its world.

config

Retrieves the current configuration of the robot model.

velocity

Retreives the current velocity of the robot model.

Methods:

loadFile(fn)

Loads the robot from the file fn.

saveFile(fn[, geometryPrefix])

Saves the robot to the file fn.

getID()

Returns the ID of the robot in its world.

getName()

rtype:

str

setName(name)

Sets the name of the robot.

numLinks()

Returns the number of links = number of DOF's.

link(*args)

Returns a reference to the link by index or name.

numDrivers()

Returns the number of drivers.

driver(*args)

Returns a reference to the driver by index or name.

getJointType(*args)

Returns the joint type of the joint connecting the link to its parent, where the link is identified by index or by name.

getConfig()

Retrieves the current configuration of the robot model.

getVelocity()

Retreives the current velocity of the robot model.

setConfig(q)

Sets the current configuration of the robot.

setVelocity(dq)

Sets the current velocity of the robot model.

getJointLimits()

Returns a pair (qmin,qmax) of min/max joint limit vectors.

setJointLimits(qmin, qmax)

Sets the min/max joint limit vectors (must have length numLinks())

getVelocityLimits()

Returns the velocity limit vector vmax, the constraint is \(|dq[i]| \leq vmax[i]\)

setVelocityLimits(vmax)

Sets the velocity limit vector vmax, the constraint is \(|dq[i]| \leq vmax[i]\)

getAccelerationLimits()

Returns the acceleration limit vector amax, the constraint is \(|ddq[i]| \leq amax[i]\)

setAccelerationLimits(amax)

Sets the acceleration limit vector amax, the constraint is \(|ddq[i]| \leq amax[i]\)

getTorqueLimits()

Returns the torque limit vector tmax, the constraint is \(|torque[i]| \leq tmax[i]\)

setTorqueLimits(tmax)

Sets the torque limit vector tmax, the constraint is \(|torque[i]| \leq tmax[i]\)

setDOFPosition(*args)

Sets a single DOF's position (by index or by name).

getDOFPosition(*args)

Returns a single DOF's position (by name)

getCom()

Returns the 3D center of mass at the current config.

getComVelocity()

Returns the 3D velocity of the center of mass at the current config / velocity.

getComJacobian()

Computes the Jacobian matrix of the current center of mass.

getComJacobianCols(links)

Returns the Jacobian matrix of the current center of mass w.r.t.

getLinearMomentum()

Computes the 3D linear momentum vector.

getAngularMomentum()

Computes the 3D angular momentum vector.

getKineticEnergy()

Computes the kinetic energy at the current config / velocity.

getTotalInertia()

Computes the 3x3 total inertia matrix of the robot.

getMassMatrix()

Computes the nxn mass matrix B(q).

getMassMatrixInv()

Computes the inverse of the nxn mass matrix B(q)^-1.

getMassMatrixDeriv(i)

Computes the derivative of the nxn mass matrix with respect to q_i.

getMassMatrixTimeDeriv()

Computes the derivative of the nxn mass matrix with respect to t, given the robot's current velocity.

getCoriolisForceMatrix()

Computes the Coriolis force matrix C(q,dq) for current config and velocity.

getCoriolisForces()

Computes the Coriolis forces C(q,dq)*dq for current config and velocity.

getGravityForces(g)

Computes the generalized gravity vector G(q) for the given workspace gravity vector g (usually (0,0,-9.8)).

torquesFromAccel(ddq)

Computes the inverse dynamics.

accelFromTorques(t)

Computes the foward dynamics.

interpolate(a, b, u)

Interpolates smoothly between two configurations, properly taking into account nonstandard joints.

distance(a, b)

Computes a distance between two configurations, properly taking into account nonstandard joints.

interpolateDeriv(a, b)

Returns the configuration derivative at a as you interpolate toward b at unit speed.

randomizeConfig([unboundedScale])

Samples a random configuration and updates the robot's pose.

configToDrivers(config)

Converts a full configuration (length numLinks()) to a list of driver values (length numDrivers()).

velocityToDrivers(velocities)

Converts a full velocity vector (length numLinks()) to a list of driver velocities (length numDrivers()).

configFromDrivers(driverValues)

Converts a list of driver values (length numDrivers()) to a full configuration (length numLinks()).

velocityFromDrivers(driverVelocities)

Converts a list of driver velocities (length numDrivers()) to a full velocity vector (length numLinks()).

selfCollisionEnabled(link1, link2)

Queries whether self collisions between two links is enabled.

enableSelfCollision(link1, link2, value)

Enables/disables self collisions between two links (depending on value)

selfCollides()

Returns true if the robot is in self collision (faster than manual testing)

drawGL([keepAppearance])

Draws the robot geometry.

reduce(robot)

Sets self to a reduced version of robot, where all fixed DOFs are eliminated.

mount(link, subRobot, R, t)

Mounts a sub-robot onto a link, with its origin at a given local transform (R,t).

sensor(*args)

Returns a sensor by index or by name.

addSensor(name, type)

Adds a new sensor with a given name and type.

property thisown

The membership flag

loadFile(fn)[source]

Loads the robot from the file fn.

Return type:

bool

Parameters:

fn (str) –

Returns:

True if successful, False if failed.

saveFile(fn, geometryPrefix=None)[source]

Saves the robot to the file fn.

Return type:

bool

Parameters:
  • fn (str) –

  • geometryPrefix (str, optional) – default value None

If geometryPrefix == None (default), the geometry is not saved. Otherwise, the geometry of each link will be saved to files named geometryPrefix+name, where name is either the name of the geometry file that was loaded, or [link_name].off

getID()[source]

Returns the ID of the robot in its world.

Return type:

int

Note

The world ID is not the same as the robot index.

getName()[source]
Return type:

str

setName(name)[source]

Sets the name of the robot.

Return type:

None

Parameters:

name (str) –

Returns the number of links = number of DOF’s.

Return type:

int

Returns a reference to the link by index or name.

link (index): RobotModelLink

link (name): RobotModelLink

Return type:

RobotModelLink

Parameters:
  • index (int, optional) –

  • name (str, optional) –

Returns:

Return type:

RobotModelLink

numDrivers()[source]

Returns the number of drivers.

Return type:

int

driver(*args)[source]

Returns a reference to the driver by index or name.

driver (index): RobotModelDriver

driver (name): RobotModelDriver

Return type:

RobotModelDriver

Parameters:
  • index (int, optional) –

  • name (str, optional) –

Returns:

Return type:

RobotModelDriver

getJointType(*args)[source]

Returns the joint type of the joint connecting the link to its parent, where the link is identified by index or by name.

getJointType (index): str

getJointType (name): str

Return type:

str

Parameters:
  • index (int, optional) –

  • name (str, optional) –

Returns:

Return type:

str

getConfig()[source]

Retrieves the current configuration of the robot model.

Return type:

None

getVelocity()[source]

Retreives the current velocity of the robot model.

Return type:

None

setConfig(q)[source]

Sets the current configuration of the robot. Input q is a vector of length numLinks(). This also updates forward kinematics of all links.

Return type:

None

Parameters:

q (list of floats) –

Again, it is important to realize that the RobotModel is not the same as a simulated robot, and this will not change the simulation world. Many functions such as IK and motion planning use the RobotModel configuration as a temporary variable, so if you need to keep the configuration through a robot-modifying function call, you should call q = robot.getConfig() before the call, and then robot.setConfig(q) after it.

setVelocity(dq)[source]

Sets the current velocity of the robot model. Like the configuration, this is also essentially a temporary variable.

Return type:

None

Parameters:

dq (list of floats) –

getJointLimits()[source]

Returns a pair (qmin,qmax) of min/max joint limit vectors.

Return type:

None

setJointLimits(qmin, qmax)[source]

Sets the min/max joint limit vectors (must have length numLinks())

Return type:

None

Parameters:
  • qmin (list of floats) –

  • qmax (list of floats) –

getVelocityLimits()[source]

Returns the velocity limit vector vmax, the constraint is \(|dq[i]| \leq vmax[i]\)

Return type:

None

setVelocityLimits(vmax)[source]

Sets the velocity limit vector vmax, the constraint is \(|dq[i]| \leq vmax[i]\)

Return type:

None

Parameters:

vmax (list of floats) –

getAccelerationLimits()[source]

Returns the acceleration limit vector amax, the constraint is \(|ddq[i]| \leq amax[i]\)

Return type:

None

setAccelerationLimits(amax)[source]

Sets the acceleration limit vector amax, the constraint is \(|ddq[i]| \leq amax[i]\)

Return type:

None

Parameters:

amax (list of floats) –

getTorqueLimits()[source]

Returns the torque limit vector tmax, the constraint is \(|torque[i]| \leq tmax[i]\)

Return type:

None

setTorqueLimits(tmax)[source]

Sets the torque limit vector tmax, the constraint is \(|torque[i]| \leq tmax[i]\)

Return type:

None

Parameters:

tmax (list of floats) –

setDOFPosition(*args)[source]

Sets a single DOF’s position (by index or by name).

setDOFPosition (i,qi)

setDOFPosition (name,qi)

Return type:

None

Parameters:
  • i (int, optional) –

  • qi (float) –

  • name (str, optional) –

Note

If you are setting several joints at once, use setConfig because this function computes forward kinematics for all descendant links each time it is called.

getDOFPosition(*args)[source]

Returns a single DOF’s position (by name)

getDOFPosition (i): float

getDOFPosition (name): float

Return type:

float

Parameters:
  • i (int, optional) –

  • name (str, optional) –

Returns:

Return type:

float

getCom()[source]

Returns the 3D center of mass at the current config.

Return type:

None

getComVelocity()[source]

Returns the 3D velocity of the center of mass at the current config / velocity.

Return type:

None

getComJacobian()[source]

Computes the Jacobian matrix of the current center of mass.

Returns: :rtype: None

ndarray: a 3xn matrix J such that np.dot(J,dq) gives the COM velocity at the currene configuration

getComJacobianCols(links)[source]

Returns the Jacobian matrix of the current center of mass w.r.t. some links of the robot.

Return type:

None

Parameters:

links (list of int) –

Returns:

a 3xlen(links) matrix J such that np.dot(J,dqlinks) gives the COM velocity at the current configuration, and dqlinks is the array of velocities of the links given by links

Return type:

ndarray

getLinearMomentum()[source]

Computes the 3D linear momentum vector.

Return type:

None

getAngularMomentum()[source]

Computes the 3D angular momentum vector.

Return type:

None

getKineticEnergy()[source]

Computes the kinetic energy at the current config / velocity.

Return type:

float

getTotalInertia()[source]

Computes the 3x3 total inertia matrix of the robot.

Return type:

None

getMassMatrix()[source]

Computes the nxn mass matrix B(q).

Takes O(n^2) time

Return type:

None

getMassMatrixInv()[source]

Computes the inverse of the nxn mass matrix B(q)^-1.

Takes O(n^2) time, which is much faster than inverting the result of getMassMatrix

Return type:

None

getMassMatrixDeriv(i)[source]

Computes the derivative of the nxn mass matrix with respect to q_i.

Return type:

None

Parameters:

i (int) –

Takes O(n^3) time.

getMassMatrixTimeDeriv()[source]

Computes the derivative of the nxn mass matrix with respect to t, given the robot’s current velocity.

Takes O(n^4) time.

Return type:

None

getCoriolisForceMatrix()[source]

Computes the Coriolis force matrix C(q,dq) for current config and velocity.

Takes O(n^2) time.

Return type:

None

getCoriolisForces()[source]

Computes the Coriolis forces C(q,dq)*dq for current config and velocity.

Takes O(n) time, which is faster than computing matrix and doing the product.

(“Forces” is somewhat of a misnomer; the result is a joint torque vector)

Return type:

None

getGravityForces(g)[source]

Computes the generalized gravity vector G(q) for the given workspace gravity vector g (usually (0,0,-9.8)).

Return type:

None

Parameters:

g (list of 3 floats) –

Note

“Forces” is somewhat of a misnomer; the result is a vector of joint torques.

Returns:

the n-element generalized gravity vector at the robot’s current configuration.

Return type:

list of floats

torquesFromAccel(ddq)[source]

Computes the inverse dynamics. Uses Recursive Newton Euler solver and takes O(n) time.

Return type:

None

Parameters:

ddq (list of floats) –

Specifically, solves for \(\tau\) in the (partial) dynamics equation:

\[`B(q) \ddot{q} + C(q,@dot {q}) = \tau`\]

Note

Does not include gravity term G(q). getGravityForces(g) will need to be added to the result.

Returns:

the n-element torque vector that would produce the joint accelerations ddq in the absence of external forces.

Return type:

list of floats

accelFromTorques(t)[source]

Computes the foward dynamics. Uses Recursive Newton Euler solver and takes O(n) time.

Return type:

None

Parameters:

t (list of floats) –

Specifically, solves for \(\ddot{q}\) in the (partial) dynamics equation:

\[`B(q) \ddot{q} + C(q,@dot {q}) = \tau`\]

Note

Does not include gravity term G(q). getGravityForces(g) will need to be subtracted from the argument t.

Returns:

the n-element joint acceleration vector that would result from joint torques t in the absence of external forces.

Return type:

list of floats

interpolate(a, b, u)[source]

Interpolates smoothly between two configurations, properly taking into account nonstandard joints.

Return type:

None

Parameters:
  • a (list of floats) –

  • b (list of floats) –

  • u (float) –

Returns:

The n-element configuration that is u fraction of the way from a to b.

distance(a, b)[source]

Computes a distance between two configurations, properly taking into account nonstandard joints.

Return type:

float

Parameters:
  • a (list of floats) –

  • b (list of floats) –

interpolateDeriv(a, b)[source]

Returns the configuration derivative at a as you interpolate toward b at unit speed.

Return type:

None

Parameters:
  • a (list of floats) –

  • b (list of floats) –

randomizeConfig(unboundedScale=1.0)[source]

Samples a random configuration and updates the robot’s pose. Properly handles non-normal joints and handles DOFs with infinite bounds using a centered Laplacian distribution with the given scaling term.

Return type:

None

Parameters:

unboundedScale (float, optional) – default value 1.0

Note

Python random module seeding does not affect the result.

configToDrivers(config)[source]

Converts a full configuration (length numLinks()) to a list of driver values (length numDrivers()).

Return type:

None

Parameters:

config (list of floats) –

velocityToDrivers(velocities)[source]

Converts a full velocity vector (length numLinks()) to a list of driver velocities (length numDrivers()).

Return type:

None

Parameters:

velocities (list of floats) –

configFromDrivers(driverValues)[source]

Converts a list of driver values (length numDrivers()) to a full configuration (length numLinks()).

Return type:

None

Parameters:

driverValues (list of floats) –

velocityFromDrivers(driverVelocities)[source]

Converts a list of driver velocities (length numDrivers()) to a full velocity vector (length numLinks()).

Return type:

None

Parameters:

driverVelocities (list of floats) –

selfCollisionEnabled(link1, link2)[source]

Queries whether self collisions between two links is enabled.

Return type:

bool

Parameters:
  • link1 (int) –

  • link2 (int) –

enableSelfCollision(link1, link2, value)[source]

Enables/disables self collisions between two links (depending on value)

Return type:

None

Parameters:
  • link1 (int) –

  • link2 (int) –

  • value (bool) –

selfCollides()[source]

Returns true if the robot is in self collision (faster than manual testing)

Return type:

bool

drawGL(keepAppearance=True)[source]

Draws the robot geometry. If keepAppearance=true, the current appearance is honored. Otherwise, only the raw geometry is drawn.

Return type:

None

Parameters:

keepAppearance (bool, optional) – default value True

PERFORMANCE WARNING: if keepAppearance is false, then this does not properly reuse OpenGL display lists. A better approach to changing the robot’s appearances is to set the link Appearance’s directly.

reduce(robot)[source]

Sets self to a reduced version of robot, where all fixed DOFs are eliminated. The return value is a map from the original robot DOF indices to the reduced DOFs.

Return type:

None

Parameters:

robot (RobotModel) –

Note that any geometries fixed to the world will disappear.

mount(link, subRobot, R, t)[source]

Mounts a sub-robot onto a link, with its origin at a given local transform (R,t). The sub-robot’s links will be renamed to subRobot.getName() + ‘:’ + link.getName() unless subRobot.getName() is ‘’, in which case the link names are preserved.

Return type:

None

Parameters:
  • link (int) –

  • subRobot (RobotModel) –

  • R (list of 9 floats (so3 element)) –

  • t (list of 3 floats) –

sensor(*args)[source]

Returns a sensor by index or by name.

sensor (index): SimRobotSensor

sensor (name): SimRobotSensor

Return type:

SimRobotSensor

Parameters:
  • index (int, optional) –

  • name (str, optional) –

Returns:

Return type:

SimRobotSensor

If out of bounds or unavailable, a null sensor is returned (i.e., SimRobotSensor.name() or SimRobotSensor.type()) will return the empty string.)

addSensor(name, type)[source]

Adds a new sensor with a given name and type.

Return type:

SimRobotSensor

Parameters:
  • name (str) –

  • type (str) –

Returns:

The new sensor.

property world

world : int

property index

index : int

property robot

robot : p.Klampt::RobotModel

property dirty_dynamics

dirty_dynamics : bool

property name: str
property id: int

Returns the ID of the robot in its world.

Note

The world ID is not the same as the robot index.

property config: None

Retrieves the current configuration of the robot model.

property velocity: None

Retreives the current velocity of the robot model.

Bases: object

A reference to a link of a RobotModel.

The link stores many mostly-constant items (id, name, parent, geometry, appearance, mass, joint axes). There are two exceptions:

A RobotModelLink is not created by hand, but instead accessed using RobotModel.link() (index or name).

C++ includes: robotmodel.h

Attributes:

thisown

The membership flag

world

world : int

robotIndex

robotIndex : int

robotPtr

robotPtr : p.Klampt::RobotModel

index

index : int

name

Returns the name of the robot link.

parent

Returns the index of the link's parent (on its robot).

mass

Returns the inertial properties of the link.

parentTransform

Gets the transformation (R,t) to the parent link.

axis

Gets the local rotational / translational axis.

prismatic

Returns whether the joint is prismatic.

transform

Gets the link's current transformation (R,t) to the world frame.

Methods:

getID()

Returns the ID of the robot link in its world.

getName()

Returns the name of the robot link.

setName(name)

Sets the name of the robot link.

robot()

Returns a reference to the link's robot.

getIndex()

Returns the index of the link (on its robot).

getParent()

Returns the index of the link's parent (on its robot).

setParent(*args)

Sets the link's parent (must be on the same robot).

geometry()

Returns a reference to the link's geometry.

appearance()

Returns a reference to the link's appearance.

getMass()

Returns the inertial properties of the link.

setMass(mass)

Sets the inertial proerties of the link.

getParentTransform()

Gets the transformation (R,t) to the parent link.

setParentTransform(R, t)

Sets transformation (R,t) to the parent link.

getAxis()

Gets the local rotational / translational axis.

setAxis(axis)

Sets the local rotational / translational axis.

isPrismatic()

Returns whether the joint is prismatic.

isRevolute()

Returns whether the joint is revolute.

setPrismatic(prismatic)

Changes a link from revolute to prismatic or vice versa.

getWorldPosition(plocal)

Converts point from local to world coordinates.

getWorldDirection(vlocal)

Converts direction from local to world coordinates.

getLocalPosition(pworld)

Converts point from world to local coordinates.

getLocalDirection(vworld)

Converts direction from world to local coordinates.

getTransform()

Gets the link's current transformation (R,t) to the world frame.

setTransform(R, t)

Sets the link's current transformation (R,t) to the world frame.

getVelocity()

Computes the velocity of the link's origin given the robot's current joint configuration and velocities.

getAngularVelocity()

Computes the angular velocity of the link given the robot's current joint configuration and velocities.

getPointVelocity(plocal)

Computes the world velocity of a point attached to the link, given the robot's current joint configuration and velocities.

getJacobian(plocal)

Computes the total jacobian of a point on this link w.r.t.

getPositionJacobian(plocal)

Computes the position jacobian of a point on this link w.r.t.

getOrientationJacobian()

Computes the orientation jacobian of this link w.r.t.

getJacobianCols(plocal, links)

Returns the jacobian of a point on this link w.r.t.

getPositionJacobianCols(plocal, links)

Returns the position jacobian of a point on this link w.r.t.

getOrientationJacobianCols(links)

Returns the orientation jacobian this link w.r.t.

getAcceleration(ddq)

Computes the acceleration of the link origin given the robot's current joint configuration and velocities, and the joint accelerations ddq.

getPointAcceleration(plocal, ddq)

Computes the acceleration of the point given the robot's current joint configuration and velocities, and the joint accelerations ddq.

getAngularAcceleration(ddq)

Computes the angular acceleration of the link given the robot's current joint configuration and velocities, and the joint accelerations ddq.

getPositionHessian(plocal)

Computes the Hessians of each component of the position p w.r.t the robot's configuration q.

getOrientationHessian()

Computes the Hessians of each orientation component of the link w.r.t the robot's configuration q.

drawLocalGL([keepAppearance])

Draws the link's geometry in its local frame.

drawWorldGL([keepAppearance])

Draws the link's geometry in the world frame.

property thisown

The membership flag

getID()[source]

Returns the ID of the robot link in its world.

Return type:

int

Note

The world ID is not the same as the link’s index, retrieved by getIndex.

getName()[source]

Returns the name of the robot link.

Return type:

str

setName(name)[source]

Sets the name of the robot link.

Return type:

None

Parameters:

name (str) –

robot()[source]

Returns a reference to the link’s robot.

Return type:

RobotModel

getIndex()[source]

Returns the index of the link (on its robot).

Return type:

int

getParent()[source]

Returns the index of the link’s parent (on its robot).

Return type:

int

setParent(*args)[source]

Sets the link’s parent (must be on the same robot).

setParent (p)

setParent (l)

Return type:

None

Parameters:
geometry()[source]

Returns a reference to the link’s geometry.

Return type:

Geometry3D

appearance()[source]

Returns a reference to the link’s appearance.

Return type:

Appearance

getMass()[source]

Returns the inertial properties of the link. (Note that the Mass is given with origin at the link frame, not about the COM.)

Return type:

Mass

setMass(mass)[source]

Sets the inertial proerties of the link. (Note that the Mass is given with origin at the link frame, not about the COM.)

Return type:

None

Parameters:

mass (Mass) –

getParentTransform()[source]

Gets the transformation (R,t) to the parent link.

Returns: :rtype: None

se3 object: a pair (R,t), with R a 9-list and t a 3-list of floats, giving the local transform from this link to its parent, in the reference (zero) configuration.

setParentTransform(R, t)[source]

Sets transformation (R,t) to the parent link.

Return type:

None

Parameters:
  • R (list of 9 floats (so3 element)) –

  • t (list of 3 floats) –

getAxis()[source]

Gets the local rotational / translational axis.

Return type:

None

setAxis(axis)[source]

Sets the local rotational / translational axis.

Return type:

None

Parameters:

axis (list of 3 floats) –

isPrismatic()[source]

Returns whether the joint is prismatic.

Return type:

bool

isRevolute()[source]

Returns whether the joint is revolute.

Return type:

bool

setPrismatic(prismatic)[source]

Changes a link from revolute to prismatic or vice versa.

Return type:

None

Parameters:

prismatic (bool) –

getWorldPosition(plocal)[source]

Converts point from local to world coordinates.

Return type:

None

Parameters:

plocal (list of 3 floats) –

Returns:

the world coordinates of the local point plocal

Return type:

list of 3 floats

getWorldDirection(vlocal)[source]

Converts direction from local to world coordinates.

Return type:

None

Parameters:

vlocal (list of 3 floats) –

Returns:

the world coordinates of the local direction vlocal

Return type:

list of 3 floats

getLocalPosition(pworld)[source]

Converts point from world to local coordinates.

Return type:

None

Parameters:

pworld (list of 3 floats) –

Returns:

the local coordinates of the world point pworld

Return type:

list of 3 floats

getLocalDirection(vworld)[source]

Converts direction from world to local coordinates.

Return type:

None

Parameters:

vworld (list of 3 floats) –

Returns:

the local coordinates of the world direction vworld

Return type:

list of 3 floats

getTransform()[source]

Gets the link’s current transformation (R,t) to the world frame.

Returns: :rtype: None

se3 object: a pair (R,t), with R a 9-list and t a 3-list of floats.

setTransform(R, t)[source]

Sets the link’s current transformation (R,t) to the world frame.

Return type:

None

Parameters:
  • R (list of 9 floats (so3 element)) –

  • t (list of 3 floats) –

Note

This does NOT perform inverse kinematics. The transform is overwritten when the robot’s setConfig() method is called.

getVelocity()[source]

Computes the velocity of the link’s origin given the robot’s current joint configuration and velocities. Equivalent to getPointVelocity([0,0,0]).

Returns: :rtype: None

list of 3 floats: the current velocity of the link’s origin, in world coordinates

getAngularVelocity()[source]

Computes the angular velocity of the link given the robot’s current joint configuration and velocities.

Returns: :rtype: None

list of 3 floats: the current angular velocity of the link, in world coordinates

getPointVelocity(plocal)[source]

Computes the world velocity of a point attached to the link, given the robot’s current joint configuration and velocities.

Return type:

None

Parameters:

plocal (list of 3 floats) –

Returns:

the current velocity of the point, in world coordinates.

Return type:

list of 3 floats

getJacobian(plocal)[source]

Computes the total jacobian of a point on this link w.r.t. the robot’s configuration q.

Return type:

None

Parameters:

plocal (list of 3 floats) –

The orientation jacobian is given in the first 3 rows, and is stacked on the position jacobian, which is given in the last 3 rows.

Returns:

the 6xn total Jacobian matrix of the point given by local coordinates plocal.

Return type:

ndarray

getPositionJacobian(plocal)[source]

Computes the position jacobian of a point on this link w.r.t. the robot’s configuration q.

Return type:

None

Parameters:

plocal (list of 3 floats) –

This matrix J gives the point’s velocity (in world coordinates) via np.dot(J,dq), where dq is the robot’s joint velocities.

Returns:

the 3xn Jacobian matrix of the point given by local coordinates plocal.

Return type:

ndarray

getOrientationJacobian()[source]

Computes the orientation jacobian of this link w.r.t. the robot’s configuration q.

This matrix J gives the link’s angular velocity (in world coordinates) via np.dot(J,dq), where dq is the robot’s joint velocities.

Returns: :rtype: None

ndarray:: the 3xn orientation Jacobian matrix of the link.

getJacobianCols(plocal, links)[source]

Returns the jacobian of a point on this link w.r.t. specified entries of the robot’s configuration q given by links.

Return type:

None

Parameters:
  • plocal (list of 3 floats) –

  • links (list of int) –

The orientation jacobian is given in the first 3 rows, and is stacked on the position jacobian, which is given in the last 3 rows.

Returns:

the 6xlen(links) Jacobian matrix of the point given by local coordinates plocal.

Return type:

ndarray

getPositionJacobianCols(plocal, links)[source]

Returns the position jacobian of a point on this link w.r.t. specified entries of the robot’s configuration q given by links.

Return type:

None

Parameters:
  • plocal (list of 3 floats) –

  • links (list of int) –

This matrix J gives the point’s velocity (in world coordinates) via np.dot(J,dqlinks), where dqlinks are the joint velocities of the links in links

Returns:

the 3xlen(links) position Jacobian matrix of the point given by local coordinates plocal.

Return type:

ndarray

getOrientationJacobianCols(links)[source]

Returns the orientation jacobian this link w.r.t. specified entries of the robot’s configuration q given by links.

Return type:

None

Parameters:

links (list of int) –

This matrix J gives the point’s angular velocity (in world coordinates) via np.dot(J,dqlinks), where dqlinks are the joint velocities of the links in links

Returns:

the 3xlen(links) orientation Jacobian matrix of the link.

Return type:

ndarray

getAcceleration(ddq)[source]

Computes the acceleration of the link origin given the robot’s current joint configuration and velocities, and the joint accelerations ddq.

Return type:

None

Parameters:

ddq (list of floats) –

ddq can be empty, which calculates the acceleration with acceleration 0, and is a little faster than setting ddq to [0]*n

Returns:

the acceleration of the link’s origin, in world coordinates.

Return type:

list of 3 floats

getPointAcceleration(plocal, ddq)[source]

Computes the acceleration of the point given the robot’s current joint configuration and velocities, and the joint accelerations ddq.

Return type:

None

Parameters:
  • plocal (list of 3 floats) –

  • ddq (list of floats) –

Returns:

the acceleration of the point, in world coordinates.

Return type:

list of 3 floats

getAngularAcceleration(ddq)[source]

Computes the angular acceleration of the link given the robot’s current joint configuration and velocities, and the joint accelerations ddq.

Return type:

None

Parameters:

ddq (list of floats) –

Returns:

the angular acceleration of the link, in world coordinates.

Return type:

list of 3 floats

getPositionHessian(plocal)[source]

Computes the Hessians of each component of the position p w.r.t the robot’s configuration q.

Return type:

None

Parameters:

plocal (list of 3 floats) –

Returns:

a 3xnxn array with each of the elements in the first axis corresponding respectively, to the (x,y,z) components of the Hessian.

Return type:

ndarray

getOrientationHessian()[source]

Computes the Hessians of each orientation component of the link w.r.t the robot’s configuration q.

Returns: :rtype: None

ndarray: a 3xnxn array with each of the elements in the first axis corresponding, respectively, to the (wx,wy,wz) components of the Hessian.

drawLocalGL(keepAppearance=True)[source]

Draws the link’s geometry in its local frame. If keepAppearance=true, the current Appearance is honored. Otherwise, just the geometry is drawn.

Return type:

None

Parameters:

keepAppearance (bool, optional) – default value True

drawWorldGL(keepAppearance=True)[source]

Draws the link’s geometry in the world frame. If keepAppearance=true, the current Appearance is honored. Otherwise, just the geometry is drawn.

Return type:

None

Parameters:

keepAppearance (bool, optional) – default value True

property world

world : int

property robotIndex

robotIndex : int

property robotPtr

robotPtr : p.Klampt::RobotModel

property index

index : int

property name: str

Returns the name of the robot link.

property parent: int

Returns the index of the link’s parent (on its robot).

property mass: Mass

Returns the inertial properties of the link. (Note that the Mass is given with origin at the link frame, not about the COM.)

property parentTransform: None

Gets the transformation (R,t) to the parent link.

Returns:

a pair (R,t), with R a 9-list and t a 3-list of floats, giving the local transform from this link to its parent, in the reference (zero) configuration.

Return type:

se3 object

property axis: None

Gets the local rotational / translational axis.

property prismatic: bool

Returns whether the joint is prismatic.

property transform: None

Gets the link’s current transformation (R,t) to the world frame.

Returns:

a pair (R,t), with R a 9-list and t a 3-list of floats.

Return type:

se3 object

class klampt.RigidObjectModel[source]

Bases: object

A rigid movable object.

A rigid object has a name, geometry, appearance, mass, surface properties, and current transform / velocity.

State is retrieved/set using get/setTransform, and get/setVelocity

C++ includes: robotmodel.h

Attributes:

thisown

The membership flag

world

world : int

index

index : int

object

object : p.Klampt::RigidObjectModel

Methods:

loadFile(fn)

Loads the object from the file fn.

saveFile(fn[, geometryName])

Saves the object to the file fn.

getID()

Returns the ID of the rigid object in its world.

getName()

rtype:

str

setName(name)

rtype:

None

geometry()

Returns a reference to the geometry associated with this object.

appearance()

Returns a reference to the appearance associated with this object.

getMass()

Returns a copy of the Mass of this rigid object.

setMass(mass)

rtype:

None

getContactParameters()

Returns a copy of the ContactParameters of this rigid object.

setContactParameters(params)

rtype:

None

getTransform()

Retrieves the rotation / translation of the rigid object (R,t)

setTransform(R, t)

Sets the rotation / translation (R,t) of the rigid object.

getVelocity()

Retrieves the (angular velocity, velocity) of the rigid object.

setVelocity(angularVelocity, velocity)

Sets the (angular velocity, velocity) of the rigid object.

drawGL([keepAppearance])

Draws the object's geometry.

property thisown

The membership flag

loadFile(fn)[source]

Loads the object from the file fn.

Return type:

bool

Parameters:

fn (str) –

saveFile(fn, geometryName=None)[source]

Saves the object to the file fn. If geometryName is given, the geometry is saved to that file.

Return type:

bool

Parameters:
  • fn (str) –

  • geometryName (str, optional) – default value None

getID()[source]

Returns the ID of the rigid object in its world.

Return type:

int

Note

The world ID is not the same as the rigid object index.

getName()[source]
Return type:

str

setName(name)[source]
Return type:

None

Parameters:

name (str) –

geometry()[source]

Returns a reference to the geometry associated with this object.

Return type:

Geometry3D

appearance()[source]

Returns a reference to the appearance associated with this object.

Return type:

Appearance

getMass()[source]

Returns a copy of the Mass of this rigid object.

Return type:

Mass

Note

To change the mass properties, you should call m=object.getMass(), change the desired properties in m, and then object.setMass(m)

setMass(mass)[source]
Return type:

None

Parameters:

mass (Mass) –

getContactParameters()[source]

Returns a copy of the ContactParameters of this rigid object.

Return type:

ContactParameters

Note

To change the contact parameters, you should call p=object.getContactParameters(), change the desired properties in p, and then call object.setContactParameters(p)

setContactParameters(params)[source]
Return type:

None

Parameters:

params (ContactParameters) –

getTransform()[source]

Retrieves the rotation / translation of the rigid object (R,t)

Returns: :rtype: None

se3 object: a pair (R,t), with R a 9-list and t a 3-list of floats, giving the transform to world coordinates.

setTransform(R, t)[source]

Sets the rotation / translation (R,t) of the rigid object.

Return type:

None

Parameters:
  • R (list of 9 floats (so3 element)) –

  • t (list of 3 floats) –

getVelocity()[source]

Retrieves the (angular velocity, velocity) of the rigid object.

Returns: :rtype: None

A pair of 3-lists (w,v) where w is the angular velocity vector and v is the translational velocity vector (both in world coordinates)

setVelocity(angularVelocity, velocity)[source]

Sets the (angular velocity, velocity) of the rigid object.

Return type:

None

Parameters:
  • angularVelocity (list of 3 floats) –

  • velocity (list of 3 floats) –

drawGL(keepAppearance=True)[source]

Draws the object’s geometry. If keepAppearance=true, the current appearance is honored. Otherwise, only the raw geometry is drawn.

Return type:

None

Parameters:

keepAppearance (bool, optional) – default value True

PERFORMANCE WARNING: if keepAppearance is false, then this does not properly reuse OpenGL display lists. A better approach is to change the object’s Appearance directly.

property world

world : int

property index

index : int

property object

object : p.Klampt::RigidObjectModel

class klampt.TerrainModel[source]

Bases: object

Static environment geometry.

C++ includes: robotmodel.h

Attributes:

thisown

The membership flag

world

world : int

index

index : int

terrain

terrain : p.Klampt::TerrainModel

Methods:

loadFile(fn)

Loads the terrain from the file fn.

saveFile(fn[, geometryName])

Saves the terrain to the file fn.

getID()

Returns the ID of the terrain in its world.

getName()

rtype:

str

setName(name)

rtype:

None

geometry()

Returns a reference to the geometry associated with this object.

appearance()

Returns a reference to the appearance associated with this object.

setFriction(friction)

Changes the friction coefficient for this terrain.

drawGL([keepAppearance])

Draws the object's geometry.

property thisown

The membership flag

loadFile(fn)[source]

Loads the terrain from the file fn.

Return type:

bool

Parameters:

fn (str) –

saveFile(fn, geometryName=None)[source]

Saves the terrain to the file fn. If geometryName is given, the geometry is saved to that file.

Return type:

bool

Parameters:
  • fn (str) –

  • geometryName (str, optional) – default value None

getID()[source]

Returns the ID of the terrain in its world.

Return type:

int

Note

The world ID is not the same as the terrain index.

getName()[source]
Return type:

str

setName(name)[source]
Return type:

None

Parameters:

name (str) –

geometry()[source]

Returns a reference to the geometry associated with this object.

Return type:

Geometry3D

appearance()[source]

Returns a reference to the appearance associated with this object.

Return type:

Appearance

setFriction(friction)[source]

Changes the friction coefficient for this terrain.

Return type:

None

Parameters:

friction (float) –

drawGL(keepAppearance=True)[source]

Draws the object’s geometry. If keepAppearance=true, the current appearance is honored. Otherwise, only the raw geometry is drawn.

Return type:

None

Parameters:

keepAppearance (bool, optional) – default value True

PERFORMANCE WARNING: if keepAppearance is false, then this does not properly reuse OpenGL display lists. A better approach is to change the object’s Appearance directly.

property world

world : int

property index

index : int

property terrain

terrain : p.Klampt::TerrainModel

class klampt.Mass[source]

Bases: object

Stores mass information for a rigid body or robot link.

Note

Recommended to use the set/get functions rather than changing the members directly due to strangeness in SWIG’s handling of vectors.

mass

the actual mass (typically in kg)

Type:

float

com

the center of mass position, in local coordinates.

Type:

list of 3 floats

inertia

the inertia matrix in local coordinates. If 3 floats, this is a diagonal matrix. If 9 floats, this gives all entries of the 3x3 inertia matrix (in column major or row major order, it doesn’t matter since inertia matrices are symmetric)

Type:

list of 3 floats or 9 floats

C++ includes: robotmodel.h

Attributes:

thisown

The membership flag

mass

mass : double

com

Returns the COM as a list of 3 floats.

inertia

Returns the inertia matrix as a list of 3 floats or 9 floats.

Methods:

setMass(_mass)

rtype:

None

getMass()

rtype:

float

setCom(_com)

rtype:

None

getCom()

Returns the COM as a list of 3 floats.

setInertia(_inertia)

Sets an inertia matrix.

getInertia()

Returns the inertia matrix as a list of 3 floats or 9 floats.

estimate(g, mass[, surfaceFraction])

Estimates the com and inertia of a geometry, with a given total mass.

property thisown

The membership flag

setMass(_mass)[source]
Return type:

None

Parameters:

_mass (float) –

getMass()[source]
Return type:

float

setCom(_com)[source]
Return type:

None

Parameters:

_com (list of floats) –

getCom()[source]

Returns the COM as a list of 3 floats.

Return type:

None

setInertia(_inertia)[source]

Sets an inertia matrix.

Return type:

None

Parameters:

_inertia (list of floats) –

getInertia()[source]

Returns the inertia matrix as a list of 3 floats or 9 floats.

Return type:

None

estimate(g, mass, surfaceFraction=0)[source]

Estimates the com and inertia of a geometry, with a given total mass.

Return type:

None

Parameters:
  • g (Geometry3D) –

  • mass (float) –

  • surfaceFraction (float, optional) – default value 0

For TriangleMesh types, surfaceFraction dictates how much of the object’s mass is concentrated at the surface rather than the interior.

property mass

mass : double

property com: None

Returns the COM as a list of 3 floats.

property inertia: None

Returns the inertia matrix as a list of 3 floats or 9 floats.

class klampt.ContactParameters[source]

Bases: object

Stores contact parameters for an entity. Currently only used for simulation, but could be used for contact mechanics in the future.

kFriction

The coefficient of (Coulomb) friction, in range [0,inf).

Type:

float

kRestitution

The coefficient of restitution, in range [0,1].

Type:

float

kStiffness

The stiffness of the material, in range (0,inf) (default inf, perfectly rigid).

Type:

float

kDamping

The damping of the material, in range (0,inf) (default inf, perfectly rigid).

Type:

float

C++ includes: robotmodel.h

Attributes:

thisown

The membership flag

kFriction

kFriction : double

kRestitution

kRestitution : double

kStiffness

kStiffness : double

kDamping

kDamping : double

property thisown

The membership flag

property kFriction

kFriction : double

property kRestitution

kRestitution : double

property kStiffness

kStiffness : double

property kDamping

kDamping : double

class klampt.SimRobotController[source]

Bases: object

A controller for a simulated robot.

By default a SimRobotController has three possible modes:

  • Motion queue + PID mode: the controller has an internal trajectory queue that may be added to and modified. This queue supports piecewise linear interpolation, cubic interpolation, and time-optimal move-to commands.

  • PID mode: the user controls the motor’s PID setpoints directly

  • Torque control: the user controlls the motor torques directly.

The “standard” way of using this is in move-to mode which accepts a milestone (setMilestone) or list of milestones (repeated calls to addMilestone) and interpolates dynamically from the current configuration/velocity. To handle disturbances, a PID loop is run automatically at the controller’s specified rate.

To get finer-grained control over the motion queue’s timing, you may use the setLinear/setCubic/addLinear/addCubic functions. In these functions it is up to the user to respect velocity, acceleration, and torque limits.

Whether in motion queue or PID mode, the constants of the PID loop are initially set in the robot file. You can programmatically tune these via the setPIDGains function.

Arbitrary trajectories can be tracked by using setVelocity over short time steps. Force controllers can be implemented using setTorque, again using short time steps.

If the setVelocity, setTorque, or setPID command are called, the motion queue behavior will be completely overridden. To reset back to motion queue control, setManualMode(False) must be called first.

Individual joints cannot be addressed with mixed motion queue mode and torque/PID mode. However, you can mix PID and torque mode between different joints with a workaround:

# setup by zeroing out PID constants for torque controlled joints
pid_joint_indices = [...]
torque_joint_indices = [...] # complement of pid_joint_indices
kp,ki,kp = controller.getPIDGains()
for i in torque_joint_indices:  #turn off PID gains here
   kp[i] = ki[i] = kp[i] = 0

# to send PID command (qcmd,dqcmd) and torque commands tcmd, use
# a PID command with feedforward torques.  First we build a whole-robot
# command:
qcmd_whole = [0]*controller.model().numLinks()
dqcmd_whole = [0]*controller.model().numLinks()
tcmd_whole = [0]*controller.model().numLinks()
for i,k in enumerate(pid_joint_indices):
    qcmd_whole[k],dqcmd_whole[i] = qcmd[i],dqcmd[i]
for i,k in enumerate(torque_joint_indices):
    tcmd_whole[k] = tcmd[i]
# Then we send it to the controller
controller.setPIDCommand(qcmd_whole,dqcmd_whole,tcmd_whole)

C++ includes: robotsim.h

Attributes:

thisown

The membership flag

index

index : int

sim

sim : p.Simulator

controller

controller : p.Klampt::SimRobotController

Methods:

model()

Retrieves the robot model associated with this controller.

setRate(dt)

Sets the current feedback control rate, in s.

getRate()

Returns The current feedback control rate, in s.

getCommandedConfig()

Returns The current commanded configuration (size model().numLinks())

getCommandedVelocity()

Returns The current commanded velocity (size model().numLinks())

getCommandedTorque()

Returns The current commanded (feedforward) torque (size model().numDrivers())

getSensedConfig()

Returns The current "sensed" configuration from the simulator (size model().numLinks())

getSensedVelocity()

Returns The current "sensed" velocity from the simulator (size model().numLinks())

getSensedTorque()

Returns The current "sensed" (feedback) torque from the simulator.

sensor(*args)

Returns a sensor by index or by name.

addSensor(name, type)

Adds a new sensor with a given name and type.

commands()

Returns a custom command list.

sendCommand(name, args)

Sends a custom string command to the controller.

settings()

Returns all valid setting names.

getSetting(name)

Returns a setting of the controller.

setSetting(name, val)

Sets a setting of the controller.

setMilestone(*args)

Uses a dynamic interpolant to get from the current state to the desired milestone (with optional ending velocity).

addMilestone(*args)

Same as setMilestone, but appends an interpolant onto an internal motion queue starting at the current queued end state.

addMilestoneLinear(q)

Same as addMilestone, but enforces that the motion should move along a straight- line joint-space path.

setLinear(q, dt)

Uses linear interpolation to get from the current configuration to the desired configuration after time dt.

setCubic(q, v, dt)

Uses cubic (Hermite) interpolation to get from the current configuration/velocity to the desired configuration/velocity after time dt.

addLinear(q, dt)

Same as setLinear but appends an interpolant onto the motion queue.

addCubic(q, v, dt)

Same as setCubic but appends an interpolant onto the motion queue.

remainingTime()

Returns the remaining duration of the motion queue.

setVelocity(dq, dt)

Sets a rate controller from the current commanded config to move at rate dq for time dt > 0.

setTorque(t)

Sets a torque command controller.

setPIDCommand(*args)

Sets a PID command controller.

setManualMode(enabled)

Turns on/off manual mode, if either the setTorque or setPID command were previously set.

getControlType()

Returns the control type for the active controller.

setPIDGains(kP, kI, kD)

Sets the PID gains.

getPIDGains()

Returns the PID gains for the PID controller.

property thisown

The membership flag

model()[source]

Retrieves the robot model associated with this controller.

Return type:

RobotModel

setRate(dt)[source]

Sets the current feedback control rate, in s.

Return type:

None

Parameters:

dt (float) –

getRate()[source]

Returns The current feedback control rate, in s.

Return type:

float

getCommandedConfig()[source]

Returns The current commanded configuration (size model().numLinks())

Return type:

None

getCommandedVelocity()[source]

Returns The current commanded velocity (size model().numLinks())

Return type:

None

getCommandedTorque()[source]

Returns The current commanded (feedforward) torque (size model().numDrivers())

Return type:

None

getSensedConfig()[source]

Returns The current “sensed” configuration from the simulator (size model().numLinks())

Return type:

None

getSensedVelocity()[source]

Returns The current “sensed” velocity from the simulator (size model().numLinks())

Return type:

None

getSensedTorque()[source]

Returns The current “sensed” (feedback) torque from the simulator. (size model().numDrivers())

Note: a default robot doesn’t have a torque sensor, so this will be 0

Return type:

None

sensor(*args)[source]

Returns a sensor by index or by name. If out of bounds or unavailable, a null sensor is returned (i.e., SimRobotSensor.name() or SimRobotSensor.type()) will return the empty string.)

sensor (index): SimRobotSensor

sensor (name): SimRobotSensor

Return type:

SimRobotSensor

Parameters:
  • index (int, optional) –

  • name (str, optional) –

Returns:

Return type:

SimRobotSensor

addSensor(name, type)[source]

Adds a new sensor with a given name and type.

Return type:

SimRobotSensor

Parameters:
  • name (str) –

  • type (str) –

Returns:

The new sensor.

commands()[source]

Returns a custom command list.

Return type:

Sequence[str]

sendCommand(name, args)[source]

Sends a custom string command to the controller.

Return type:

bool

Parameters:
  • name (str) –

  • args (str) –

settings()[source]

Returns all valid setting names.

Return type:

Sequence[str]

getSetting(name)[source]

Returns a setting of the controller.

Return type:

str

Parameters:

name (str) –

setSetting(name, val)[source]

Sets a setting of the controller.

Return type:

bool

Parameters:
  • name (str) –

  • val (str) –

setMilestone(*args)[source]

Uses a dynamic interpolant to get from the current state to the desired milestone (with optional ending velocity). This interpolant is time-optimal with respect to the velocity and acceleration bounds.

setMilestone (q)

setMilestone (q,dq)

Return type:

None

Parameters:
  • q (list of floats) –

  • dq (list of floats, optional) –

addMilestone(*args)[source]

Same as setMilestone, but appends an interpolant onto an internal motion queue starting at the current queued end state.

addMilestone (q)

addMilestone (q,dq)

Return type:

None

Parameters:
  • q (list of floats) –

  • dq (list of floats, optional) –

addMilestoneLinear(q)[source]

Same as addMilestone, but enforces that the motion should move along a straight- line joint-space path.

Return type:

None

Parameters:

q (list of floats) –

setLinear(q, dt)[source]

Uses linear interpolation to get from the current configuration to the desired configuration after time dt.

Return type:

None

Parameters:
  • q (list of floats) –

  • dt (float) –

q has size model().numLinks(). dt must be > 0.

setCubic(q, v, dt)[source]

Uses cubic (Hermite) interpolation to get from the current configuration/velocity to the desired configuration/velocity after time dt.

Return type:

None

Parameters:
  • q (list of floats) –

  • v (list of floats) –

  • dt (float) –

q and v have size model().numLinks(). dt must be > 0.

addLinear(q, dt)[source]

Same as setLinear but appends an interpolant onto the motion queue.

Return type:

None

Parameters:
  • q (list of floats) –

  • dt (float) –

addCubic(q, v, dt)[source]

Same as setCubic but appends an interpolant onto the motion queue.

Return type:

None

Parameters:
  • q (list of floats) –

  • v (list of floats) –

  • dt (float) –

remainingTime()[source]

Returns the remaining duration of the motion queue.

Return type:

float

setVelocity(dq, dt)[source]

Sets a rate controller from the current commanded config to move at rate dq for time dt > 0. dq has size model().numLinks()

Return type:

None

Parameters:
  • dq (list of floats) –

  • dt (float) –

setTorque(t)[source]

Sets a torque command controller. t can have size model().numDrivers() or model().numLinks().

Return type:

None

Parameters:

t (list of floats) –

setPIDCommand(*args)[source]

Sets a PID command controller. If tfeedforward is provided, it is the feedforward torque vector.

setPIDCommand (qdes,dqdes)

setPIDCommand (qdes,dqdes,tfeedforward)

Return type:

None

Parameters:
  • qdes (list of floats) –

  • dqdes (list of floats) –

  • tfeedforward (list of floats, optional) –

setManualMode(enabled)[source]

Turns on/off manual mode, if either the setTorque or setPID command were previously set.

Return type:

None

Parameters:

enabled (bool) –

getControlType()[source]

Returns the control type for the active controller.

Returns: :rtype: str

One of

  • unknown

  • off

  • torque

  • PID

  • locked_velocity

setPIDGains(kP, kI, kD)[source]

Sets the PID gains. Arguments have size model().numDrivers().

Return type:

None

Parameters:
  • kP (list of floats) –

  • kI (list of floats) –

  • kD (list of floats) –

getPIDGains()[source]

Returns the PID gains for the PID controller.

Return type:

None

property index

index : int

property sim

sim : p.Simulator

property controller

controller : p.Klampt::SimRobotController

class klampt.SimRobotSensor(robot, sensor)[source]

Bases: object

A sensor on a simulated robot. Retrieve one from the controller using SimRobotController.sensor(), or create a new one using SimRobotController.addSensor(). You may also use kinematically-simulated sensors using RobotModel.sensor() or create a new one using RobotModel.addSensor().

Use getMeasurements() to get the currently simulated measurement vector.

Sensors are automatically updated through the Simulator.simulate() call, and getMeasurements() retrieves the updated values. As a result, you may get garbage measurements before the first Simulator.simulate call is made.

There is also a mode for doing kinematic simulation, which is supported (i.e., makes sensible measurements) for some types of sensors when just a robot / world model is given. This is similar to Simulation.fakeSimulate but the entire controller structure is bypassed. You can arbitrarily set the robot’s position, call kinematicReset(), and then call kinematicSimulate(). Subsequent calls assume the robot is being driven along a trajectory until the next kinematicReset() is called.

LaserSensor, CameraSensor, TiltSensor, AccelerometerSensor, GyroSensor, JointPositionSensor, JointVelocitySensor support kinematic simulation mode. FilteredSensor and TimeDelayedSensor also work. The force-related sensors (ContactSensor and ForceTorqueSensor) return 0’s in kinematic simulation.

To use get/setSetting, you will need to know the sensor attribute names and types as described in the Klampt sensor documentation (same as in the world or sensor XML file). Common settings include:

  • rate (float): how frequently the sensor is simulated

  • enabled (bool): whether the simulator simulates this sensor

  • link (int): the link on which this sensor lies (-1 for world)

  • Tsensor (se3 transform, serialized with loader.write_se3(T)): the transform of the sensor on the robot / world.

C++ includes: robotsim.h

Parameters:
  • robot (RobotModel) –

  • sensor (Klampt::SensorBase *) –

Attributes:

thisown

The membership flag

robotModel

robotModel : RobotModel

sensor

sensor : p.Klampt::SensorBase

Methods:

name()

Returns the name of the sensor.

type()

Returns the type of the sensor.

robot()

Returns the model of the robot to which this belongs.

measurementNames()

Returns a list of names for the measurements (one per measurement).

getMeasurements()

Returns an array of measurements from the previous simulation (or kinematicSimulate) timestep.

settings()

Returns all setting names.

getSetting(name)

Returns the value of the named setting (you will need to manually parse this)

setSetting(name, val)

Sets the value of the named setting (you will need to manually cast an int/float/etc to a str)

getEnabled()

Return whether the sensor is enabled during simulation (helper for getSetting)

setEnabled(enabled)

Sets whether the sensor is enabled (helper for setSetting)

getLink()

Returns the link on which the sensor is mounted (helper for getSetting)

setLink(*args)

Sets the link on which the sensor is mounted (helper for setSetting)

getTransform()

Returns the local transform of the sensor on the robot's link.

getTransformWorld()

Returns the world transform of the sensor given the robot's current configuration.

setTransform(R, t)

Sets the local transform of the sensor on the robot's link.

drawGL(*args)

Draws a sensor indicator using OpenGL.

kinematicSimulate(*args)

kinematicSimulate (dt)

kinematicReset()

resets a kinematic simulation so that a new initial condition can be set

property thisown

The membership flag

name()[source]

Returns the name of the sensor.

Return type:

str

type()[source]

Returns the type of the sensor.

Return type:

str

robot()[source]

Returns the model of the robot to which this belongs.

Return type:

RobotModel

measurementNames()[source]

Returns a list of names for the measurements (one per measurement).

Return type:

Sequence[str]

getMeasurements()[source]

Returns an array of measurements from the previous simulation (or kinematicSimulate) timestep.

Return type:

None

settings()[source]

Returns all setting names.

Return type:

Sequence[str]

getSetting(name)[source]

Returns the value of the named setting (you will need to manually parse this)

Return type:

str

Parameters:

name (str) –

setSetting(name, val)[source]

Sets the value of the named setting (you will need to manually cast an int/float/etc to a str)

Return type:

None

Parameters:
  • name (str) –

  • val (str) –

getEnabled()[source]

Return whether the sensor is enabled during simulation (helper for getSetting)

Return type:

bool

setEnabled(enabled)[source]

Sets whether the sensor is enabled (helper for setSetting)

Return type:

None

Parameters:

enabled (bool) –

Returns the link on which the sensor is mounted (helper for getSetting)

Return type:

RobotModelLink

Sets the link on which the sensor is mounted (helper for setSetting)

setLink (link)

Return type:

None

Parameters:

link (RobotModelLink or int) –

getTransform()[source]

Returns the local transform of the sensor on the robot’s link. (helper for getSetting)

If the sensor doesn’t have a transform (such as a joint position or torque sensor) an exception will be raised.

Return type:

None

getTransformWorld()[source]

Returns the world transform of the sensor given the robot’s current configuration. (helper for getSetting)

If the sensor doesn’t have a transform (such as a joint position or torque sensor) an exception will be raised.

Return type:

None

setTransform(R, t)[source]

Sets the local transform of the sensor on the robot’s link. (helper for setSetting)

Return type:

None

Parameters:
  • R (list of 9 floats (so3 element)) –

  • t (list of 3 floats) –

If the sensor doesn’t have a transform (such as a joint position or torque sensor) an exception will be raised.

drawGL(*args)[source]

Draws a sensor indicator using OpenGL. If measurements are given, the indicator is drawn as though these are the latest measurements, otherwise only an indicator is drawn.

drawGL ()

drawGL (np_array)

Return type:

None

Parameters:

np_array (1D Numpy array of floats, optional) –

kinematicSimulate(*args)[source]

kinematicSimulate (dt)

Return type:

None

Parameters:
kinematicReset()[source]

resets a kinematic simulation so that a new initial condition can be set

Return type:

None

property robotModel

robotModel : RobotModel

property sensor

sensor : p.Klampt::SensorBase

class klampt.SimBody[source]

Bases: object

A reference to a rigid body inside a Simulator (either a RigidObjectModel, TerrainModel, or a link of a RobotModel).

Can use this class to directly apply forces to or control positions / velocities of objects in the simulation.

Note

All changes are applied in the current simulation substep, not the duration provided to Simulation.simulate(). If you need fine-grained control, make sure to call Simulation.simulate() with time steps equal to the value provided to Simulation.setSimStep() (this is 0.001s by default). Or, use a hook from SimpleSimulator.

Note

The transform of the body is centered at the object’s center of mass rather than the object’s reference frame given in the RobotModelLink or RigidObjectModel.

C++ includes: robotsim.h

A reference to a rigid body inside a Simulator (either a RigidObjectModel, TerrainModel, or a link of a RobotModel).

Can use this class to directly apply forces to or control positions / velocities of objects in the simulation.

Note

All changes are applied in the current simulation substep, not the duration provided to Simulation.simulate(). If you need fine-grained control, make sure to call Simulation.simulate() with time steps equal to the value provided to Simulation.setSimStep() (this is 0.001s by default). Or, use a hook from SimpleSimulator.

Note

The transform of the body is centered at the object’s center of mass rather than the object’s reference frame given in the RobotModelLink or RigidObjectModel.

C++ includes: robotsim.h

Attributes:

thisown

The membership flag

sim

sim : p.Simulator

objectID

objectID : int

geometry

geometry : p.Klampt::ODEGeometry

body

body : dBodyID

Methods:

getID()

Returns the object ID that this body associated with.

enable([enabled])

Sets the simulation of this body on/off.

isEnabled()

Returns true if this body is being simulated.

enableDynamics([enabled])

Turns dynamic simulation of the body on/off.

isDynamicsEnabled()

rtype:

bool

applyWrench(f, t)

Applies a force and torque about the COM over the duration of the next Simulator.simulate(t) call.

applyForceAtPoint(f, pworld)

Applies a force at a given point (in world coordinates) over the duration of the next Simulator.simulate(t) call.

applyForceAtLocalPoint(f, plocal)

Applies a force at a given point (in local center-of-mass-centered coordinates) over the duration of the next Simulator.simulate(t) call.

setTransform(R, t)

Sets the body's transformation at the current simulation time step (in center- of-mass centered coordinates).

getTransform()

Gets the body's transformation at the current simulation time step (in center- of-mass centered coordinates).

setObjectTransform(R, t)

Sets the body's transformation at the current simulation time step (in object- native coordinates)

getObjectTransform()

Gets the body's transformation at the current simulation time step (in object- native coordinates).

setVelocity(w, v)

Sets the angular velocity and translational velocity at the current simulation time step.

getVelocity()

Returns the angular velocity and translational velocity.

setCollisionPadding(padding)

Sets the collision padding used for contact generation.

getCollisionPadding()

rtype:

float

setCollisionPreshrink([shrinkVisualization])

If set, preshrinks the geometry so that the padded geometry better matches the original mesh.

getSurface()

Gets (a copy of) the surface properties.

setSurface(params)

Sets the surface properties.

property thisown

The membership flag

getID()[source]

Returns the object ID that this body associated with.

Return type:

int

enable(enabled=True)[source]

Sets the simulation of this body on/off.

Return type:

None

Parameters:

enabled (bool, optional) – default value True

isEnabled()[source]

Returns true if this body is being simulated.

Return type:

bool

enableDynamics(enabled=True)[source]

Turns dynamic simulation of the body on/off. If false, velocities will simply be integrated forward, and forces will not affect velocity i.e., it will be pure kinematic simulation.

Return type:

None

Parameters:

enabled (bool, optional) – default value True

isDynamicsEnabled()[source]
Return type:

bool

applyWrench(f, t)[source]

Applies a force and torque about the COM over the duration of the next Simulator.simulate(t) call.

Return type:

None

Parameters:
  • f (list of 3 floats) –

  • t (list of 3 floats) –

applyForceAtPoint(f, pworld)[source]

Applies a force at a given point (in world coordinates) over the duration of the next Simulator.simulate(t) call.

Return type:

None

Parameters:
  • f (list of 3 floats) –

  • pworld (list of 3 floats) –

applyForceAtLocalPoint(f, plocal)[source]

Applies a force at a given point (in local center-of-mass-centered coordinates) over the duration of the next Simulator.simulate(t) call.

Return type:

None

Parameters:
  • f (list of 3 floats) –

  • plocal (list of 3 floats) –

setTransform(R, t)[source]

Sets the body’s transformation at the current simulation time step (in center- of-mass centered coordinates).

Return type:

None

Parameters:
  • R (list of 9 floats (so3 element)) –

  • t (list of 3 floats) –

getTransform()[source]

Gets the body’s transformation at the current simulation time step (in center- of-mass centered coordinates).

Return type:

None

setObjectTransform(R, t)[source]

Sets the body’s transformation at the current simulation time step (in object- native coordinates)

Return type:

None

Parameters:
  • R (list of 9 floats (so3 element)) –

  • t (list of 3 floats) –

getObjectTransform()[source]

Gets the body’s transformation at the current simulation time step (in object- native coordinates).

Return type:

None

setVelocity(w, v)[source]

Sets the angular velocity and translational velocity at the current simulation time step.

Return type:

None

Parameters:
  • w (list of 3 floats) –

  • v (list of 3 floats) –

getVelocity()[source]

Returns the angular velocity and translational velocity.

Return type:

None

setCollisionPadding(padding)[source]

Sets the collision padding used for contact generation. At 0 padding the simulation will be unstable for triangle mesh and point cloud geometries. A larger value is useful to maintain simulation stability for thin or soft objects. Default is 0.0025.

Return type:

None

Parameters:

padding (float) –

getCollisionPadding()[source]
Return type:

float

setCollisionPreshrink(shrinkVisualization=False)[source]

If set, preshrinks the geometry so that the padded geometry better matches the original mesh. If shrinkVisualization=true, the underlying mesh is also shrunk (helps debug simulation artifacts due to preshrink)

Return type:

None

Parameters:

shrinkVisualization (bool, optional) – default value False

getSurface()[source]

Gets (a copy of) the surface properties.

Return type:

ContactParameters

setSurface(params)[source]

Sets the surface properties.

Return type:

None

Parameters:

params (ContactParameters) –

property sim

sim : p.Simulator

property objectID

objectID : int

property geometry

geometry : p.Klampt::ODEGeometry

property body

body : dBodyID

class klampt.SimJoint[source]

Bases: object

An interface to ODE’s hinge and slider joints. You may use this to create custom objects, e.g., drawers, doors, cabinets, etc. It can also be used to attach objects together, e.g., an object to a robot’s gripper.

C++ includes: robotsim.h

Attributes:

thisown

The membership flag

type

type : int

a

a : p.q(const).SimBody

b

b : p.q(const).SimBody

joint

joint : dJointID

Methods:

makeHinge(*args)

makeHinge (a,pt,axis)

makeSlider(*args)

makeSlider (a,axis)

makeFixed(a, b)

Creates a fixed joint between a and b.

destroy()

Removes the joint from the simulation.

setLimits(min, max)

Sets the joint limits, relative to the initial configuration of the bodies.

setFriction(friction)

Sets the (dry) friction of the joint.

setVelocity(vel, fmax)

Locks velocity of the joint, up to force fmax.

addForce(force)

Adds a torque for the hinge joint and a force for a slider joint.

property thisown

The membership flag

makeHinge(*args)[source]

makeHinge (a,pt,axis)

Return type:

None

Parameters:
  • a (SimBody) –

  • b (SimBody, optional) –

  • pt (list of 3 floats) –

  • axis (list of 3 floats) –

makeSlider(*args)[source]

makeSlider (a,axis)

Return type:

None

Parameters:
  • a (SimBody) –

  • b (SimBody, optional) –

  • axis (list of 3 floats) –

makeFixed(a, b)[source]

Creates a fixed joint between a and b. (There’s no method to fix a to the world; just call a.enableDynamics(False))

Return type:

None

Parameters:
destroy()[source]

Removes the joint from the simulation.

Return type:

None

setLimits(min, max)[source]

Sets the joint limits, relative to the initial configuration of the bodies. Units are in radians for hinges and meters for sliders.

Return type:

None

Parameters:
  • min (float) –

  • max (float) –

setFriction(friction)[source]

Sets the (dry) friction of the joint.

Return type:

None

Parameters:

friction (float) –

setVelocity(vel, fmax)[source]

Locks velocity of the joint, up to force fmax. Can’t be used with setFriction.

Return type:

None

Parameters:
  • vel (float) –

  • fmax (float) –

addForce(force)[source]

Adds a torque for the hinge joint and a force for a slider joint.

Return type:

None

Parameters:

force (float) –

property type

type : int

property a

a : p.q(const).SimBody

property b

b : p.q(const).SimBody

property joint

joint : dJointID

class klampt.Simulator(model)[source]

Bases: object

A dynamics simulator for a WorldModel.

C++ includes: robotsim.h

Constructs the simulator from a WorldModel. If the WorldModel was loaded from an XML file, then the simulation setup is loaded from it.

Parameters:

model (WorldModel) –

Attributes:

thisown

The membership flag

STATUS_NORMAL

STATUS_ADAPTIVE_TIME_STEPPING

STATUS_CONTACT_UNRELIABLE

STATUS_UNSTABLE

STATUS_ERROR

index

index : int

world

world : WorldModel

sim

sim : p.Klampt::Simulator

initialState

initialState : std::string

Methods:

reset()

Resets to the initial state (same as setState(initialState))

getStatus()

Returns an indicator code for the simulator status.

getStatusString([s])

Returns a string indicating the simulator's status.

checkObjectOverlap()

Checks if any objects are overlapping.

getState()

Gets the current simulation state, including controller parameters, etc.

setState(str)

Sets the current simulation state from a Base64 string returned by a prior getState call.

simulate(t)

Advances the simulation by time t, and updates the world model from the simulation state.

fakeSimulate(t)

Advances a faked simulation by time t, and updates the world model from the faked simulation state.

getTime()

Returns the simulation time.

updateWorld()

Updates the world model from the current simulation state.

getActualConfig(robot)

Returns the current actual configuration of the robot from the simulator.

getActualVelocity(robot)

Returns the current actual velocity of the robot from the simulator.

getActualTorque(robot)

Returns the current actual torques on the robot's drivers from the simulator.

getActualTorques(robot)

Deprecated: renamed to getActualTorque to be consistent with SimRobotController methods.

enableContactFeedback(obj1, obj2)

Call this to enable contact feedback between the two objects (arguments are indexes returned by object.getID()).

enableContactFeedbackAll()

Call this to enable contact feedback between all pairs of objects.

inContact(aid, bid)

Returns true if the objects (indexes returned by object.getID()) are in contact on the current time step.

getContacts(aid, bid)

Returns the nx7 list of contacts (x,n,kFriction) at the last time step.

getContactForces(aid, bid)

Returns the list of contact forces on object a at the last time step.

contactForce(aid, bid)

Returns the contact force on object a at the last time step.

contactTorque(aid, bid)

Returns the contact force on object a (about a's origin) at the last time step.

hadContact(aid, bid)

Returns true if the objects had contact over the last simulate() call.

hadSeparation(aid, bid)

Returns true if the objects had ever separated during the last simulate() call.

hadPenetration(aid, bid)

Returns true if the objects interpenetrated during the last simulate() call.

meanContactForce(aid, bid)

Returns the average contact force on object a over the last simulate() call.

controller(*args)

Returns a controller for the indicated robot, either by index or by RobotModel.

body(*args)

Return the SimBody corresponding to the given link, rigid object, or terrain.

getJointForces(link)

Returns the joint force and torque local to the link, as would be read by a force-torque sensor mounted at the given link's origin.

setGravity(g)

Sets the overall gravity vector.

setSimStep(dt)

Sets the internal simulation substep.

settings()

Returns all setting names.

getSetting(name)

Retrieves some simulation setting.

setSetting(name, value)

Sets some simulation setting.

property thisown

The membership flag

STATUS_NORMAL = 0
STATUS_ADAPTIVE_TIME_STEPPING = 1
STATUS_CONTACT_UNRELIABLE = 2
STATUS_UNSTABLE = 3
STATUS_ERROR = 4
reset()[source]

Resets to the initial state (same as setState(initialState))

Return type:

None

getStatus()[source]

Returns an indicator code for the simulator status.

Returns: :rtype: int

One of the STATUS_X flags. (Technically, this returns the worst status over the last simulate() call)

getStatusString(s=-1)[source]

Returns a string indicating the simulator’s status. If s is provided and >= 0, this function maps the indicator code s to a string.

Return type:

str

Parameters:

s (int, optional) – default value -1

checkObjectOverlap()[source]

Checks if any objects are overlapping.

Returns: :rtype: None

A pair of lists of integers, giving the pairs of object ids that are overlapping.

getState()[source]

Gets the current simulation state, including controller parameters, etc.

Returns: :rtype: str

A Base64 string representing the binary data for the state

setState(str)[source]

Sets the current simulation state from a Base64 string returned by a prior getState call.

Return type:

None

Parameters:

str (str) –

simulate(t)[source]

Advances the simulation by time t, and updates the world model from the simulation state.

Return type:

None

Parameters:

t (float) –

fakeSimulate(t)[source]

Advances a faked simulation by time t, and updates the world model from the faked simulation state.

Return type:

None

Parameters:

t (float) –

getTime()[source]

Returns the simulation time.

Return type:

float

updateWorld()[source]

Updates the world model from the current simulation state. This only needs to be called if you change the world model and want to revert back to the simulation state.

Return type:

None

getActualConfig(robot)[source]

Returns the current actual configuration of the robot from the simulator.

Return type:

None

Parameters:

robot (int) –

getActualVelocity(robot)[source]

Returns the current actual velocity of the robot from the simulator.

Return type:

None

Parameters:

robot (int) –

getActualTorque(robot)[source]

Returns the current actual torques on the robot’s drivers from the simulator.

Return type:

None

Parameters:

robot (int) –

getActualTorques(robot)[source]

Deprecated: renamed to getActualTorque to be consistent with SimRobotController methods.

Return type:

None

Parameters:

robot (int) –

enableContactFeedback(obj1, obj2)[source]

Call this to enable contact feedback between the two objects (arguments are indexes returned by object.getID()). Contact feedback has a small overhead so you may want to do this selectively. This must be called before using inContact, getContacts, getContactForces, contactForce, contactTorque, hadContact, hadSeparation, hadPenetration, and meanContactForce.

Return type:

None

Parameters:
  • obj1 (int) –

  • obj2 (int) –

enableContactFeedbackAll()[source]

Call this to enable contact feedback between all pairs of objects. Contact feedback has a small overhead so you may want to do this selectively.

Return type:

None

inContact(aid, bid)[source]

Returns true if the objects (indexes returned by object.getID()) are in contact on the current time step. You can set bid=-1 to tell if object a is in contact with any object.

Return type:

bool

Parameters:
  • aid (int) –

  • bid (int) –

getContacts(aid, bid)[source]

Returns the nx7 list of contacts (x,n,kFriction) at the last time step. Normals point into object a. Each contact point (x,n,kFriction) is represented as a 7-element vector.

Return type:

None

Parameters:
  • aid (int) –

  • bid (int) –

getContactForces(aid, bid)[source]

Returns the list of contact forces on object a at the last time step. Result is an nx3 array.

Return type:

None

Parameters:
  • aid (int) –

  • bid (int) –

contactForce(aid, bid)[source]

Returns the contact force on object a at the last time step. You can set bid to -1 to get the overall contact force on object a.

Return type:

None

Parameters:
  • aid (int) –

  • bid (int) –

contactTorque(aid, bid)[source]

Returns the contact force on object a (about a’s origin) at the last time step. You can set bid to -1 to get the overall contact force on object a.

Return type:

None

Parameters:
  • aid (int) –

  • bid (int) –

hadContact(aid, bid)[source]

Returns true if the objects had contact over the last simulate() call. You can set bid to -1 to determine if object a had contact with any other object.

Return type:

bool

Parameters:
  • aid (int) –

  • bid (int) –

hadSeparation(aid, bid)[source]

Returns true if the objects had ever separated during the last simulate() call. You can set bid to -1 to determine if object a had no contact with any other object.

Return type:

bool

Parameters:
  • aid (int) –

  • bid (int) –

hadPenetration(aid, bid)[source]

Returns true if the objects interpenetrated during the last simulate() call. If so, the simulation may lead to very inaccurate results or artifacts.

Return type:

bool

Parameters:
  • aid (int) –

  • bid (int) –

You can set bid to -1 to determine if object a penetrated any object, or you can set aid=bid=-1 to determine whether any object is penetrating any other (indicating that the simulation will not be functioning properly in general).

meanContactForce(aid, bid)[source]

Returns the average contact force on object a over the last simulate() call.

Return type:

None

Parameters:
  • aid (int) –

  • bid (int) –

controller(*args)[source]

Returns a controller for the indicated robot, either by index or by RobotModel.

controller (robot): SimRobotController

Return type:

SimRobotController

Parameters:

robot (RobotModel or int) –

Returns:

Return type:

SimRobotController

body(*args)[source]

Return the SimBody corresponding to the given link, rigid object, or terrain.

body (link): SimBody

body (object): SimBody

body (terrain): SimBody

Return type:

SimBody

Parameters:
Returns:

Return type:

SimBody

getJointForces(link)[source]

Returns the joint force and torque local to the link, as would be read by a force-torque sensor mounted at the given link’s origin.

Return type:

None

Parameters:

link (RobotModelLink) –

Returns:

6 entries of the wrench (fx,fy,fz,mx,my,mz)

setGravity(g)[source]

Sets the overall gravity vector.

Return type:

None

Parameters:

g (list of 3 floats) –

setSimStep(dt)[source]

Sets the internal simulation substep. Values < 0.01 are recommended.

Return type:

None

Parameters:

dt (float) –

settings()[source]

Returns all setting names.

Return type:

Sequence[str]

getSetting(name)[source]

Retrieves some simulation setting.

Return type:

str

Parameters:

name (str) –

Valid names are:

  • gravity: the gravity vector (default “0 0 -9.8”)

  • simStep: the internal simulation step (default “0.001”)

  • autoDisable: whether to disable bodies that don’t move much between time steps (default “0”, set to “1” for many static objects)

  • boundaryLayerCollisions: whether to use the Klampt inflated boundaries for contact detection’(default “1”, recommended)

  • rigidObjectCollisions: whether rigid objects should collide (default “1”)

  • robotSelfCollisions: whether robots should self collide (default “0”)

  • robotRobotCollisions: whether robots should collide with other robots (default “1”)

  • adaptiveTimeStepping: whether adaptive time stepping should be used to improve stability. Slower but more stable. (default “1”)

  • minimumAdaptiveTimeStep: the minimum size of an adaptive time step before giving up (default “1e-6”)

  • maxContacts: max # of clustered contacts between pairs of objects (default “20”)

  • clusterNormalScale: a parameter for clustering contacts (default “0.1”)

  • errorReductionParameter: see ODE docs on ERP (default “0.95”)

  • dampedLeastSquaresParameter: see ODE docs on CFM (default “1e-6”)

  • instabilityConstantEnergyThreshold: parameter c0 in instability correction (default “1”)

  • instabilityLinearEnergyThreshold: parameter c1 in instability correction (default “1.5”)

  • instabilityMaxEnergyThreshold: parameter cmax in instability correction (default “100000”)

  • instabilityPostCorrectionEnergy: kinetic energy scaling parameter if instability is detected (default “0.8”)

Instability correction kicks in whenever the kinetic energy K(t) of an object exceeds min(c0*m + c1*K(t-dt),cmax). m is the object’s mass.

See Klampt/Simulation/ODESimulator.h for detailed descriptions of these parameters.

Returns:

A string encoding the data. This will need to be cast to int or float manually.

setSetting(name, value)[source]

Sets some simulation setting. Raises an exception if the name is unknown or the value is of improper format.

Return type:

None

Parameters:
  • name (str) –

  • value (str) –

property index

index : int

property world

world : WorldModel

property sim

sim : p.Klampt::Simulator

property initialState

initialState : std::string

class klampt.Geometry3D(*args)[source]

Bases: object

The three-D geometry container used throughout Klampt.

There are five currently supported types of geometry:

This class acts as a uniform container of all of these types.

There are two modes in which a Geometry3D can be used. It can be a standalone geometry, which means it is a container of geometry data, or it can be a reference to a world item’s geometry. For references, modifiers change the world item’s geometry.

Current transform

Each geometry stores a “current” transform, which is automatically updated for world items’ geometries. Proximity queries are then performed with respect to the transformed geometries. Crucially, the underlying geometry is not changed, because that could be computationally expensive.

Creating / modifying the geometry

Use the constructor, the set(), or the set[TYPE]() methods to completely change the geometry’s data.

Note: if you want to set a world item’s geometry to be equal to a standalone geometry, use the set(rhs) function rather than the assignment (=) operator.

Modifiers include:

Note

Avoid the use of translate, rotate, and transform to represent object movement. Use setCurrentTransform instead.

Proximity queries

For most geometry types (TriangleMesh, PointCloud, ConvexHull), the first time you perform a query, some collision detection data structures will be initialized. This preprocessing step can take some time for complex geometries.

Collision margins

Each object also has a “collision margin” which may virtually fatten the object, as far as proximity queries are concerned. This is useful for setting collision avoidance margins in motion planning. Use the setCollisionMargin() and getCollisionMargin() methods to access the margin. By default the margin is zero.

Note

The geometry margin is NOT the same thing as simulation body collision padding! All proximity queries are affected by the collision padding, inside or outside of simulation.

Conversions

Many geometry types can be converted to and from one another using the convert() method. This can also be used to remesh TriangleMesh objects and PointCloud objects.

C++ includes: geometry.h

__init__ (): Geometry3D

__init__ (arg2): Geometry3D

Parameters:

arg2 (Geometry3D or VolumeGrid or PointCloud or GeometricPrimitive or TriangleMesh or ConvexHull, optional) –

Attributes:

thisown

The membership flag

world

world : int

id

id : int

geomPtr

geomPtr : p.void

Methods:

clone()

Creates a standalone geometry from this geometry (identical to copy.

copy()

Creates a standalone geometry from this geometry.

set(arg2)

Copies the geometry of the argument into this geometry.

isStandalone()

Returns True if this is a standalone geometry.

free()

Frees the data associated with this geometry, if standalone.

type()

Returns the type of geometry: TriangleMesh, PointCloud, VolumeGrid, GeometricPrimitive, or Group.

empty()

Returns True if this has no contents (not the same as numElements()==0)

getTriangleMesh()

Returns a TriangleMesh if this geometry is of type TriangleMesh.

getPointCloud()

Returns a PointCloud if this geometry is of type PointCloud.

getGeometricPrimitive()

Returns a GeometricPrimitive if this geometry is of type GeometricPrimitive.

getConvexHull()

Returns a ConvexHull if this geometry is of type ConvexHull.

getVolumeGrid()

Returns a VolumeGrid if this geometry is of type VolumeGrid.

setTriangleMesh(arg2)

Sets this Geometry3D to a TriangleMesh.

setPointCloud(arg2)

Sets this Geometry3D to a PointCloud.

setGeometricPrimitive(arg2)

Sets this Geometry3D to a GeometricPrimitive.

setConvexHull(arg2)

Sets this Geometry3D to a ConvexHull.

setConvexHullGroup(g1, g2)

Sets this Geometry3D to be a convex hull of two geometries.

setVolumeGrid(arg2)

Sets this Geometry3D to a volumeGrid.

setGroup()

Sets this Geometry3D to a group geometry.

getElement(element)

Returns an element of the Geometry3D if it is a Group, TriangleMesh, or PointCloud.

setElement(element, data)

Sets an element of the Geometry3D if it is a Group, TriangleMesh, or PointCloud.

numElements()

Returns the number of sub-elements in this geometry.

loadFile(fn)

Loads from file.

saveFile(fn)

Saves to file.

setCurrentTransform(R, t)

Sets the current transformation (not modifying the underlying data)

getCurrentTransform()

Gets the current transformation.

translate(t)

Translates the geometry data.

scale(*args)

Scales the geometry data with different factors on each axis.

rotate(R)

Rotates the geometry data.

transform(R, t)

Translates/rotates/scales the geometry data.

setCollisionMargin(margin)

Sets a padding around the base geometry which affects the results of proximity queries.

getCollisionMargin()

Returns the padding around the base geometry.

getBB()

Returns an axis-aligned bounding box of the object as a tuple (bmin,bmax).

getBBTight()

Computes a tighter axis-aligned bounding box of the object than Geometry3D.getBB().

convert(type[, param])

Converts a geometry to another type, if a conversion is available.

collides(other)

Returns true if this geometry collides with the other.

withinDistance(other, tol)

Returns true if this geometry is within distance tol to other.

distance_simple(other[, relErr, absErr])

Version 0.8: this is the same as the old distance() function.

distance_point(pt)

Returns the the distance and closest point to the input point, given in world coordinates.

distance_point_ext(pt, settings)

A customizable version of Geometry3D.distance_point().

distance(other)

Returns the the distance and closest points between the given geometries.

distance_ext(other, settings)

A customizable version of Geometry3D.distance().

rayCast(s, d)

Performs a ray cast.

rayCast_ext(s, d)

A more sophisticated ray cast.

contacts(other, padding1, padding2[, ...])

Returns the set of contact points between this and other.

support(dir)

Calculates the furthest point on this geometry in the direction dir.

slice(R, t, tol)

Calculates a 2D slice through the data.

roi(query, bmin, bmax)

Calculates a region of interest of the data for the bounding box [bmin,bmax].

property thisown

The membership flag

clone()[source]

Creates a standalone geometry from this geometry (identical to copy… will be deprecated in a future version)

Return type:

Geometry3D

copy()[source]

Creates a standalone geometry from this geometry.

Return type:

Geometry3D

set(arg2)[source]

Copies the geometry of the argument into this geometry.

Return type:

None

Parameters:

arg2 (Geometry3D) –

isStandalone()[source]

Returns True if this is a standalone geometry.

Return type:

bool

free()[source]

Frees the data associated with this geometry, if standalone.

Return type:

None

type()[source]

Returns the type of geometry: TriangleMesh, PointCloud, VolumeGrid, GeometricPrimitive, or Group.

Return type:

str

empty()[source]

Returns True if this has no contents (not the same as numElements()==0)

Return type:

bool

getTriangleMesh()[source]

Returns a TriangleMesh if this geometry is of type TriangleMesh.

Return type:

TriangleMesh

getPointCloud()[source]

Returns a PointCloud if this geometry is of type PointCloud.

Return type:

PointCloud

getGeometricPrimitive()[source]

Returns a GeometricPrimitive if this geometry is of type GeometricPrimitive.

Return type:

GeometricPrimitive

getConvexHull()[source]

Returns a ConvexHull if this geometry is of type ConvexHull.

Return type:

ConvexHull

getVolumeGrid()[source]

Returns a VolumeGrid if this geometry is of type VolumeGrid.

Return type:

VolumeGrid

setTriangleMesh(arg2)[source]

Sets this Geometry3D to a TriangleMesh.

Return type:

None

Parameters:

arg2 (TriangleMesh) –

setPointCloud(arg2)[source]

Sets this Geometry3D to a PointCloud.

Return type:

None

Parameters:

arg2 (PointCloud) –

setGeometricPrimitive(arg2)[source]

Sets this Geometry3D to a GeometricPrimitive.

Return type:

None

Parameters:

arg2 (GeometricPrimitive) –

setConvexHull(arg2)[source]

Sets this Geometry3D to a ConvexHull.

Return type:

None

Parameters:

arg2 (ConvexHull) –

setConvexHullGroup(g1, g2)[source]

Sets this Geometry3D to be a convex hull of two geometries. Note: the relative transform of these two objects is frozen in place; i.e., setting the current transform of g2 doesn’t do anything to this object.

Return type:

None

Parameters:
setVolumeGrid(arg2)[source]

Sets this Geometry3D to a volumeGrid.

Return type:

None

Parameters:

arg2 (VolumeGrid) –

setGroup()[source]

Sets this Geometry3D to a group geometry. To add sub-geometries, repeatedly call setElement() with increasing indices.

Return type:

None

getElement(element)[source]

Returns an element of the Geometry3D if it is a Group, TriangleMesh, or PointCloud. Raises an error if this is of any other type.

Return type:

Geometry3D

Parameters:

element (int) –

The element will be in local coordinates.

setElement(element, data)[source]

Sets an element of the Geometry3D if it is a Group, TriangleMesh, or PointCloud. The element will be in local coordinates. Raises an error if this is of any other type.

Return type:

None

Parameters:
numElements()[source]

Returns the number of sub-elements in this geometry.

Return type:

int

loadFile(fn)[source]

Loads from file. Standard mesh types, PCD files, and .geom files are supported.

Return type:

bool

Parameters:

fn (str) –

Returns:

True on success, False on failure

saveFile(fn)[source]

Saves to file. Standard mesh types, PCD files, and .geom files are supported.

Return type:

bool

Parameters:

fn (str) –

setCurrentTransform(R, t)[source]

Sets the current transformation (not modifying the underlying data)

Return type:

None

Parameters:
  • R (list of 9 floats (so3 element)) –

  • t (list of 3 floats) –

getCurrentTransform()[source]

Gets the current transformation.

Return type:

None

translate(t)[source]

Translates the geometry data. Permanently modifies the data and resets any collision data structures.

Return type:

None

Parameters:

t (list of 3 floats) –

scale(*args)[source]

Scales the geometry data with different factors on each axis. Permanently modifies the data and resets any collision data structures.

scale (s)

scale (sx,sy,sz)

Return type:

None

Parameters:
  • s (float, optional) –

  • sx (float, optional) –

  • sy (float, optional) –

  • sz (float, optional) –

rotate(R)[source]

Rotates the geometry data. Permanently modifies the data and resets any collision data structures.

Return type:

None

Parameters:

R (list of 9 floats (so3 element)) –

transform(R, t)[source]

Translates/rotates/scales the geometry data. Permanently modifies the data and resets any collision data structures.

Return type:

None

Parameters:
  • R (list of 9 floats (so3 element)) –

  • t (list of 3 floats) –

setCollisionMargin(margin)[source]

Sets a padding around the base geometry which affects the results of proximity queries.

Return type:

None

Parameters:

margin (float) –

getCollisionMargin()[source]

Returns the padding around the base geometry. Default 0.

Return type:

float

getBB()[source]

Returns an axis-aligned bounding box of the object as a tuple (bmin,bmax).

Note: O(1) time, but may not be tight

Return type:

None

getBBTight()[source]

Computes a tighter axis-aligned bounding box of the object than Geometry3D.getBB(). Worst case O(n) time.

Return type:

None

convert(type, param=0)[source]

Converts a geometry to another type, if a conversion is available. The interpretation of param depends on the type of conversion, with 0 being a reasonable default.

Return type:

Geometry3D

Parameters:
  • type (str) –

  • param (float, optional) – default value 0

Available conversions are:

  • TriangleMesh -> PointCloud. param is the desired dispersion of the points, by default set to the average triangle diameter. At least all of the mesh’s vertices will be returned.

  • TriangleMesh -> VolumeGrid. Converted using the fast marching method with good results only if the mesh is watertight. param is the grid resolution, by default set to the average triangle diameter.

  • TriangleMesh -> ConvexHull. If param==0, just calculates a convex hull. Otherwise, uses convex decomposition with the HACD library.

  • PointCloud -> TriangleMesh. Available if the point cloud is structured. param is the threshold for splitting triangles by depth discontinuity. param is by default infinity.

  • PointCloud -> ConvexHull. Converted using SOLID / Qhull.

  • GeometricPrimitive -> anything. param determines the desired resolution.

  • VolumeGrid -> TriangleMesh. param determines the level set for the marching cubes algorithm.

  • VolumeGrid -> PointCloud. param determines the level set.

  • ConvexHull -> TriangleMesh.

  • ConvexHull -> PointCloud. param is the desired dispersion of the points. Equivalent to ConvexHull -> TriangleMesh -> PointCloud

collides(other)[source]

Returns true if this geometry collides with the other.

Return type:

bool

Parameters:

other (Geometry3D) –

Unsupported types:

  • VolumeGrid - GeometricPrimitive [aabb, box, triangle, polygon]

  • VolumeGrid - TriangleMesh

  • VolumeGrid - VolumeGrid

  • ConvexHull - anything else besides ConvexHull

withinDistance(other, tol)[source]

Returns true if this geometry is within distance tol to other.

Return type:

bool

Parameters:
distance_simple(other, relErr=0, absErr=0)[source]

Version 0.8: this is the same as the old distance() function.

Return type:

float

Parameters:
  • other (Geometry3D) –

  • relErr (float, optional) – default value 0

  • absErr (float, optional) – default value 0

Returns the distance from this geometry to the other. If either geometry contains volume information, this value may be negative to indicate penetration. See Geometry3D.distance() for more information.

distance_point(pt)[source]

Returns the the distance and closest point to the input point, given in world coordinates. An exception is raised if this operation is not supported with the given geometry type.

Return type:

DistanceQueryResult

Parameters:

pt (list of 3 floats) –

The return value contains the distance, closest points, and gradients if available.

For some geometry types, the signed distance is returned. The signed distance returns the negative penetration depth if pt is within this. The following geometry types return signed distances:

  • GeometricPrimitive

  • PointCloud (approximate, if the cloud is a set of balls with the radius property)

  • VolumeGrid

  • ConvexHull

For other types, a signed distance will be returned if the geometry has a positive collision margin, and the point penetrates less than this margin.

distance_point_ext(pt, settings)[source]

A customizable version of Geometry3D.distance_point(). The settings for the calculation can be customized with relErr, absErr, and upperBound, e.g., to break if the closest points are at least upperBound distance from one another.

Return type:

DistanceQueryResult

Parameters:
distance(other)[source]

Returns the the distance and closest points between the given geometries. This may be either the normal distance or the signed distance, depending on the geometry type.

Return type:

DistanceQueryResult

Parameters:

other (Geometry3D) –

The normal distance returns 0 if the two objects are touching (this.collides(other)=True).

The signed distance returns the negative penetration depth if the objects are touching. Only the following combinations of geometry types return signed distances:

  • GeometricPrimitive-GeometricPrimitive (Python-supported sub-types only)

  • GeometricPrimitive-TriangleMesh (surface only)

  • GeometricPrimitive-PointCloud

  • GeometricPrimitive-VolumeGrid

  • TriangleMesh (surface only)-GeometricPrimitive

  • PointCloud-VolumeGrid

  • ConvexHull - ConvexHull

If penetration is supported, a negative distance is returned and cp1,cp2 are the deepest penetrating points.

Unsupported types:

  • GeometricPrimitive-GeometricPrimitive subtypes segment vs aabb

  • PointCloud-PointCloud

  • VolumeGrid-TriangleMesh

  • VolumeGrid-VolumeGrid

  • ConvexHull - anything else besides ConvexHull

See the comments of the distance_point function

distance_ext(other, settings)[source]

A customizable version of Geometry3D.distance(). The settings for the calculation can be customized with relErr, absErr, and upperBound, e.g., to break if the closest points are at least upperBound distance from one another.

Return type:

DistanceQueryResult

Parameters:
rayCast(s, d)[source]

Performs a ray cast.

Return type:

bool

Parameters:
  • s (list of 3 floats) –

  • d (list of 3 floats) –

Supported types:

  • GeometricPrimitive

  • TriangleMesh

  • PointCloud (need a positive collision margin, or points need to have a ‘radius’ property assigned)

  • VolumeGrid

  • Group (groups of the aforementioned types)

Returns:

(hit,pt) where hit is true if the ray starting at s and pointing in direction d hits the geometry (given in world coordinates); pt is the hit point, in world coordinates.

rayCast_ext(s, d)[source]

A more sophisticated ray cast.

Return type:

int

Parameters:
  • s (list of 3 floats) –

  • d (list of 3 floats) –

Supported types:

  • GeometricPrimitive

  • TriangleMesh

  • PointCloud (need a positive collision margin, or points need to have a ‘radius’ property assigned)

  • VolumeGrid

  • Group (groups of the aforementioned types)

Returns:

(hit_element,pt) where hit_element is >= 0 if ray starting at s and pointing in direction d hits the geometry (given in world coordinates).

  • hit_element is -1 if the object is not hit, otherwise it gives the index of the element (triangle, point, sub-object) that was hit. For geometric primitives, this will be 0.

  • pt is the hit point, in world coordinates.

contacts(other, padding1, padding2, maxContacts=0)[source]

Returns the set of contact points between this and other. This set is a discrete representation of the region of surface overlap, which is defined as all pairs of points within distance self.collisionMargin + other.collisionMargin + padding1 + padding2.

Return type:

ContactQueryResult

Parameters:
  • other (Geometry3D) –

  • padding1 (float) –

  • padding2 (float) –

  • maxContacts (int, optional) – default value 0

For some geometry types (TriangleMesh-TriangleMesh, TriangleMesh-PointCloud, PointCloud-PointCloud) padding must be positive to get meaningful contact poitns and normals.

If maxContacts != 0 a clustering postprocessing step is performed.

Unsupported types:

  • GeometricPrimitive-GeometricPrimitive subtypes segment vs aabb

  • VolumeGrid-GeometricPrimitive any subtypes except point and sphere. also, the results are potentially inaccurate for non-convex VolumeGrids.

  • VolumeGrid-TriangleMesh

  • VolumeGrid-VolumeGrid

  • ConvexHull - anything

support(dir)[source]

Calculates the furthest point on this geometry in the direction dir.

Return type:

None

Parameters:

dir (list of 3 floats) –

Supported types:

  • ConvexHull

slice(R, t, tol)[source]

Calculates a 2D slice through the data. The slice is given by the local X-Y plane of a transform (R,T) with orientation R and translation t. The return Geometry’s data is in the local frame of (R,t), and (R,t) is set as its current transform.

Return type:

Geometry3D

Parameters:
  • R (list of 9 floats (so3 element)) –

  • t (list of 3 floats) –

  • tol (float) –

The geometry’s current transform is respected.

O(N) time.

Supported types:

  • PointCloud. Needs tol > 0. A PointCloud is returned.

  • TriangleMesh. tol is ignored. A Group of GeometricPrimitives (segments) is returned.

roi(query, bmin, bmax)[source]

Calculates a region of interest of the data for the bounding box [bmin,bmax]. The geometry’s current transform is respected.

Return type:

Geometry3D

Parameters:
  • query (str) –

  • bmin (list of 3 floats) –

  • bmax (list of 3 floats) –

query can be “intersect”, “touching”, or “within”. If “intersect”, this tries to get a representation of the geometry intersecting the box. If “touching”, all elements touching the box are returned. If “within”, only elements entirely inside the box are returned.

query can also be prefaced with a ‘~’ which indicates that the ROI should be inverted, i.e. select everything that does NOT intersect with a box.

O(N) time.

Supported types:

  • PointCloud

  • TriangleMesh

property world

world : int

property id

id : int

property geomPtr

geomPtr : p.void

class klampt.Appearance(*args)[source]

Bases: object

Geometry appearance information. Supports vertex/edge/face rendering, per-vertex color, and basic color texture mapping. Uses OpenGL display lists, so repeated calls are fast.

For more complex appearances, you will need to call your own OpenGL calls.

Appearances can be either references to appearances of objects in the world, or they can be standalone.

Performance note: Avoid rebuilding buffers (e.g., via refresh()) as much as possible.

C++ includes: appearance.h

__init__ (): Appearance

__init__ (app): Appearance

Parameters:

app (Appearance, optional) –

Attributes:

thisown

The membership flag

ALL

VERTICES

EDGES

FACES

EMISSIVE

SPECULAR

world

world : int

id

id : int

appearancePtr

appearancePtr : p.void

Methods:

refresh([deep])

call this to rebuild internal buffers, e.g., when the OpenGL context changes.

clone()

Creates a standalone appearance from this appearance.

set(arg2)

Copies the appearance of the argument into this appearance.

isStandalone()

Returns true if this is a standalone appearance.

free()

Frees the data associated with this appearance, if standalone.

setDraw(*args)

Turns on/off visibility of the object or a feature.

getDraw(*args)

Returns whether this object or feature is visible.

setColor(*args)

Sets color of the object or a feature.

getColor(*args)

Gets color of the object or a feature.

setColors(feature, np_array2)

Sets per-element color for elements of the given feature type.

setTintColor(color, strength)

Sets a temporary tint color that modulates the appearance of the object.

getTintColor()

Retrieves the tint color.

getTintStrength()

Retrieves the tint strength.

setShininess(shininess[, strength])

Sets the specular highlight shininess and strength.

getShininess()

Retrieves the specular highlight shininess.

setElementColor(feature, element, r, g, b[, a])

Sets the per-element color for the given feature.

getElementColor(feature, element)

Gets the per-element color for the given feature.

setTexture1D_b(format, np_array)

Sets a 1D texture of the given width.

setTexture1D_i(format, np_array, m)

Sets a 1D texture of the given width.

setTexture1D_channels(format, np_array2)

Sets a 1D texture of the given width, given a 2D array of channels.

setTexture2D_b(format, np_array2[, topdown])

Sets a 2D texture of the given width/height.

setTexture2D_i(format, np_array2[, topdown])

Sets a 2D texture of the given width/height.

setTexture2D_channels(format, np_array3[, ...])

Sets a 2D texture of the given width/height from a 3D array of channels.

setTexcoords1D(np_array)

Sets per-vertex texture coordinates for a 1D texture.

setTexcoords2D(np_array2)

Sets per-vertex texture coordinates for a 2D texture.

setTexgen(np_array2[, worldcoordinates])

Sets the texture generation.

setTexWrap(wrap)

Sets whether textures are to wrap (default true)

setPointSize(size)

For point clouds, sets the point size.

setCreaseAngle(creaseAngleRads)

For meshes, sets the crease angle.

setSilhouette(radius[, r, g, b, a])

For meshes sets a silhouette radius and color.

drawGL(*args)

Draws the given geometry with this appearance.

drawWorldGL(geom)

Draws the given geometry with this appearance.

setTexture1D(format, array)

Sets a 1D texture.

setTexture2D(format, array)

Sets a 2D texture.

setTexcoords(array)

Sets texture coordinates for the mesh.

property thisown

The membership flag

ALL = 0
VERTICES = 1
EDGES = 2
FACES = 3
EMISSIVE = 4
SPECULAR = 5
refresh(deep=True)[source]

call this to rebuild internal buffers, e.g., when the OpenGL context changes. If deep=True, the entire data structure will be revised. Use this for streaming data, for example.

Return type:

None

Parameters:

deep (bool, optional) – default value True

clone()[source]

Creates a standalone appearance from this appearance.

Return type:

Appearance

set(arg2)[source]

Copies the appearance of the argument into this appearance.

Return type:

None

Parameters:

arg2 (Appearance) –

isStandalone()[source]

Returns true if this is a standalone appearance.

Return type:

bool

free()[source]

Frees the data associated with this appearance, if standalone.

Return type:

None

setDraw(*args)[source]

Turns on/off visibility of the object or a feature.

setDraw (draw)

setDraw (feature,draw)

Return type:

None

Parameters:
  • draw (bool) –

  • feature (int, optional) –

If one argument is given, turns the object visibility on or off

If two arguments are given, turns the feature (first int argument) visibility on or off. feature can be ALL, VERTICES, EDGES, or FACES.

getDraw(*args)[source]

Returns whether this object or feature is visible.

getDraw (): bool

getDraw (feature): bool

Return type:

bool

Parameters:

feature (int, optional) –

Returns:

Return type:

bool

If no arguments are given, returns whether the object is visible.

If one int argument is given, returns whether the given feature is visible. feature can be ALL, VERTICES, EDGES, or FACES.

setColor(*args)[source]

Sets color of the object or a feature.

setColor (r,g,b,a=1)

setColor (feature,r,g,b,a)

Return type:

None

Parameters:
  • r (float) –

  • g (float) –

  • b (float) –

  • a (float) – default value 1

  • feature (int, optional) –

If 3 or 4 arguments are given, changes the object color.

If 5 arguments are given, changes the color of the given feature. feature can be ALL, VERTICES, EDGES, FACES, EMISSIVE, or SPECULAR.

getColor(*args)[source]

Gets color of the object or a feature.

getColor ()

getColor (feature)

Return type:

None

Parameters:

feature (int, optional) –

If 0 arguments are given, retrieves the main object color.

If 1 arguments are given, returns the color of the given feature. feature. feature can be ALL, VERTICES, EDGES, FACES, EMISSIVE, or SPECULAR.

setColors(feature, np_array2)[source]

Sets per-element color for elements of the given feature type. Must be an mxn array. m is the number of features of that type, and n is either 3 or 4.

Return type:

None

Parameters:
  • feature (int) –

  • np_array2 (2D Numpy array of np.float32) –

If n == 4, they are assumed to be rgba values, and

If n == 3, each row is an rgb value.

Only supports feature=VERTICES and feature=FACES

setTintColor(color, strength)[source]

Sets a temporary tint color that modulates the appearance of the object. This works with both flat colors and per-vertex / per-face colors.

Return type:

None

Parameters:
  • color (list of 4 wfloats) –

  • strength (float) –

getTintColor()[source]

Retrieves the tint color.

Return type:

None

getTintStrength()[source]

Retrieves the tint strength.

Return type:

float

setShininess(shininess, strength=-1)[source]

Sets the specular highlight shininess and strength. To turn off, use setShininess(0). The specular strength can be set via the second argument. setShininess(20,0.1). Note that this changes the specular color.

Return type:

None

Parameters:
  • shininess (float) –

  • strength (float, optional) – default value -1

getShininess()[source]

Retrieves the specular highlight shininess.

Return type:

float

setElementColor(feature, element, r, g, b, a=1)[source]

Sets the per-element color for the given feature.

Return type:

None

Parameters:
  • feature (int) –

  • element (int) –

  • r (float) –

  • g (float) –

  • b (float) –

  • a (float, optional) – default value 1

getElementColor(feature, element)[source]

Gets the per-element color for the given feature.

Return type:

None

Parameters:
  • feature (int) –

  • element (int) –

setTexture1D_b(format, np_array)[source]

Sets a 1D texture of the given width. Valid format strings are.

Return type:

None

Parameters:
  • format (str) –

  • np_array (unsigned char *) –

  • “”: turn off texture mapping

  • l8: unsigned byte grayscale colors

setTexture1D_i(format, np_array, m)[source]

Sets a 1D texture of the given width. Valid format strings are.

Return type:

None

Parameters:
  • format (str) –

  • np_array (unsigned int *) –

  • m (int) –

  • “”: turn off texture mapping

  • rgba8: unsigned byte RGBA colors with red in the 1st byte and alpha in the 4th

  • bgra8: unsigned byte RGBA colors with blue in the 1st byte and alpha in the 4th

setTexture1D_channels(format, np_array2)[source]

Sets a 1D texture of the given width, given a 2D array of channels. Valid format strings are.

Return type:

None

Parameters:
  • format (str) –

  • np_array2 (unsigned char *) –

  • “”: turn off texture mapping

  • rgb8: unsigned byte RGB colors with red in the 1st column, green in the 2nd, blue in the 3rd

  • bgr8: unsigned byte RGB colors with blue in the 1st column, green in the 2nd, green in the 3rd

  • rgba8: unsigned byte RGBA colors with red in the 1st column and alpha in the 4th

  • bgra8: unsigned byte RGBA colors with blue in the 1st column and alpha in the 4th

  • l8: unsigned byte grayscale colors, one channel

setTexture2D_b(format, np_array2, topdown=True)[source]

Sets a 2D texture of the given width/height. See setTexture1D_b() for valid format strings.

Return type:

None

Parameters:
  • format (str) –

  • np_array2 (unsigned char *) –

  • topdown (bool, optional) – default value True

The array is given in top to bottom order if topdown==True. Otherwise, it is given in order bottom to top.

setTexture2D_i(format, np_array2, topdown=True)[source]

Sets a 2D texture of the given width/height. See setTexture1D_i() for valid format strings.

Return type:

None

Parameters:
  • format (str) –

  • np_array2 (unsigned int *) –

  • topdown (bool, optional) – default value True

The array is given in top to bottom order if topdown==True. Otherwise, it is given in order bottom to top.

setTexture2D_channels(format, np_array3, topdown=True)[source]

Sets a 2D texture of the given width/height from a 3D array of channels. See setTexture1D_channels() for valid format strings.

Return type:

None

Parameters:
  • format (str) –

  • np_array3 (unsigned char *) –

  • topdown (bool, optional) – default value True

The array is given in top to bottom order if topdown==True. Otherwise, it is given in order bottom to top.

setTexcoords1D(np_array)[source]

Sets per-vertex texture coordinates for a 1D texture.

Return type:

None

Parameters:

np_array (1D Numpy array of floats) –

You may also set uvs to be empty, which turns off texture mapping altogether.

setTexcoords2D(np_array2)[source]

Sets per-vertex texture coordinates for a 2D texture. uvs is an array of shape (nx2) containing U-V coordinates [[u1, v1], [u2, v2], …, [un, vn]].

Return type:

None

Parameters:

np_array2 (2D Numpy array of floats) –

You may also set uvs to be empty, which turns off texture mapping altogether.

setTexgen(np_array2, worldcoordinates=False)[source]

Sets the texture generation. The array must be size m x 4, with m in the range 0,…,4. If worldcoordinates=true, the texture generation is performed in world coordinates rather than object coordinates.

Return type:

None

Parameters:
  • np_array2 (2D Numpy array of floats) –

  • worldcoordinates (bool, optional) – default value False

setTexWrap(wrap)[source]

Sets whether textures are to wrap (default true)

Return type:

None

Parameters:

wrap (bool) –

setPointSize(size)[source]

For point clouds, sets the point size.

Return type:

None

Parameters:

size (float) –

setCreaseAngle(creaseAngleRads)[source]

For meshes, sets the crease angle. Set to 0 to disable smoothing.

Return type:

None

Parameters:

creaseAngleRads (float) –

setSilhouette(radius, r=0, g=0, b=0, a=1)[source]

For meshes sets a silhouette radius and color. Set the radius to 0 to disable silhouette drawing.

Return type:

None

Parameters:
  • radius (float) –

  • r (float, optional) – default value 0

  • g (float, optional) – default value 0

  • b (float, optional) – default value 0

  • a (float, optional) – default value 1

drawGL(*args)[source]

Draws the given geometry with this appearance. NOTE: for best performance, an appearance should only be drawn with a single geometry. Otherwise, the OpenGL display lists will be completely recreated.

drawGL ()

drawGL (geom)

Return type:

None

Parameters:

geom (Geometry3D, optional) –

Note that the geometry’s current transform is NOT respected, and this only draws the geometry in its local transform.

drawWorldGL(geom)[source]

Draws the given geometry with this appearance. NOTE: for best performance, an appearance should only be drawn with a single geometry. Otherwise, the OpenGL display lists will be completely recreated.

Return type:

None

Parameters:

geom (Geometry3D) –

Differs from drawGL in that the geometry’s current transform is applied before drawing.

property world

world : int

property id

id : int

property appearancePtr

appearancePtr : p.void

setTexture1D(format, array)[source]

Sets a 1D texture.

Parameters:
  • format (str) –

    describes how the array is specified. Valid values include:

    • ’’: turn off texture mapping

    • ’rgb8’: unsigned byte RGB colors with red in the 1st

      column, green in the 2nd, blue in the 3rd.

    • ’bgr8’: unsigned byte RGB colors with blue in the 1st

      column, green in the 2nd, green in the 3rd

    • ’rgba8’: unsigned byte RGBA colors with red in the 1st

      column and alpha in the 4th

    • ’bgra8’: unsigned byte RGBA colors with blue in the 1st

      column and alpha in the 4th

    • ’l8’: unsigned byte grayscale colors, one channel

  • array (np.ndarray) –

    a 1D or 2D array, of size w or w x c where w is the width and c is the number of channels.

    Datatype is of type uint8, or for rgba8 / bgra8, can also be packed into uint32 elements. In this case, the pixel format is 0xaarrggbb or 0xaabbggrr, respectively.

setTexture2D(format, array)[source]

Sets a 2D texture.

Parameters:
  • format (str) –

    describes how the array is specified. Valid values include:

    • ’’: turn off texture mapping

    • ’rgb8’: unsigned byte RGB colors with red in the 1st

      column, green in the 2nd, blue in the 3rd.

    • ’bgr8’: unsigned byte RGB colors with blue in the 1st

      column, green in the 2nd, green in the 3rd

    • ’rgba8’: unsigned byte RGBA colors with red in the 1st

      column and alpha in the 4th

    • ’bgra8’: unsigned byte RGBA colors with blue in the 1st

      column and alpha in the 4th

    • ’l8’: unsigned byte grayscale colors, one channel

  • array (np.ndarray) –

    a 2D or 3D array, of size h x w or h x w x c where h is the height, w is the width, and c is the number of channels.

    Datatype is of type uint8, or for rgba8 / bgra8, can also be packed into uint32 elements. In this case, the pixel format is 0xaarrggbb or 0xaabbggrr, respectively.

setTexcoords(array)[source]

Sets texture coordinates for the mesh.

Parameters:

array (np.ndarray) – a 1D or 2D array, of size N or Nx2, where N is the number of vertices in the mesh.

class klampt.DistanceQuerySettings[source]

Bases: object

Configures the _ext distance queries of Geometry3D.

The calculated result satisfies \(Dcalc \leq D(1+relErr) + absErr\) unless \(D \geq upperBound\), in which case Dcalc=upperBound may be returned.

relErr

Allows a relative error in the reported distance to speed up computation. Default 0.

Type:

float, optional

absErr

Allows an absolute error in the reported distance to speed up computation. Default 0.

Type:

float, optional

upperBound

The calculation may branch if D exceeds this bound.

Type:

float, optional

C++ includes: geometry.h

Attributes:

thisown

The membership flag

relErr

relErr : double

absErr

absErr : double

upperBound

upperBound : double

property thisown

The membership flag

property relErr

relErr : double

property absErr

absErr : double

property upperBound

upperBound : double

class klampt.DistanceQueryResult[source]

Bases: object

The result from a “fancy” distance query of Geometry3D.

d

The calculated distance, with negative values indicating penetration. Can also be upperBound if the branch was hit.

Type:

float

hasClosestPoints

If true, the closest point information is given in cp0 and cp1, and elem1 and elem2

Type:

bool

hasGradients

f true, distance gradient information is given in grad0 and grad1.

Type:

bool

cp1, cp2

closest points on self vs other, both given in world coordinates

Type:

list of 3 floats, optional

grad1, grad2

the gradients of the objects’ signed distance fields at the closest points. Given in world coordinates.

I.e., to move object1 to touch object2, move it in direction grad1 by distance -d. Note that grad2 is always -grad1.

Type:

list of 3 floats, optional

elems1, elems2

for compound objects, these are the element indices corresponding to the closest points.

Type:

int

C++ includes: geometry.h

Attributes:

thisown

The membership flag

d

d : double

hasClosestPoints

hasClosestPoints : bool

hasGradients

hasGradients : bool

cp1

cp1 : std::vector<(double,std::allocator<(double)>)>

cp2

cp2 : std::vector<(double,std::allocator<(double)>)>

grad1

grad1 : std::vector<(double,std::allocator<(double)>)>

grad2

grad2 : std::vector<(double,std::allocator<(double)>)>

elem1

elem1 : int

elem2

elem2 : int

property thisown

The membership flag

property d

d : double

property hasClosestPoints

hasClosestPoints : bool

property hasGradients

hasGradients : bool

property cp1

cp1 : std::vector<(double,std::allocator<(double)>)>

property cp2

cp2 : std::vector<(double,std::allocator<(double)>)>

property grad1

grad1 : std::vector<(double,std::allocator<(double)>)>

property grad2

grad2 : std::vector<(double,std::allocator<(double)>)>

property elem1

elem1 : int

property elem2

elem2 : int

class klampt.ContactQueryResult[source]

Bases: object

The result from a contact query of Geometry3D. The number of contacts n is variable.

depths

penetration depths for each contact point. The depth is measured with respect to the padded geometry, and must be nonnegative. A value of 0 indicates that depth cannot be determined accurately.

Type:

list of n floats

points1, points2

contact points on self vs other, The top level list has n entries, and each entry is a 3-list expressed in world coordinates. If an object is padded, these points are on the surface of the padded geometry.

Type:

list of n lists of floats

normals

the outward-facing contact normal from this to other at each contact point, given in world coordinates. Each entry is a 3-list, and can be a unit vector, or [0,0,0] if the the normal cannot be computed properly.

Type:

list of n lists of floats

elems1, elems2

for compound objects, these are the element indices corresponding to each contact.

Type:

list of n ints

C++ includes: geometry.h

Attributes:

thisown

The membership flag

depths

depths : std::vector<(double,std::allocator<(double)>)>

points1

points1 : std::vector<(std::vector<(double,std::allocator<(double)>)>,std::allocator<(std::vector<(double,std::allocator<(double)>)>)>)>

points2

points2 : std::vector<(std::vector<(double,std::allocator<(double)>)>,std::allocator<(std::vector<(double,std::allocator<(double)>)>)>)>

normals

normals : std::vector<(std::vector<(double,std::allocator<(double)>)>,std::allocator<(std::vector<(double,std::allocator<(double)>)>)>)>

elems1

elems1 : std::vector<(int,std::allocator<(int)>)>

elems2

elems2 : std::vector<(int,std::allocator<(int)>)>

property thisown

The membership flag

property depths

depths : std::vector<(double,std::allocator<(double)>)>

property points1

points1 : std::vector<(std::vector<(double,std::allocator<(double)>)>,std::allocator<(std::vector<(double,std::allocator<(double)>)>)>)>

property points2

points2 : std::vector<(std::vector<(double,std::allocator<(double)>)>,std::allocator<(std::vector<(double,std::allocator<(double)>)>)>)>

property normals

normals : std::vector<(std::vector<(double,std::allocator<(double)>)>,std::allocator<(std::vector<(double,std::allocator<(double)>)>)>)>

property elems1

elems1 : std::vector<(int,std::allocator<(int)>)>

property elems2

elems2 : std::vector<(int,std::allocator<(int)>)>

class klampt.TriangleMesh[source]

Bases: object

A 3D indexed triangle mesh class.

vertices

a list of vertices, given as a flattened coordinate list [x1, y1, z1, x2, y2, …]

Type:

SWIG vector of floats

indices

a list of triangle vertices given as indices into the vertices list, i.e., [a1,b1,c2, a2,b2,c2, …]

Type:

SWIG vector of ints

Note: because the bindings are generated by SWIG, you can access the indices / vertices members via some automatically generated accessors / modifiers. In particular len(), append(), and indexing via [] are useful. Some other methods like resize() are also provided. However, you CANNOT set these items via assignment.

Examples:

m = TriangleMesh()
m.vertices.append(0)
m.vertices.append(0)
m.vertices.append(0)
print(len(m.vertices))  #prints 3
m.vertices = [0,0,0]   #this is an error
m.vertices += [1,2,3]   #this is also an error

To get all vertices as a numpy array:

verts = m.getVertices()

To get all indices as a numpy array:

inds = m.getIndices()

C++ includes: geometry.h

Attributes:

thisown

The membership flag

indices

indices : std::vector<(int,std::allocator<(int)>)>

vertices

vertices : std::vector<(double,std::allocator<(double)>)>

Methods:

getVertices()

Retrieves an array view of the vertices.

setVertices(np_array2)

Sets all vertices to the given nx3 Numpy array.

getIndices()

Retrieves an array view of the triangle indices.

setIndices(np_array2)

Sets all indices to the given mx3 Numpy array.

translate(t)

Translates all the vertices by v=v+t.

transform(R, t)

Transforms all the vertices by the rigid transform v=R*v+t.

property thisown

The membership flag

getVertices()[source]

Retrieves an array view of the vertices.

Returns: :rtype: None

ndarray: an nx3 Numpy array. Setting elements of this array will change the vertices.

setVertices(np_array2)[source]

Sets all vertices to the given nx3 Numpy array.

Return type:

None

Parameters:

np_array2 (2D Numpy array of floats) –

getIndices()[source]

Retrieves an array view of the triangle indices.

Returns: :rtype: None

ndarray: an mx3 Numpy array of int32 type. Setting elements of this array will change the indices.

setIndices(np_array2)[source]

Sets all indices to the given mx3 Numpy array.

Return type:

None

Parameters:

np_array2 (2D Numpy array of ints) –

translate(t)[source]

Translates all the vertices by v=v+t.

Return type:

None

Parameters:

t (list of 3 floats) –

transform(R, t)[source]

Transforms all the vertices by the rigid transform v=R*v+t.

Return type:

None

Parameters:
  • R (list of 9 floats (so3 element)) –

  • t (list of 3 floats) –

property indices

indices : std::vector<(int,std::allocator<(int)>)>

property vertices

vertices : std::vector<(double,std::allocator<(double)>)>

class klampt.PointCloud[source]

Bases: object

A 3D point cloud class.

vertices

a list of vertices, given as a list [x1, y1, z1, x2, y2, … zn]

Type:

SWIG vector of floats

properties

a list of vertex properties, given as a list [p11, p21, …, pk1, p12, p22, …, pk2, …, p1n, p2n, …, pkn] where each vertex has k properties. The name of each property is given by the propertyNames member.

Type:

SWIG vector of floats

propertyNames

a list of the names of each property

Type:

SWIG vector of strs

settings

a general property map .

Type:

SWIG map of strs to strs

Note

Because the bindings are generated by SWIG, you can access the members via some automatically generated accessors / modifiers. In particular len(), append(), and indexing via [] are useful. Some other methods like resize() and iterators are also provided. However, you CANNOT set these items via assignment, i.e., pc.vertices = [0,0,0] is not allowed.

Property names are usually lowercase but follow PCL naming convention, and often include:

  • normal_x, normal_y, normal_z: the outward normal

  • rgb, rgba: integer encoding of RGB (24 bit int, format 0xrrggbb) or RGBA color (32 bit int, format 0xaarrggbb)

  • opacity: opacity, in range [0,1]

  • c: opacity, in range [0,255]

  • r,g,b,a: color channels, in range [0,1]

  • u,v: texture coordinate

  • radius: treats the point cloud as a collection of balls

Settings are usually lowercase but follow PCL naming convention, and often include:

  • version: version of the PCL file, typically “0.7”

  • id: integer id

  • width: the width (in pixels) of a structured point cloud

  • height: the height (in pixels) of a structured point cloud

  • viewpoint: Camera position and orientation in the form ox oy oz qw qx qy qz, with (ox,oy,oz) the focal point and (qw,qx,qy,qz) the quaternion representation of the orientation (canonical representation, with X right, Y down, Z forward).

Examples:

pc = PointCloud()
pc.propertyNames.append('rgb')
#add 1 point with coordinates (0,0,0) and color #000000 (black)
pc.vertices.append(0)
pc.vertices.append(0)
pc.vertices.append(0)
pc.properties.append(0)
print(len(pc.vertices)) #prints 3
print(pc.numPoints())   #prints 1
#add another point with coordinates (1,2,3)
pc.addPoint([1,2,3])
#this prints 2
print(pc.numPoints() )
print(pc.getPoints())   #prints [[0,0,0],[1,2,3]]
#this prints 2, because there is 1 property category x 2 points
print(pc.properties.size())
assert pc.propertyNames.size() == pc.getAllProperties().shape[1]
#this prints 0; this is the default value added when addPoint is called
print(pc.getProperty(1,0) )

To get all points as an n x 3 numpy array:

points = pc.getPoints()

To get all properties as a n x k numpy array:

properties = pc.getAllProperties()

C++ includes: geometry.h

Attributes:

thisown

The membership flag

vertices

vertices : std::vector<(double,std::allocator<(double)>)>

propertyNames

propertyNames : std::vector<(std::string,std::allocator<(std::string)>)>

properties

properties : std::vector<(double,std::allocator<(double)>)>

settings

settings : std::map<(std::string,std::string,std::less<(std::string)>,std::allocator<(std::pair<(q(const).std::string,std::string)>)>)>

Methods:

numPoints()

Returns the number of points.

numProperties()

Returns the number of properties.

getPoints()

Returns a view of the points.

setPoints(np_array2)

Sets all the points to the given nx3 Numpy array.

setPointsAndProperties(np_array2)

Sets all the points and m properties from the given n x (3+m) array.

addPoint(p)

Adds a point.

setPoint(index, p)

Sets the position of the point at the given index to p.

getPoint(index)

Returns the position of the point at the given index.

addProperty(*args)

Adds a new property with name pname, and sets values for this property to the given length-n array.

setProperties(*args)

Sets property pindex of all points to the given length-n array.

setProperty(*args)

Sets the property named pname of point index to the given value.

getProperty(*args)

Returns the property named pname of point index.

getProperties(*args)

Returns property named pindex of all points as an array.

getAllProperties()

Returns all the properties of all points as an array view.

translate(t)

Translates all the points by v=v+t.

transform(R, t)

Transforms all the points by the rigid transform v=R*v+t.

join(pc)

Adds the given point cloud to this one.

setSetting(key, value)

Sets the given setting.

getSetting(key)

Returns the given setting.

setDepthImage_d(intrinsics, np_array2, ...)

Sets a structured point cloud from a depth image.

setDepthImage_f(intrinsics, np_depth2, ...)

Sets a structured point cloud from a depth image.

setDepthImage_s(intrinsics, np_depth2, ...)

Sets a structured point cloud from a depth image.

setRGBDImages_i_d(intrinsics, np_array2, ...)

Sets a structured point cloud from an RGBD (color,depth) image pair.

setRGBDImages_i_f(intrinsics, np_array2, ...)

Sets a structured point cloud from an RGBD (color,depth) image pair.

setRGBDImages_i_s(intrinsics, np_array2, ...)

Sets a structured point cloud from an RGBD (color,depth) image pair.

setRGBDImages_b_d(intrinsics, np_array3, ...)

Sets a structured point cloud from an RGBD (color,depth) image pair.

setRGBDImages_b_f(intrinsics, np_array3, ...)

Sets a structured point cloud from an RGBD (color,depth) image pair.

setRGBDImages_b_s(intrinsics, np_array3, ...)

Sets a structured point cloud from an RGBD (color,depth) image pair.

setDepthImage(intrinsics, depth[, depth_scale])

Sets a structured point cloud from a depth image.

setRGBDImages(intrinsics, color, depth[, ...])

Sets a structured point cloud from a color,depth image pair.

property thisown

The membership flag

numPoints()[source]

Returns the number of points.

Return type:

int

numProperties()[source]

Returns the number of properties.

Return type:

int

getPoints()[source]

Returns a view of the points.

Returns: :rtype: None

ndarray: an nx3 Numpy array. Setting elements of this array will change the points.

setPoints(np_array2)[source]

Sets all the points to the given nx3 Numpy array.

Return type:

None

Parameters:

np_array2 (2D Numpy array of floats) –

setPointsAndProperties(np_array2)[source]

Sets all the points and m properties from the given n x (3+m) array.

Return type:

None

Parameters:

np_array2 (2D Numpy array of floats) –

addPoint(p)[source]

Adds a point. Sets all its properties to 0.

Return type:

int

Parameters:

p (list of 3 floats) –

Returns the point’s index.

setPoint(index, p)[source]

Sets the position of the point at the given index to p.

Return type:

None

Parameters:
  • index (int) –

  • p (list of 3 floats) –

getPoint(index)[source]

Returns the position of the point at the given index.

Return type:

None

Parameters:

index (int) –

addProperty(*args)[source]

Adds a new property with name pname, and sets values for this property to the given length-n array.

addProperty (pname)

addProperty (pname,np_array)

Return type:

None

Parameters:
  • pname (str) –

  • np_array (1D Numpy array of floats, optional) –

setProperties(*args)[source]

Sets property pindex of all points to the given length-n array.

setProperties (np_array2)

setProperties (pindex,np_array)

Return type:

None

Parameters:
  • np_array2 (2D Numpy array of floats, optional) –

  • pindex (int, optional) –

  • np_array (1D Numpy array of floats, optional) –

setProperty(*args)[source]

Sets the property named pname of point index to the given value.

setProperty (index,pindex,value)

setProperty (index,pname,value)

Return type:

None

Parameters:
  • index (int) –

  • pindex (int, optional) –

  • value (float) –

  • pname (str, optional) –

getProperty(*args)[source]

Returns the property named pname of point index.

getProperty (index,pindex): float

getProperty (index,pname): float

Return type:

float

Parameters:
  • index (int) –

  • pindex (int, optional) –

  • pname (str, optional) –

Returns:

Return type:

float

getProperties(*args)[source]

Returns property named pindex of all points as an array.

getProperties (pindex)

getProperties (pname)

Return type:

None

Parameters:
  • pindex (int, optional) –

  • pname (str, optional) –

Returns:

an n-D Numpy array.

Return type:

ndarray

getAllProperties()[source]

Returns all the properties of all points as an array view.

Returns: :rtype: None

ndarray: an nxk Numpy array. Setting elements of this array will change the vertices.

translate(t)[source]

Translates all the points by v=v+t.

Return type:

None

Parameters:

t (list of 3 floats) –

transform(R, t)[source]

Transforms all the points by the rigid transform v=R*v+t.

Return type:

None

Parameters:
  • R (list of 9 floats (so3 element)) –

  • t (list of 3 floats) –

join(pc)[source]

Adds the given point cloud to this one. They must share the same properties or else an exception is raised.

Return type:

None

Parameters:

pc (PointCloud) –

setSetting(key, value)[source]

Sets the given setting.

Return type:

None

Parameters:
  • key (str) –

  • value (str) –

getSetting(key)[source]

Returns the given setting.

Return type:

str

Parameters:

key (str) –

setDepthImage_d(intrinsics, np_array2, depth_scale)[source]

Sets a structured point cloud from a depth image. [fx,fy,cx,cy] are the intrinsics parameters. The depth is given as a size hxw array, top to bottom.

Return type:

None

Parameters:
  • intrinsics (double [4]) –

  • np_array2 (2D Numpy array of floats) –

  • depth_scale (float) –

setDepthImage_f(intrinsics, np_depth2, depth_scale)[source]

Sets a structured point cloud from a depth image. [fx,fy,cx,cy] are the intrinsics parameters. The depth is given as a size hxw array, top to bottom.

Return type:

None

Parameters:
  • intrinsics (double [4]) –

  • np_depth2 (float *) –

  • depth_scale (float) –

setDepthImage_s(intrinsics, np_depth2, depth_scale)[source]

Sets a structured point cloud from a depth image. [fx,fy,cx,cy] are the intrinsics parameters. The depth is given as a size hxw array, top to bottom.

Return type:

None

Parameters:
  • intrinsics (double [4]) –

  • np_depth2 (unsigned short *) –

  • depth_scale (float) –

setRGBDImages_i_d(intrinsics, np_array2, np_depth2, depth_scale)[source]

Sets a structured point cloud from an RGBD (color,depth) image pair. [fx,fy,cx,cy] are the intrinsics parameters. The RGB colors are packed in 0xrrggbb order, size hxw, top to bottom.

Return type:

None

Parameters:
  • intrinsics (double [4]) –

  • np_array2 (unsigned int *) –

  • np_depth2 (double *) –

  • depth_scale (float) –

setRGBDImages_i_f(intrinsics, np_array2, np_depth2, depth_scale)[source]

Sets a structured point cloud from an RGBD (color,depth) image pair. [fx,fy,cx,cy] are the intrinsics parameters. The RGB colors are packed in 0xrrggbb order, size hxw, top to bottom.

Return type:

None

Parameters:
  • intrinsics (double [4]) –

  • np_array2 (unsigned int *) –

  • np_depth2 (float *) –

  • depth_scale (float) –

setRGBDImages_i_s(intrinsics, np_array2, np_depth2, depth_scale)[source]

Sets a structured point cloud from an RGBD (color,depth) image pair. [fx,fy,cx,cy] are the intrinsics parameters. The RGB colors are packed in 0xrrggbb order, size hxw, top to bottom.

Return type:

None

Parameters:
  • intrinsics (double [4]) –

  • np_array2 (unsigned int *) –

  • np_depth2 (unsigned short *) –

  • depth_scale (float) –

setRGBDImages_b_d(intrinsics, np_array3, np_depth2, depth_scale)[source]

Sets a structured point cloud from an RGBD (color,depth) image pair. [fx,fy,cx,cy] are the intrinsics parameters. The RGB colors are packed in 0xrrggbb order, size hxw, top to bottom.

Return type:

None

Parameters:
  • intrinsics (double [4]) –

  • np_array3 (unsigned char *) –

  • np_depth2 (double *) –

  • depth_scale (float) –

setRGBDImages_b_f(intrinsics, np_array3, np_depth2, depth_scale)[source]

Sets a structured point cloud from an RGBD (color,depth) image pair. [fx,fy,cx,cy] are the intrinsics parameters. The RGB colors are an h x w x 3 array, top to bottom.

Return type:

None

Parameters:
  • intrinsics (double [4]) –

  • np_array3 (unsigned char *) –

  • np_depth2 (float *) –

  • depth_scale (float) –

setRGBDImages_b_s(intrinsics, np_array3, np_depth2, depth_scale)[source]

Sets a structured point cloud from an RGBD (color,depth) image pair. [fx,fy,cx,cy] are the intrinsics parameters. The RGB colors are an h x w x 3 array, top to bottom.

Return type:

None

Parameters:
  • intrinsics (double [4]) –

  • np_array3 (unsigned char *) –

  • np_depth2 (unsigned short *) –

  • depth_scale (float) –

property vertices

vertices : std::vector<(double,std::allocator<(double)>)>

property propertyNames

propertyNames : std::vector<(std::string,std::allocator<(std::string)>)>

property properties

properties : std::vector<(double,std::allocator<(double)>)>

property settings

settings : std::map<(std::string,std::string,std::less<(std::string)>,std::allocator<(std::pair<(q(const).std::string,std::string)>)>)>

setDepthImage(intrinsics, depth, depth_scale=1.0)[source]

Sets a structured point cloud from a depth image.

Parameters:
  • intrinsics (4-list) – the intrinsics parameters [fx,fy,cx,cy].

  • depth (np.ndarray) – the depth values, of size h x w. Should have dtype float, np.float32, or np.uint16 for best performance.

  • depth_scale (float, optional) – converts depth image values to real depth units.

setRGBDImages(intrinsics, color, depth, depth_scale=1.0)[source]

Sets a structured point cloud from a color,depth image pair.

Parameters:
  • intrinsics (4-list) – the intrinsics parameters [fx,fy,cx,cy].

  • color (np.ndarray) – the color values, of size h x w or h x w x 3. In first case, must have dtype np.uint32 with r,g,b values packed in 0xrrggbb order. In second case, if dtype is np.uint8, min and max are [0,255]. If dtype is float or np.float32, min and max are [0,1].

  • depth (np.ndarray) – the depth values, of size h x w. Should have dtype float, np.float32, or np.uint16 for best performance.

  • depth_scale (float, optional) – converts depth image values to real depth units.

class klampt.GeometricPrimitive[source]

Bases: object

A geometric primitive. So far only points, spheres, segments, and AABBs can be constructed manually in the Python API.

type

Can be “Point”, “Sphere”, “Segment”, “Triangle”, “Polygon”, “AABB”, and “Box”. Semi-supported types include “Ellipsoid”, and “Cylinder”.

Type:

str

properties

a list of parameters defining the primitive. The interpretation is type-specific.

Type:

SWIG vector

C++ includes: geometry.h

Attributes:

thisown

The membership flag

type

type : std::string

properties

properties : std::vector<(double,std::allocator<(double)>)>

Methods:

setPoint(pt)

rtype:

None

setSphere(c, r)

rtype:

None

setSegment(a, b)

rtype:

None

setTriangle(a, b, c)

rtype:

None

setPolygon(verts)

rtype:

None

setAABB(bmin, bmax)

rtype:

None

setBox(ori, R, dims)

rtype:

None

loadString(str)

rtype:

bool

saveString()

rtype:

str

property thisown

The membership flag

setPoint(pt)[source]
Return type:

None

Parameters:

pt (list of 3 floats) –

setSphere(c, r)[source]
Return type:

None

Parameters:
  • c (list of 3 floats) –

  • r (float) –

setSegment(a, b)[source]
Return type:

None

Parameters:
  • a (list of 3 floats) –

  • b (list of 3 floats) –

setTriangle(a, b, c)[source]
Return type:

None

Parameters:
  • a (list of 3 floats) –

  • b (list of 3 floats) –

  • c (list of 3 floats) –

setPolygon(verts)[source]
Return type:

None

Parameters:

verts (list of floats) –

setAABB(bmin, bmax)[source]
Return type:

None

Parameters:
  • bmin (list of 3 floats) –

  • bmax (list of 3 floats) –

setBox(ori, R, dims)[source]
Return type:

None

Parameters:
  • ori (list of 3 floats) –

  • R (list of 9 floats (so3 element)) –

  • dims (list of 3 floats) –

loadString(str)[source]
Return type:

bool

Parameters:

str (str) –

saveString()[source]
Return type:

str

property type

type : std::string

property properties

properties : std::vector<(double,std::allocator<(double)>)>

class klampt.ConvexHull[source]

Bases: object

Stores a set of points to be set into a ConvexHull type. Note: These may not actually be the vertices of the convex hull; the actual convex hull may be computed internally for some datatypes.

points

a list of points, given as a flattened coordinate list [x1,y1,z1,x2,y2,…]

Type:

SWIG vector of floats

C++ includes: geometry.h

Attributes:

thisown

The membership flag

points

points : std::vector<(double,std::allocator<(double)>)>

Methods:

numPoints()

Returns the # of points.

getPoints()

Retrieves a view of the points.

setPoints(np_array2)

Sets all points to the given nx3 Numpy array.

addPoint(pt)

Adds a point.

getPoint(index)

Retrieves a point.

translate(t)

Translates all the vertices by v=v+t.

transform(R, t)

Transforms all the vertices by the rigid transform v=R*v+t.

property thisown

The membership flag

numPoints()[source]

Returns the # of points.

Return type:

int

getPoints()[source]

Retrieves a view of the points.

Returns: :rtype: None

ndarray: an nx3 Numpy array. Setting elements of this array will change the points.

setPoints(np_array2)[source]

Sets all points to the given nx3 Numpy array.

Return type:

None

Parameters:

np_array2 (2D Numpy array of floats) –

addPoint(pt)[source]

Adds a point.

Return type:

None

Parameters:

pt (list of 3 floats) –

getPoint(index)[source]

Retrieves a point.

Return type:

None

Parameters:

index (int) –

translate(t)[source]

Translates all the vertices by v=v+t.

Return type:

None

Parameters:

t (list of 3 floats) –

transform(R, t)[source]

Transforms all the vertices by the rigid transform v=R*v+t.

Return type:

None

Parameters:
  • R (list of 9 floats (so3 element)) –

  • t (list of 3 floats) –

property points

points : std::vector<(double,std::allocator<(double)>)>

class klampt.VolumeGrid[source]

Bases: object

An axis-aligned volumetric grid, typically a signed distance transform with > 0 indicating outside and < 0 indicating inside. Can also store an occupancy grid with 1 indicating inside and 0 indicating outside.

In general, values are associated with cells rather than vertices. So, cell (i,j,k) is associated with a single value, and has size (w,d,h) = ((bmax[0]-bmin[0])/dims[0], (bmax[1]-bmin[1])/dims[1], (bmax[2]-bmin[2])/dims[2]). It ranges over the box [w*i,w*(i+1)) x [d*j,d*(j+1)) x [h*k,h*(k+1)).

For SDFs and TSDFs which assume values at vertices, the values are specified at the centers of cells. I.e., at (w*(i+1/2),d*(j+1/2),h*(k+1/2)).

bbox

contains min and max bounds (xmin,ymin,zmin),(xmax,ymax,zmax)

Type:

SWIG vector of 6 doubles

dims

size of grid in each of 3 dimensions

Type:

SWIG vector of of 3 ints

values

contains a 3D array of dims[0]*dims[1]*dims[1] values.

The cell index (i,j,k) is flattened to i*dims[1]*dims[2] + j*dims[2] + k.

The array index i is associated to cell index (i/(dims[1]*dims[2]), (i/dims[2]) % dims[1], i%dims[2])

Type:

SWIG vector of doubles

C++ includes: geometry.h

Attributes:

thisown

The membership flag

bbox

bbox : std::vector<(double,std::allocator<(double)>)>

dims

dims : std::vector<(int,std::allocator<(int)>)>

values

Returns a 3D Numpy array view of the values.

Methods:

setBounds(bmin, bmax)

rtype:

None

resize(sx, sy, sz)

rtype:

None

set(*args)

Sets a specific element of a cell.

get(i, j, k)

Gets a specific element of a cell.

shift(dv)

rtype:

None

getValues()

Returns a 3D Numpy array view of the values.

setValues(np_array3)

Sets the values to a 3D numpy array.

property thisown

The membership flag

setBounds(bmin, bmax)[source]
Return type:

None

Parameters:
  • bmin (list of 3 floats) –

  • bmax (list of 3 floats) –

resize(sx, sy, sz)[source]
Return type:

None

Parameters:
  • sx (int) –

  • sy (int) –

  • sz (int) –

set(*args)[source]

Sets a specific element of a cell.

set (value)

set (i,j,k,value)

Return type:

None

Parameters:
  • value (float) –

  • i (int, optional) –

  • j (int, optional) –

  • k (int, optional) –

get(i, j, k)[source]

Gets a specific element of a cell.

Return type:

float

Parameters:
  • i (int) –

  • j (int) –

  • k (int) –

shift(dv)[source]
Return type:

None

Parameters:

dv (float) –

getValues()[source]

Returns a 3D Numpy array view of the values.

Return type:

None

setValues(np_array3)[source]

Sets the values to a 3D numpy array.

Return type:

None

Parameters:

np_array3 (3D Numpy array of floats) –

property bbox

bbox : std::vector<(double,std::allocator<(double)>)>

property dims

dims : std::vector<(int,std::allocator<(int)>)>

property values: None

Returns a 3D Numpy array view of the values.

class klampt.IKObjective(*args)[source]

Bases: object

A class defining an inverse kinematic target. Either a link on a robot can take on a fixed position/orientation in the world frame, or a relative position/orientation to another frame.

The positionScale and orientationScale attributes scale the solver’s residual vector. This affects whether the convergence tolerance is met, and also controls the emphasis on each objective / component when the objective cannot be reached. By default these are both 1.

C++ includes: robotik.h

With no arguments, constructs a blank IKObjective. Given an IKObjective, acts as a copy constructor.

__init__ (): IKObjective

__init__ (arg2): IKObjective

Parameters:

arg2 (IKObjective, optional) –

Attributes:

thisown

The membership flag

goal

goal : IKGoal

positionScale

positionScale : float

rotationScale

rotationScale : float

Methods:

copy()

Copy constructor.

link()

The index of the robot link that is constrained.

destLink()

The index of the destination link, or -1 if fixed to the world.

numPosDims()

Returns: The number of position dimensions constrained (0-3)

numRotDims()

Returns: The number of rotation dimensions constrained (0-3)

setFixedPoint(link, plocal, pworld)

Sets a fixed-point constraint.

setFixedPoints(link, plocals, pworlds)

Sets a multiple fixed-point constraint.

setFixedTransform(link, R, t)

Sets a fixed-transform constraint (R,t)

setRelativePoint(link1, link2, p1, p2)

Sets a fixed-point constraint relative to link2.

setRelativePoints(link1, link2, p1s, p2s)

Sets a multiple fixed-point constraint relative to link2.

setRelativeTransform(link, linkTgt, R, t)

Sets a fixed-transform constraint (R,t) relative to linkTgt.

setLinks(link[, link2])

Manual construction.

setFreePosition()

Deprecated: use setFreePosConstraint.

setFreePosConstraint()

Manual: Sets a free position constraint.

setFixedPosConstraint(tlocal, tworld)

Manual: Sets a fixed position constraint.

setPlanarPosConstraint(tlocal, nworld, oworld)

Manual: Sets a planar position constraint nworld^T T(link)*tlocal + oworld = 0.

setLinearPosConstraint(tlocal, sworld, dworld)

Manual: Sets a linear position constraint T(link)*tlocal = sworld + u*dworld for some real value u.

setFreeRotConstraint()

Manual: Sets a free rotation constraint.

setFixedRotConstraint(R)

Manual: Sets a fixed rotation constraint.

setAxialRotConstraint(alocal, aworld)

Manual: Sets an axial rotation constraint.

getPosition()

Returns the local and global position of the position constraint.

getPositionDirection()

For linear and planar constraints, returns the direction.

getRotation()

For fixed rotation constraints, returns the orientation.

getRotationAxis()

For axis rotation constraints, returns the local and global axes.

getTransform()

For fixed-transform constraints, returns the transform (R,t)

transform(R, t)

Tranforms the target position/rotation of this IK constraint by transform (R,t)

transformLocal(R, t)

Tranforms the local position/rotation of this IK constraint by transform (R,t)

matchDestination(R, t)

Sets the destination coordinates of this constraint to fit the given target transform.

closestMatch(R, t)

Gets the transform T that's closest to the transform (R,t) and that satisfies the IK goal's constraints.

sampleTransform()

Returns a transformation (R,t) from link relative to link2, sampled at random from the space of transforms that satisfies the objective obj.

loadString(str)

Loads the objective from a Klamp't-native formatted string.

saveString()

Saves the objective to a Klamp't-native formatted string.

property thisown

The membership flag

copy()[source]

Copy constructor.

Return type:

IKObjective

The index of the robot link that is constrained.

Return type:

int

The index of the destination link, or -1 if fixed to the world.

Return type:

int

numPosDims()[source]

Returns: The number of position dimensions constrained (0-3)

Return type:

int

numRotDims()[source]

Returns: The number of rotation dimensions constrained (0-3)

Return type:

int

setFixedPoint(link, plocal, pworld)[source]

Sets a fixed-point constraint.

Return type:

None

Parameters:
  • link (int) –

  • plocal (list of 3 floats) –

  • pworld (list of 3 floats) –

setFixedPoints(link, plocals, pworlds)[source]

Sets a multiple fixed-point constraint.

Return type:

None

Parameters:
  • link (int) –

  • plocals (object) –

  • pworlds (object) –

setFixedTransform(link, R, t)[source]

Sets a fixed-transform constraint (R,t)

Return type:

None

Parameters:
  • link (int) –

  • R (list of 9 floats (so3 element)) –

  • t (list of 3 floats) –

setRelativePoint(link1, link2, p1, p2)[source]

Sets a fixed-point constraint relative to link2.

Return type:

None

Parameters:
  • link1 (int) –

  • link2 (int) –

  • p1 (list of 3 floats) –

  • p2 (list of 3 floats) –

setRelativePoints(link1, link2, p1s, p2s)[source]

Sets a multiple fixed-point constraint relative to link2.

Return type:

None

Parameters:
  • link1 (int) –

  • link2 (int) –

  • p1s (object) –

  • p2s (object) –

setRelativeTransform(link, linkTgt, R, t)[source]

Sets a fixed-transform constraint (R,t) relative to linkTgt.

Return type:

None

Parameters:
  • link (int) –

  • linkTgt (int) –

  • R (list of 9 floats (so3 element)) –

  • t (list of 3 floats) –

Manual construction.

Return type:

None

Parameters:
  • link (int) –

  • link2 (int, optional) – default value -1

setFreePosition()[source]

Deprecated: use setFreePosConstraint.

Return type:

None

setFreePosConstraint()[source]

Manual: Sets a free position constraint.

Return type:

None

setFixedPosConstraint(tlocal, tworld)[source]

Manual: Sets a fixed position constraint.

Return type:

None

Parameters:
  • tlocal (list of 3 floats) –

  • tworld (list of 3 floats) –

setPlanarPosConstraint(tlocal, nworld, oworld)[source]

Manual: Sets a planar position constraint nworld^T T(link)*tlocal + oworld = 0.

Return type:

None

Parameters:
  • tlocal (list of 3 floats) –

  • nworld (list of 3 floats) –

  • oworld (float) –

setLinearPosConstraint(tlocal, sworld, dworld)[source]

Manual: Sets a linear position constraint T(link)*tlocal = sworld + u*dworld for some real value u.

Return type:

None

Parameters:
  • tlocal (list of 3 floats) –

  • sworld (list of 3 floats) –

  • dworld (list of 3 floats) –

setFreeRotConstraint()[source]

Manual: Sets a free rotation constraint.

Return type:

None

setFixedRotConstraint(R)[source]

Manual: Sets a fixed rotation constraint.

Return type:

None

Parameters:

R (list of 9 floats (so3 element)) –

setAxialRotConstraint(alocal, aworld)[source]

Manual: Sets an axial rotation constraint.

Return type:

None

Parameters:
  • alocal (list of 3 floats) –

  • aworld (list of 3 floats) –

getPosition()[source]

Returns the local and global position of the position constraint.

Return type:

None

getPositionDirection()[source]

For linear and planar constraints, returns the direction.

Return type:

None

getRotation()[source]

For fixed rotation constraints, returns the orientation.

Return type:

None

getRotationAxis()[source]

For axis rotation constraints, returns the local and global axes.

Return type:

None

getTransform()[source]

For fixed-transform constraints, returns the transform (R,t)

Return type:

None

transform(R, t)[source]

Tranforms the target position/rotation of this IK constraint by transform (R,t)

Return type:

None

Parameters:
  • R (list of 9 floats (so3 element)) –

  • t (list of 3 floats) –

transformLocal(R, t)[source]

Tranforms the local position/rotation of this IK constraint by transform (R,t)

Return type:

None

Parameters:
  • R (list of 9 floats (so3 element)) –

  • t (list of 3 floats) –

matchDestination(R, t)[source]

Sets the destination coordinates of this constraint to fit the given target transform. In other words, if (R,t) is the current link transform, this sets the destination position / orientation so that this objective has zero error. The current position/rotation constraint types are kept.

Return type:

None

Parameters:
  • R (list of 9 floats (so3 element)) –

  • t (list of 3 floats) –

closestMatch(R, t)[source]

Gets the transform T that’s closest to the transform (R,t) and that satisfies the IK goal’s constraints.

Return type:

None

Parameters:
  • R (list of 9 floats (so3 element)) –

  • t (list of 3 floats) –

sampleTransform()[source]

Returns a transformation (R,t) from link relative to link2, sampled at random from the space of transforms that satisfies the objective obj.

Return type:

None

loadString(str)[source]

Loads the objective from a Klamp’t-native formatted string. For a more readable but verbose format, try the JSON IO routines klampt.io.loader.to_json() / klampt.io.loader.from_json()

Return type:

bool

Parameters:

str (str) –

saveString()[source]

Saves the objective to a Klamp’t-native formatted string. For a more readable but verbose format, try the JSON IO routines klampt.io.loader.to_json() / klampt.io.loader.from_json()

Return type:

str

property goal

goal : IKGoal

property positionScale

positionScale : float

property rotationScale

rotationScale : float

class klampt.IKSolver(*args)[source]

Bases: object

An inverse kinematics solver based on the Newton-Raphson technique.

Typical calling pattern is:

s = IKSolver(robot)
s.add(objective1)
s.add(objective2)
s.setMaxIters(100)
s.setTolerance(1e-4)
res = s.solve()
if res:
    print("IK solution:",robot.getConfig(),"found in",
        s.lastSolveIters(),"iterations, residual",s.getResidual())
else:
    print("IK failed:",robot.getConfig(),"found in",
        s.lastSolveIters(),"iterations, residual",s.getResidual())

C++ includes: robotik.h

Initializes an IK solver. Given a RobotModel, an empty solver is created. Given an IK solver, acts as a copy constructor.

__init__ (robot): IKSolver

__init__ (solver): IKSolver

Parameters:

Attributes:

thisown

The membership flag

robot

robot : RobotModel

objectives

objectives : std::vector<(IKObjective,std::allocator<(IKObjective)>)>

secondary_objectives

secondary_objectives : std::vector<(IKObjective,std::allocator<(IKObjective)>)>

tol

tol : double

maxIters

maxIters : int

activeDofs

activeDofs : std::vector<(int,std::allocator<(int)>)>

useJointLimits

useJointLimits : bool

qmin

qmin : std::vector<(double,std::allocator<(double)>)>

qmax

qmax : std::vector<(double,std::allocator<(double)>)>

biasConfig

biasConfig : std::vector<(double,std::allocator<(double)>)>

lastIters

lastIters : int

Methods:

copy()

Copy constructor.

add(objective)

Adds a new simultaneous objective.

set(i, objective)

Assigns an existing objective added by add.

addSecondary(objective)

Adds a new objective to the secondary objectives list.

setSecondary(i, objective)

Assigns an existing objective added by addsecondary.

clear()

Clears objectives.

setMaxIters(iters)

Sets the max # of iterations (default 100)

getMaxIters()

Returns the max # of iterations.

setTolerance(res)

Sets the constraint solve tolerance (default 1e-3)

getTolerance()

Returns the constraint solve tolerance.

setActiveDofs(active)

Sets the active degrees of freedom.

getActiveDofs()

Returns the active degrees of freedom.

setJointLimits(qmin, qmax)

Sets limits on the robot's configuration.

getJointLimits()

Returns the limits on the robot's configuration (by default this is the robot's joint limits.

setBiasConfig(biasConfig)

Biases the solver to approach a given configuration.

getBiasConfig()

Returns the solvers' bias configuration.

isSolved()

Returns True if the current configuration residual is less than tol.

getResidual()

Returns the vector describing the error of the objective at the current configuration.

getJacobian()

Computes the matrix describing the instantaneous derivative of the objective with respect to the active Dofs.

getSecondaryResidual()

Returns the vector describing the error of the secondary objective at the current configuration.

solve()

Tries to find a configuration that satifies all simultaneous objectives up to the desired tolerance.

minimize(*args)

Tries to find a configuration that satifies all simultaneous objectives up to the desired tolerance or minimizes the residual.

lastSolveIters()

Returns the number of Newton-Raphson iterations used in the last solve() call or the number of Quasi-Newton iterations used in the last minimize() call.

sampleInitial()

Samples an initial random configuration.

property thisown

The membership flag

copy()[source]

Copy constructor.

Return type:

IKSolver

add(objective)[source]

Adds a new simultaneous objective.

Return type:

None

Parameters:

objective (IKObjective) –

set(i, objective)[source]

Assigns an existing objective added by add.

Return type:

None

Parameters:
addSecondary(objective)[source]

Adds a new objective to the secondary objectives list.

Return type:

None

Parameters:

objective (IKObjective) –

setSecondary(i, objective)[source]

Assigns an existing objective added by addsecondary.

Return type:

None

Parameters:
clear()[source]

Clears objectives.

Return type:

None

setMaxIters(iters)[source]

Sets the max # of iterations (default 100)

Return type:

None

Parameters:

iters (int) –

getMaxIters()[source]

Returns the max # of iterations.

Return type:

int

setTolerance(res)[source]

Sets the constraint solve tolerance (default 1e-3)

Return type:

None

Parameters:

res (float) –

getTolerance()[source]

Returns the constraint solve tolerance.

Return type:

float

setActiveDofs(active)[source]

Sets the active degrees of freedom.

Return type:

None

Parameters:

active (list of int) –

getActiveDofs()[source]

Returns the active degrees of freedom.

Return type:

None

setJointLimits(qmin, qmax)[source]

Sets limits on the robot’s configuration. If empty, this turns off joint limits.

Return type:

None

Parameters:
  • qmin (list of floats) –

  • qmax (list of floats) –

getJointLimits()[source]

Returns the limits on the robot’s configuration (by default this is the robot’s joint limits.

Return type:

None

setBiasConfig(biasConfig)[source]

Biases the solver to approach a given configuration. Setting an empty vector clears the bias term.

Return type:

None

Parameters:

biasConfig (list of floats) –

getBiasConfig()[source]

Returns the solvers’ bias configuration.

Return type:

None

isSolved()[source]

Returns True if the current configuration residual is less than tol.

Return type:

bool

getResidual()[source]

Returns the vector describing the error of the objective at the current configuration.

Return type:

None

getJacobian()[source]

Computes the matrix describing the instantaneous derivative of the objective with respect to the active Dofs.

Return type:

None

getSecondaryResidual()[source]

Returns the vector describing the error of the secondary objective at the current configuration.

Return type:

None

solve()[source]

Tries to find a configuration that satifies all simultaneous objectives up to the desired tolerance.

All of the primary and the secondary objectives are solved simultaneously.

Returns: :rtype: bool

True if x converged.

minimize(*args)[source]

Tries to find a configuration that satifies all simultaneous objectives up to the desired tolerance or minimizes the residual.

minimize (): bool

minimize (secondary_objective,secondary_objective_grad): bool

Return type:

bool

Parameters:
  • secondary_objective (object, optional) –

  • secondary_objective_grad (object, optional) –

The relation to :func:solve is that solve uses a root-finding method that tries indirectly to minimize the residual, but it may stall out when the objectives are infeasible.

If secondary objectives are specified, this tries to minimize them once the primary objectives are satisfied, i.e., it will minimize on the solution manifold of the primary constraints.

There are two flavors of secondary objectives. If no arguments are given, then any constraints added via addSecondary will have their residuals minimized.

If the user provides a pair of functions (f,grad), then a custom objective is specified. Here, f(q) is the secondary objective to minimize and grad(q) its gradient. This will override the secondary objectives added via addSecondary. Specifically, q is a function of all robot DOFs, and grad(q) should return a list or tuple of length len(q)`.

Note

The minimization will occur only over the current active DOFs, which will include default active DOFs for secondary objectives.

Arguments: secondary_objective (callable): a function f(q)->float that should be minimized. secondary_objective_grad (callable): a function grad(q)->`sequence of length `len(q) giving the gradient of f at q.

Returns:

True if x converged on the primary objectives.

lastSolveIters()[source]

Returns the number of Newton-Raphson iterations used in the last solve() call or the number of Quasi-Newton iterations used in the last minimize() call.

Return type:

int

sampleInitial()[source]

Samples an initial random configuration. More initial configurations can be sampled in case the prior configs lead to local minima.

Return type:

None

property robot

robot : RobotModel

property objectives

objectives : std::vector<(IKObjective,std::allocator<(IKObjective)>)>

property secondary_objectives

secondary_objectives : std::vector<(IKObjective,std::allocator<(IKObjective)>)>

property tol

tol : double

property maxIters

maxIters : int

property activeDofs

activeDofs : std::vector<(int,std::allocator<(int)>)>

property useJointLimits

useJointLimits : bool

property qmin

qmin : std::vector<(double,std::allocator<(double)>)>

property qmax

qmax : std::vector<(double,std::allocator<(double)>)>

property biasConfig

biasConfig : std::vector<(double,std::allocator<(double)>)>

property lastIters

lastIters : int

class klampt.GeneralizedIKObjective(*args)[source]

Bases: object

An inverse kinematics target for matching points between two robots and/or objects.

The objects are chosen upon construction, so the following are valid:

  • GeneralizedIKObjective(a) is an objective for object a to be constrained relative to the environment.

  • GeneralizedIKObjective(a,b) is an objective for object a to be constrained relative to b. Here a and b can be links on any robot or rigid objects.

Once constructed, call setPoint, setPoints, or setTransform to specify the nature of the constraint.

C++ includes: robotik.h

__init__ (obj): GeneralizedIKObjective

__init__ (link): GeneralizedIKObjective

__init__ (link,link2): GeneralizedIKObjective

__init__ (link,obj2): GeneralizedIKObjective

__init__ (obj,link2): GeneralizedIKObjective

__init__ (obj,obj2): GeneralizedIKObjective

Parameters:

Attributes:

thisown

The membership flag

link1

link1 : RobotModelLink

link2

link2 : RobotModelLink

obj1

obj1 : RigidObjectModel

obj2

obj2 : RigidObjectModel

isObj1

isObj1 : bool

isObj2

isObj2 : bool

goal

goal : IKGoal

Methods:

setPoint(p1, p2)

rtype:

None

setPoints(p1s, p2s)

rtype:

None

setTransform(R, t)

rtype:

None

sampleTransform()

Returns a transformation (R,t) from link relative to link2, sampled at random from the space of transforms that satisfies the objective obj.

property thisown

The membership flag

setPoint(p1, p2)[source]
Return type:

None

Parameters:
  • p1 (list of 3 floats) –

  • p2 (list of 3 floats) –

setPoints(p1s, p2s)[source]
Return type:

None

Parameters:
  • p1s (object) –

  • p2s (object) –

setTransform(R, t)[source]
Return type:

None

Parameters:
  • R (list of 9 floats (so3 element)) –

  • t (list of 3 floats) –

sampleTransform()[source]

Returns a transformation (R,t) from link relative to link2, sampled at random from the space of transforms that satisfies the objective obj.

Return type:

None

property link1

link1 : RobotModelLink

property link2

link2 : RobotModelLink

property obj1

obj1 : RigidObjectModel

property obj2

obj2 : RigidObjectModel

property isObj1

isObj1 : bool

property isObj2

isObj2 : bool

property goal

goal : IKGoal

class klampt.GeneralizedIKSolver(world)[source]

Bases: object

An inverse kinematics solver between multiple robots and/or objects. NOT IMPLEMENTED YET.

C++ includes: robotik.h

Parameters:

world (WorldModel) –

Attributes:

thisown

The membership flag

world

world : WorldModel

objectives

objectives : std::vector<(GeneralizedIKObjective,std::allocator<(GeneralizedIKObjective)>)>

tol

tol : double

maxIters

maxIters : int

useJointLimits

useJointLimits : bool

Methods:

add(objective)

Adds a new simultaneous objective.

setMaxIters(iters)

Sets the max # of iterations (default 100)

setTolerance(res)

Sets the constraint solve tolerance (default 1e-3)

getResidual()

Returns a vector describing the error of the objective.

getJacobian()

Returns a matrix describing the instantaneous derivative of the objective with respect to the active parameters.

solve()

Tries to find a configuration that satifies all simultaneous objectives up to the desired tolerance.

sampleInitial()

Samples an initial random configuration.

property thisown

The membership flag

add(objective)[source]

Adds a new simultaneous objective.

Return type:

None

Parameters:

objective (GeneralizedIKObjective) –

setMaxIters(iters)[source]

Sets the max # of iterations (default 100)

Return type:

None

Parameters:

iters (int) –

setTolerance(res)[source]

Sets the constraint solve tolerance (default 1e-3)

Return type:

None

Parameters:

res (float) –

getResidual()[source]

Returns a vector describing the error of the objective.

Return type:

None

getJacobian()[source]

Returns a matrix describing the instantaneous derivative of the objective with respect to the active parameters.

Return type:

None

solve()[source]

Tries to find a configuration that satifies all simultaneous objectives up to the desired tolerance.

Returns: res,iters (pair of bool, int): res indicates whether x converged, and iters is the number of iterations used.

Return type:

object

sampleInitial()[source]

Samples an initial random configuration.

Return type:

None

property world

world : WorldModel

property objectives

objectives : std::vector<(GeneralizedIKObjective,std::allocator<(GeneralizedIKObjective)>)>

property tol

tol : double

property maxIters

maxIters : int

property useJointLimits

useJointLimits : bool

klampt.robotsim.set_random_seed(seed)[source]

Sets the random seed used by the motion planner.

Return type:

None

Parameters:

seed (int) –

klampt.robotsim.com_equilibrium(*args)[source]

Tests whether the given COM com is stable for the given contacts and the given external force fext.

com_equilibrium (contacts,m,n,fext,com): object

com_equilibrium (contactPositions,frictionCones,fext,com): object

The 2-argument version is a “fancy” version that allows more control over the constraint planes.

Args: contacts (list of 7-float lists or tuples): the list of contacts, each specified as a 7-list or tuple [x,y,z,nx,ny,nz,k], with: :rtype: object

  • (x,y,z): the contact position

  • (nx,ny,nz): the contact normal

  • k: the coefficient of friction (>= 0)

contactPositions (list of 3-float lists or tuples): the list of contact point positions. frictionCones (list of lists): Each item of this list specifies linear inequalities that must be met of the force at the corresponding contact point. The item must have length k*4 where k is an integer, and each inequality gives the entries (ax,ay,az,b) of a constraint ax*fx+ay*fy+az*fz <= b that limits the contact force (fx,fy,fz) at the i’th contact. Each of the k 4-tuples is laid out sequentially per-contact. fext (3-tuple or list): the external force vector. com (3-tuple or list, or None): the center of mass coordinates. If None, assumes that you want to test whether ANY COM may be in equilibrium for the given contacts.

Returns:

if com is given, and there are feasible equilibrium forces, this returns a list of 3 tuples giving equilibrium forces at each of the contacts. None is returned if no such forces exist.

If com = None, the result is True or False.

Return type:

bool, None, or list

klampt.robotsim.com_equilibrium_2d(*args)[source]

Tests whether the given COM com is stable for the given contacts and the given external force fext.

com_equilibrium_2d (contacts,m,n,fext,com): object

com_equilibrium_2d (contactPositions,frictionCones,fext,com): object

The 2-argument version is a “fancy” version that allows more control over the constraint planes.

Args: :rtype: object

contacts (list of 4-float lists or tuples): the list of contacts, each

specified as a 4-list or tuple [x,y,theta,k], with:

  • (x,y,z): the contact position

  • theta: is the normal angle (in radians, CCW to the x axis)

  • k: the coefficient of friction (>= 0)

contactPositions (list of 2-float lists or tuples): the list of contact

point positions.

frictionCones (list of lists): The i’th element in this list has length

k*3 (for some integer k), and gives the contact force constraints (ax,ay,b) where ax*fx+ay*fy <= b limits the contact force (fx,fy) at the i’th contact. Each of the k 3-tuples is laid out sequentially per-contact.

fext (2-tuple or list): the external force vector. com (2-tuple or list, or None): the center of mass coordinates. If None,

assumes that you want to test whether ANY COM may be in equilibrium for the given contacts.

Returns:

if com is given, and there are feasible equilibrium forces, this returns a list of 2-tuples giving equilibrium forces at each of the contacts. None is returned if no such forces exist.

If com = None, the result is True or False.

Return type:

bool, None, or list

klampt.robotsim.equilibrium_torques(*args)[source]

Solves for the torques / forces that keep the robot balanced against gravity.

equilibrium_torques (robot,contacts,m,n,links,fext,norm=0): object

equilibrium_torques (robot,contacts,m,n,links,fext,internalTorques,norm=0): object

The problem being solved is

\(min_{t,f_1,...,f_N} \|t\|_p\)

\(s.t. t_{int} + G(q) = t + sum_{i=1}^N J_i(q)^T f_i\)

\(|t| \leq t_{max}\)

\(f_i \in FC_i\)

Args: :rtype: object

robot (RobotModel): the robot, posed in its current configuration contacts (ndarray): an N x 7 array of contact points, each given as 7-lists

[x,y,z,nx,ny,nz,kFriction]

links (list of N ints): a list of the links on which those contact points

lie

fext (list of 3 floats): the external force (e.g., gravity) norm (double): the torque norm to minimize.

  • If 0, minimizes the l-infinity norm (default)

  • If 1, minimizes the l-1 norm.

  • If 2, minimizes the l-2 norm (experimental, may not get good results).

internalTorques (list of robot.numLinks() floats, optional): allows you to

solve for dynamic situations, e.g., with coriolis forces taken into account. These are added to the RHS of the torque balance equation. If not given, t_int is assumed to be zero.

To use dynamics, set the robot’s joint velocities dq, calculate then calculate the torques via robot.torquesFromAccel(ddq), and pass the result into internalTorques.

Returns:

a pair (torque,force) if a solution exists, giving valid joint torques t and frictional contact forces (f1,…,fn).

None is returned if no solution exists.

Return type:

pair of lists, optional

klampt.robotsim.force_closure(*args)[source]

Returns true if the list of contact points has force closure.

force_closure (contacts,m,n): bool

force_closure (contactPositions,frictionCones): bool

Return type:

bool

Returns:

Return type:

bool

In the 1-argument version, each contact point is specified by a list of 7 floats, [x,y,z,nx,ny,nz,k] where (x,y,z) is the position, (nx,ny,nz) is the normal, and k is the coefficient of friction.

The 2-argument version is a “fancy” version that allows more control over the constraint planes.

Parameters:
  • contacts (list of 7-float lists or tuples) –

    the list of contacts, each specified as a 7-list or tuple [x,y,z,nx,ny,nz,k], with:

    • (x,y,z): the contact position

    • (nx,ny,nz): the contact normal

    • k: the coefficient of friction (>= 0)

  • contactPositions (list of 3-float lists or tuples) – the list of contact point positions.

  • frictionCones (list of lists) – Each item of this list specifies linear inequalities that must be met of the force at the corresponding contact point. The item must have length k*4 where k is an integer, and each inequality gives the entries (ax,ay,az,b) of a constraint ax*fx+ay*fy+az*fz <= b that limits the contact force (fx,fy,fz) at the i’th contact. Each of the k 4-tuples is laid out sequentially per-contact.

klampt.robotsim.force_closure_2d(*args)[source]

Returns true if the list of 2D contact points has force closure.

force_closure_2d (contacts,m,n): bool

force_closure_2d (contactPositions,frictionCones): bool

Return type:

bool

Returns:

Return type:

bool

In the 1-argument version, each contact point is given by a list of 4 floats, [x,y,theta,k] where (x,y) is the position, theta is the normal angle, and k is the coefficient of friction

The 2-argument version is a “fancy” version that allows more control over the constraint planes.

Parameters:
  • contacts (list of 4-float lists or tuples) –

    the list of contacts, each specified as a 4-list or tuple [x,y,theta,k], with:

    • (x,y): the contact position

    • theta: is the normal angle (in radians, CCW to the x axis)

    • k: the coefficient of friction (>= 0)

  • contactPositions (list of 2-float lists or tuples) – the list of contact point positions.

  • frictionCones (list of lists) – The i’th element in this list has length k*3 (for some integer k), and gives the contact force constraints (ax,ay,b) where ax*fx+ay*fy <= b limits the contact force (fx,fy) at the i’th contact. Each of the k 3-tuples is laid out sequentially per-contact.

klampt.robotsim.set_friction_cone_approximation_edges(numEdges)[source]

Globally sets the number of edges used in the friction cone approximation. The default value is 4.

Return type:

None

Parameters:

numEdges (int) –

klampt.robotsim.support_polygon(*args)[source]

Calculates the support polygon for a given set of contacts and a downward external force (0,0,-g).

support_polygon (contacts,m,n): object

support_polygon (contactPositions,frictionCones): object

In the 1-argument version, a contact point is given by a list of 7 floats, [x,y,z,nx,ny,nz,k] as usual. The 2-argument version is a “fancy” version that allows more control over the constraint planes.

Args: :rtype: object

contacts (list of 7-float lists or tuples): the list of contacts, each

specified as a 7-list or tuple [x,y,z,nx,ny,nz,k], with:

  • (x,y,z): the contact position

  • (nx,ny,nz): the contact normal

  • k: the coefficient of friction (>= 0)

contactPositions (list of 3-float lists or tuples): the list of contact

point positions.

frictionCones (list of lists): Each item of this list specifies linear

inequalities that must be met of the force at the corresponding contact point. The item must have length k*4 where k is an integer, and each inequality gives the entries (ax,ay,az,b) of a constraint ax*fx+ay*fy+az*fz <= b that limits the contact force (fx,fy,fz) at the i’th contact. Each of the k 4-tuples is laid out sequentially per-contact.

Returns:

The sorted plane boundaries of the support polygon. The format of a plane is (nx,ny,ofs) where (nx,ny) are the outward facing normals, and ofs is the offset from 0. In other words to test stability of a com with x-y coordinates [x,y], you can test whether dot([nx,ny],[x,y]) <= ofs for all planes.

Hint: with numpy, you can do:

Ab = np.array(supportPolygon(args))
A=Ab[:,0:2]
b=Ab[:,2]
myComEquilibrium = lambda x: np.all(np.dot(A,x)<=b)

Return type:

list of 3-tuples

klampt.robotsim.support_polygon_2d(*args)[source]

Calculates the support polygon (interval) for a given set of contacts and a downward external force (0,-g).

support_polygon_2d (contacts,m,n): object

support_polygon_2d (contacts,frictionCones): object

The 2-argument version is a “fancy” version that allows more control over the constraint planes.

Args: :rtype: object

contacts (list of 4-float lists or tuples): the list of contacts, each

specified as a 4-list or tuple [x,y,theta,k], with:

  • (x,y,z): the contact position

  • theta: is the normal angle (in radians, CCW to the x axis)

  • k: the coefficient of friction (>= 0)

contactPositions (list of 2-float lists or tuples): the list of contact

point positions.

frictionCones (list of lists): The i’th element in this list has length

k*3 (for some integer k), and gives the contact force constraints (ax,ay,b) where ax*fx+ay*fy <= b limits the contact force (fx,fy) at the i’th contact. Each of the k 3-tuples is laid out sequentially per-contact.

Returns:

gives the min/max extents of the support polygon. If the support interval is empty, (inf,inf) is returned.

Return type:

2-tuple

class klampt.robotsim.Widget[source]
class klampt.robotsim.WidgetSet[source]
class klampt.robotsim.ObjectPoser(object)[source]
Parameters:

object (RigidObjectModel) –

class klampt.robotsim.RobotPoser(robot)[source]
Parameters:

robot (RobotModel) –

class klampt.robotsim.PointPoser[source]
class klampt.robotsim.TransformPoser[source]
class klampt.robotsim.Viewport[source]