Miscellaneous Submodules

klampt.math.geodesic module

Common interface for geodesic interpolation and distances on manifolds.

Classes:

GeodesicSpace()

Base class for geodesic spaces.

CartesianSpace(d)

The standard geodesic on R^d

MultiGeodesicSpace(*components)

This forms the cartesian product of one or more GeodesicSpace's.

SO2Space()

The space of 2D rotations SO(2).

SO3Space()

The space of 3D rotations SO(3).

SE3Space()

The space of 3D rigid transforms SE(3).

class klampt.math.geodesic.GeodesicSpace[source]

Bases: object

Base class for geodesic spaces. A geodesic is equipped with a a geodesic (interpolation via the interpolate(a,b,u) method), a natural arc length distance metric (distance(a,b) method), an intrinsic dimension (intrinsicDimension() method), an extrinsic dimension (extrinsicDimension() method), and natural tangents (the difference and integrate methods).

Methods:

intrinsicDimension()

extrinsicDimension()

distance(a, b)

interpolate(a, b, u)

difference(a, b)

For Lie groups, returns a difference vector that, when integrated would get to a from b.

integrate(x, d)

For Lie groups, returns the point that would be arrived at via integrating the difference vector d starting from x.

intrinsicDimension()[source]
extrinsicDimension()[source]
distance(a, b)[source]
interpolate(a, b, u)[source]
difference(a, b)[source]

For Lie groups, returns a difference vector that, when integrated would get to a from b. In Cartesian spaces it is a-b. In other spaces, it should be d/du interpolate(b,a,u) at u=0.

integrate(x, d)[source]

For Lie groups, returns the point that would be arrived at via integrating the difference vector d starting from x. Must satisfy the relationship a = integrate(b,difference(a,b)). In Cartesian spaces it is x+d

class klampt.math.geodesic.CartesianSpace(d)[source]

Bases: GeodesicSpace

The standard geodesic on R^d

Methods:

intrinsicDimension()

extrinsicDimension()

intrinsicDimension()[source]
extrinsicDimension()[source]
class klampt.math.geodesic.MultiGeodesicSpace(*components)[source]

Bases: GeodesicSpace

This forms the cartesian product of one or more GeodesicSpace’s. Distances are simply added together.

Methods:

intrinsicDimension()

extrinsicDimension()

split(x)

join(xs)

distance(a, b)

interpolate(a, b, u)

difference(a, b)

For Lie groups, returns a difference vector that, when integrated would get to a from b.

integrate(x, diff)

For Lie groups, returns the point that would be arrived at via integrating the difference vector d starting from x.

intrinsicDimension()[source]
extrinsicDimension()[source]
split(x)[source]
join(xs)[source]
distance(a, b)[source]
interpolate(a, b, u)[source]
difference(a, b)[source]

For Lie groups, returns a difference vector that, when integrated would get to a from b. In Cartesian spaces it is a-b. In other spaces, it should be d/du interpolate(b,a,u) at u=0.

integrate(x, diff)[source]

For Lie groups, returns the point that would be arrived at via integrating the difference vector d starting from x. Must satisfy the relationship a = integrate(b,difference(a,b)). In Cartesian spaces it is x+d

class klampt.math.geodesic.SO2Space[source]

Bases: GeodesicSpace

The space of 2D rotations SO(2).

Methods:

intrinsicDimension()

extrinsicDimension()

distance(a, b)

interpolate(a, b, u)

difference(a, b)

For Lie groups, returns a difference vector that, when integrated would get to a from b.

integrate(x, d)

For Lie groups, returns the point that would be arrived at via integrating the difference vector d starting from x.

intrinsicDimension()[source]
extrinsicDimension()[source]
distance(a, b)[source]
interpolate(a, b, u)[source]
difference(a, b)[source]

For Lie groups, returns a difference vector that, when integrated would get to a from b. In Cartesian spaces it is a-b. In other spaces, it should be d/du interpolate(b,a,u) at u=0.

integrate(x, d)[source]

