Skip to content

The constructor process

Peter Corke edited this page Sep 24, 2020 · 2 revisions

The class hierarchy is

The top level class wraps methods provided by collections.UserList and provides its own __new__ function which calls the UserList __init__ function, thus there is no need for any of the subclasses to explicitly call the superclass initialiser.

Each object has a an attribute .data which is a list of NumPy arrays representing the object, ie. a 4x4 array for an SE(3) matrix, a 1x4 array for a unit quaternion, or a 1x6 array for a 3D twist. An instance with a single value has a single element list on .data whereas an instant with N values has a list of length N on .data. It is critical that .data:

  • is always a list, it is never a reference to a NumPy array
  • the elements of the list are always the right kind of NumPy array, it cannot contain a sublist of NumPy arrays
  • the elements of the list are valid values for the class

Consider the case for the SE3 constructor but all other spatial math classes are similar. The __init__ method follows this pattern:

def __init(self, arg1=None, arg2=None, arg3=None, ... check=True):

  if arg2 is None and arg3 is None:
    # zero or one arguments passed
    if super().arghandler(self, arg1, check=check, convertfrom=(Z,)):
      return
    else:
      # deal with other one argument cases
  elif ....:
    # process two and three argument cases
  else:
    # no idea how to handle what was passed
    raise ValueError('bad argument to constructor')

The call to arghandler deals with the following common cases:

  1. SE3()
  2. SE3(X) where X is an SE3 instance
  3. SE3(T) where T is 4x4 NumPy array
  4. SE3([T1, T2, ... TN]) where Ti is 4x4 NumPy array
  5. SE3([X1, X2, ... XN]) where Xi is an SE3 instance
  6. SE3(Z) where Z is a class that can be converted to an SE3

and returns true if one of these cases is satisfied. If it cannot handle the argument it returns false and it is upto the user code to handle.

For case 1, the instance is initialised with the identity or null value of the spatial math object, and that is obtained by calling the class's static method _identity().

Case 2 is a copy constructor, the new value is the same as the argument, but a copy not a reference.

The constructor has a keyword check argument which is important. By default it is true which means that, for cases 3 and 4, the matrices are checked to be valid members of SE(3). This test is expensive, so if we can guarantee that the matrix is a valid member of SE(3) then we can skip the check. This is done by many other methods of SE3 that construct guaranteed members of SE(3).

For cases 3 and 4 the values are passed to an import method with signature

_import(self, value, check)

which can be overridden if required. If check is true the test is performed by a static isvalid method of the class, SE3.isvalid() in this case. It returns the value if valid otherwise None. For twist objects where the NumPy array might have two possible shapes: a 4x4 augmented skew-symmetric matrix or a 6-vector, the class should provide this method which checks the value and returns the shape that is used internally for representation (a 6-vector in the case of 3D twists).

Case 6 requires that the object Z has a method .SE3 which converts a Z to an SE3 instance. If that is the case, the conversion method is called and resulting value used to construct a new SE3 object. The following are equivalent:

  • Y = SE3(Z)
  • Y = Z.SE3()
Clone this wiki locally