Miscellaneous Submodules¶
klampt.math.geodesic module¶
Common interface for geodesic interpolation and distances on manifolds.
Classes:
The standard geodesic on R^d |
|
Base class for geodesic spaces. |
|
|
This forms the cartesian product of one or more GeodesicSpace’s. |
|
The space of 3D rigid transforms SE(3). |
|
The space of 2D rotations SO(2). |
|
The space of 3D rotations SO(3). |
-
class
klampt.math.geodesic.
CartesianSpace
(d)[source]¶ Bases:
klampt.math.geodesic.GeodesicSpace
The standard geodesic on R^d
Methods:
-
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:
difference
(a, b)For Lie groups, returns a difference vector that, when integrated would get to a from b.
distance
(a, b)integrate
(x, d)For Lie groups, returns the point that would be arrived at via integrating the difference vector d starting from x.
interpolate
(a, b, u)-
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.
-
-
class
klampt.math.geodesic.
MultiGeodesicSpace
(*components)[source]¶ Bases:
klampt.math.geodesic.GeodesicSpace
This forms the cartesian product of one or more GeodesicSpace’s. Distances are simply added together.
Methods:
difference
(a, b)For Lie groups, returns a difference vector that, when integrated would get to a from b.
distance
(a, b)integrate
(x, diff)For Lie groups, returns the point that would be arrived at via integrating the difference vector d starting from x.
interpolate
(a, b, u)join
(xs)split
(x)-
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.
-
-
class
klampt.math.geodesic.
SE3Space
[source]¶ Bases:
klampt.math.geodesic.GeodesicSpace
The space of 3D rigid transforms SE(3). The representation is 9 entries of SO(3) + 3 entries of translation.
Methods:
difference
(a, b)For Lie groups, returns a difference vector that, when integrated would get to a from b.
distance
(a, b)from_se3
(T)integrate
(x, d)For Lie groups, returns the point that would be arrived at via integrating the difference vector d starting from x.
interpolate
(a, b, u)to_se3
(x)-
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.
-
-
class
klampt.math.geodesic.
SO2Space
[source]¶ Bases:
klampt.math.geodesic.GeodesicSpace
The space of 2D rotations SO(2).
Methods:
difference
(a, b)For Lie groups, returns a difference vector that, when integrated would get to a from b.
distance
(a, b)integrate
(x, d)For Lie groups, returns the point that would be arrived at via integrating the difference vector d starting from x.
interpolate
(a, b, u)-
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.
-
-
class
klampt.math.geodesic.
SO3Space
[source]¶ Bases:
klampt.math.geodesic.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:
difference
(a, b)For Lie groups, returns a difference vector that, when integrated would get to a from b.
distance
(a, b)integrate
(x, d)For Lie groups, returns the point that would be arrived at via integrating the difference vector d starting from x.
interpolate
(a, b, u)-
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.
-
klampt.math.spline module¶
Spline utilities.
-
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_length_bound
(x1, x2, x3, x4)[source]¶ Returns an upper bound on the arc length of the bezier 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_to_hermite
(x1, x2, x3, x4)[source]¶ Returns the cubic bezier representation of a hermite curve
-
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_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_length_bound
(x1, v1, x2, v2)[source]¶ Returns an upper bound on the arc length of the hermite curve