klampt.vis.ipython package

Basic classes

KlamptWidget(**kwargs)

A Python interface with the Jupyter notebook frontend.

Playback(**kwargs)

A play/pause/reset widget associated with a KlamptWidget.

EditPoint([value, min, max, labels, ...])

Creates a Jupyter widget for interactive editing of an xyz point

EditTransform([value, xmin, xmax, labels, ...])

Creates a Jupyter widget for interactive editing of a rigid transform point

EditConfig(robot[, klampt_widget, ghost, ...])

Creates a Jupyter widget for interactive editing of the robot's configuration.

Submodules

klampt.vis.ipython._version module

klampt.vis.ipython.widgets module

A Jupyter Notebook interface to Klampt.

Examples

Basic usage:

from klampt import *
from klampt.vis.ipython import KlamptWidget
from IPython.display import display

world = WorldModel()
... #set up the world...
kvis = KlamptWidget(world,width=800,height=640)
display(kvis)   # This pops up a window in Jupyter

Immedate changes can be made using the methods in KlamptWidget:

kvis.addText(name="text_id",text="hello",position=(10,10))
kvis.addSphere(x=0,y=1.5,z=0,r=0.4)

Change the configuration of things in the world, and then call update() to see the changes:

robot = world.robot(0)
q = robot.getConfig()
q[2] += 1.0
robot.setConfig(q)
kvis.update()   # The previous changes are not made until this is called

If you completely change the number of objects in the world, or their underlying geometries, you will need to call w.setWorld(world) again. This is relatively expensive, so try not to do it too often:

world.readElement(...)
kvis.setWorld(world)
class klampt.vis.ipython.widgets.KlamptWidget(**kwargs: Any)[source]

Bases: DOMWidget

A Python interface with the Jupyter notebook frontend. The API is similar to the vis module, but has a reduced and slightly modified set of hooks.

width

the width of the view in pixels (public property)

Type:

Int

height

the height of the view in pixels (public property)

Type:

Int

scene

the scene JSON message (private)

Type:

Dict

transforms

the transforms JSON message (private)

Type:

Dict

rpc

the rpc JSON message (private)

Type:

Dict

_camera

the incoming camera JSON message from the frontend (private)

Type:

Dict

camera

the outgoing camera JSON message (private)

Type:

Dict

drawn

the incoming drawn message from the frontend (private)

Type:

Int

events

incoming events from the frontend (private)

Type:

List

world

the WorldModel isinstance

Type:

WorldModel

_extras

a dict mapping extra item names to (type,threejs_items) pairs

Type:

dict

_rpc_calls

a list of pending RPC calls between beginRpc() and endRpc()

Type:

list

_aggregating_rpc

non-zero if between beginRpc and endRpc

Type:

int

Public constructor

width

An int trait.

height

An int trait.

scene

An instance of a Python dict.

One or more traits can be passed to the constructor to validate the keys and/or values of the dict. If you need more detailed validation, you may use a custom validator method.

Changed in version 5.0: Added key_trait for validating dict keys.

Changed in version 5.0: Deprecated ambiguous trait, traits args in favor of value_trait, per_key_traits.

transforms

An instance of a Python dict.

One or more traits can be passed to the constructor to validate the keys and/or values of the dict. If you need more detailed validation, you may use a custom validator method.

Changed in version 5.0: Added key_trait for validating dict keys.

Changed in version 5.0: Deprecated ambiguous trait, traits args in favor of value_trait, per_key_traits.

events

An instance of a Python list.

drawn

An int trait.

rpc

An instance of a Python dict.

One or more traits can be passed to the constructor to validate the keys and/or values of the dict. If you need more detailed validation, you may use a custom validator method.

Changed in version 5.0: Added key_trait for validating dict keys.

Changed in version 5.0: Deprecated ambiguous trait, traits args in favor of value_trait, per_key_traits.

setWorld(world)[source]

Resets the world to a new WorldModel object.

update()[source]

Updates the view with changes to the world. Unlike setWorld(), this only pushes the geometry transforms, so it’s much faster.

clear()[source]

Clears everything from the visualization, including the world.

clearExtras()[source]

Erases all ghosts, lines, points, text, etc from the visualization, but keeps the world.

add(name, item, type='auto', **kwargs)[source]

Adds the item to the world, and returns a list of identifiers associated with it.

Parameters:
  • name (str) – the name of the item, which will be used to refer to it from now on

  • item – the item data

  • type (str, optional) – either ‘auto’ (default) or a string describing the type of item, which can help disambiguate some types like ‘Config’ vs ‘Vector3’ (see below)

  • kwargs – possible attributes. Examples include color, size, length, and width

