diff --git a/docs/rsts/api/qsrlib_io.rst b/docs/rsts/api/qsrlib_io.rst index 4c33e8a..29cfa00 100644 --- a/docs/rsts/api/qsrlib_io.rst +++ b/docs/rsts/api/qsrlib_io.rst @@ -6,8 +6,8 @@ Submodules .. toctree:: - qsrlib_io.world_trace qsrlib_io.world_qsr_trace + qsrlib_io.world_trace Module contents --------------- diff --git a/docs/rsts/api/qsrlib_qsrs.qsr_ra3d.rst b/docs/rsts/api/qsrlib_qsrs.qsr_ra3d.rst new file mode 100644 index 0000000..958722e --- /dev/null +++ b/docs/rsts/api/qsrlib_qsrs.qsr_ra3d.rst @@ -0,0 +1,7 @@ +qsrlib_qsrs.qsr_ra3d module +=========================== + +.. automodule:: qsrlib_qsrs.qsr_ra3d + :members: + :undoc-members: + :show-inheritance: diff --git a/docs/rsts/api/qsrlib_qsrs.qsr_ra_abstract.rst b/docs/rsts/api/qsrlib_qsrs.qsr_ra_abstract.rst new file mode 100644 index 0000000..692afca --- /dev/null +++ b/docs/rsts/api/qsrlib_qsrs.qsr_ra_abstract.rst @@ -0,0 +1,7 @@ +qsrlib_qsrs.qsr_ra_abstract module +================================== + +.. automodule:: qsrlib_qsrs.qsr_ra_abstract + :members: + :undoc-members: + :show-inheritance: diff --git a/docs/rsts/api/qsrlib_qsrs.rst b/docs/rsts/api/qsrlib_qsrs.rst index f6fd614..965fc53 100644 --- a/docs/rsts/api/qsrlib_qsrs.rst +++ b/docs/rsts/api/qsrlib_qsrs.rst @@ -20,6 +20,8 @@ Submodules qsrlib_qsrs.qsr_qtc_c_simplified qsrlib_qsrs.qsr_qtc_simplified_abstractclass qsrlib_qsrs.qsr_ra + qsrlib_qsrs.qsr_ra3d + qsrlib_qsrs.qsr_ra_abstract qsrlib_qsrs.qsr_rcc2 qsrlib_qsrs.qsr_rcc3_rectangle_bounding_boxes_2d qsrlib_qsrs.qsr_rcc4 diff --git a/docs/rsts/handwritten/qsrs/qsrs.rst b/docs/rsts/handwritten/qsrs/qsrs.rst index 5d97bbf..0704258 100644 --- a/docs/rsts/handwritten/qsrs/qsrs.rst +++ b/docs/rsts/handwritten/qsrs/qsrs.rst @@ -45,6 +45,8 @@ Currently, the following QSRs are supported: +----------------+---------------------------------------------------+---------------------------------------------------------------------------------------------------------+----------------+ | **ra** | Rectangle Algebra | :doc:`descr. ` \| :mod:`api ` | [5]_ | +----------------+---------------------------------------------------+---------------------------------------------------------------------------------------------------------+----------------+ +| **ra3d** | Rectangle Algebra 3D | :doc:`descr. ` \| :mod:`api ` | [5]_ | ++----------------+---------------------------------------------------+---------------------------------------------------------------------------------------------------------+----------------+ | **rcc2** | Region Connection Calculus 2 | :doc:`descr. ` \| :mod:`api ` | [2]_ [3]_ | +----------------+---------------------------------------------------+---------------------------------------------------------------------------------------------------------+----------------+ | **rcc3** | Region Connection Calculus 3 | :doc:`descr. ` \| :mod:`api ` | [2]_ [3]_ | diff --git a/docs/rsts/handwritten/qsrs/ra.rst b/docs/rsts/handwritten/qsrs/ra.rst index 64ff5f9..f7debb9 100644 --- a/docs/rsts/handwritten/qsrs/ra.rst +++ b/docs/rsts/handwritten/qsrs/ra.rst @@ -21,7 +21,7 @@ of two rectangles. API --- -The API can be found :mod:`here `. +The API for RA can be found in the following links: :mod:`2D version` | :mod:`3D version `. References diff --git a/qsr_lib/src/qsrlib_io/world_trace.py b/qsr_lib/src/qsrlib_io/world_trace.py index aeba28e..3ee6073 100644 --- a/qsr_lib/src/qsrlib_io/world_trace.py +++ b/qsr_lib/src/qsrlib_io/world_trace.py @@ -126,6 +126,23 @@ def return_bounding_box_2d(self, xsize_minimal=0, ysize_minimal=0): ysize = ysize_minimal if isnan(self.ysize) else self.ysize return [self.x-xsize/2, self.y-ysize/2, self.x+xsize/2, self.y+ysize/2] + def return_bounding_box_3d(self, xsize_minimal=0, ysize_minimal=0, zsize_minimal=0): + """Compute the 3D bounding box of the object. + + :param xsize_minimal: If object has no x-size (i.e. a point) then compute bounding box based on this minimal x-size. + :type xsize_minimal: positive int or float + :param ysize_minimal: If object has no y-size (i.e. a point) then compute bounding box based on this minimal y-size. + :type ysize_minimal: positive int or float + :param zsize_minimal: If object has no z-size (i.e. a point) then compute bounding box based on this minimal z-size. + :type zsize_minimal: positive int or float + :return: The 3D coordinates of the first (closest to origin) and third (farthest from origin) corners of the bounding box. + :rtype: list of 6 int or float + """ + xsize = xsize_minimal if isnan(self.xsize) else self.xsize + ysize = ysize_minimal if isnan(self.ysize) else self.ysize + zsize = zsize_minimal if isnan(self.zsize) else self.zsize + return [self.x-xsize/2, self.y-ysize/2, self.z-zsize/2, self.x+xsize/2, self.y+ysize/2, self.z+zsize/2] + class World_State(object): """Data class structure that is holding various information about the world at a particular time.""" diff --git a/qsr_lib/src/qsrlib_qsrs/__init__.py b/qsr_lib/src/qsrlib_qsrs/__init__.py index 595f637..eff492c 100644 --- a/qsr_lib/src/qsrlib_qsrs/__init__.py +++ b/qsr_lib/src/qsrlib_qsrs/__init__.py @@ -12,7 +12,9 @@ from qsr_moving_or_stationary import QSR_Moving_or_Stationary from qsr_new_mwe import QSR_MWE from qsr_ra import QSR_RA +from qsr_ra3d import QSR_RA3D from qsr_tpcc import QSR_TPCC + # register new qsrs by class name below qsrs_registry = (QSR_RCC2, QSR_RCC3_Rectangle_Bounding_Boxes_2D, @@ -28,4 +30,5 @@ QSR_Moving_or_Stationary, QSR_MWE, QSR_RA, + QSR_RA3D, QSR_TPCC) diff --git a/qsr_lib/src/qsrlib_qsrs/qsr_abstractclass.py b/qsr_lib/src/qsrlib_qsrs/qsr_abstractclass.py index c6f7ac4..d7272e1 100644 --- a/qsr_lib/src/qsrlib_qsrs/qsr_abstractclass.py +++ b/qsr_lib/src/qsrlib_qsrs/qsr_abstractclass.py @@ -18,6 +18,7 @@ class QSR_Abstractclass(object): * "points": self._return_points * "bounding_boxes": self._return_bounding_boxes_2d * "bounding_boxes_2d": self._return_bounding_boxes_2d + * "bounding_boxes_3d": self._return_bounding_boxes_3d """ @@ -123,6 +124,14 @@ def _return_bounding_boxes_2d(self): """ return + @abstractmethod + def _return_bounding_boxes_3d(self): + """Return the 3D bounding boxes of the arguments. + + :return: 3D bounding boxes of the arguments. + """ + return + @property def unique_id(self): """Getter for the unique identifier of a QSR. diff --git a/qsr_lib/src/qsrlib_qsrs/qsr_dyadic_abstractclass.py b/qsr_lib/src/qsrlib_qsrs/qsr_dyadic_abstractclass.py index b27d44e..532142a 100644 --- a/qsr_lib/src/qsrlib_qsrs/qsr_dyadic_abstractclass.py +++ b/qsr_lib/src/qsrlib_qsrs/qsr_dyadic_abstractclass.py @@ -61,6 +61,17 @@ def _return_bounding_boxes_2d(self, data1, data2): """ return data1.return_bounding_box_2d(), data2.return_bounding_box_2d() + def _return_bounding_boxes_3d(self, data1, data2): + """Return the 3D bounding boxes of the arguments. + + :param data1: First object data. + :type data1: :class:`Object_State ` + :param data2: Second object data. + :type data2: :class:`Object_State ` + :return: `bbox1`, `bbox2` + :rtype: two lists of floats + """ + return data1.return_bounding_box_3d(), data2.return_bounding_box_3d() class QSR_Dyadic_1t_Abstractclass(QSR_Dyadic_Abstractclass): """Special case abstract class of dyadic QSRs. Works with dyadic QSRs that require data over one timestamp.""" diff --git a/qsr_lib/src/qsrlib_qsrs/qsr_monadic_abstractclass.py b/qsr_lib/src/qsrlib_qsrs/qsr_monadic_abstractclass.py index ede5071..349d3ec 100644 --- a/qsr_lib/src/qsrlib_qsrs/qsr_monadic_abstractclass.py +++ b/qsr_lib/src/qsrlib_qsrs/qsr_monadic_abstractclass.py @@ -59,6 +59,17 @@ def _return_bounding_boxes_2d(self, data1, data2): """ raise data1.return_bounding_box_2d(), data2.return_bounding_box_2d() + def _return_bounding_boxes_3d(self, data1, data2): + """Return the 3D bounding boxes of the arguments. + + :param data1: First object data. + :type data1: :class:`Object_State ` + :param data2: Second object data. + :type data2: :class:`Object_State ` + :return: `bbox1`, `bbox2` + :rtype: two lists of floats + """ + return data1.return_bounding_box_3d(), data2.return_bounding_box_3d() class QSR_Monadic_2t_Abstractclass(QSR_Monadic_Abstractclass): """Special case abstract class of monadic QSRs. Works with monadic QSRs that require data over two timestamps.""" diff --git a/qsr_lib/src/qsrlib_qsrs/qsr_ra.py b/qsr_lib/src/qsrlib_qsrs/qsr_ra.py index 0f233c4..4959811 100644 --- a/qsr_lib/src/qsrlib_qsrs/qsr_ra.py +++ b/qsr_lib/src/qsrlib_qsrs/qsr_ra.py @@ -1,38 +1,45 @@ # -*- coding: utf-8 -*- from __future__ import print_function, division -from numpy import isnan -from qsrlib_qsrs.qsr_dyadic_abstractclass import QSR_Dyadic_1t_Abstractclass +import itertools +from qsrlib_qsrs.qsr_ra_abstract import QSR_RA_Abstract -class QSR_RA(QSR_Dyadic_1t_Abstractclass): +class QSR_RA(QSR_RA_Abstract): """Rectangle Algebra. Members: - * _unique_id: "ra" - * _all_possible_relations: ("<", ">", "m", "mi", "o", "oi", "s", "si", "d", "di", "f", "fi", "=") - * _dtype: "bounding_boxes" + * **_unique_id** = "ra" + * **_all_possible_relations** = quite long to list here (169) but they are all possible pairs between the 13 Allen's relations + * **_dtype** = "bounding_boxes_2d" + + QSR specific `dynamic_args` + * **'qfactor'** (*int or float*) = 0.0: This factor provides some tolerance on the edges that are difficult + when the variables are floats, e.g. in the 'meets' relation it is unlikely that the end of one + segment will meet the beginning of the other to the decimal value. + + .. warning:: + Use of 'qfactor' might have strange and undesired results. Use it at your own risk. + + For further details, you might want to consult with the exact implementation of the method + `_allen`_ in class `QSR_RA`. .. seealso:: For further details about RA, refer to its :doc:`description. <../handwritten/qsrs/ra>` + + .. _`_allen`: https://github.com/strands-project/strands_qsr_lib/blob/master/qsr_lib/src/qsrlib_qsrs/qsr_ra.py """ _unique_id = "ra" """str: Unique identifier name of the QSR.""" - _all_possible_relations = ("<", ">", "m", "mi", "o", "oi", "s", "si", "d", "di", "f", "fi", "=") - """tuple: All possible relations of the QSR.""" - - _dtype = "bounding_boxes" + _dtype = "bounding_boxes_2d" """str: On what kind of data the QSR works with.""" - _inverse_map = {"<": ">", "m": "mi", "o": "oi", "s": "si", "d": "di", "f": "fi", - ">": "<", "mi": "m", "o1": "o", "si": "s", "di": "d", "fi": "f"} - """dict: Inverse relations""" + _all_possible_relations = tuple(itertools.product(("<", ">", "m", "mi", "o", "oi", "s", "si", "d", "di", "f", "fi", "="), + repeat=2)) + """tuple: All possible relations of the QSR.""" def __init__(self): - """Constructor. - - :return: - """ + """Constructor.""" super(QSR_RA, self).__init__() def _compute_qsr(self, bb1, bb2, qsr_params, **kwargs): @@ -48,32 +55,5 @@ def _compute_qsr(self, bb1, bb2, qsr_params, **kwargs): :return: The computed QSR value: two/three comma separated Allen relations for 2D/3D. :rtype: str """ - if len(bb1) == 4 and len(bb2) == 4: # 2D version - return ",".join([self.__allen((bb1[0], bb1[2]), (bb2[0], bb2[2])), - self.__allen((bb1[1], bb1[3]), (bb2[1], bb2[3]))]) - elif len(bb1) == 6 and len(bb2) == 6: # 3D version - return ",".join([self.__allen((bb1[0], bb1[3]), (bb2[0], bb2[3])), - self.__allen((bb1[1], bb1[4]), (bb2[1], bb2[4])), - self.__allen((bb1[2], bb1[5]), (bb2[2], bb2[5]))]) - else: - raise ValueError("bb1 and bb2 must have length of 4 (2D) or 6 (3D)") - - def __allen(self, i1, i2): - if isnan(i1).any() or isnan(i2).any(): # nan values cause dragons - raise ValueError("illegal 'nan' values found") - - if i1[1] < i2[0]: - return "<" - if i1[1] == i2[0]: - return "m" - if i1[0] < i2[0] < i1[1] and i2[0] < i1[1] < i2[1]: - return "o" - if i1[0] == i2[0] and i1[1] < i2[1]: - return "s" - if i2[0] < i1[0] < i2[1] and i2[0] < i1[1] < i2[1]: - return "d" - if i2[0] < i1[0] < i2[1] and i1[1] == i2[1]: - return "f" - if i1[0] == i2[0] and i1[1] == i2[1]: - return "=" - return self._inverse_map[self.__allen(i2, i1)] + return ",".join([self._allen((bb1[0], bb1[2]), (bb2[0], bb2[2]), qsr_params), + self._allen((bb1[1], bb1[3]), (bb2[1], bb2[3]), qsr_params)]) diff --git a/qsr_lib/src/qsrlib_qsrs/qsr_ra3d.py b/qsr_lib/src/qsrlib_qsrs/qsr_ra3d.py new file mode 100644 index 0000000..d7e3d12 --- /dev/null +++ b/qsr_lib/src/qsrlib_qsrs/qsr_ra3d.py @@ -0,0 +1,60 @@ +# -*- coding: utf-8 -*- +from __future__ import print_function, division +import itertools +from qsr_ra_abstract import QSR_RA_Abstract + + +class QSR_RA3D(QSR_RA_Abstract): + """Rectangle Algebra. + + Members: + * **_unique_id** = "ra3d" + * **_all_possible_relations** = quite long to list here (2197) but they are all possible triplets between the 13 Allen's relations + * **_dtype** = "bounding_boxes_3d" + + QSR specific `dynamic_args` + * **'qfactor'** (*int or float*) = 0.0: This factor provides some tolerance on the edges that are difficult + when the variables are floats, e.g. in the 'meets' relation it is unlikely that the end of one + segment will meet the beginning of the other to the decimal value. + + .. warning:: + Use of 'qfactor' might have strange and undesired results. Use it at your own risk. + + For further details, you might want to consult with the exact implementation of the method + `_allen`_ in class `QSR_RA`. + + .. seealso:: For further details about RA, refer to its :doc:`description. <../handwritten/qsrs/ra>` + + .. _`_allen`: https://github.com/strands-project/strands_qsr_lib/blob/master/qsr_lib/src/qsrlib_qsrs/qsr_ra.py + """ + + _unique_id = "ra3d" + """str: Unique identifier name of the QSR.""" + + _dtype = "bounding_boxes_3d" + """str: On what kind of data the QSR works with.""" + + _all_possible_relations = tuple(itertools.product(("<", ">", "m", "mi", "o", "oi", "s", "si", "d", "di", "f", "fi", "="), + repeat=3)) + """tuple: All possible relations of the QSR.""" + + def __init__(self): + """Constructor.""" + super(QSR_RA3D, self).__init__() + + def _compute_qsr(self, bb1, bb2, qsr_params, **kwargs): + """Compute QSR value. + + :param bb1: First object's 3D bounding box. + :type bb2: tuple or list + :param bb2: Second object's 3D bounding box. + :type bb2: tuple or list + :param qsr_params: QSR specific parameters passed in `dynamic_args`. + :type qsr_params: dict + :param kwargs: Optional further arguments. + :return: The computed QSR value: two/three comma separated Allen relations for 2D/3D. + :rtype: str + """ + return ",".join([self._allen((bb1[0], bb1[3]), (bb2[0], bb2[3])), + self._allen((bb1[1], bb1[4]), (bb2[1], bb2[4])), + self._allen((bb1[2], bb1[5]), (bb2[2], bb2[5]))]) diff --git a/qsr_lib/src/qsrlib_qsrs/qsr_ra_abstract.py b/qsr_lib/src/qsrlib_qsrs/qsr_ra_abstract.py new file mode 100644 index 0000000..9771287 --- /dev/null +++ b/qsr_lib/src/qsrlib_qsrs/qsr_ra_abstract.py @@ -0,0 +1,109 @@ +# -*- coding: utf-8 -*- +from __future__ import print_function, division +from abc import ABCMeta, abstractmethod +from numpy import isnan, abs +from qsrlib_qsrs.qsr_dyadic_abstractclass import QSR_Dyadic_1t_Abstractclass + + +class QSR_RA_Abstract(QSR_Dyadic_1t_Abstractclass): + """Rectangle Algebra abstract class. + + QSR specific `dynamic_args` + * **'qfactor'** (*int or float*) = 0.0: This factor provides some tolerance on the edges that are difficult + when the variables are floats, e.g. in the 'meets' relation it is unlikely that the end of one + segment will meet the beginning of the other to the decimal value. + + .. warning:: + Use of 'qfactor' might have strange and undesired results. Use it at your own risk. + + For further details, you might want to consult with the exact implementation of the method + `_allen`_ in class `QSR_RA`. + + .. seealso:: For further details about RA, refer to its :doc:`description. <../handwritten/qsrs/ra>` + + .. _`_allen`: https://github.com/strands-project/strands_qsr_lib/blob/master/qsr_lib/src/qsrlib_qsrs/qsr_ra.py + """ + + __metaclass__ = ABCMeta + + __inverse_map = {"<": ">", "m": "mi", "o": "oi", "s": "si", "d": "di", "f": "fi", + ">": "<", "mi": "m", "o1": "o", "si": "s", "di": "d", "fi": "f"} + """dict: Inverse relations""" + + __qsr_params_defaults = {"qfactor": 0.0} + """dict: Default values of the QSR parameters.""" + + def __init__(self): + """Constructor.""" + super(QSR_RA_Abstract, self).__init__() + + def _process_qsr_parameters_from_request_parameters(self, req_params, **kwargs): + """Extract QSR specific parameters from the QSRlib request call parameters. + + :param req_params: QSRlib request call parameters. + :type req_params: dict + :param kwargs: kwargs arguments. + :return: QSR specific parameter settings. + :rtype: dict + """ + qsr_params = self.__qsr_params_defaults.copy() + try: + qsr_params["qfactor"] = float(req_params["dynamic_args"][self._unique_id]["qfactor"]) + if not isinstance(qsr_params["qfactor"], (int, float)) or qsr_params["qfactor"] < 0: + raise ValueError("qfactor must be positive numeric") + except (KeyError, TypeError): + pass + return qsr_params + + @abstractmethod + def _compute_qsr(self, bb1, bb2, qsr_params, **kwargs): + """Compute QSR value. + + :param bb1: First object's bounding box. + :type bb2: tuple or list + :param bb2: Second object's bounding box. + :type bb2: tuple or list + :param qsr_params: QSR specific parameters passed in `dynamic_args`. + :type qsr_params: dict + :param kwargs: Optional further arguments. + :return: The computed QSR value: two/three comma separated Allen relations for 2D/3D. + :rtype: str + """ + + def _allen(self, i1, i2, qsr_params): + if isnan(i1).any() or isnan(i2).any(): # nan values cause dragons + raise ValueError("illegal 'nan' values found") + + if not qsr_params["qfactor"]: # normal + if i1[1] < i2[0]: + return "<" + if i1[1] == i2[0]: + return "m" + if i1[0] < i2[0] < i1[1] and i2[0] < i1[1] < i2[1]: + return "o" + if i1[0] == i2[0] and i1[1] < i2[1]: + return "s" + if i2[0] < i1[0] < i2[1] and i2[0] < i1[1] < i2[1]: + return "d" + if i2[0] < i1[0] < i2[1] and i1[1] == i2[1]: + return "f" + if i1[0] == i2[0] and i1[1] == i2[1]: + return "=" + + else: # qfactor compensation, can produce strange and undesired results + if i1[1]+qsr_params["qfactor"] < i2[0]: + return "<" + if abs(i1[1]-i2[0]) <= qsr_params["qfactor"]: + return "m" + if abs(i1[0]-i2[0]) <= qsr_params["qfactor"] and i1[1] < i2[1]: + return "s" + if i2[0] < i1[0] < i2[1] and abs(i1[1]-i2[1]) <= qsr_params["qfactor"]: + return "f" + if abs(i1[0]-i2[0]) <= qsr_params["qfactor"] and abs(i1[1]-i2[1]) <= qsr_params["qfactor"]: + return "=" + if i1[0] < i2[0] < i1[1] and i2[0] < i1[1] < i2[1]: + return "o" + if i2[0] < i1[0] < i2[1] and i2[0] < i1[1] < i2[1]: + return "d" + + return self.__inverse_map[self._allen(i2, i1, qsr_params)] diff --git a/qsr_lib/src/qsrlib_qsrs/qsr_triadic_abstractclass.py b/qsr_lib/src/qsrlib_qsrs/qsr_triadic_abstractclass.py index 0136d42..d3bac3d 100644 --- a/qsr_lib/src/qsrlib_qsrs/qsr_triadic_abstractclass.py +++ b/qsr_lib/src/qsrlib_qsrs/qsr_triadic_abstractclass.py @@ -65,6 +65,19 @@ def _return_bounding_boxes_2d(self, data1, data2, data3): """ return data1.return_bounding_box_2d(), data2.return_bounding_box_2d(), data3.return_bounding_box_2d() + def _return_bounding_boxes_3d(self, data1, data2, data3): + """Return the 3D bounding boxes of the arguments. + + :param data1: First object data. + :type data1: :class:`Object_State ` + :param data2: Second object data. + :type data2: :class:`Object_State ` + :param data3: Third object data. + :type data3: :class:`Object_State ` + :return: `bbox1`, `bbox2`, `bbox3` + :rtype: three lists of floats + """ + return data1.return_bounding_box_3d(), data2.return_bounding_box_3d(), data3.return_bounding_box_3d() class QSR_Triadic_1t_Abstractclass(QSR_Triadic_Abstractclass): """Special case abstract class of triadic QSRs. Works with triadic QSRs that require data over one timestamp.""" diff --git a/qsr_lib/tests/multiple_tester.py b/qsr_lib/tests/multiple_tester.py index fa7b1c5..cc38042 100755 --- a/qsr_lib/tests/multiple_tester.py +++ b/qsr_lib/tests/multiple_tester.py @@ -11,8 +11,11 @@ class Multiple_Test(AbstractClass_UnitTest): def __init__(self, *args): super(Multiple_Test, self).__init__(*args) + + self.__EXCLUDE = ["ra3d"] + self._unique_id = "multiple" - self.__which_qsr = sorted(self._qsrlib.qsrs_registry.keys()) + self.__which_qsr = self.__multiple() self.__seed = 100 self.__dynamic_args = {"argd": {"qsr_relations_and_values": {"close": 10.0, "near": 20.0, "far": 30.0, "veryfar": 40.0}}, @@ -22,6 +25,15 @@ def __init__(self, *args): "qtccs": {"validate": False, "no_collapse": True}, "qtcbcs": {"validate": False, "no_collapse": True}} + def __multiple(self): + which_qsr = sorted(self._qsrlib.qsrs_registry.keys()) + for i in self.__EXCLUDE: + try: + which_qsr.remove(i) + except ValueError: + pass + return which_qsr + def test_defaults(self): random.seed(self.__seed) self.assertItemsEqual(*self.defaults("data1", "data1_multiple_defaults.txt"))