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.
|
The main world class, containing robots, rigid objects, and static environment geometry. |
A model of a dynamic and kinematic robot. |
|
A reference to a link of a RobotModel. |
|
|
A reference to a driver of a RobotModel. |
|
A sensor on a simulated robot. |
A rigid movable object. |
|
Static environment geometry. |
|
|
Stores mass information for a rigid body or robot link. |
Stores contact parameters for an entity. |
|
|
Sets the random seed used by the RobotModel.randomizeConfig() method and sampling-based motion planners. |
|
destroys internal data structures |
Modeling geometries
Imported into the main klampt
package.
|
The three-D geometry container used throughout Klampt. |
|
Geometry appearance information. |
|
A geometric primitive. |
|
A 3D indexed triangle mesh class. |
|
A 3D point cloud class. |
|
An axis-aligned volumetric grid representing a signed distance transform with > 0 indicating outside and < 0 indicating inside. |
|
An occupancy grid with 1 indicating inside and 0 indicating outside. |
|
Stores a set of points to be set into a ConvexHull type. |
Configures the _ext distance queries of |
|
The result from a "fancy" distance query of |
|
The result from a contact query of |
Inverse kinematics
Imported into the main klampt
package.
|
A class defining an inverse kinematic target. |
|
An inverse kinematics solver based on the Newton-Raphson technique. |
|
An inverse kinematics target for matching points between two robots and/or objects. |
|
An inverse kinematics solver between multiple robots and/or objects. |
Simulation
Imported into the main klampt
package.
|
A dynamics simulator for a WorldModel. |
|
A reference to a rigid body inside a Simulator (either a RigidObjectModel, TerrainModel, or a link of a RobotModel). |
|
An interface to ODE's hinge and slider joints. |
A controller for a simulated robot. |
Equilibrium testing
See also the aliases in the klampt.model.contact module.
|
Tests whether the given COM com is stable for the given contacts and the given external force fext. |
|
Tests whether the given COM com is stable for the given contacts and the given external force fext. |
|
Solves for the torques / forces that keep the robot balanced against gravity. |
|
Returns true if the list of contact points has force closure. |
|
Returns true if the list of 2D contact points has force closure. |
|
Globally sets the number of edges used in the friction cone approximation. |
|
Calculates the support polygon for a given set of contacts and a downward external force (0,0,-g). |
|
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
|
Subscribes a Geometry3D to a stream. |
|
Unsubscribes from a stream previously subscribed to via |
|
Does some processing on stream subscriptions. |
|
Waits up to timeout seconds for an update on the given stream. |
|
Exports the WorldModel to a JSON string ready for use in Three.js. |
|
Exports the WorldModel to a JSON string ready for use in Three.js. |
Visualization
Viewport
is used to model cameras (SensorModel
) and heightmaps ((Heightmap
)).
Widgets and posers are used in GLWidgetPlugin
.
|
A class that represents an idealized pinhole camera. |
|
Args: |
Args: |
|
|
Args: |
|
Args: |
Args: |
|
Args: |
Module contents
Classes:
|
The main world class, containing robots, rigid objects, and static environment geometry. |
A model of a dynamic and kinematic robot. |
|
A reference to a link of a RobotModel. |
|
A rigid movable object. |
|
Static environment geometry. |
|
|
A sensor on a simulated robot. |
|
Stores mass information for a rigid body or robot link. |
Stores contact parameters for an entity. |
|
A controller for a simulated robot. |
|
|
A reference to a rigid body inside a Simulator (either a RigidObjectModel, TerrainModel, or a link of a RobotModel). |
|
An interface to ODE's hinge and slider joints. |
|
A dynamics simulator for a WorldModel. |
|
The three-D geometry container used throughout Klampt. |
|
Geometry appearance information. |
Configures the _ext distance queries of |
|
The result from a "fancy" distance query of |
|
The result from a contact query of |
|
|
A 3D indexed triangle mesh class. |
|
A 3D point cloud class. |
|
A geometric primitive. |
|
Stores a set of points to be set into a ConvexHull type. |
|
An axis-aligned volumetric grid representing a signed distance transform with > 0 indicating outside and < 0 indicating inside. |
|
An occupancy grid with 1 indicating inside and 0 indicating outside. |
|
A height (elevation) map or a depth map. |
|
A class defining an inverse kinematic target. |
|
An inverse kinematics solver based on the Newton-Raphson technique. |
|
An inverse kinematics target for matching points between two robots and/or objects. |
|
An inverse kinematics solver between multiple robots and/or objects. |
- class klampt.WorldModel(*args)[source]
Bases:
object
The main world class, containing robots, rigid objects, and static environment geometry.
Args:
- - robots
a list of RobotModel instances
- - rigidObjects
a list of RigidObjectModel instances
- - terrains
a list of TerrainModel instances
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().
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)
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.
Returns the number of robots.
numRobotLinks
(robot)Returns the number of links on the given robot.
Returns the number of rigid objects.
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.
Returns a list of all robots in the world.
Returns a dictionary mapping robot names to RobotModel instances.
Returns a list of all rigid objects in the world.
Returns a dictionary mapping rigid object names to RigidObjectModel instances.
Returns a list of all rigid objects in the world.
Returns a dictionary mapping rigid object names to RigidObjectModel instances.
Attributes:
int
Returns a list of all robots in the world.
Returns a dictionary mapping robot names to RobotModel instances.
Returns a list of all rigid objects in the world.
Returns a dictionary mapping rigid object names to RigidObjectModel instances.
Returns a list of all rigid objects in the world.
Returns a dictionary mapping rigid object names to RigidObjectModel instances.
- copy()[source]
Creates a copy of the world model. Note that geometries and appearances are shared, so this is very quick.
- Return type:
- Return type:
- readFile(fn)[source]
Reads from a world XML file.
- Return type:
bool
- Parameters:
fn (str)
- Returns:
True if successful, False if failed.
- saveFile(fn, elementDir=None)[source]
Saves to a world XML file. Elements in the world will be saved to a folder.
- Return type:
bool
- Parameters:
fn (str)
elementDir (str, optional) – default value None
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)
- numRobotLinks(robot)[source]
Returns the number of links on the given robot.
- Return type:
int
- Parameters:
robot (int)
- robot(*args)[source]
Returns a RobotModel in the world by index or name.
robot (index):
RobotModel
robot (name):
RobotModel
- Return type:
- Parameters:
index (int, optional)
name (str, optional)
- Return type:
- robotLink(*args)[source]
Returns a RobotModelLink of some RobotModel in the world by index or name.
robotLink (robot,index):
RobotModelLink
robotLink (robot,name):
RobotModelLink
- Return type:
- Parameters:
robot (int or str)
index (int, optional)
name (str, optional)
- Return type:
- rigidObject(*args)[source]
Returns a RigidObjectModel in the world by index or name.
rigidObject (index):
RigidObjectModel
rigidObject (name):
RigidObjectModel
- Return type:
- Parameters:
index (int, optional)
name (str, optional)
- Return type:
- terrain(*args)[source]
Returns a TerrainModel in the world by index or name.
terrain (index):
TerrainModel
terrain (name):
TerrainModel
- Return type:
- Parameters:
index (int, optional)
name (str, optional)
- Return type:
- makeRobot(name)[source]
Creates a new empty robot. (Not terribly useful now since you can’t resize the number of links yet)
- Return type:
- Parameters:
name (str)
- Return type:
- makeRigidObject(name)[source]
Creates a new empty rigid object.
- Return type:
- Parameters:
name (str)
- Return type:
- makeTerrain(name)[source]
Creates a new empty terrain.
- Return type:
- Parameters:
name (str)
- Return type:
- loadRobot(fn)[source]
Loads a robot from a .rob or .urdf file. An empty robot is returned if loading fails.
- Return type:
- Parameters:
fn (str)
- Return type:
- 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:
- Parameters:
fn (str)
- Return type:
- loadTerrain(fn)[source]
Loads a rigid object from a mesh file. An empty terrain is returned if loading fails.
- Return type:
- Parameters:
fn (str)
- Return type:
- 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:
- Parameters:
name (str)
robot (
RobotModel
, optional)obj (
RigidObjectModel
, optional)terrain (
TerrainModel
, optional)
- Return type:
(
RigidObjectModel
orTerrainModel
orRobotModel
)
- 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:
robot (
RobotModel
, optional)object (
RigidObjectModel
, optional)terrain (
TerrainModel
, optional)
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:
- Parameters:
id (int)
- Return type:
- appearance(id)[source]
Retrieves an appearance for a given element ID.
- Return type:
- Parameters:
id (int)
- Return type:
- 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
int
- Type:
index
- getRobots()[source]
Returns a list of all robots in the world.
Args:
- Return type:
Tuple
[RobotModel
]
- getRobotsDict()[source]
Returns a dictionary mapping robot names to RobotModel instances.
Args:
- Return type:
Dict
[str
,RobotModel
]
- getRigidObjects()[source]
Returns a list of all rigid objects in the world.
Args:
- Return type:
Tuple
[RigidObjectModel
]
- getRigidObjectsDict()[source]
Returns a dictionary mapping rigid object names to RigidObjectModel instances.
Args:
- Return type:
Dict
[str
,RigidObjectModel
]
- getTerrains()[source]
Returns a list of all rigid objects in the world.
Args:
- Return type:
Tuple
[TerrainModel
]
- getTerrainsDict()[source]
Returns a dictionary mapping rigid object names to RigidObjectModel instances.
Args:
- Return type:
Dict
[str
,TerrainModel
]
- property robots: Tuple[RobotModel]
Returns a list of all robots in the world.
Args:
- property robotsDict: Dict[str, RobotModel]
Returns a dictionary mapping robot names to RobotModel instances.
Args:
- property rigidObjects: Tuple[RigidObjectModel]
Returns a list of all rigid objects in the world.
Args:
- property rigidObjectsDict: Dict[str, RigidObjectModel]
Returns a dictionary mapping rigid object names to RigidObjectModel instances.
Args:
- property terrains: Tuple[TerrainModel]
Returns a list of all rigid objects in the world.
Args:
- property terrainsDict: Dict[str, TerrainModel]
Returns a dictionary mapping rigid object names to RigidObjectModel instances.
Args:
- class klampt.RobotModel[source]
Bases:
object
A model of a dynamic and kinematic robot.
Args:
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
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
()Gets the name of the robot.
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.
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.
Retrieves the current configuration of the robot model.
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.
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())
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]\)
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]\)
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.
Returns the 3D velocity of the center of mass at the current config / velocity.
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.
Computes the 3D linear momentum vector.
Computes the 3D angular momentum vector.
Computes the kinetic energy at the current config / velocity.
Computes the 3x3 total inertia matrix of the robot.
Computes the nxn mass matrix B(q).
Computes the inverse of the nxn mass matrix B(q)^-1.
Computes the derivative of the nxn mass matrix with respect to q_i.
Computes the derivative of the nxn mass matrix with respect to t, given the robot's current velocity.
Computes the Coriolis force matrix C(q,dq) for current config and velocity.
Computes the Coriolis forces C(q,dq)*dq for current config and velocity.
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.
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)
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).
Returns the number of sensors.
addSensor
(name, type)Adds a new sensor with a given name and type.
getLinks
()Returns a list of all links on the robot.
Returns a dictionary mapping link names to RobotModelLink instances.
Returns a list of all drivers on the robot.
Returns a dictionary mapping driver names to RobotModelDriver instances.
sensor
(index_or_name)Retrieves the sensor with the given index or name.
Returns a list of all sensors on the robot.
Returns a dictionary mapping sensor names to SensorModel instances.
Attributes:
int
int
p.Klampt::RobotModel
Gets the name of the robot.
Returns the ID of the robot in its world.
Retrieves the current configuration of the robot model.
Retreives the current velocity of the robot model.
Returns a list of all links on the robot.
Returns a dictionary mapping link names to RobotModelLink instances.
Returns a list of all drivers on the robot.
Returns a dictionary mapping driver names to RobotModelDriver instances.
Returns a list of all sensors on the robot.
Returns a dictionary mapping sensor names to SensorModel instances.
- 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. Geometries may be saved as well.
- 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.
- link(*args)[source]
Returns a reference to the link by index or name.
link (index):
RobotModelLink
link (name):
RobotModelLink
- Return type:
- Parameters:
index (int, optional)
name (str, optional)
- Return type:
- 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)
- 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)
- getConfig()[source]
Retrieves the current configuration of the robot model.
- Return type:
Sequence
[float
]
- getVelocity()[source]
Retreives the current velocity of the robot model.
- Return type:
Sequence
[float
]
- 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:
Tuple
[Sequence
[float
],Sequence
[float
]]
- 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:
Sequence
[float
]
- 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:
Sequence
[float
]
- 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:
Sequence
[float
]
- 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)
- getComVelocity()[source]
Returns the 3D velocity of the center of mass at the current config / velocity.
- Return type:
Sequence
[float
]
- getComJacobian()[source]
Computes the Jacobian matrix of the current center of mass.
Returns: :rtype:
ndarray
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:
ndarray
- 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
- getKineticEnergy()[source]
Computes the kinetic energy at the current config / velocity.
- Return type:
float
- 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:
ndarray
- getMassMatrixDeriv(i)[source]
Computes the derivative of the nxn mass matrix with respect to q_i.
- Return type:
ndarray
- 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:
ndarray
- getCoriolisForceMatrix()[source]
Computes the Coriolis force matrix C(q,dq) for current config and velocity.
Takes O(n^2) time.
- Return type:
ndarray
- 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:
Sequence
[float
]
- getGravityForces(g)[source]
Computes the generalized gravity vector G(q) for the given workspace gravity vector g (usually (0,0,-9.8)).
- Return type:
Sequence
[float
]- 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:
Sequence
[float
]- 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:
Sequence
[float
]- 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:
Sequence
[float
]- 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:
Sequence
[float
]- 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:
Sequence
[float
]- 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:
Sequence
[float
]- Parameters:
velocities (
list of floats
)
- configFromDrivers(driverValues)[source]
Converts a list of driver values (length numDrivers()) to a full configuration (length numLinks()).
- Return type:
Sequence
[float
]- 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:
Sequence
[float
]- 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:
List
[int
]- 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
)
- addSensor(name, type)[source]
Adds a new sensor with a given name and type.
- Return type:
- Parameters:
name (str)
type (str)
- Returns:
The new sensor.
- property world
int
- Type:
world
- property index
int
- Type:
index
- property robot
p.Klampt::RobotModel
- Type:
robot
- getLinks()[source]
Returns a list of all links on the robot.
Args:
- Return type:
Tuple
[RobotModelLink
]
- getLinksDict()[source]
Returns a dictionary mapping link names to RobotModelLink instances.
Args:
- Return type:
Dict
[str
,RobotModelLink
]
- getDrivers()[source]
Returns a list of all drivers on the robot.
Args:
- Return type:
Tuple
[RobotModelDriver
]
- getDriversDict()[source]
Returns a dictionary mapping driver names to RobotModelDriver instances.
Args:
- Return type:
Dict
[str
,RobotModelDriver
]
- sensor(index_or_name)[source]
Retrieves the sensor with the given index or name. A KeyError is raised if it does not exist.
Args:
- Return type:
- getSensors()[source]
Returns a list of all sensors on the robot.
Args:
- Return type:
Tuple
[SensorModel
]
- getSensorsDict()[source]
Returns a dictionary mapping sensor names to SensorModel instances.
Args:
- Return type:
Dict
[str
,SensorModel
]
- property name: str
Gets the name of the robot.
- 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: Sequence[float]
Retrieves the current configuration of the robot model.
- property velocity: Sequence[float]
Retreives the current velocity of the robot model.
- property links: Tuple[RobotModelLink]
Returns a list of all links on the robot.
Args:
- property linksDict: Dict[str, RobotModelLink]
Returns a dictionary mapping link names to RobotModelLink instances.
Args:
- property drivers: Tuple[RobotModelDriver]
Returns a list of all drivers on the robot.
Args:
- property driversDict: Dict[str, RobotModelDriver]
Returns a dictionary mapping driver names to RobotModelDriver instances.
Args:
- property sensors: Tuple[SensorModel]
Returns a list of all sensors on the robot.
Args:
- property sensorsDict: Dict[str, SensorModel]
Returns a dictionary mapping sensor names to SensorModel instances.
Args:
- class klampt.RobotModelLink[source]
Bases:
object
A reference to a link of a RobotModel.
Args:
The link stores many mostly-constant items (id, name, parent, geometry, appearance, mass, joint axes). There are two exceptions:
the link’s current transform, which is affected by the RobotModel’s current configuration, i.e., the last
RobotModel.setConfig()
call.The various Jacobians of points on the link, accessed by
RobotModelLink.getJacobian()
,RobotModelLink.getPositionJacobian()
, andRobotModelLink.getOrientationJacobian()
, which are configuration dependent.
A RobotModelLink is not created by hand, but instead accessed using
RobotModel.link()
(index or name).C++ includes: robotmodel.h
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).
Returns the index of the link's parent (on its robot).
Sets the index of the link's parent (on its robot).
Returns a reference to the link's parent, or a NULL link if it has no parent.
Sets the link's parent (must be on the same robot).
geometry
()Returns a reference to the link's geometry.
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.
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.
Returns whether the joint is prismatic.
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.
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.
Computes the velocity of the link's origin given the robot's current joint configuration and velocities.
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.
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.
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.
Computes the pseudo-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.
setParent
(index_or_link)Attributes:
int
int
p.Klampt::RobotModel
int
Returns the name of the robot link.
Returns the index of the link's parent (on its robot).
Returns the inertial properties of the link.
Gets the transformation (R,t) to the parent link.
Gets the local rotational / translational axis.
Returns whether the joint is prismatic.
Gets the link's current transformation (R,t) to the world frame.
- 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.
- getParentIndex()[source]
Returns the index of the link’s parent (on its robot). -1 indicates no parent.
- Return type:
int
- setParentIndex(p)[source]
Sets the index of the link’s parent (on its robot).
- Return type:
None
- Parameters:
p (int)
- getParentLink()[source]
Returns a reference to the link’s parent, or a NULL link if it has no parent.
- Return type:
- Return type:
- setParentLink(l)[source]
Sets the link’s parent (must be on the same robot).
- Return type:
None
- Parameters:
l (
RobotModelLink
)
- 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.)
- 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:
Tuple
[Sequence
[float
],Sequence
[float
]]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
)
- setAxis(axis)[source]
Sets the local rotational / translational axis.
- Return type:
None
- Parameters:
axis (
list of 3 floats
)
- 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:
Sequence
[float
]- 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:
Sequence
[float
]- 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:
Sequence
[float
]- 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:
Sequence
[float
]- 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:
Tuple
[Sequence
[float
],Sequence
[float
]]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:
Sequence
[float
]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:
Sequence
[float
]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:
Sequence
[float
]- 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:
ndarray
- 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:
ndarray
- 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:
ndarray
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:
ndarray
- 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:
ndarray
- 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:
ndarray
- 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:
Sequence
[float
]- 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:
Sequence
[float
]- 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:
Sequence
[float
]- 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:
ndarray
- 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 pseudo-Hessians of each orientation component of the link w.r.t the robot’s configuration q. The pseudo-Hessian is the derivative of the angular velocity of this link w.r.t. the joint velocities.
Returns: :rtype:
ndarray
ndarray: a 3xnxn array with each of the elements in the first axis corresponding, respectively, to the (wx,wy,wz) components of the pseudo-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
int
- Type:
world
- property robotIndex
int
- Type:
robotIndex
- property robotPtr
p.Klampt::RobotModel
- Type:
robotPtr
- property index
int
- Type:
index
- property name: str
Returns the name of the robot link.
- property parent: int
Returns the index of the link’s parent (on its robot). -1 indicates no parent.
- 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.)
- Return type:
- property parentTransform: Tuple[Sequence[float], Sequence[float]]
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: Sequence[float]
Gets the local rotational / translational axis.
- property prismatic: bool
Returns whether the joint is prismatic.
- property transform: Tuple[Sequence[float], Sequence[float]]
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.
Args:
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
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
()setName
(name)geometry
()Returns a reference to the geometry associated with this object.
Returns a reference to the appearance associated with this object.
getMass
()Returns a copy of the Mass of this rigid object.
setMass
(mass)Returns a copy of the ContactParameters of this rigid object.
setContactParameters
(params)Retrieves the rotation / translation of the rigid object (R,t)
setTransform
(R, t)Sets the rotation / translation (R,t) of the rigid object.
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.
Attributes:
int
int
p.Klampt::RigidObjectModel
Returns the ID of the rigid object in its world.
Returns a copy of the Mass of this rigid object.
Retrieves the rotation / translation of the rigid object (R,t)
- 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.
- geometry()[source]
Returns a reference to the geometry associated with this object.
- Return type:
- Return type:
- appearance()[source]
Returns a reference to the appearance associated with this object.
- Return type:
- Return type:
- getMass()[source]
Returns a copy of the Mass of this rigid object.
- Return type:
Note
To change the mass properties, you should call
m=object.getMass()
, change the desired properties in m, and thenobject.setMass(m)
- Return type:
- getContactParameters()[source]
Returns a copy of the ContactParameters of this rigid object.
- Return type:
Note
To change the contact parameters, you should call
p=object.getContactParameters()
, change the desired properties in p, and then callobject.setContactParameters(p)
- Return type:
- setContactParameters(params)[source]
- Return type:
None
- Parameters:
params (
ContactParameters
)
- getTransform()[source]
Retrieves the rotation / translation of the rigid object (R,t)
Returns: :rtype:
Tuple
[Sequence
[float
],Sequence
[float
]]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:
Tuple
[Sequence
[float
],Sequence
[float
]]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
int
- Type:
world
- property index
int
- Type:
index
- property object
p.Klampt::RigidObjectModel
- Type:
object
- property name: str
- property id: int
Returns the ID of the rigid object in its world.
Note
The world ID is not the same as the rigid object index.
- property mass: Mass
Returns a copy of the Mass of this rigid object.
Note
To change the mass properties, you should call
m=object.getMass()
, change the desired properties in m, and thenobject.setMass(m)
- Return type:
- property transform: Tuple[Sequence[float], Sequence[float]]
Retrieves the rotation / translation of the rigid object (R,t)
- Returns:
a pair (R,t), with R a 9-list and t a 3-list of floats, giving the transform to world coordinates.
- Return type:
se3 object
- class klampt.TerrainModel[source]
Bases:
object
Static environment geometry.
Args:
C++ includes: robotmodel.h
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
()setName
(name)geometry
()Returns a reference to the geometry associated with this object.
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.
Attributes:
int
int
p.Klampt::TerrainModel
Returns the ID of the terrain in its world.
- 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.
- geometry()[source]
Returns a reference to the geometry associated with this object.
- Return type:
- Return type:
- appearance()[source]
Returns a reference to the appearance associated with this object.
- Return type:
- Return type:
- 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
int
- Type:
world
- property index
int
- Type:
index
- property terrain
p.Klampt::TerrainModel
- Type:
terrain
- property name: str
- property id: int
Returns the ID of the terrain in its world.
Note
The world ID is not the same as the terrain index.
- class klampt.SensorModel(robot, sensor)[source]
Bases:
object
A sensor on a simulated robot.
Args:
Kinematic models of sensors are retrieved using
RobotModel.sensor()
and can be created usingRobotModel.addSensor()
.Physically-simulated sensors are retrieved from a controller using
SimRobotController.sensor()
, and can be created usingSimRobotController.addSensor()
.Some types of sensors can be kinematically-simulated such that they make sensible measurements. To use kinematic simulation, you may arbitrarily set the robot’s position, call
kinematicReset()
, and then callkinematicSimulate()
. Subsequent calls assume the robot is being driven along a coherent trajectory until the nextkinematicReset()
is called. This is necessary for sensors that estimate accelerations, e.g., ForceTorqueSensor, AccelerometerPhysically-simulated sensors are automatically updated through the
Simulator.simulate()
call.Use
getMeasurements()
to get the currently simulated measurement vector. You may get garbage measurements before kinematicSimulate / Simulator.simulate are 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: robotmodel.h
- Parameters:
robot (
RobotModel
)sensor (
Klampt::SensorBase *
)
Methods:
getName
()Returns the name of the sensor.
setName
(name)Sets the name of the sensor.
getType
()Returns the type of the sensor.
robot
()Returns the model of the robot to which this belongs.
Returns a list of names for the measurements (one per measurement).
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)
Return whether the sensor is enabled during simulation (helper for getSetting)
setEnabled
(enabled)Sets whether the sensor is enabled in physics simulation.
Returns the local transform of the sensor on the robot's link.
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)
resets a kinematic simulation so that a new initial condition can be set
getLink
()Retrieves the link that this sensor is mounted on, or None for world-mounted sensors.
setLink
(link)Sets the link that this sensor is mounted on, or None / -1 for world-mounted sensors.
Attributes:
RobotModel
p.Klampt::SensorBase
Returns the name of the sensor.
A string giving the sensor's type.
Whether the sensor is enabled in physical simulation.
The link that this sensor lies on.
- measurementNames()[source]
Returns a list of names for the measurements (one per measurement).
- Return type:
Sequence
[str
]- Return type:
stringVector
- getMeasurements()[source]
Returns an array of measurements from the previous simulation (or kinematicSimulate) timestep.
- Return type:
ndarray
- 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 in physics simulation.
- Return type:
None
- Parameters:
enabled (bool)
- 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:
Tuple
[Sequence
[float
],Sequence
[float
]]
- 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:
Tuple
[Sequence
[float
],Sequence
[float
]]
- 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:
world (
WorldModel
, optional)dt (float)
- kinematicReset()[source]
resets a kinematic simulation so that a new initial condition can be set
- Return type:
None
- property robotModel
RobotModel
- Type:
robotModel
- property sensor
p.Klampt::SensorBase
- Type:
sensor
- getLink()[source]
Retrieves the link that this sensor is mounted on, or None for world-mounted sensors.
Args:
- Return type:
Optional
[RobotModelLink
]
- setLink(link)[source]
Sets the link that this sensor is mounted on, or None / -1 for world-mounted sensors.
Args:
- property name: str
Returns the name of the sensor.
- property type: str
A string giving the sensor’s type. Read-only.
- property enabled: bool
Whether the sensor is enabled in physical simulation.
- property link: RobotModelLink | None
The link that this sensor lies on. May be None.
- class klampt.Mass[source]
Bases:
object
Stores mass information for a rigid body or robot link.
Args:
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
Methods:
setMass
(_mass)getMass
()setCom
(_com)getCom
()Returns the COM.
setInertia
(_inertia)Sets an inertia matrix.
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.
Attributes:
double
The object's center of mass in local coordinates (3-list)
The object's inertia in local coordinates (9-list)
- 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:
Sequence
[float
]
- 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
double
- Type:
mass
- property com: Sequence[float]
The object’s center of mass in local coordinates (3-list)
- property inertia: Sequence[float]
The object’s inertia in local coordinates (9-list)
- 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.
Args:
- 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:
double
double
double
double
- property kFriction
double
- Type:
kFriction
- property kRestitution
double
- Type:
kRestitution
- property kStiffness
double
- Type:
kStiffness
- property kDamping
double
- Type:
kDamping
- class klampt.SimRobotController[source]
Bases:
object
A controller for a simulated robot.
Args:
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
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.
Returns The current commanded configuration (size model().numLinks())
Returns The current commanded velocity (size model().numLinks())
Returns The current commanded (feedforward) torque (size model().numDrivers())
Returns The current "sensed" configuration from the simulator (size model().numLinks())
Returns The current "sensed" velocity from the simulator (size model().numLinks())
Returns The current "sensed" (feedback) torque from the simulator.
Returns the number of sensors.
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.
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.
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.
Returns the control type for the active controller.
setPIDGains
(kP, kI, kD)Sets the PID gains.
Returns the PID gains for the PID controller.
sensor
(index_or_name)Retrieves the sensor with the given index or name.
Returns a list of all sensors on the robot.
Returns a dictionary mapping sensor names to SensorModel instances.
Attributes:
int
p.Simulator
p.Klampt::SimRobotController
Returns The current feedback control rate, in s.
Returns a list of all sensors on the robot.
Returns a dictionary mapping sensor names to SensorModel instances.
- model()[source]
Retrieves the robot model associated with this controller.
- Return type:
- Return type:
- setRate(dt)[source]
Sets the current feedback control rate, in s.
- Return type:
None
- Parameters:
dt (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
- addSensor(name, type)[source]
Adds a new sensor with a given name and type.
- Return type:
- Parameters:
name (str)
type (str)
- Returns:
The new sensor.
- commands()[source]
Returns a custom command list.
- Return type:
Sequence
[str
]- Return type:
stringVector
- 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
]- Return type:
stringVector
- 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)
- 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
)
- property index
int
- Type:
index
- property sim
p.Simulator
- Type:
sim
- property controller
p.Klampt::SimRobotController
- Type:
controller
- sensor(index_or_name)[source]
Retrieves the sensor with the given index or name. A KeyError is raised if it does not exist.
Args:
- Return type:
- getSensors()[source]
Returns a list of all sensors on the robot.
Args:
- Return type:
Tuple
[SensorModel
]
- getSensorsDict()[source]
Returns a dictionary mapping sensor names to SensorModel instances.
Args:
- Return type:
Dict
[str
,SensorModel
]
- property rate: float
Returns The current feedback control rate, in s.
- property sensors: Tuple[SensorModel]
Returns a list of all sensors on the robot.
Args:
- property sensorsDict: Dict[str, SensorModel]
Returns a dictionary mapping sensor names to SensorModel instances.
Args:
- 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).
Args:
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. The object’s reference frame is retrieved/set by getObjectTransform()/setObjectTransform().
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. The object’s reference frame is retrieved/set by getObjectTransform()/setObjectTransform().
C++ includes: robotsim.h
Methods:
getID
()Returns the object ID that this body associated with.
enable
([enabled])Sets the simulation of this body on/off.
Returns true if this body is being simulated.
enableDynamics
([enabled])Turns dynamic simulation of the body on/off.
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.
applyForceAtCOMLocalPoint
(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.
applyForceAtObjectLocalPoint
(f, plocal)Applies a force at a given point (in local object-centered coordinates) over the duration of the next Simulator.simulate(t) call.
applyForceAtLocalPoint
(f, plocal_com)Deprecated: use applyForceAtCOMLocalPoint instead to match old behavior.
setTransform
(R, t)Sets the body's transformation at the current simulation time step (in center- of-mass centered coordinates).
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)
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 (of the COM) at the current simulation time step.
Returns the angular velocity and translational velocity (of the COM)
setObjectVelocity
(w, v)Sets the angular velocity and translational velocity (of the object origin) at the current simulation time step.
Returns the angular velocity and translational velocity (of the object origin)
setCollisionPadding
(padding)Sets the collision padding used for contact generation.
setCollisionPreshrink
([shrinkVisualization])If set, preshrinks the geometry so that the padded geometry better matches the original mesh.
Gets (a copy of) the surface properties.
setSurface
(params)Sets the surface properties.
Attributes:
p.Simulator
int
p.Klampt::ODEGeometry
dBodyID
- enable(enabled=True)[source]
Sets the simulation of this body on/off.
- Return type:
None
- Parameters:
enabled (bool, optional) – default value True
- 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
- 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
)
- applyForceAtCOMLocalPoint(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
)
- applyForceAtObjectLocalPoint(f, plocal)[source]
Applies a force at a given point (in local object-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
)
- applyForceAtLocalPoint(f, plocal_com)[source]
Deprecated: use applyForceAtCOMLocalPoint instead to match old behavior.
- Return type:
None
- Parameters:
f (
list of 3 floats
)plocal_com (
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:
Tuple
[Sequence
[float
],Sequence
[float
]]
- 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:
Tuple
[Sequence
[float
],Sequence
[float
]]
- setVelocity(w, v)[source]
Sets the angular velocity and translational velocity (of the COM) 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 (of the COM)
- Return type:
Tuple
[Sequence
[float
],Sequence
[float
]]
- setObjectVelocity(w, v)[source]
Sets the angular velocity and translational velocity (of the object origin) at the current simulation time step.
- Return type:
None
- Parameters:
w (
list of 3 floats
)v (
list of 3 floats
)
- getObjectVelocity()[source]
Returns the angular velocity and translational velocity (of the object origin)
- Return type:
Tuple
[Sequence
[float
],Sequence
[float
]]
- 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)
- 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
- setSurface(params)[source]
Sets the surface properties.
- Return type:
None
- Parameters:
params (
ContactParameters
)
- property sim
p.Simulator
- Type:
sim
- property objectID
int
- Type:
objectID
- property geometry
p.Klampt::ODEGeometry
- Type:
geometry
- property body
dBodyID
- Type:
body
- 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.
Args:
C++ includes: robotsim.h
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.
Attributes:
int
p.q(const).SimBody
p.q(const).SimBody
dJointID
- 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))
- 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
int
- Type:
type
- property a
p.q(const).SimBody
- Type:
a
- property b
p.q(const).SimBody
- Type:
b
- property joint
dJointID
- Type:
joint
- class klampt.Simulator(model)[source]
Bases:
object
A dynamics simulator for a WorldModel.
Args:
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:
int
WorldModel
p.Klampt::Simulator
std::string
Methods:
reset
()Resets to the initial state (same as setState(initialState))
Returns an indicator code for the simulator status.
getStatusString
([s])Returns a string indicating the simulator's status.
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.
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.
enableContactFeedback
(obj1, obj2)Call this to enable contact feedback between the two objects (arguments are indexes returned by object.getID()).
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.
- STATUS_NORMAL = 0
- STATUS_ADAPTIVE_TIME_STEPPING = 1
- STATUS_CONTACT_UNRELIABLE = 2
- STATUS_UNSTABLE = 3
- STATUS_ERROR = 4
- 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:
Tuple
[list
,list
]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)
- 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:
Sequence
[float
]- Parameters:
robot (int)
- getActualVelocity(robot)[source]
Returns the current actual velocity of the robot from the simulator.
- Return type:
Sequence
[float
]- Parameters:
robot (int)
- getActualTorque(robot)[source]
Returns the current actual torques on the robot’s drivers from the simulator.
- Return type:
Sequence
[float
]- 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:
ndarray
- 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:
ndarray
- 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:
Sequence
[float
]- 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:
Sequence
[float
]- 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:
Sequence
[float
]- 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:
- Parameters:
robot (int or
RobotModel
)- Return type:
- 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:
- Parameters:
link (
RobotModelLink
, optional)object (
RigidObjectModel
, optional)terrain (
TerrainModel
, optional)
- Return type:
- 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:
Sequence
[float
]- 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)
- 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
int
- Type:
index
- property world
WorldModel
- Type:
world
- property sim
p.Klampt::Simulator
- Type:
sim
- property initialState
std::string
- Type:
initialState
- class klampt.Geometry3D(*args)[source]
Bases:
object
The three-D geometry container used throughout Klampt.
Args:
There are eight currently supported types of geometry:
primitives (
GeometricPrimitive
)convex hulls (
ConvexHull
)triangle meshes (
TriangleMesh
)point clouds (
PointCloud
)implicit surfaces (
ImplicitSurface
)occupancy grids (
OccupancyGrid
)heightmaps (
Heightmap
)groups (“Group” type)
For now we also support the “VolumeGrid” identifier which is treated as an alias for “ImplicitSurface”. This will be deprecated in a future version
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:
setCurrentTransform()
: updates the current transform. (This call is very fast.)translate()
,scale()
,rotate()
, andtransform()
transform the underlying geometry. Any collision data structures will be recomputed after transformation.loadFile()
: load from OFF, OBJ, STL, PCD, etc. Also supports native Klamp’t types .geom and .vol.
Note
Avoid the use of translate, rotate, and transform to represent object movement. Use setCurrentTransform instead.
Proximity queries
collides()
: boolean collision query.withinDistance()
: boolean proximity query.distance()
anddistance_ext()
: numeric-valued distance query. The distance may be negative to indicate signed distance, available for certain geometry types. Also returns closest points for certain geometry types.distance_point()
anddistance_point_ext()
: numeric valued distance-to-point queries.contacts()
: estimates the contact region between two objects.rayCast()
andrayCast_ext()
: ray-cast 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()
andgetCollisionMargin()
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, PointCloud, ImplicitSurface, OccupancyGrid, and Heightmap objects.C++ includes: geometry.h
__init__ ():
Geometry3D
__init__ (arg2):
Geometry3D
- Parameters:
arg2 (
TriangleMesh
orImplicitSurface
orGeometry3D
orOccupancyGrid
orConvexHull
orPointCloud
orHeightmap
orGeometricPrimitive
, optional)
Methods:
copy
()Creates a standalone geometry from this geometry.
set
(arg2)Copies the geometry of the argument into this geometry.
free
()Frees the data associated with this geometry, if standalone.
type
()Returns the type of geometry: GeometricPrimitive, ConvexHull, TriangleMesh, PointCloud, ImplicitSurface, OccupancyGrid, Heightmap, or Group.
empty
()Returns True if this has no contents (not the same as numElements()==0)
Returns a TriangleMesh if this geometry is of type TriangleMesh.
Returns a PointCloud if this geometry is of type PointCloud.
Returns a GeometricPrimitive if this geometry is of type GeometricPrimitive.
Returns a ConvexHull if this geometry is of type ConvexHull.
Returns the ImplicitSurface if this geometry is of type ImplicitSurface.
Returns the OccupancyGrid if this geometry is of type OccupancyGrid.
Returns the Heightmap if this geometry is of type Heightmap.
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.
setImplicitSurface
(grid)Sets this Geometry3D to an ImplicitSurface.
setOccupancyGrid
(grid)Sets this Geometry3D to an OccupancyGrid.
setHeightmap
(hm)Sets this Geometry3D to a Heightmap.
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.
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)
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.
Returns the padding around the base geometry.
getBB
()Returns an axis-aligned bounding box of the object as a tuple (bmin,bmax).
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.
contains_point
(pt)Returns true if this geometry contains the given point.
collides
(other)Returns true if this geometry collides with the other.
collides_ext
(other, maxContacts)Same as collide, but will also return the elements of each geometry that collide.
withinDistance
(other, tol)Returns true if this geometry is within distance tol to other.
withinDistance_ext
(other, tol, maxContacts)Same as withinDistance, but will also return the elements of each geometry that are within distance tol.
distance_simple
(other[, relErr, absErr])Returns the distance from this geometry to the other.
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].
merge
(other)Merges another geometry into this geometry.
Attributes:
int
int
- set(arg2)[source]
Copies the geometry of the argument into this geometry.
- Return type:
None
- Parameters:
arg2 (
Geometry3D
)
- type()[source]
Returns the type of geometry: GeometricPrimitive, ConvexHull, TriangleMesh, PointCloud, ImplicitSurface, OccupancyGrid, Heightmap, 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:
- Return type:
- getPointCloud()[source]
Returns a PointCloud if this geometry is of type PointCloud.
- Return type:
- Return type:
- getGeometricPrimitive()[source]
Returns a GeometricPrimitive if this geometry is of type GeometricPrimitive.
- Return type:
- Return type:
- getConvexHull()[source]
Returns a ConvexHull if this geometry is of type ConvexHull.
- Return type:
- Return type:
- getImplicitSurface()[source]
Returns the ImplicitSurface if this geometry is of type ImplicitSurface.
- Return type:
- Return type:
- getOccupancyGrid()[source]
Returns the OccupancyGrid if this geometry is of type OccupancyGrid.
- Return type:
- Return type:
- 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:
g1 (
Geometry3D
)g2 (
Geometry3D
)
- setImplicitSurface(grid)[source]
Sets this Geometry3D to an ImplicitSurface.
- Return type:
None
- Parameters:
grid (
ImplicitSurface
)
- setOccupancyGrid(grid)[source]
Sets this Geometry3D to an OccupancyGrid.
- Return type:
None
- Parameters:
grid (
OccupancyGrid
)
- setHeightmap(hm)[source]
Sets this Geometry3D to a Heightmap.
- Return type:
None
- Parameters:
hm (
Heightmap
)
- 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:
- Parameters:
element (int)
The element will be in local coordinates.
- Return type:
- 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:
element (int)
data (
Geometry3D
)
- 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:
Tuple
[Sequence
[float
],Sequence
[float
]]
- 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:
Tuple
[Sequence
[float
],Sequence
[float
]]
- getBBTight()[source]
Computes a tighter axis-aligned bounding box of the object than
Geometry3D.getBB()
. Worst case O(n) time.- Return type:
Tuple
[Sequence
[float
],Sequence
[float
]]
- 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:
- 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 -> ImplicitSurface. 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 -> OccupancyGrid. Converted using rasterization. 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.
TriangleMesh -> Heightmap. Converted using rasterization. param is the grid resolution, by default set to max mesh dimension / 256.
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 -> OccupancyGrid. param is the grid resolution, by default some reasonable number.
PointCloud -> ConvexHull. Converted using SOLID / Qhull.
PointCloud -> Heightmap. param is the grid resolution, by default set to max point cloud dimension / 256.
GeometricPrimitive -> anything. param determines the desired resolution.
ImplicitSurface -> TriangleMesh. param determines the level set for the marching cubes algorithm.
ImplicitSurface -> PointCloud. param determines the level set.
ImplicitSurface -> Heightmap.
OccupancyGrid -> TriangleMesh. Creates a mesh around each block.
OccupancyGrid -> PointCloud. Outputs a point for each block.
OccupancyGrid -> Heightmap.
ConvexHull -> TriangleMesh.
ConvexHull -> PointCloud. param is the desired dispersion of the points. Equivalent to ConvexHull -> TriangleMesh -> PointCloud
- Return type:
- contains_point(pt)[source]
Returns true if this geometry contains the given point.
- Return type:
bool
- Parameters:
pt (
list of 3 floats
)
An approximate method is used for TriangleMesh. For PointCloud, the point is considered to be contained if it is one of the points in the cloud, or if points have a radius attribute, within the given radius.
- collides(other)[source]
Returns true if this geometry collides with the other.
- Return type:
bool
- Parameters:
other (
Geometry3D
)
Unsupported types:
ImplicitSurface - GeometricPrimitive [aabb, box, triangle, polygon]
ImplicitSurface - ConvexHull
- collides_ext(other, maxContacts)[source]
Same as collide, but will also return the elements of each geometry that collide.
- Return type:
Tuple
[list
,list
]- Parameters:
other (
Geometry3D
)maxContacts (int)
Returns: (elem1, elem2) where elem1 and elem2 are the indices of the elements that collide. If len(elem1) == 0, then there is no detected collision.
- withinDistance(other, tol)[source]
Returns true if this geometry is within distance tol to other.
- Return type:
bool
- Parameters:
other (
Geometry3D
)tol (float)
- withinDistance_ext(other, tol, maxContacts)[source]
Same as withinDistance, but will also return the elements of each geometry that are within distance tol.
- Return type:
Tuple
[list
,list
]- Parameters:
other (
Geometry3D
)tol (float)
maxContacts (int)
Returns: (elem1, elem2) where elem1 and elem2 are the indices of the elements that are within distance tol. If len(elem1) == 0, then there is no detected proximity.
- distance_simple(other, relErr=0, absErr=0)[source]
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.- Return type:
float
- Parameters:
other (
Geometry3D
)relErr (float, optional) – default value 0
absErr (float, optional) – default value 0
- 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:
- 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
ImplictSurface
Heightmap (approximate, only accurate in the viewing direction)
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.
- Return type:
- 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:
- Parameters:
pt (
list of 3 floats
)settings (
DistanceQuerySettings
)
- Return type:
- 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:
- 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 (missing some for boxes, segments, and tris)
GeometricPrimitive-TriangleMesh (surface only)
GeometricPrimitive-PointCloud
GeometricPrimitive-ImplicitSurface
TriangleMesh (surface only)-GeometricPrimitive
PointCloud-ImplicitSurface
PointCloud-ConvexHull
ConvexHull-ConvexHull
ConvexHull-GeometricPrimitive
If penetration is supported, a negative distance is returned and cp1,cp2 are the deepest penetrating points.
Unsupported types:
PointCloud-PointCloud
ImplicitSurface-TriangleMesh
ImplicitSurface-ImplicitSurface
OccupancyGrid - anything
ConvexHull - anything else besides ConvexHull
See the comments of the distance_point function
- Return type:
- 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:
- Parameters:
other (
Geometry3D
)settings (
DistanceQuerySettings
)
- Return type:
- rayCast(s, d)[source]
Performs a ray cast.
- Return type:
Tuple
[bool
,Sequence
[float
]]- Parameters:
s (
list of 3 floats
)d (
list of 3 floats
)
All types supported, but PointCloud needs a positive collision margin, or points need to have a ‘radius’ property assigned)
- 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:
Tuple
[int
,Sequence
[float
]]- Parameters:
s (
list of 3 floats
)d (
list of 3 floats
)
All types supported, but PointCloud needs a positive collision
margin, or points need to have a ‘radius’ property assigned) 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:
- Parameters:
other (
Geometry3D
)padding1 (float)
padding2 (float)
maxContacts (int, optional) – default value 0
Relatively few geometry types are supported.
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.
- Return type:
- support(dir)[source]
Calculates the furthest point on this geometry in the direction dir.
- Return type:
Sequence
[float
]- Parameters:
dir (
list of 3 floats
)
Supported types:
ConvexHull
GeometricPrimitive
PointCloud
TriangleMesh
OccupancyGrid
- 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:
- 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.
- Return type:
- 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:
- 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
- Return type:
- merge(other)[source]
Merges another geometry into this geometry. The result is stored inplace and the type of the result is the same as this geometry. This can be used to calculate the union of PointClouds, TriangleMeshes, ConvexPolytopes, and ImplicitSurfaces, OccupancyGrids, and Heightmaps.
- Return type:
None
- Parameters:
other (
Geometry3D
)
ImplicitSurface, OccupancyGrid, and Heightmap merges preserve the domain of the current grid. They can also be merged with many other geometries.
- property world
int
- Type:
world
- property id
int
- Type:
id
- 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.
Args:
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:
int
int
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.
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.
getColors
(feature)Retrieves 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.
Retrieves the tint color.
Retrieves the tint strength.
setShininess
(shininess[, strength])Sets the specular highlight shininess and strength.
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)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.
Retrieves a 1D texture format, returning '' if the texture is not set.
Retrieves a view into the 1D texture data.
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.
Retrieves a 2D texture format, returning '' if the texture is not set.
Retrieves a view into the 2D texture data.
setTexcoords1D
(np_array)Sets per-vertex texture coordinates for a 1D texture.
Gets per-vertex texture coordinates for a 1D texture.
setTexcoords2D
(np_array2)Sets per-vertex texture coordinates for a 2D texture.
Gets per-vertex texture coordinates for a 2D texture.
setTexgen
(np_array2[, worldcoordinates])Sets the texture generation.
Retrieves the texture generation.
Returns whether texture generation is performed in world coordinates.
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.
- 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
- set(arg2)[source]
Copies the appearance of the argument into this appearance.
- Return type:
None
- Parameters:
arg2 (
Appearance
)
- 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)
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:
Tuple
[float
,float
,float
,float
]- 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
- getColors(feature)[source]
Retrieves per-element color for elements of the given feature type. If per- element colors are not enabled, then a 1 x 4 array is returned. Otherwise, returns an m x 4 array, where m is the number of featuress of that type.
- Return type:
ndarray
- Parameters:
feature (int)
- 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)
- 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
- 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:
Tuple
[float
,float
,float
,float
]- 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)[source]
Sets a 1D texture of the given width. Valid format strings are.
- Return type:
None
- Parameters:
format (str)
np_array (
unsigned 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
- getTexture1D_format()[source]
Retrieves a 1D texture format, returning ‘’ if the texture is not set.
- Return type:
str
- getTexture1D_channels()[source]
Retrieves a view into the 1D texture data. If the texture is not set, throws an exception.
- Return type:
ndarray
- 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.
- getTexture2D_format()[source]
Retrieves a 2D texture format, returning ‘’ if the texture is not set.
- Return type:
str
- getTexture2D_channels()[source]
Retrieves a view into the 2D texture data. If the texture is not set, throws an exception.
- Return type:
ndarray
- 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.
- getTexcoords1D()[source]
Gets per-vertex texture coordinates for a 1D texture. If no 1D texture is set, throws an exception.
- Return type:
ndarray
- 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.
- getTexcoords2D()[source]
Gets per-vertex texture coordinates for a 2D texture. If no 2D texture is set, throws an exception.
- Return type:
ndarray
- 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
- getTexgenMatrix()[source]
Retrieves the texture generation. The array will be size m x 4, with m in the range 0,…,4. The texture generation is performed in
- Return type:
ndarray
- isTexgenWorld()[source]
Returns whether texture generation is performed in world coordinates.
- Return type:
bool
- 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
int
- Type:
world
- property id
int
- Type:
id
- property appearancePtr
p.void
- Type:
appearancePtr
- 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.
- class klampt.DistanceQuerySettings[source]
Bases:
object
Configures the _ext distance queries of
Geometry3D
.Args:
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:
double
double
double
- property relErr
double
- Type:
relErr
- property absErr
double
- Type:
absErr
- property upperBound
double
- Type:
upperBound
- class klampt.DistanceQueryResult[source]
Bases:
object
The result from a “fancy” distance query of
Geometry3D
.Args:
- 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:
double
bool
bool
std::vector<(double,std::allocator<(double)>)>
std::vector<(double,std::allocator<(double)>)>
std::vector<(double,std::allocator<(double)>)>
std::vector<(double,std::allocator<(double)>)>
int
int
- property d
double
- Type:
d
- property hasClosestPoints
bool
- Type:
hasClosestPoints
- property hasGradients
bool
- Type:
hasGradients
- property cp1
std::vector<(double,std::allocator<(double)>)>
- Type:
cp1
- property cp2
std::vector<(double,std::allocator<(double)>)>
- Type:
cp2
- property grad1
std::vector<(double,std::allocator<(double)>)>
- Type:
grad1
- property grad2
std::vector<(double,std::allocator<(double)>)>
- Type:
grad2
- property elem1
int
- Type:
elem1
- property elem2
int
- Type:
elem2
- class klampt.ContactQueryResult[source]
Bases:
object
The result from a contact query of
Geometry3D
. The number of contacts n is variable.Args:
- 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:
std::vector<(double,std::allocator<(double)>)>
std::vector<(std::vector<(double,std::allocator<(double)>)>,std::allocator<(std::vector<(double,std::allocator<(double)>)>)>)>
std::vector<(std::vector<(double,std::allocator<(double)>)>,std::allocator<(std::vector<(double,std::allocator<(double)>)>)>)>
std::vector<(std::vector<(double,std::allocator<(double)>)>,std::allocator<(std::vector<(double,std::allocator<(double)>)>)>)>
std::vector<(int,std::allocator<(int)>)>
std::vector<(int,std::allocator<(int)>)>
- property depths
std::vector<(double,std::allocator<(double)>)>
- Type:
depths
- property points1
std::vector<(std::vector<(double,std::allocator<(double)>)>,std::allocator<(std::vector<(double,std::allocator<(double)>)>)>)>
- Type:
points1
- property points2
std::vector<(std::vector<(double,std::allocator<(double)>)>,std::allocator<(std::vector<(double,std::allocator<(double)>)>)>)>
- Type:
points2
- property normals
std::vector<(std::vector<(double,std::allocator<(double)>)>,std::allocator<(std::vector<(double,std::allocator<(double)>)>)>)>
- Type:
normals
- property elems1
std::vector<(int,std::allocator<(int)>)>
- Type:
elems1
- property elems2
std::vector<(int,std::allocator<(int)>)>
- Type:
elems2
- class klampt.TriangleMesh(*args)[source]
Bases:
object
A 3D indexed triangle mesh class.
Args:
- vertices
an n x 3 array of vertices.
- Type:
numpy array
- indices
an m x 3 list of triangle vertices, given as indices into the vertices list, i.e., [[a1,b1,c2], [a2,b2,c2], …]
- Type:
numpy int32 array
Examples:
m = TriangleMesh() m.addVertex((0,0,0)) m.addVertex((1,0,0)) m.addVertex((0,1,0)) m.addTriangle(0,1,2) print(len(m.vertices)) #prints 3 print(len(m.indices)) #prints 1
C++ includes: geometry.h
__init__ ():
TriangleMesh
__init__ (rhs):
TriangleMesh
- Parameters:
rhs (
TriangleMesh
, optional)
Methods:
copy
()Creates a standalone object that is a copy of this.
set
(arg2)Copies the data of the argument into this.
Retrieves an array view of the vertices.
setVertices
(np_array2)Sets all vertices to the given nx3 Numpy array.
addVertex
(p)Adds a new vertex.
Retrieves an array view of the triangle indices.
setIndices
(np_array2)Sets all indices to the given mx3 Numpy array.
Adds a new triangle.
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.
triangle
(i)Returns the i'th triangle of the mesh as a tuple of 3 3-tuples.
Computes outward triangle normals.
vertexNormals
([area_weighted])Computes outward vertex normals.
Attributes:
The vertices of the mesh.
The triangles of the mesh, given as indices into the vertices array.
- set(arg2)[source]
Copies the data of the argument into this.
- Return type:
None
- Parameters:
arg2 (
TriangleMesh
)
- getVertices()[source]
Retrieves an array view of the vertices.
Returns: :rtype:
ndarray
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:
ndarray
ndarray: an mx3 Numpy array of int32 type. Setting elements of this array will change the triangle 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 vertices: ndarray
The vertices of the mesh.
- property indices: ndarray
The triangles of the mesh, given as indices into the vertices array.
- triangle(i)[source]
Returns the i’th triangle of the mesh as a tuple of 3 3-tuples.
Args:
- Return type:
Tuple
[Tuple
[float
,float
,float
],Tuple
[float
,float
,float
],Tuple
[float
,float
,float
]]
- class klampt.PointCloud(*args)[source]
Bases:
object
A 3D point cloud class.
Args:
- vertices
a n x 3 array of vertices.
- Type:
numpy array
- properties
a n x k array of vertex properties. The name of each property is either anonymous or retrieved by getPropertyName.
- Type:
numpy array
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.addProperty('rgb') #add 1 point with coordinates (0,0,0) and color #000000 (black) pc.addPoint((0,0,0)) pc.setProperty(0,0) print(len(pc.points)) # prints 1 #add another point with coordinates (1,2,3) pc.addPoint([1,2,3]) #this prints 2 print(len(pc.points)) print(pc.points) #prints [[0,0,0],[1,2,3]] #this prints (2,1), because there is 1 property category x 2 points print(pc.properties.shape) #this prints 0; this is the default value added when addPoint was called print(pc.getProperty(1,0) )
C++ includes: geometry.h
__init__ ():
PointCloud
__init__ (rhs):
PointCloud
- Parameters:
rhs (
PointCloud
, optional)
Methods:
copy
()Creates a standalone object that is a copy of this.
set
(arg2)Copies the data of the argument into this.
Returns a view of the points.
setPoints
(np_array2)Sets all the points to the given nx3 Numpy 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.
Returns the number of properties.
setPointsAndProperties
(np_array2)Sets all the points and m properties from the given n x (3+k) array.
setProperties
(np_array2)Sets all the properties of all points to the given nxk array.
Returns all the properties of all points as an array view.
addProperty
(*args)Adds a new property with name pname, and sets values for this property to the given length-n array.
setPropertyName
(pindex, pname)Sets the name of a given property.
getPropertyName
(pindex)Returns the name of a given property.
propertyIndex
(pname)Returns the index of a named property or -1 if it does not exist.
setProperty
(*args)Sets the property named pname of point index to the given value.
getProperty
(*args)Returns the property named pname of point index.
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.
Returns the names of the properties.
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.
getColors
([format])Returns the colors of the point cloud in the given format.
setColors
(colors[, color_format, pc_property])Sets the colors of the point cloud.
Attributes:
The points of the point cloud.
The properties of the point cloud.
- set(arg2)[source]
Copies the data of the argument into this.
- Return type:
None
- Parameters:
arg2 (
PointCloud
)
- getPoints()[source]
Returns a view of the points.
Returns: :rtype:
ndarray
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
)
- addPoint(p)[source]
Adds a point. Sets all its properties to 0.
- Return type:
int
- Parameters:
p (
list of 3 floats
)
Slow if properties are already set. Setting the points and properties as matrices is faster.
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:
Sequence
[float
]- Parameters:
index (int)
- setPointsAndProperties(np_array2)[source]
Sets all the points and m properties from the given n x (3+k) array.
- Return type:
None
- Parameters:
np_array2 (
2D Numpy array of floats
)
- setProperties(np_array2)[source]
Sets all the properties of all points to the given nxk array.
- Return type:
None
- Parameters:
np_array2 (
2D Numpy array of floats
)
- getProperties()[source]
Returns all the properties of all points as an array view.
Returns: :rtype:
ndarray
ndarray: an nxk Numpy array. Setting elements of this array will change the vertices.
- addProperty(*args)[source]
Adds a new property with name pname, and sets values for this property to the given length-n array.
addProperty (pname): int
addProperty (pname,np_array): int
- Return type:
int
- Parameters:
pname (str)
np_array (
1D Numpy array of floats
, optional)
- setPropertyName(pindex, pname)[source]
Sets the name of a given property.
- Return type:
None
- Parameters:
pindex (int)
pname (str)
- getPropertyName(pindex)[source]
Returns the name of a given property.
- Return type:
str
- Parameters:
pindex (int)
- propertyIndex(pname)[source]
Returns the index of a named property or -1 if it does not exist.
- Return type:
int
- Parameters:
pname (str)
- 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)
- 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)
- 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 points: ndarray
The points of the point cloud.
- property properties: ndarray
The properties of the point cloud.
- setDepthImage(intrinsics, depth, depth_scale=1.0)[source]
Sets a structured point cloud from a depth image.
- Parameters:
intrinsics (list or dict) – intrinsics parameters [fx,fy,cx,cy] or a dictionary containing keys ‘fx’, ‘fy’, ‘cx’, ‘cy’.
depth (np.ndarray) – the depth values, of shape (h,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 (list or dict) – intrinsics parameters [fx,fy,cx,cy] or a dictionary containing keys ‘fx’, ‘fy’, ‘cx’, ‘cy’.
color (np.ndarray) – the color values, of shape (h,w) or (h,w,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 shape (h,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.
- getColors(format='rgb')[source]
Returns the colors of the point cloud in the given format. If the point cloud has no colors, this returns None. If the point cloud has no colors but has opacity, this returns white colors.
- Return type:
ndarray
- Parameters:
format –
describes the output color format, either:
- ’rgb’: packed 32bit int, with the hex format 0xrrggbb (only 24
bits used),
- ’bgr’: packed 32bit int, with the hex format 0xbbggrr (only 24
bits used),
’rgba’: packed 32bit int, with the hex format 0xrrggbbaa,
’bgra’: packed 32bit int, with the hex format 0xbbggrraa,
’argb’: packed 32bit int, with the hex format 0xaarrggbb,
’abgr’: packed 32bit int, with the hex format 0xaabbggrr,
(‘r’,’g’,’b’): triple with each channel in range [0,1]
(‘r’,’g’,’b’,’a’): tuple with each channel in range [0,1]
- ’channels’: returns a list of channels, in the form (r,g,b) or
(r,g,b,a), where each value in the channel has range [0,1].
’opacity’: returns opacity only, in the range [0,1].
- Returns:
A an array of len(pc.points) colors corresponding to the points in the point cloud. If format=’channels’, the return value is a tuple (r,g,b) or (r,g,b,a).
- setColors(colors, color_format='rgb', pc_property='auto')[source]
Sets the colors of the point cloud.
- Parameters:
colors (list or numpy.ndarray) – the array of colors, and each color can be either ints, tuples, or channels, depending on color_format.
color_format –
describes the format of each element of
colors
, and can be:- ’rgb’: packed 32bit int, with the hex format 0xrrggbb (only 24
bits used),
- ’bgr’: packed 32bit int, with the hex format 0xbbggrr (only 24
bits used),
’rgba’: packed 32bit int, with the hex format 0xrrggbbaa,
’bgra’: packed 32bit int, with the hex format 0xbbggrraa,
’argb’: packed 32bit int, with the hex format 0xaarrggbb,
’abgr’: packed 32bit int, with the hex format 0xaabbggrr,
- (‘r’,’g’,’b’): triple with each channel in range [0,1]. Also use
this if colors is an n x 3 numpy array.
- (‘r’,’g’,’b’,’a’): tuple with each channel in range [0,1]. Also
use this if colors is an n x 4 numpy array.
- ’channels’:
colors
is a list of 3 or 4 channels, in the form (r,g,b) or (r,g,b,a), where each element in a channel has range [0,1].
- ’channels’:
’opacity’: opacity only, in the range [0,1].
pc_property (str) – describes to which property the colors should be set. ‘auto’ determines chooses the property from the point cloud if it’s already colored, or color_format if not. ‘channels’ sets the ‘r’, ‘g’, ‘b’, and optionally ‘a’ properties.
- class klampt.GeometricPrimitive(*args)[source]
Bases:
object
A geometric primitive. So far only points, spheres, segments, and AABBs can be constructed manually in the Python API.
Args:
- 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:
numpy array
C++ includes: geometry.h
__init__ ():
GeometricPrimitive
__init__ (rhs):
GeometricPrimitive
- Parameters:
rhs (
GeometricPrimitive
, optional)
Methods:
copy
()Creates a standalone object that is a copy of this.
set
(arg2)Copies the data of the argument into this.
setPoint
(pt)setSphere
(c, r)setSegment
(a, b)setTriangle
(a, b, c)setPolygon
(verts)setAABB
(bmin, bmax)setBox
(ori, R, dims)getType
()setProperties
(np_array)loadString
(str)Attributes:
The type of the geometric primitive.
The properties of the geometric primitive.
- set(arg2)[source]
Copies the data of the argument into this.
- Return type:
None
- Parameters:
arg2 (
GeometricPrimitive
)
- setTriangle(a, b, c)[source]
- Return type:
None
- Parameters:
a (
list of 3 floats
)b (
list of 3 floats
)c (
list of 3 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
)
- property type: str
The type of the geometric primitive.
- property properties: None
The properties of the geometric primitive. Type dependent.
- class klampt.ConvexHull(*args)[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.
Args:
- points
an nx3 numpy array of points.
- Type:
numpy array
C++ includes: geometry.h
__init__ ():
ConvexHull
__init__ (rhs):
ConvexHull
- Parameters:
rhs (
ConvexHull
, optional)
Methods:
copy
()Creates a standalone object that is a copy of this.
set
(arg2)Copies the data of the argument into this.
Retrieves a view of the points.
setPoints
(np_array2)Sets all points to the given nx3 Numpy array.
addPoint
(pt)Adds 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.
Attributes:
The points of the convex hull.
- set(arg2)[source]
Copies the data of the argument into this.
- Return type:
None
- Parameters:
arg2 (
ConvexHull
)
- getPoints()[source]
Retrieves a view of the points.
Returns: :rtype:
ndarray
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
)
- 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: ndarray
The points of the convex hull.
- class klampt.ImplicitSurface(*args)[source]
Bases:
object
An axis-aligned volumetric grid representing a signed distance transform with > 0 indicating outside and < 0 indicating inside.
Args:
In general, values are associated with cells rather than vertices.
Cell (i,j,k) contains a 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)).
The field should be assumed sampled at the centers of cells, i.e., at (w*(i+1/2),d*(j+1/2),h*(k+1/2)).
- bmin
contains the minimum bounds.
- Type:
array of 3 doubles
- bmax
contains the maximum bounds.
- Type:
array of 3 doubles
- values
contains a 3D array of
dims[0] x dims[1] x dims[2]
values.- Type:
numpy array
- truncationDistance
inf for SDFs, and the truncation distance for TSDFs. Cells whose values are >= d are considered “sufficiently far” and distance / tolerance queries outside of this range are usually not meaningful.
- Type:
float
C++ includes: geometry.h
__init__ ():
ImplicitSurface
__init__ (rhs):
ImplicitSurface
- Parameters:
rhs (
ImplicitSurface
, optional)
Methods:
copy
()Creates a standalone object that is a copy of this.
getBmin
()setBmin
(bmin)getBmax
()setBmax
(bmax)resize
(sx, sy, sz)Resizes the x, y, and z dimensions of the grid.
set
(*args)Sets a specific element of a cell.
get
(i, j, k)Gets a specific element of a cell.
shift
(dv)Shifts the value uniformly.
scale
(cv)Scales the value uniformly.
Returns a 3D Numpy array view of the values.
setValues
(np_array3)Sets the values to a 3D numpy array.
Sets the truncation distance for TSDFs.
Retrieves the truncation distance for TSDFs.
setBounds
(bounds)@deprecated
@deprecated
Attributes:
The lower bound of the domain.
The upper bound of the domain.
Klampt 0.9 backwards compatibility accessor for the (bmin, bmax) pair.
The 3D array of values in the grid (numpy.ndarray)
- resize(sx, sy, sz)[source]
Resizes the x, y, and z dimensions of the grid.
- Return type:
None
- Parameters:
sx (int)
sy (int)
sz (int)
- set(*args)[source]
Sets a specific element of a cell.
set (arg2)
set (value)
set (i,j,k,value)
- Return type:
None
- Parameters:
arg2 (
ImplicitSurface
, optional)value (float, optional)
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)
- setValues(np_array3)[source]
Sets the values to a 3D numpy array.
- Return type:
None
- Parameters:
np_array3 (
3D Numpy array of floats
)
- setTruncationDistance(d)[source]
Sets the truncation distance for TSDFs.
- Return type:
None
- Parameters:
d (float)
- property bmin: None
The lower bound of the domain.
- property bmax: None
The upper bound of the domain.
- property bounds
Klampt 0.9 backwards compatibility accessor for the (bmin, bmax) pair.
- property values: ndarray
The 3D array of values in the grid (numpy.ndarray)
- class klampt.OccupancyGrid(*args)[source]
Bases:
object
An occupancy grid with 1 indicating inside and 0 indicating outside. Can also be a fuzzy (probabilistic / density) grid.
Args:
In general, values are associated with cells rather than vertices.
Cell (i,j,k) contains an occupancy / density 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)).
- bmin
contains the minimum bounds.
- Type:
array of 3 doubles
- bmax
contains the maximum bounds.
- Type:
array of 3 doubles
- values
contains a 3D array of
dims[0] x dims[1] x dims[2]
values.- Type:
numpy array
- occupancyThreshold
set to 0.5 by default. Collision detection treats all cells whose values are greater than this value as occupied.
- Type:
float
C++ includes: geometry.h
__init__ ():
OccupancyGrid
__init__ (rhs):
OccupancyGrid
- Parameters:
rhs (
OccupancyGrid
, optional)
Methods:
copy
()Creates a standalone object that is a copy of this.
getBmin
()setBmin
(bmin)getBmax
()setBmax
(bmax)resize
(sx, sy, sz)Resizes the x, y, and z dimensions of the grid.
set
(*args)Sets a specific element of a cell.
get
(i, j, k)Gets a specific element of a cell.
shift
(dv)Shifts the value uniformly.
scale
(cv)Scales the value uniformly.
Returns a 3D Numpy array view of the values.
setValues
(np_array3)Sets the values to a 3D numpy array.
setOccupancyThreshold
(threshold)Sets the threshold for collision detection.
Gets the threshold for collision detection.
setBounds
(bounds)@deprecated
@deprecated
Attributes:
The lower bound of the domain.
The upper bound of the domain.
Klampt 0.9 backwards compatibility accessor for the (bmin, bmax) pair.
The 3D array of values in the grid (numpy.ndarray)
- setBmin(bmin)[source]