klampt.io package¶
An exporter that converts scenes / animations to shareable HTML files. |
|
Functions for loading/saving Klampt’ objects to disk in the same format as the Klampt C++ bindings / JSON formats. |
|
Easy I/O with resources stored on disk and visual editing. |
|
A module for converting between Klamp’t objects and ROS messages. |
|
Conversions to and from Numpy objects; makes numerical computations much more convenient. |
|
Conversions to and from the Open3D library. |
|
klampt.io.html module¶
An exporter that converts scenes / animations to shareable HTML files.
Bases:
object
An exporter that converts scenes / animations to shareable HTML files.
Examples:
sharer = HTMLSharePath("mypath.html",name="My spiffy path") sharer.start(sim) #can accept a sim or a world while [simulation is running]: #do whatever control you wish to do here sim.simulate(...) sharer.animate() sharer.end() #this saves to the filename given in the constructor
- Parameters
filename (str, optional) – the HTML file to generate. If None, then the end() method returns the HTML string.
name (str) – the title of the HTML page
boilerplate (str) – the location of the boilerplate HTML file. If ‘auto’, it’s automatically found in the
klampt/data
folder.libraries (str) – either ‘static’ or ‘dynamic’. In the latter case, the html file loads the libraries from the Klamp’t website dynamically. This reduces the size of the HTML file by about 600kb, but the viewer needs an internet connection
Updates the path from the world. If the world wasn’t a simulator, the time argument needs to be provided.
If you want to include extra things, provide them in the rpc argument (as a list of KlamptFrontend rpc calls)
Begins the path saving with the given WorldModel or Simulator
klampt.io.loader module¶
Functions for loading/saving Klampt’ objects to disk in the same format as the Klampt C++ bindings / JSON formats.
Can read/write objects using the general purpose reader/writer functions ‘read(type,text)’ and ‘write(x,type)’.
Can load/save objects using the general purpose loader/saver functions ‘load(type,fileName)’ and ‘save(x,type,fileName)’. The load functions also support URLs
Json serialization/deserialization are handled using the toJson()
and
fromJson()
functions.
Module summary¶
High level interface¶
|
General-purpose write of an arbitrary Klampt object to a str. |
|
General-purpose read of an arbitrary Klampt object from a str. |
|
General-purpose load of an arbitrary Klampt object from a file or URL. |
|
General-purpose save of an arbitrary Klampt object to a file. |
|
Converts from a Klamp’t object to a JSON-compatible structure. |
|
Converts from a JSON structure to a Klamp’t object of the appropriate type. |
dict mapping file extensions to lists of compatible Klampt types. |
|
dict mapping Klamp’t types to lists of compatible file extensions. |
|
List of Klampt types that cannot currently be exported to JSON |
|
|
Returns the Klampt types possibly represented by the given filename’s extension. |
|
Returns one Klampt type represented by the given filename’s extension. |
Implementation¶
|
Reads a length-prepended vector from a string ‘n v1 . |
|
Writes a vector to a string in the length-prepended format ‘n v1 . |
|
Reads a vector from a raw string ‘v1 . |
Writes a vector to a string in the raw format ‘v1 . |
|
|
Reads a list of endline-separated vectors from a string |
Writes a list of vectors to string |
|
|
Reads a matrix from a string in the format m n x11 x12 . |
|
Writes a matrix to a string in the format m n x11 x12 . |
|
Reads a 3x3 matrix from a string |
|
Writes a 3x3 matrix to a string |
|
Reads a length-prepended vector from a string ‘n v1 . |
|
Reads a length-prepended vector from a string ‘n v1 . |
|
Reads an so3 element, i.e., rotation matrix, from string in the same format as written to by Klampt C++ bindings (row major). |
|
Writes an so3 element, i.e., rotation matrix, to string in the same format as written to by Klampt C++ bindings (row major). |
|
Reads an se3 element, i.e., rigid transformation, to string in the same format as written to by Klampt C++ bindings (row major R, followed by t). |
|
Writes an se3 element, i.e., rigid transformation, to string in the same format as written to by Klampt C++ bindings (row major R, followed by t). |
|
Reads an IKObjective from a string in the Klamp’t native format |
|
|
|
Reads a contact point from a string ‘x1 x2 x3 n1 n2 n3 kFriction’ |
Writes a contact point to a string ‘x1 x2 x3 n1 n2 n3 kFriction’ |
|
|
Loads a Hold from a string |
|
Writes a Hold to a string |
|
|
|
|
|
|
|
|
|
-
klampt.io.loader.
autoType
(obj, validTypes)[source]¶ Returns a type string for the Klamp’t object obj, restricted to the set of validTypes. If there are multiple interpretations, the first type in objectToTypes that matches a valid type is returned.
- Parameters
obj – A Klamp’t-compatible object
validTypes – a set or dict of possible valid types
- Returns
The type of the object, or None if no valid type was found
- Return type
str or None
-
klampt.io.loader.
extensionToTypes
= {'.config': ['Config'], '.configs': ['Configs'], '.dae': ['Geometry3D', 'TriangleMesh'], '.env': ['TerrainModel'], '.geom': ['Geometry3D', 'GeometricPrimitive'], '.grasp': ['Grasp'], '.hold': ['Hold'], '.ikgoal': ['IKGoal'], '.matrix3': ['Matrix3'], '.obj': ['Geometry3D', 'RigidObjectModel', 'TriangleMesh'], '.off': ['Geometry3D', 'TriangleMesh'], '.path': ['Trajectory', 'LinearPath', 'SE3Trajectory', 'SO3Trajectory'], '.pcd': ['Geometry3D', 'PointCloud'], '.ply': ['Geometry3D', 'TriangleMesh'], '.poly': ['Geometry3D', 'TriangleMesh'], '.rob': ['RobotModel'], '.stance': ['Stance'], '.stl': ['Geometry3D', 'TriangleMesh'], '.tri': ['Geometry3D', 'TriangleMesh'], '.urdf': ['RobotModel'], '.vector3': ['Vector3'], '.wrl': ['Geometry3D', 'TriangleMesh'], '.xform': ['RigidTransform'], '.xml': ['WorldModel', 'MultiPath']}¶ dict mapping file extensions to lists of compatible Klampt types.
-
klampt.io.loader.
filenameToType
(name)[source]¶ Returns one Klampt type represented by the given filename’s extension.
If the file is a dynamic type (.xml or .json), just ‘xml’ or ‘json’ is returned because the type will need to be determined after parsing the file.
If the type is ambiguous (like .obj), the first type in extensionToTypes is returned.
- Returns
The Klamp’t type
- Return type
str
-
klampt.io.loader.
filenameToTypes
(name)[source]¶ Returns the Klampt types possibly represented by the given filename’s extension.
-
klampt.io.loader.
fromJson
(jsonobj, type='auto')[source]¶ Converts from a JSON structure to a Klamp’t object of the appropriate type.
Note: a JSON structure can be created from a JSON string using the
json.loads()
function in the Python builtinjson
module.Not all objects are supported yet, notably geometry-related objects and world entities.
-
klampt.io.loader.
load
(type, fn)[source]¶ General-purpose load of an arbitrary Klampt object from a file or URL.
An exception is raised if there is an error loading or parsing the file. Possible exception types include IOError, ValueError, and HTTPError.
- Parameters
type (str) – a Klamp’t type, ‘json’, or ‘auto’
fn (str) – a filename.
- Returns
Klamp’t object
-
klampt.io.loader.
parseLines
(text)[source]¶ Returns a list of lines from the given text. Understands end-of-line escapes ‘n’
-
klampt.io.loader.
read
(type, text)[source]¶ General-purpose read of an arbitrary Klampt object from a str.
- Parameters
type (str) – Either the Klamp’t type, or ‘json’. Future versions may support ‘xml’ but this is not supported right now. ‘auto’ may not be specified.
text (str) – A string containing the object data.
- Returns
Klamp’t object
-
klampt.io.loader.
readContactPoint
(text)[source]¶ Reads a contact point from a string ‘x1 x2 x3 n1 n2 n3 kFriction’
-
klampt.io.loader.
readIKObjective
(text)[source]¶ Reads an IKObjective from a string in the Klamp’t native format
link destLink posConstraintType [pos constraint items] ... rotConstraintType [rot constraint items]
where link and destLink are integers, posConstraintType is one of
N: no constraint
P: position constrained to a plane
L: position constrained to a line
F: position constrained to a point
and rotConstraintType is one of
N: no constraint
T: two-axis constraint (not supported)
A: rotation constrained about axis
F: fixed rotation
The [pos constraint items] contain a variable number of whitespace- separated items, dependending on posConstraintType:
N: 0 items
P: the local position xl yl zl, world position x y z on the plane, and plane normal nx,ny,nz
L: the local position xl yl zl, world position x y z on the line, and line axis direction nx,ny,nz
F: the local position xl yl zl and world position x y z
The [rot constraint items] contain a variable number of whitespace- separated items, dependending on rotConstraintType:
N: 0 items
T: not supported
A: the local axis xl yl zl and the world axis x y z
F: the world rotation matrix, in moment (aka exponential map) form mx my mz (see so3.from_moment())
-
klampt.io.loader.
readIntArray
(text)[source]¶ Reads a length-prepended vector from a string ‘n v1 … vn’
-
klampt.io.loader.
readMatrix
(text)[source]¶ Reads a matrix from a string in the format m n x11 x12 … x1n … xm1 xm2 … xmn
-
klampt.io.loader.
readSe3
(text)[source]¶ Reads an se3 element, i.e., rigid transformation, to string in the same format as written to by Klampt C++ bindings (row major R, followed by t).
-
klampt.io.loader.
readSo3
(text)[source]¶ Reads an so3 element, i.e., rotation matrix, from string in the same format as written to by Klampt C++ bindings (row major).
-
klampt.io.loader.
readStringArray
(text)[source]¶ Reads a length-prepended vector from a string ‘n v1 … vn’
-
klampt.io.loader.
readVector
(text)[source]¶ Reads a length-prepended vector from a string ‘n v1 … vn’
-
klampt.io.loader.
readVectorList
(text)[source]¶ Reads a list of endline-separated vectors from a string
-
klampt.io.loader.
save
(obj, type, fn)[source]¶ General-purpose save of an arbitrary Klampt object to a file.
This also works with RobotModel, RigidObjectModel, and TerrainModel (which don’t work with load).
- Parameters
obj – a Klamp’t object.
type (str) – the Klampt type, ‘json’, or ‘auto’
fn (str) – a file name
- Returns
True if successful.
- Return type
bool
-
klampt.io.loader.
toJson
(obj, type='auto')[source]¶ Converts from a Klamp’t object to a JSON-compatible structure.
The resulting structure can be converted to a JSON string using
json.dumps()
in the Python builtinjson
module.Not all objects are supported yet, notably geometry-related objects and world entities.
- Parameters
obj – A Klamp’t object.
type (str, optional) – the type of the object (see
types
) If ‘auto’ (default), the type of the object is inferred automatically.
-
klampt.io.loader.
typeToExtensions
= {'Config': ['.config'], 'Configs': ['.configs'], 'GeometricPrimitive': ['.geom'], 'Geometry3D': ['.wrl', '.poly', '.pcd', '.geom', '.stl', '.ply', '.tri', '.obj', '.off', '.dae'], 'Grasp': ['.grasp'], 'Hold': ['.hold'], 'IKGoal': ['.ikgoal'], 'LinearPath': ['.path'], 'Matrix3': ['.matrix3'], 'MultiPath': ['.xml'], 'PointCloud': ['.pcd'], 'RigidObjectModel': ['.obj'], 'RigidTransform': ['.xform'], 'RobotModel': ['.urdf', '.rob'], 'SE3Trajectory': ['.path'], 'SO3Trajectory': ['.path'], 'Stance': ['.stance'], 'TerrainModel': ['.env'], 'Trajectory': ['.path'], 'TriangleMesh': ['.wrl', '.poly', '.stl', '.ply', '.tri', '.obj', '.off', '.dae'], 'Vector3': ['.vector3'], 'WorldModel': ['.xml']}¶ dict mapping Klamp’t types to lists of compatible file extensions.
-
klampt.io.loader.
unsupportedJsonTypes
= ['Geometry3D', 'TriangleMesh', 'PointCloud', 'GeometricPrimitive', 'VolumeGrid', 'RobotModel', 'RigidObjectModel', 'TerrainModel', 'WorldModel']¶ List of Klampt types that cannot currently be exported to JSON
-
klampt.io.loader.
write
(obj, type)[source]¶ General-purpose write of an arbitrary Klampt object to a str.
- Parameters
obj – A Klampt object
type (str) – Either the Klamp’t type, ‘json’, or ‘auto’. If ‘auto’, the type will be auto-detected from the object.
- Returns
The encoding of the object.
- Return type
str
-
klampt.io.loader.
writeContactPoint
(cp)[source]¶ Writes a contact point to a string ‘x1 x2 x3 n1 n2 n3 kFriction’
-
klampt.io.loader.
writeMatrix
(x)[source]¶ Writes a matrix to a string in the format m n x11 x12 … x1n … xm1 xm2 … xmn
-
klampt.io.loader.
writeSe3
(x)[source]¶ Writes an se3 element, i.e., rigid transformation, to string in the same format as written to by Klampt C++ bindings (row major R, followed by t).
-
klampt.io.loader.
writeSo3
(x)[source]¶ Writes an so3 element, i.e., rotation matrix, to string in the same format as written to by Klampt C++ bindings (row major).
klampt.io.resource module¶
Easy I/O with resources stored on disk and visual editing.
Use the get()
,
set()
, and
edit()
functions to retrieve / store / edit
resources dynamically.
load()
and save()
launch
a file browser (available in Qt only).
By default, resources are stored in the resources/
subdirectory of the
current working directory.
Use getDirectory()
and
setDirectory()
to change where resources are
stored Alternatively, the directory=[DIRNAME]
keyword
argument can be provided to get, set, load, and save.
Warning
Don’t use from klampt.io.resource import *
, because this will
override the built-in set class.
Example usage can be seen in Klampt-examples/Python/demos/resourcetest.py.
Classes:
|
Functions:
|
|
|
Launches an editor for the given value. |
|
Retrieve a resource of the given name from the current resources directory. |
Returns the current resource directory. |
|
Returns all known resource file extensions |
|
Returns all known resource types |
|
|
Pops up a dialog that asks the user to load a resource file of a given type. |
|
Pops up a dialog that asks the user to save a resource to a file of the correct type. |
|
Saves a resource to disk under the given name. |
|
Sets the current resource directory. |
|
Retrieves an image of the given item, resized to the given size. |
Returns types that can be visually edited |
-
class
klampt.io.resource.
FileGetter
(title='Open file')[source]¶ Bases:
object
Methods:
getOpen
()getSave
()
-
klampt.io.resource.
console_edit
(name, value, type, description=None, world=None, frame=None)[source]¶
-
klampt.io.resource.
edit
(name, value, type='auto', description=None, editor='visual', world=None, referenceObject=None, frame=None)[source]¶ Launches an editor for the given value.
- Parameters
name (str) – the displayed name of the edited value. Can be None, in which case ‘Anonymous’ is displayed.
value – the value to be edited. Can be None, in which case ‘type’ must be specified and a default value is created.
type (str) – the type string of the value to be edited. Usually can be auto-detected from value.
description (str, optional) – a descriptive string, displayed to the person editing.
editor (str) – either ‘visual’ or ‘console’. If ‘visual’, will display a GUI for visually editing the item. If ‘console’, the user will have to type in the value.
world (WorldModel or str, optional) – either a WorldModel instance or a string specifying a world file. This is necessary for visual editing.
referenceObject (optional) – a RobotModel or other object to which the value “refers to”. For configurations and trajectories, this is the object that will be moved by the trajectory. In the case of a RigidTransform value, this can be an object or a list of objects that will be transformed by the transform.
frame (optional) – for Vector3, Matrix3, Point, Rotation, and RigidTransform types, the returned value will be given relative to this reference frame. The reference frame can be either an element of se3, a RigidObjectModel, a RobotModelLink, or a string indicating a named rigid element of the world.
- Returns
A pair (save, result) containing:
save (bool): True if the user pressed OK, False if Cancel or the close box were chosen.
result: the edited value.
- Return type
tuple
-
klampt.io.resource.
get
(name, type='auto', directory=None, default=None, doedit='auto', description=None, editor='visual', world=None, referenceObject=None, frame=None)[source]¶ Retrieve a resource of the given name from the current resources directory. If the resource does not already exist, an edit prompt will be shown, and the result from the prompt will be saved to disk under the given name.
Resources may be of type Config, Configs, IKGoal, Hold, Stance, MultiPath, Trajectory/LinearPath, and ContactPoint, or any of the basic Klampt object types, geometry types, and math types.
Resources can also be edited using
klampt_browser
and RobotPose.- Parameters
name (str) – the resource name. If type=’auto’, this is assumed to have a suffix of a file of the desired type. The name can also be nested of the form ‘group/subgroup/name.type’.
type (str) – the resource type, or ‘auto’ to determine it automatically.
directory (str, optional) – the search directory. If None, uses the current resource directory.
default (optional) – the default value if the resource does not exist on disk. If None, some arbitrary default value will be inferred.
doedit – if ‘auto’, if the resource does not exist on disk, an edit prompt will be displayed. If False, an RuntimeError will be raised if the resource does not exist on disk. If True, the user will be given an edit prompt to optionally edit the resource before this call returns.
description (str, optional) – an optional text description of the resource, for use in the edit prompt.
editor (str) – either ‘visual’ or ‘console’, determining whether to use the visual OpenGL or console editor.
world (WorldModel, optional) – for a visual editor, this world will be shown along with the item to edit. If this is a string it points to a file that will be loaded for the world (e.g., a world XML file, or a robot file).
referenceObject (optional) – to give visual reference points, one or more RobotModels, ObjectModels, Geometry3D’s, or RobotModelLink’s may be designated to follow the edited object. Currently works with Config’s / Configs’ / Trajectories / rigid transforms / rotations / points.
frame (optional) – for rigid transforms / rotations / points, the reference frame in which the quantity is represented. This is an element of se3, or an ObjectModel, or a RobotModelLink, or a string indicating a named rigid element of the world.
- Returns
If the named resource exists, loads and returns a Klampt object. If the object doesn’t exist and
doedit=True
and the user presses OK on the editor, then the object will be saved as the resourcename
. Otherwise,default
will be returned.- Return type
Klampt object or None
-
klampt.io.resource.
load
(type=None, directory=None)[source]¶ Pops up a dialog that asks the user to load a resource file of a given type.
- Parameters
type (str, optional) – The Klampt type the user should open. If not given, all resource file types are shown in the dialog as options.
directory (str, optional) – if given, overrides the current resources directory.
- Returns
a (filename,value) pair if OK is pressed, or None if the operation was canceled
- Return type
tuple or None
-
klampt.io.resource.
save
(value, type='auto', directory=None)[source]¶ Pops up a dialog that asks the user to save a resource to a file of the correct type.
- Parameters
value – a Klamp’t object that has a resource type
type (str, optional) – The Klampt type the user should open. If ‘auto’, the type is auto-detected.
directory (str, optional) – if given, overrides the current resources directory.
- Returns
the file saved to, if OK is pressed, or None if the operation was canceled.
- Return type
str or None
-
klampt.io.resource.
set
(name, value, type='auto', directory=None)[source]¶ Saves a resource to disk under the given name.
- Parameters
name (str) – the file name. Please make sure to get the right file extension. .json files are also OK for many types.
value – a Klamp’t resource (see list of compatible types in get())
type (str, optional) – The resource type. If ‘auto’, the type is determined by the file extension. If this fails, the type is determined by the value.
- Returns
True on success, False otherwise
- Return type
bool
-
klampt.io.resource.
thumbnail
(value, size, type='auto', world=None, frame=None)[source]¶ Retrieves an image of the given item, resized to the given size.
- Parameters
value – a resource type.
size (pair of ints) – the (width,height) of the thumbnail, in pixels.
type (str, optional) – the type of value
world (WorldModel, optional) – if given, the resource will be drawn with this world in the background. If the resource needs an associated object (e.g., Config, Configs, Trajectory), the object will be drawn with that given object.
frame (se3 element, optional) – not supported yet. Will eventually let you draw Points or RigidTransforms relative to some reference frame.
- Returns
A PIL Image if PIL is available, or just a raw RGBA memory buffer otherwise.
- Return type
Image or bytes
klampt.io.ros module¶
A module for converting between Klamp’t objects and ROS messages. Tested on ROS Kinetic.
The easiest way to use this is to use the toMsg(klampt_obj) and fromMsg(ros_obj) functions. However, certain objects, like JointState and JointTrajectory, have several configuration options that may need to be specified.
Another simple way to use this is to use the publisher, subscriber, object_publisher, object_subscriber, broadcast_tf, and listen_tf functions.
The C++ bindings allow you to subscribe to ROS PointCloud messages natively (Geometry3D.loadFile(“ros://…”) or SubscribeToStream()). It has not been determined whether using the functions in this module with rospy interferes with those bindings.
Classes:
|
You shouldn’t need to use this explicitly. |
|
You shouldn’t need to use this explicitly. |
Functions:
|
Broadcasts Klampt frames to the ROS tf module. |
|
General conversion from ROS messages to corresponding Klamp’t objects. |
|
Fills in some information about a Klampt SimRobotSensor, GLViewport, or Viewport using a ROS CameraInfo message. |
|
From ROS Float32MultiArray to Klamp’t Config |
|
From ROS JointState to Klamp’t robot configuration. |
|
Returns a Klamp’t Trajectory or RobotTrajectory for a JointTrajectory message. |
|
From a ROS Mesh to a Klampt TriangleMesh |
|
Converts a ROS Path to a Klamp’t SE3Trajectory. |
|
From ROS Point to Klamp’t point |
|
From a ROS PointCloud2 to a Klampt PointCloud |
|
From ROS Pose to Klamp’t se3 element |
|
From ROS PoseStamped to Klamp’t se3 element |
|
From ROS Quaternion to Klamp’t so3 element |
|
From tf.Transform to Klampt se3 element |
|
From ROS Vector3 to Klamp’t point |
|
Reads Klampt frames from the ROS tf module. |
|
Convenience function. |
|
Convenience function. |
|
Convenience function. |
|
|
|
Convenience function. |
|
General conversion from Klamp’t objects to corresponding ROS messages. |
|
Converts a Klampt SimRobotSensor, GLViewport, or Viewport to a ROS CameraInfo message. |
|
|
|
Returns a ROS JointState message for a Klamp’t robot or controller. |
|
Returns a ROS JointTrajectory message for a Klamp’t Trajectory or RobotTrajectory. |
|
From a Klampt Geometry3D or TriangleMesh to a ROS Mesh |
|
Converts a Klampt SE3Trajectory, SO3Trajectory, or 2D or 3D Trajectory to a ROS Path. |
|
From Klamp’t point to ROS Point |
|
Converts a Klampt Geometry3D or PointCloud to a ROS PointCloud2 message. |
|
From Klamp’t se3 element to ROS Pose |
|
From Klamp’t se3 element to ROS PoseStamped |
|
From Klamp’t so3 element to ROS Quaternion |
|
Converts a sensor’s measurements to a ROS message(s). |
|
|
|
From Klampt se3 element to ROS Transform |
|
From Klamp’t point to ROS Vector3 |
-
class
klampt.io.ros.
KlamptROSCameraPublisher
(topic, frame_id, frame_prefix, *args, **kwargs)[source]¶ Bases:
object
You shouldn’t need to use this explicitly. Use
object_publisher()
instead.Methods:
publish
(camera)Publishes a Klamp’t camera data to the topics:
-
publish
(camera)[source]¶ Publishes a Klamp’t camera data to the topics:
[topic]/rgb/camera_info
[topic]/rgb/image_rect_color
[topic]/depth_registered/camera_info
[topic]/depth_registered/image_rect
- Parameters
camera (SimRobotSensor) – an updated sensor of ‘CameraSensor’ type.
-
-
class
klampt.io.ros.
KlamptROSPublisher
(converter, *args, **kwargs)[source]¶ Bases:
rospy.topics.Publisher
You shouldn’t need to use this explicitly. Use
publisher()
orobject_publisher()
instead.Methods:
publish
(klampt_obj[, header])Publishes a Klamp’t object to the advertised topic.
-
klampt.io.ros.
broadcast_tf
(broadcaster, klampt_obj, frameprefix='klampt', root='world', stamp=0.0)[source]¶ Broadcasts Klampt frames to the ROS tf module.
- Parameters
broadcaster (tf.TransformBroadcaster) – the tf broadcaster
klampt_obj – the object to publish. Can be WorldModel, Simulator, RobotModel, SimRobotController, anything with a getTransform or getCurrentTransform method, or se3 element
frameprefix (str) – the name of the base frame for this object
root (str) – the name of the TF world frame.
Note
If klampt_obj is a Simulator or SimRobotController, then its corresponding model will be updated.
-
klampt.io.ros.
fromMsg
(ros_obj, *args, **kwargs)[source]¶ General conversion from ROS messages to corresponding Klamp’t objects.
-
klampt.io.ros.
from_CameraInfo
(ros_ci, klampt_obj)[source]¶ Fills in some information about a Klampt SimRobotSensor, GLViewport, or Viewport using a ROS CameraInfo message. Modifies the object in-place.
-
klampt.io.ros.
from_JointState
(ros_js, robot, joint_link_indices=None)[source]¶ From ROS JointState to Klamp’t robot configuration. The Klamp’t robot must be given, and any indices not specified in ros_js are kept at their current values
- Parameters
ros_js (sensor_msgs.msg.JointState) – the JointState object
robot (RobotModel) – the robot
joint_link_indices (dict, optional) – if given, maps ROS joint names to Klampt link indices. Default uses the Klamp’t link names.
- Returns
a pair (config,velocity,effort). Each item may be None if the JointState message does not contain position, velocity, or effort info.
- Return type
tuple
-
klampt.io.ros.
from_JointTrajectory
(ros_traj, robot=None, joint_link_indices=None)[source]¶ Returns a Klamp’t Trajectory or RobotTrajectory for a JointTrajectory message.
- Parameters
ros_traj (sensor_msgs.msg.JointTrajectory) – the JointTrajectory object
robot (RobotModel) – the robot, optional
joint_link_indices (dict, optional) – if given, maps ROS joint names to Klampt link indices. Default uses the Klamp’t link names.
-
klampt.io.ros.
from_Path
(ros_path)[source]¶ Converts a ROS Path to a Klamp’t SE3Trajectory.
Times are assigned relative to header’s time stamp.
-
klampt.io.ros.
listen_tf
(listener, klampt_obj, frameprefix='klampt', root='world', onerror=None)[source]¶ Reads Klampt frames from the ROS tf module.
- Parameters
listener (tf.TransformListener) – the tf listener
klampt_obj –
the object to update. Can be WorldModel, RobotModel, anything with a setTransform or setCurrentTransform method, or None (in the latter case, a se3 object will be returned).
Note
RobotModel configurations will not be changed, just the link transforms.
frameprefix (str) – the name of the base frame for this object
root (str) – the name of the TF world frame.
onerror (str or None) – either ‘raise’ in which case a tf exception is raised, ‘print’, in which case the error is printed, or None, in which case any exception is silently ignored.
-
klampt.io.ros.
object_publisher
(topic, klampt_object, convert_kwargs=None, **kwargs)[source]¶ Convenience function. If klampt_object is an object, this sets up the publisher to be of the correct type. You can then call publish on the returned publisher using the same klampt_object (or another compatible Klampt objects).
SimRobotSensors (particularly, cameras) can be published to multiple topics of the form [topic]/[subtopic].
- Returns
KlamptROSPublisher
-
klampt.io.ros.
object_subscriber
(topic, klampt_obj, convert_kwargs=None, **kwargs)[source]¶ Convenience function. Every time a message arrives on the ROS topic, the given klampt object is updated.
Only valid for:
points / transforms provided as lists
Config (Float32MultiArray or JointState messages)
RobotModel (JointState messages)
SimRobotController (JointState messages)
Trajectory (JointTrajectory messages)
- Returns
rospy.Subscriber
-
klampt.io.ros.
publisher
(topic, klampt_type, convert_kwargs=None, ros_type=None, **kwargs)[source]¶ Convenience function. The publisher can be called in the form pub.publish(klampt_obj), which will convert a klampt_obj to a ROS message before publishing to a topic.
- Returns
KlamptROSPublisher
-
klampt.io.ros.
publisher_SimRobotSensor
(topic, klampt_sensor, convert_kwargs=None, **kwargs)[source]¶
-
klampt.io.ros.
subscriber
(topic, klampt_type, callback, convert_kwargs=None, **kwargs)[source]¶ Convenience function. The subscriber automatically converts ROS messages to a Klampt type to be passed to the callback.
- Returns
rospy.Subscriber
-
klampt.io.ros.
toMsg
(klampt_obj, *args, **kwargs)[source]¶ General conversion from Klamp’t objects to corresponding ROS messages.
-
klampt.io.ros.
to_CameraInfo
(klampt_obj)[source]¶ Converts a Klampt SimRobotSensor, GLViewport, or Viewport to a ROS CameraInfo message.
-
klampt.io.ros.
to_JointState
(robot, q='current', dq='current', effort=None, indices='auto', link_joint_names=None)[source]¶ Returns a ROS JointState message for a Klamp’t robot or controller.
- Parameters
robot (RobotModel or SimRobotController) – the robot
q (str or Config, optional) –
either ‘current’, ‘commanded’, ‘sensed’, ‘actual’, None, or a configuration of size robot.numLinks().
’commanded’, ‘sensed’, and ‘actual’ are available only when robot is a SimRobotController.
dq (str or Config, optional) –
either ‘current’, ‘commanded’, ‘sensed’, ‘actual’, None, or a joint velocity vector of size robot.numLinks()
’commanded’, ‘sensed’, and ‘actual’ are available only when robot is a SimRobotController.
effort (str or Config, optional) – either ‘commanded’, sensed’, ‘actual’, None, or a torque vector of size robot.numDrivers().
indices (str or list of int) – if ‘auto’, all elements are set. Otherwise, only these indices are set.
link_joint_names (list of str, optional) – if given, the i’th link is mapped to the ROS joint name link_joint_names[i].
-
klampt.io.ros.
to_JointTrajectory
(klampt_traj, indices='auto', link_joint_names=None)[source]¶ Returns a ROS JointTrajectory message for a Klamp’t Trajectory or RobotTrajectory.
- Parameters
klampt_traj (Trajectory or RobotTrajectory) – the trajectory
indices (str or list of ints) – the indices to send (only valid with RobotTrajectory)
link_joint_names (list of str, optional) – if given, the i’th link is mapped to the ROS joint name link_joint_names[i].
-
klampt.io.ros.
to_Path
(klampt_path, start_time='now', frame='1')[source]¶ Converts a Klampt SE3Trajectory, SO3Trajectory, or 2D or 3D Trajectory to a ROS Path.
start_time can be ‘now’ or a rospy.Time object.
frame is the frame_id in the object’s headers (1 means global frame).
-
klampt.io.ros.
to_PointCloud2
(klampt_pc, frame='0', stamp='now')[source]¶ Converts a Klampt Geometry3D or PointCloud to a ROS PointCloud2 message.
If it’s a Geometry3D, the points are first transformed by the current transform.
frame is the ROS frame in the header. Default ‘0’ indicates no frame.
stamp is the ROS timestamp, or ‘now’, or a numeric value.
-
klampt.io.ros.
to_PoseStamped
(klampt_se3, stamp='now')[source]¶ From Klamp’t se3 element to ROS PoseStamped
-
klampt.io.ros.
to_SensorMsg
(klampt_sensor, frame=None, frame_prefix='klampt', stamp='now')[source]¶ Converts a sensor’s measurements to a ROS message(s).
Special types are CameraSensor, ForceTorqueSensor, and LaserRangeSensor.
CameraSensor is converted to up to three messages: CameraInfo, Image (rgb, optional), and Image (depth, optional).
ForceTorqueSensor is converted to a WrenchStamped.
Generic sensors are converted to a Float32MultiArray.
- Parameters
klampt_sensor (SimRobotSensor) – the sensor
frame (str, optional) – if given, this is the frame_id used in the ROS message(s). Otherwise, the id is determined automatically.
frame_prefix (str, optional) – if frame is not given, this is the prefix used in the automatic frame_id assignment (see below)
stamp (str, float, or rospy.Time, optional) – can be ‘now’, a float, or a rospy.Time. Will be set in the ROS message header.
The ROS
frame_id
is set as follows:If frame!=None, then
frame_id=frame
.If frame==None and frame_prefix==None, then
frame_id = [robot_name]/[sensor_name]
.Otherwise,
frame_id = [frame_prefix]/[robot_name]/[sensor_name]
.
klampt.io.numpy_convert module¶
Conversions to and from Numpy objects; makes numerical computations much more convenient.
Functions:
|
Converts a numpy array or multiple numpy arrays to a Klamp’t object. |
|
Converts a Klamp’t object to a numpy array or multiple numpy arrays. |
Data:
set of supported types for numpy I/O |
-
klampt.io.numpy_convert.
from_numpy
(obj, type='auto', template=None)[source]¶ Converts a numpy array or multiple numpy arrays to a Klamp’t object.
Supports:
lists and tuples
RigidTransform: accepts a 4x4 homogeneous coordinate transform
Matrix3, Rotation: accepts a 3x3 matrix.
Configs
Trajectory: accepts a pair (times,milestones)
TriangleMesh: accepts a pair (verts,indices)
PointCloud: accepts a n x (3+k) array, where k is the # of properties
VolumeGrid: accepts a triple (bmin,bmax,array)
Geometry3D: accepts a pair (T,geomdata)
-
klampt.io.numpy_convert.
supportedTypes
= {'Config', 'Configs', 'Geometry3D', 'Matrix3', 'Point', 'PointCloud', 'RigidTransform', 'Rotation', 'Trajectory', 'TriangleMesh', 'Vector3', 'VolumeGrid'}¶ set of supported types for numpy I/O
-
klampt.io.numpy_convert.
to_numpy
(obj, type='auto')[source]¶ Converts a Klamp’t object to a numpy array or multiple numpy arrays.
Supports:
lists and tuples
RigidTransform: returned as 4x4 homogeneous coordinate transform
Matrix3, Rotation: returned as 3x3 matrix. Can’t be determined with ‘auto’, need to specify type=’Matrix3’ or ‘Rotation’.
Configs
Trajectory: returns a pair (times,milestones)
TriangleMesh: returns a pair (verts,indices)
PointCloud: returns a n x (3+k) array, where k is the # of properties
VolumeGrid: returns a triple (bmin,bmax,array)
Geometry3D: returns a pair (T,geomdata)
If you want to get a transformed point cloud or mesh, you can pass in a Geometry3D as the obj, and its geometry data type as the type.
klampt.io.open3d_convert module¶
Conversions to and from the Open3D library.
Open3D is useful for doing various point cloud processing routines. It can be installed using pip as follows:
pip install open3d-python
Functions:
|
Converts open3d geometry to a Klamp’t geometry. |
|
Converts Klamp’t geometry to an open3d geometry. |
-
klampt.io.open3d_convert.
to_open3d
(obj)[source]¶ Converts Klamp’t geometry to an open3d geometry.
Geometry3D objects are converted applying the current transform.
If the VolumeGrid is considered to be an occupancy grid (all values between 0 and 1), then it is converted to a VoxelGrid containing a voxel for any positive items. If it is considered to be a SDF, then it contains a voxel of any non-positive items. There may be issues converting from VolumeGrids whose cells are non-cubic.
klampt.io.povray module¶
Functions:
|
|
|
This is a convenient function that calls add_light multiple times |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
If you know object will not change over time, use this function to tell povray. |
|
Renders the provided scene description with POV-Ray. |
|
This will setup your properties dict to not call povray, but rather just generate a render script. |
|
This will setup your properties dict to call povray to give you an image |
|
Override default color-only material with more advanced material specification in povray |
|
Convert a frame in klampt visualization to a povray script (or render to an image) |
|
-
klampt.io.povray.
add_light
(properties, pos, tgt=None, color=[1.0, 1.0, 1.0], spotlight=False, radius=15.0, falloff=20.0, tightness=10.0, area=0.0, sample=9, adaptive=True, jitter=True)[source]¶
-
klampt.io.povray.
add_multiple_lights
(properties, object, dist, numLight, gravity=[0, 0, - 9.81], tgt=None, color=[1.0, 1.0, 1.0], spotlight=False, radius=15.0, falloff=20.0, tightness=10.0, area=0.0, sample=9, adaptive=True, jitter=True)[source]¶ This is a convenient function that calls add_light multiple times
-
klampt.io.povray.
mark_transient
(properties, object, transient=False)[source]¶ If you know object will not change over time, use this function to tell povray. This saves computation.
-
klampt.io.povray.
render_povstring
(string, outfile=None, height=None, width=None, quality=None, antialiasing=None, remove_temp=True, show_window=False, tempfile=None, includedirs=None, output_alpha=False, render=True)[source]¶ Renders the provided scene description with POV-Ray.
- Parameters
string (str) – A string representing valid POVRay code. Typically, it will be the result of
scene(*objects)
outfile (str, optional) – Name of the PNG file for the output. If outfile is None, a numpy array is returned (if numpy is installed). If outfile is ‘ipython’ and this function is called last in an IPython notebook cell, this will print the result in the notebook.
height (int, optional) – height in pixels
width (int, optional) – width in pixels
output_alpha (bool, optional) – If true, the background will be transparent, rather than the default black background. Note that this option is ignored if rendering to a numpy array, due to limitations of the intermediate ppm format.
-
klampt.io.povray.
render_to_animation
(properties, folder)[source]¶ This will setup your properties dict to not call povray, but rather just generate a render script.
-
klampt.io.povray.
render_to_file
(properties, file)[source]¶ This will setup your properties dict to call povray to give you an image
-
klampt.io.povray.
set_material
(properties, object, finish, normal)[source]¶ Override default color-only material with more advanced material specification in povray
- Parameters
finish – a vapory.Finish object
normal – a vapory.Normal object
setting up these two material parameters is not easy and requires artistic tuning. TODO: create a preset library of materials and convenient functions.
-
klampt.io.povray.
to_povray
(vis, world, properties={})[source]¶ Convert a frame in klampt visualization to a povray script (or render to an image)
- Parameters
vis – sub-class of GLProgram
world – sub-class of WorldModel
properties – some additional information that povray can take but does not map to anything in klampt.
- Note::
Do not modify properties, use the convenience functions that I provide below (after this function). These take the form
render_to_x
andadd_x
.
Module contents¶
-
klampt.io.
DetachFromStream
(protocol, name)[source]¶ Unsubscribes from a stream previously subscribed to via
SubscribeToStream()
- Parameters
protocol (str) –
name (str) –
- Returns
- Return type
bool
-
klampt.io.
ProcessStreams
(*args)[source]¶ Does some processing on stream subscriptions.
ProcessStreams (protocol): bool
ProcessStreams (): bool
- Parameters
protocol (str) – either name the protocol to be updated, or “all” for updating all subscribed streams
Returns: (bool): True if any stream was updated.
-
klampt.io.
SubscribeToStream
(*args)[source]¶ Subscribes a Geometry3D to a stream.
SubscribeToStream (g,protocol,name,type): bool
SubscribeToStream (g,protocol,name): bool
- Parameters
g (Geometry3D) – the geometry that will be updated
protocol (str) – only “ros” accepted for now.
name (str) – the name of the stream, i.e., ROS topic.
type (str, optional) – If provided, specifies the format of the data to be subscribed to. If not, tries to determine the type automatically.
Only ROS point clouds (PointCloud2) are supported for now. Note that you can also call Geometry3D.loadFile(“ros://[ROS_TOPIC]”) or Geometry3D.loadFile(“ros:PointCloud2//[ROS_TOPIC]”) to accomplish the same thing.
TODO: It has not yet been determined whether this interferes with Rospy, i.e., klampt.io.ros.
Returns: (bool): True if successful.
-
klampt.io.
ThreeJSGetScene
(arg1)[source]¶ Exports the WorldModel to a JSON string ready for use in Three.js.
- Parameters
arg1 (
WorldModel
) –- Returns
- Return type
str
-
klampt.io.
ThreeJSGetTransforms
(arg1)[source]¶ Exports the WorldModel to a JSON string ready for use in Three.js.
- Parameters
arg1 (
WorldModel
) –- Returns
- Return type
str
-
klampt.io.
WaitForStream
(protocol, name, timeout)[source]¶ Waits up to timeout seconds for an update on the given stream.
- Parameters
protocol (str) –
name (str) –
timeout (float) –
- Returns
- Return type
bool
- Returns
True if the stream was updated.
- Return type
(bool)
-
klampt.io.
fromJson
(jsonobj, type='auto')[source]¶ Converts from a JSON structure to a Klamp’t object of the appropriate type.
Note: a JSON structure can be created from a JSON string using the
json.loads()
function in the Python builtinjson
module.Not all objects are supported yet, notably geometry-related objects and world entities.
-
klampt.io.
load
(type, fn)[source]¶ General-purpose load of an arbitrary Klampt object from a file or URL.
An exception is raised if there is an error loading or parsing the file. Possible exception types include IOError, ValueError, and HTTPError.
- Parameters
type (str) – a Klamp’t type, ‘json’, or ‘auto’
fn (str) – a filename.
- Returns
Klamp’t object
-
klampt.io.
read
(type, text)[source]¶ General-purpose read of an arbitrary Klampt object from a str.
- Parameters
type (str) – Either the Klamp’t type, or ‘json’. Future versions may support ‘xml’ but this is not supported right now. ‘auto’ may not be specified.
text (str) – A string containing the object data.
- Returns
Klamp’t object
-
klampt.io.
save
(obj, type, fn)[source]¶ General-purpose save of an arbitrary Klampt object to a file.
This also works with RobotModel, RigidObjectModel, and TerrainModel (which don’t work with load).
- Parameters
obj – a Klamp’t object.
type (str) – the Klampt type, ‘json’, or ‘auto’
fn (str) – a file name
- Returns
True if successful.
- Return type
bool
-
klampt.io.
toJson
(obj, type='auto')[source]¶ Converts from a Klamp’t object to a JSON-compatible structure.
The resulting structure can be converted to a JSON string using
json.dumps()
in the Python builtinjson
module.Not all objects are supported yet, notably geometry-related objects and world entities.
- Parameters
obj – A Klamp’t object.
type (str, optional) – the type of the object (see
types
) If ‘auto’ (default), the type of the object is inferred automatically.