For Lie groups, returns the point that would be arrived at via integrating the difference vector d starting from x. Must satisfy the relationship a = integrate(b,difference(a,b)). In Cartesian spaces it is x+d

class klampt.math.geodesic.SO3Space[source]

Bases: GeodesicSpace

The space of 3D rotations SO(3). The representation is 9 entries of the rotation matrix, laid out in column-major form, like the math.so3 module.

Methods:

intrinsicDimension()

extrinsicDimension()

distance(a, b)

interpolate(a, b, u)

difference(a, b)

For Lie groups, returns a difference vector that, when integrated would get to a from b.

integrate(x, d)

For Lie groups, returns the point that would be arrived at via integrating the difference vector d starting from x.

intrinsicDimension()[source]
extrinsicDimension()[source]
distance(a, b)[source]
interpolate(a, b, u)[source]
difference(a, b)[source]

For Lie groups, returns a difference vector that, when integrated would get to a from b. In Cartesian spaces it is a-b. In other spaces, it should be d/du interpolate(b,a,u) at u=0.

integrate(x, d)[source]

For Lie groups, returns the point that would be arrived at via integrating the difference vector d starting from x. Must satisfy the relationship a = integrate(b,difference(a,b)). In Cartesian spaces it is x+d

class klampt.math.geodesic.SE3Space[source]

Bases: GeodesicSpace

The space of 3D rigid transforms SE(3). The representation is 9 entries of SO(3) + 3 entries of translation.

Methods:

intrinsicDimension()

extrinsicDimension()

to_se3(x)

from_se3(T)

distance(a, b)

interpolate(a, b, u)

difference(a, b)

For Lie groups, returns a difference vector that, when integrated would get to a from b.

integrate(x, d)

For Lie groups, returns the point that would be arrived at via integrating the difference vector d starting from x.

intrinsicDimension()[source]
extrinsicDimension()[source]
to_se3(x)[source]
from_se3(T)[source]
distance(a, b)[source]
interpolate(a, b, u)[source]
difference(a, b)[source]

For Lie groups, returns a difference vector that, when integrated would get to a from b. In Cartesian spaces it is a-b. In other spaces, it should be d/du interpolate(b,a,u) at u=0.

integrate(x, d)[source]

For Lie groups, returns the point that would be arrived at via integrating the difference vector d starting from x. Must satisfy the relationship a = integrate(b,difference(a,b)). In Cartesian spaces it is x+d

klampt.math.spline module

Spline utilities.

klampt.math.spline.hermite_eval(x1, v1, x2, v2, u)[source]

Returns the position a hermite curve with control points x1, v1, x2, v2 at the parameter u in [0,1].

klampt.math.spline.hermite_deriv(x1, v1, x2, v2, u, order=1)[source]

Returns the derivative of a hermite curve with control points x1, v1, x2, v2 at the parameter u in [0,1]. If order > 1, higher order derivatives are returned.

klampt.math.spline.hermite_subdivide(x1, v1, x2, v2, u=0.5)[source]

Subdivides a hermite curve into two hermite curves.

klampt.math.spline.hermite_length_bound(x1, v1, x2, v2)[source]

Returns an upper bound on the arc length of the hermite curve

klampt.math.spline.hermite_to_bezier(x1, v1, x2, v2)[source]

Returns the cubic bezier representation of a hermite curve

klampt.math.spline.bezier_subdivide(x1, x2, x3, x4, u=0.5)[source]

Subdivides a Bezier curve at the parameter u

klampt.math.spline.bezier_length_bound(x1, x2, x3, x4)[source]

Returns an upper bound on the arc length of the bezier curve

klampt.math.spline.bezier_discretize(x1, x2, x3, x4, res, return_params=False)[source]

Discretizes a bezier curve into a list of points. If return_params is True, a pair (points,params) is returned where params are the exact parameter values for which each point was generated. Otherwise, just the points are returned.

klampt.math.spline.bezier_to_hermite(x1, x2, x3, x4)[source]

Returns the cubic bezier representation of a hermite curve