Mathematics¶
- mil_tools.rotate_vect_by_quat(v: List[float], q: List[float]) ndarray [source]¶
Rotates a vector by a quaterion using
v' = q*vq
. Bothv
andq
should be a list of 4 floats representing [x, y, z, w].
- mil_tools.skew_symmetric_cross(vector: List[float]) ndarray [source]¶
Returns the skew symmetric matrix representation of a vector.
- Parameters
a (List[float]) – The vector to find the skew symmetric matrix representation of.
- Returns
The skew-symmetric cross product matrix of the vector.
- Return type
np.ndarray
- mil_tools.deskew(matrix: ndarray[Any, dtype[ScalarType]]) ndarray [source]¶
Finds the original vector from its skew-symmetric cross product. Finds the reverse of
mil_tools.skew_symmetric_cross()
.- Parameters
matrix (List[float]) – The matrix to find the original vector from.
- Returns
The original vector.
- Return type
numpy.typing.NDArray
- mil_tools.normalize(vector) ndarray[Any, dtype[ScalarType]] [source]¶
Normalizes a vector by dividing a non-zero vector by the vector norm.
- Parameters
vector (numpy.typing.ArrayLike) – An array to compute the normal vector of.
- Returns
The normalized vector.
- Return type
numpy.typing.NDArray
- mil_tools.compose_transformation(rotation: ndarray[Any, dtype[ScalarType]], translation: ndarray[Any, dtype[ScalarType]]) ndarray [source]¶
Compose a transformation from a rotation matrix and a translation matrix.
- Parameters
rotation (np.ndarray) – The rotation to add to the final transformation matrix.
translation (np.ndarray) – The translation to add to the final transformation matrix.
- Returns
The transformation matrix.
- Return type
np.ndarray
- mil_tools.make_rotation(vector_a: List[float], vector_b: List[float]) ndarray[Any, dtype[ScalarType]] [source]¶
Determine a 3D rotation that rotates A onto B. In other words, we want a matrix R that aligns A with B.
>>> R = make_rotation(a, b) >>> p = R.dot(a) >>> np.cross(p, a) array([0.0, 0.0, 0.0])