klampt.math.autodiff.se3_ad module
se3 module AD functions:
Note that each function takes a 12 element vector which is the concatenation
of the R and t terms in an se3 element. In other words, to convert from an
se3 element T to an entry that can be properly eval’ed, use the code
np.array(T[0] + T[1])
. Alternatively, you can use the join
function
se3_ad.join(T[0],T[1])
which is differentiable.
To extract out the rotation / translation from an autodiff-ed function, use
the se3_ad.rotation
and se3_ad.translation
functions.
Function
Derivative
Notes
join
Y
Creates a 12-element vector from R,t
identity
N/A
A constant function with no args
apply
1
apply_rotation
1
mul
N
inv
N
rotation
Y
from_rotation
Y
translation
Y
from_translation
Y
distance
N
interpolate
N
error
N
Note
To do gradient descent on se3 elements, you will need to either project to the se3 submanifold or use a non-redundant representation. The rotation vector representation (see so3_ad.rotation_vector and so3_ad.from_rotation_vector) is recommended.
The code se3_ad.join(so3_ad.from_rotation_vector(x[0:3]),x[3:6]))
will
convert from a 6-element vector x (first 3 elements encoding the rotation
vector, final 3 elements encoding the translation) to a se3 element.
Module contents
Autodiff function to join SO(3) rotation matrix and 3D translation vector into an SE(3) 12-element vector. |
|
|
A 0 argument function that returns the SO(3) identity (just an alias to so3.identity) |
Autodiff wrapper of se3.apply. |
|
Autodiff wrapper of se3.apply_rotation. |
|
Autodiff wrapper of se3.mul. |
|
Autodiff wrapper of se3.inv. |
|
Autodiff function to extract the SO(3) rotation component of an SE(3) 12-element vector. |
|
Autodiff wrapper of se3.from_rotation. |
|
Autodiff function to extract the 3-D translation component of an SE(3) 12-element vector. |
|
Autodiff wrapper of se3.from_translation. |
|
Autodiff wrapper of se3.distance. |
|
Autodiff wrapper of se3.interpolate. |
|
Autodiff wrapper of se3.error. |
- klampt.math.autodiff.se3_ad.SIZE = 12
Constant giving the dimension of an se3_ad element
- klampt.math.autodiff.se3_ad.to_klampt(T)[source]
Converts an autodiff se3 representation as a length-12 numpy array to the native Klampt representation (R,t).
- klampt.math.autodiff.se3_ad.from_klampt(T)[source]
Converts a native Klampt se3 representation (R,t) to the length-12 numpy array representation used in autodiff.
- klampt.math.autodiff.se3_ad.join(*args) = <klampt.math.autodiff.ad._ad_se3.join object>
Autodiff function to join SO(3) rotation matrix and 3D translation vector into an SE(3) 12-element vector. All derivatives are implemented.
- klampt.math.autodiff.se3_ad.rotation(*args) = <klampt.math.autodiff.ad._ad_se3.rotation object>
Autodiff function to extract the SO(3) rotation component of an SE(3) 12-element vector. All derivatives are implemented.
- klampt.math.autodiff.se3_ad.translation(*args) = <klampt.math.autodiff.ad._ad_se3.translation object>
Autodiff function to extract the 3-D translation component of an SE(3) 12-element vector. All derivatives are implemented.
- klampt.math.autodiff.se3_ad.identity()
A 0 argument function that returns the SO(3) identity (just an alias to so3.identity)
- klampt.math.autodiff.se3_ad.apply(*args) = <klampt.math.autodiff.ad._ad_se3.apply object>
Autodiff wrapper of se3.apply. First derivatives are implemented.
- klampt.math.autodiff.se3_ad.apply_rotation(*args) = <klampt.math.autodiff.ad._ad_se3.apply_rotation object>
Autodiff wrapper of se3.apply_rotation. First derivatives are implemented.
- klampt.math.autodiff.se3_ad.mul(*args) = <klampt.math.autodiff.ad._ad_se3.mul object>
Autodiff wrapper of se3.mul.
- klampt.math.autodiff.se3_ad.inv(*args) = <klampt.math.autodiff.ad._ad_se3.inv object>
Autodiff wrapper of se3.inv.
- klampt.math.autodiff.se3_ad.from_rotation(*args) = <klampt.math.autodiff.ad._ad_se3.from_rotation object>
Autodiff wrapper of se3.from_rotation. All derivatives are implemented.
- klampt.math.autodiff.se3_ad.from_translation(*args) = <klampt.math.autodiff.ad._ad_se3.from_translation object>
Autodiff wrapper of se3.from_translation. All derivatives are implemented.
- klampt.math.autodiff.se3_ad.error(*args) = <klampt.math.autodiff.ad._ad_se3.error object>
Autodiff wrapper of se3.error.
- klampt.math.autodiff.se3_ad.distance(*args) = <klampt.math.autodiff.ad._ad_se3.distance object>
Autodiff wrapper of se3.distance.
- klampt.math.autodiff.se3_ad.interpolate(*args) = <klampt.math.autodiff.ad._ad_se3.interpolate object>
Autodiff wrapper of se3.interpolate.