Supports items of type:

  • Config, as a ghost (list, same size as robot)

  • Configs, as a set of ghosts (list of lists, same size as robot)

  • Vector3, drawn as a sphere (3-list)

  • RigidTransform, drawn as an xform (pair of 9-list and 3-list)

  • Configs, drawn as a polyline (list of 3-lists)

  • Trajectory, drawn either as:

    • a polyline (3D Trajectory objects),

    • set of milestones (Trajectory or RobotTrajectory objects)

    • a polyline + set of rigid transform milestones (SE3Trajectory objects)

  • WorldModel, but only one world at once is supported (same as setWorld).

remove(name)[source]

Removes a certain named target, e.g. a ghost, line, text, etc.

resetCamera()[source]

Resets the camera to the original view

getCamera()[source]

Returns a data structure representing the current camera view

setCamera(cam)[source]

Sets the current camera view

hide(name, value=False)[source]

Changes the visibility status of a certain named target

setColor(target, r, g, b, a=1.0)[source]

Sets the given RobotModel, RobotModelLink, named link, indexed link, or object name to some RGBA color (each channel in the range [0,1]).

setTransform(name, R=[1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0], t=[0, 0, 0], matrix=None)[source]

Sets the transform of the target object. If matrix is given, it’s a 16-element array giving the 4x4 homogeneous transform matrix, in row-major format. Otherwise, R and t are the 9-element klampt.so3 rotation and 3-element translation.

addGhost(name='ghost', robot=0)[source]

Adds a ghost configuration of the robot that can be posed independently. name can be set to identify multiple ghosts.

The identifier of the ghost in the three.js scene is prefixname + robot.getName(), and all the links are identified by prefixname + link name.

getRobotConfig(robot=0)[source]

A convenience function. Gets the robot’s configuration in the visualization world.

setGhostConfig(q, name='ghost', robot=0)[source]

Sets the configuration of the ghost to q. If the ghost is named, place its name in prefixname.

addText(name='HUD_Text1', text='', position=None)[source]

Adds a new piece of text displayed on the screen. name is a unique identifier of the text, and position=(x,y) are the coordinates of upper left corner of the the text, in percent.

addSphere(name='Sphere1', x=0, y=0, z=0, r=1)[source]

Adds a new sphere to the world with the given x,y,z position and radius r.

addLine(name='Line1', x1=0, y1=0, z1=0, x2=1, y2=1, z2=1)[source]

Adds a new line segment to the world connecting point (x1,y1,z1) to (x2,y2,z2)

addXform(name='Xform1', length=0.2, width=1)[source]

Adds a new transform widget to the world with the given line length and width

addPolyline(name='Line1', pts=[])[source]

Adds a new polygonal line segment to the world connecting the given list of 3-tuples

addTriangle(name='Tri1', a=(0, 0, 0), b=(1, 0, 0), c=(0, 1, 0))[source]

Adds a new triangle with vertices a,b,c. a,b, and c are 3-lists or 3-tuples.

addQuad(name='Quad1', a=(0, 0, 0), b=(1, 0, 0), c=(1, 1, 0), d=(0, 1, 0))[source]

Adds a new quad (in CCW order) with vertices a,b,c,d. a,b,c and d are 3-lists or 3-tuples.

addBillboard(name='Billboard', image=[[]], format='auto', crange=[0, 1], colormap='auto', filter='linear', size=(1, 1))[source]

Adds a 2D billboard to the world. The image is a 2D array of values, which is texure-mapped to a quad.

By default, the billboard is centered at (0,0,0) and faces up. To modify its location or orientation, call setTransform on it.

Parameters:
  • name (str) – the name used to refer to this item

  • image (list of lists or str) – a 2D array of single-channel values, (r,g,b) tuples, or (r,g,b,a) tuples. Rows are listed top to bottom, rows from left to right. Or, can also be a URL.

  • format (str, optional) –

    The image format. Can be:

    • ’auto’: autodetect the type from the image. If the image contains values, the format is ‘value’.

    • ’value’: the values are mapped through either ‘opacity’, ‘rainbow’, or gradient color mapping.

    • ’rgb’: if the image contains values, they are interpreted as RGB values packed in 24 bit integers. Otherwise, the first 3 channels of the tuple are used.

    • ’rgba’: if the image contains values, they are interpreted as RGB values packed in 32 bit integers. Otherwise, they are assumed to be (r,g,b,a) tuples

  • crange (pair of numbers, optional) – the range of the given values / channels. By default [0,1], but if you are using uint8 encoding this should be set to [0,255].

  • colormap (optional) –

    how the color of the billboard should be set based on the image. Valid values are:

    • ’auto’: if the image contains values, the gradient ((0,0,0),(1,1,1)) is used. Otherwise ‘replace’ is used.

    • (color1,color2): interpolates between the two given (r,g,b) or (r,g,b,a) tuples.

    • ’opacity’: sets the alpha channel only.

    • ’modulate’: the value / rgb / rgba texture modulates the billboard color as set by setColor

  • filter (str, optional) – how values between pixels are interpolated. Either ‘nearest’ or ‘linear’.

  • size (pair of numbers, optional) – the (width,height) pair of the billboard, in world units.

