Public Member Functions | |
def | __init__ |
def | __mul__ |
def | __truediv__ |
def | dcm |
def | dcm |
def | inversed |
def | transform |
Public Attributes | |
dcm | |
q | |
Private Member Functions | |
def | _dcm_array_to_matrix3 |
def | _dcm_to_euler |
def | _dcm_to_q |
def | _euler_to_dcm |
def | _matrix3_to_dcm_array |
def | _q_to_dcm |
Private Attributes | |
_dcm | |
_euler | |
_q |
Quaternion class that supports pymavlink's Vector3 and Matrix3 Usage: >>> from quaternion import Quaternion >>> from rotmat import Vector3, Matrix3 >>> m = Matrix3() >>> m.from_euler(45, 0, 0) >>> print(m) Matrix3((1.00, 0.00, 0.00), (0.00, 0.53, -0.85), (-0.00, 0.85, 0.53)) >>> q = Quaternion(m) >>> print(q) [ 0.87330464 0.48717451 0. 0. ] >>> print(q.dcm) Matrix3((1.00, 0.00, 0.00), (0.00, 0.53, -0.85), (-0.00, 0.85, 0.53)) >>> v = Vector3(0, 1, 0) >>> v2 = q.transform(v) >>> print(v2) Vector3(0.00, 0.53, 0.85)
Definition at line 452 of file quaternion.py.
def pymavlink.quaternion.Quaternion.__init__ | ( | self, | |
attitude | |||
) |
Construct a quaternion from an attitude :param attitude: another Quaternion, QuaternionBase, 3 element list [roll, pitch, yaw], 4 element list [w, x, y ,z], DCM (3x3 array or Matrix3)
Reimplemented from pymavlink.quaternion.QuaternionBase.
Definition at line 475 of file quaternion.py.
def pymavlink.quaternion.Quaternion.__mul__ | ( | self, | |
other | |||
) |
:param other: Quaternion :returns: multiplaction of this Quaternion with other
Reimplemented from pymavlink.quaternion.QuaternionBase.
Definition at line 614 of file quaternion.py.
def pymavlink.quaternion.Quaternion.__truediv__ | ( | self, | |
other | |||
) |
:param other: Quaternion :returns: division of this Quaternion with other
Reimplemented from pymavlink.quaternion.QuaternionBase.
Definition at line 621 of file quaternion.py.
def pymavlink.quaternion.Quaternion._dcm_array_to_matrix3 | ( | self, | |
dcm | |||
) | [private] |
Converts dcm array into Matrix3 :param dcm: 3x3 dcm array :returns: Matrix3
Definition at line 551 of file quaternion.py.
def pymavlink.quaternion.Quaternion._dcm_to_euler | ( | self, | |
dcm | |||
) | [private] |
Create DCM from euler angles :param dcm: Matrix3 :returns: array [roll, pitch, yaw] in rad
Reimplemented from pymavlink.quaternion.QuaternionBase.
Definition at line 605 of file quaternion.py.
def pymavlink.quaternion.Quaternion._dcm_to_q | ( | self, | |
dcm | |||
) | [private] |
Create q from dcm (Matrix3) :param dcm: Matrix3 :returns: array q which represents a quaternion [w, x, y, z]
Reimplemented from pymavlink.quaternion.QuaternionBase.
Definition at line 584 of file quaternion.py.
def pymavlink.quaternion.Quaternion._euler_to_dcm | ( | self, | |
euler | |||
) | [private] |
Create DCM (Matrix3) from euler angles :param euler: array [roll, pitch, yaw] in rad :returns: Matrix3
Reimplemented from pymavlink.quaternion.QuaternionBase.
Definition at line 594 of file quaternion.py.
def pymavlink.quaternion.Quaternion._matrix3_to_dcm_array | ( | self, | |
m | |||
) | [private] |
Converts Matrix3 in an array :param m: Matrix3 :returns: 3x3 array
Definition at line 563 of file quaternion.py.
def pymavlink.quaternion.Quaternion._q_to_dcm | ( | self, | |
q | |||
) | [private] |
Create DCM (Matrix3) from q :param q: array q which represents a quaternion [w, x, y, z] :returns: Matrix3
Reimplemented from pymavlink.quaternion.QuaternionBase.
Definition at line 574 of file quaternion.py.
def pymavlink.quaternion.Quaternion.dcm | ( | self | ) |
Get the DCM :returns: Matrix3
Reimplemented from pymavlink.quaternion.QuaternionBase.
Definition at line 498 of file quaternion.py.
def pymavlink.quaternion.Quaternion.dcm | ( | self, | |
dcm | |||
) |
Set the DCM :param dcm: Matrix3
Reimplemented from pymavlink.quaternion.QuaternionBase.
Definition at line 514 of file quaternion.py.
def pymavlink.quaternion.Quaternion.inversed | ( | self | ) |
Get inversed quaternion :returns: inversed quaternion
Reimplemented from pymavlink.quaternion.QuaternionBase.
Definition at line 529 of file quaternion.py.
def pymavlink.quaternion.Quaternion.transform | ( | self, | |
v3 | |||
) |
Calculates the vector transformed by this quaternion :param v3: Vector3 to be transformed :returns: transformed vector
Reimplemented from pymavlink.quaternion.QuaternionBase.
Definition at line 537 of file quaternion.py.
pymavlink::quaternion.Quaternion::_dcm [private] |
Reimplemented from pymavlink.quaternion.QuaternionBase.
Definition at line 502 of file quaternion.py.
pymavlink::quaternion.Quaternion::_euler [private] |
Reimplemented from pymavlink.quaternion.QuaternionBase.
Definition at line 518 of file quaternion.py.
pymavlink::quaternion.Quaternion::_q [private] |
Reimplemented from pymavlink.quaternion.QuaternionBase.
Definition at line 518 of file quaternion.py.
Reimplemented from pymavlink.quaternion.QuaternionBase.
Definition at line 481 of file quaternion.py.
Reimplemented from pymavlink.quaternion.QuaternionBase.
Definition at line 481 of file quaternion.py.