Public Member Functions | Public Attributes | Static Public Attributes | Static Private Attributes | List of all members
pymavlink.rotmat.Matrix3 Class Reference
Inheritance diagram for pymavlink.rotmat.Matrix3:
Inheritance graph
[legend]

Public Member Functions

def __add__ (self, m)
 
def __copy__ (self)
 
def __div__ (self, v)
 
def __eq__ (self, m)
 
def __init__ (self, a=None, b=None, c=None)
 
def __mul__ (self, other)
 
def __ne__ (self, m)
 
def __neg__ (self)
 
def __repr__ (self)
 
def __rsub__ (self, m)
 
def __sub__ (self, m)
 
def close (self, m, tol=1e-7)
 
def from_axis_angle (self, axis, angle)
 
def from_euler (self, roll, pitch, yaw)
 
def from_euler312 (self, roll, pitch, yaw)
 
def from_two_vectors (self, vec1, vec2)
 
def identity (self)
 
def normalize (self)
 
def rotate (self, g)
 
def to_euler (self)
 
def to_euler312 (self)
 
def trace (self)
 
def transposed (self)
 

Public Attributes

 a
 
 b
 
 c
 

Static Public Attributes

def copy = __copy__
 

Static Private Attributes

def __radd__ = __add__
 

Detailed Description

a 3x3 matrix, intended as a rotation matrix

Definition at line 130 of file rotmat.py.

Constructor & Destructor Documentation

◆ __init__()

def pymavlink.rotmat.Matrix3.__init__ (   self,
  a = None,
  b = None,
  c = None 
)

Definition at line 132 of file rotmat.py.

Member Function Documentation

◆ __add__()

def pymavlink.rotmat.Matrix3.__add__ (   self,
  m 
)

Definition at line 223 of file rotmat.py.

◆ __copy__()

def pymavlink.rotmat.Matrix3.__copy__ (   self)

Definition at line 266 of file rotmat.py.

◆ __div__()

def pymavlink.rotmat.Matrix3.__div__ (   self,
  v 
)

Definition at line 260 of file rotmat.py.

◆ __eq__()

def pymavlink.rotmat.Matrix3.__eq__ (   self,
  m 
)

Definition at line 234 of file rotmat.py.

◆ __mul__()

def pymavlink.rotmat.Matrix3.__mul__ (   self,
  other 
)

Definition at line 240 of file rotmat.py.

◆ __ne__()

def pymavlink.rotmat.Matrix3.__ne__ (   self,
  m 
)

Definition at line 237 of file rotmat.py.

◆ __neg__()

def pymavlink.rotmat.Matrix3.__neg__ (   self)

Definition at line 263 of file rotmat.py.

◆ __repr__()

def pymavlink.rotmat.Matrix3.__repr__ (   self)

Definition at line 140 of file rotmat.py.

◆ __rsub__()

def pymavlink.rotmat.Matrix3.__rsub__ (   self,
  m 
)

Definition at line 231 of file rotmat.py.

◆ __sub__()

def pymavlink.rotmat.Matrix3.__sub__ (   self,
  m 
)

Definition at line 228 of file rotmat.py.

◆ close()

def pymavlink.rotmat.Matrix3.close (   self,
  m,
  tol = 1e-7 
)

Definition at line 336 of file rotmat.py.

◆ from_axis_angle()

def pymavlink.rotmat.Matrix3.from_axis_angle (   self,
  axis,
  angle 
)
create a rotation matrix from axis and angle

Definition at line 306 of file rotmat.py.

◆ from_euler()

def pymavlink.rotmat.Matrix3.from_euler (   self,
  roll,
  pitch,
  yaw 
)
fill the matrix from Euler angles in radians

Definition at line 157 of file rotmat.py.

◆ from_euler312()

def pymavlink.rotmat.Matrix3.from_euler312 (   self,
  roll,
  pitch,
  yaw 
)
fill the matrix from Euler angles in radians in 312 convention

Definition at line 204 of file rotmat.py.

◆ from_two_vectors()

def pymavlink.rotmat.Matrix3.from_two_vectors (   self,
  vec1,
  vec2 
)
get a rotation matrix from two vectors.
   This returns a rotation matrix which when applied to vec1
   will produce a vector pointing in the same direction as vec2

Definition at line 324 of file rotmat.py.

◆ identity()

def pymavlink.rotmat.Matrix3.identity (   self)

Definition at line 146 of file rotmat.py.

◆ normalize()

def pymavlink.rotmat.Matrix3.normalize (   self)
re-normalise a rotation matrix

Definition at line 292 of file rotmat.py.

◆ rotate()

def pymavlink.rotmat.Matrix3.rotate (   self,
  g 
)
rotate the matrix by a given amount on 3 axes,
where g is a vector of delta angles. Used
with DCM updates in mavextra.py

Definition at line 271 of file rotmat.py.

◆ to_euler()

def pymavlink.rotmat.Matrix3.to_euler (   self)
find Euler angles (321 convention) for the matrix

Definition at line 177 of file rotmat.py.

◆ to_euler312()

def pymavlink.rotmat.Matrix3.to_euler312 (   self)
find Euler angles (312 convention) for the matrix.
See http://www.atacolorado.com/eulersequences.doc

Definition at line 190 of file rotmat.py.

◆ trace()

def pymavlink.rotmat.Matrix3.trace (   self)
the trace of the matrix

Definition at line 302 of file rotmat.py.

◆ transposed()

def pymavlink.rotmat.Matrix3.transposed (   self)

Definition at line 151 of file rotmat.py.

Member Data Documentation

◆ __radd__

def pymavlink.rotmat.Matrix3.__radd__ = __add__
staticprivate

Definition at line 226 of file rotmat.py.

◆ a

pymavlink.rotmat.Matrix3.a

Definition at line 134 of file rotmat.py.

◆ b

pymavlink.rotmat.Matrix3.b

Definition at line 135 of file rotmat.py.

◆ c

pymavlink.rotmat.Matrix3.c

Definition at line 136 of file rotmat.py.

◆ copy

def pymavlink.rotmat.Matrix3.copy = __copy__
static

Definition at line 269 of file rotmat.py.


The documentation for this class was generated from the following file:


mavlink
Author(s): Lorenz Meier
autogenerated on Fri Aug 2 2019 03:39:47