beginRpc(strict=False)[source]

Begins collecting a set of RPC calls to be sent at once, which is a bit faster than doing multiple addX or setX calls.

Usage:

widget.beginRpc()
widget.addX()
...
widget.setX()
widget.endRpc()  #this sends all the messages at once
endRpc(strict=False)[source]

Ends collecting a set of RPC calls to be sent at once, and sends the accumulated message

on_event(e)[source]
klampt.vis.ipython.widgets.EditConfig(robot, klampt_widget=None, ghost=None, link_selector='slider', link_subset=None, callback=None)[source]

Creates a Jupyter widget for interactive editing of the robot’s configuration.

Parameters:
  • robot (RobotModel) – the robot to edit

  • klampt_widget (KlamptWidget, optional) – the KlamptWidget visualization to update, or None if you don’t want to visualize the editing.

  • ghost (str, optional) – if not None, this is the name of the ghost that should be updated. Widget updates are shown on the given ghost rather than the actual robot. To get the ghost configuration, you’ll need to update the callback.

  • link_selector (str) –

    how to select links. Either:

    • ’slider’: uses an IntSlider widget

    • ’dropdown’: uses a Dropdown widget

    • ’all’: shows sliders for all links

  • link_subset (list, optional) – if given, only a subset of links are shown. Otherwise, only non-fixed links are shown.

  • callback (function, optional) – a function callback(index,q) called when a DOF’s value has changed.

Returns:

a widget to be displayed as you like

Return type:

VBox

klampt.vis.ipython.widgets.EditPoint(value=None, min=None, max=None, labels=None, klampt_widget=None, point_name='edited_point', point_radius=0.05, callback=None)[source]

Creates a Jupyter widget for interactive editing of an xyz point

Parameters:
  • value (list of 3 floats, optional) – the initial value of the point. If given, this must be a list and will hold the edited values.

  • min/max (list of 3 floats, optional) – the minimum and maximum of the point

  • labels (list of strs, optional) – if given, the labels of each channel

  • klampt_widget (KlamptWidget, optional) – the KlamptWidget visualization to update, or None if you don’t want to visualize the point.

  • point_name (str, optional) – the name of the point in the visualization world to edit.

  • point_radius (float, optional) – the radius of the visualized point.

  • callback (function ,optional) – a function callback(xyz) called when a DOF’s value has changed.

Returns:

a widget that can be displayed as you like

Return type:

VBox

klampt.vis.ipython.widgets.EditTransform(value=None, xmin=None, xmax=None, labels=None, klampt_widget=None, xform_name='edited_xform', axis_length=0.2, axis_width=1, callback=None)[source]

Creates a Jupyter widget for interactive editing of a rigid transform point

Parameters:
  • value (klampt.se3 element) – the initial value of the transform (klampt.se3 element). If given as (R,t), the R and t members must be lists and will hold the edited values.

  • xmin/xmax (list of 3 floats, optional) – the minimum and maximum of the translation

  • labels (list of strs, optional) – if given, the labels of roll,pitch,yaw and x,y,z

  • klampt_widget (KlamptWidget, optional) – the KlamptWidget visualization to update, or None if you don’t want to visualize the point.

  • xform_name (str, optional) – the name of the xform in the visualization world to edit.

  • axis_length,axis_width (float, optional) – the length and width of the visualized widget

  • callback (function, optional) – a function callback((R,t)) called when a DOF’s value has changed.

Returns:

a widget that can be displayed as you like

Return type:

VBox

class klampt.vis.ipython.widgets.Playback(**kwargs: Any)[source]

Bases: VBox

A play/pause/reset widget associated with a KlamptWidget.

klampt_widget

the widget that should be updated after each advance call

Type:

KlamptWidget, optional

advance

a function to be called for each new frame.

Type:

function, optional

pause

a function to be called when pause is clicked.

Type:

function, optional

reset

a function to be called when reset is clicked.

Type:

function, optional

maxframes

the maximum number of frames. If None, this is unlimited.

Type:

int, optional

framerate

number of frames per second desired. If None, frames are run as quickly as possible

Type:

int, optional

quiet

if True, suppresses output during play

Type:

bool

playbutton, stepbutton, pausebutton, resetbutton

the Button widgets

Type:

Button

Public constructor

stop()[source]

Stops any ongoing playback

Module contents

Defines a Jupyter Notebook interface to Klampt.