Skip to content

Commit 6c37846

Browse files
author
Yiannis Gatsoulis
committed
QSRs abstractproperties
1 parent 629d66d commit 6c37846

11 files changed

+83
-60
lines changed

qsr_lib/src/qsrlib_qsrs/qsr_abstractclass.py

Lines changed: 18 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
# -*- coding: utf-8 -*-
22
from __future__ import print_function, division
3-
from abc import ABCMeta, abstractmethod
3+
from abc import ABCMeta, abstractmethod, abstractproperty
44

55

66
class QSR_Abstractclass(object):
@@ -9,26 +9,29 @@ class QSR_Abstractclass(object):
99
"""
1010
__metaclass__ = ABCMeta
1111

12+
_common_dynamic_args = ["qsrs_for"]
13+
"""tuple: Common across all QSRs arguments of `dynamic_args`."""
14+
1215
def __init__(self):
13-
"""Constructor.
16+
"""Constructor."""
17+
self._dtype_map = {"points": self._return_points,
18+
"bounding_boxes_2d": self._return_bounding_boxes_2d}
19+
"""dict: Mapping of _dtype to methods."""
1420

15-
:return:
16-
"""
17-
self._unique_id = ""
21+
@abstractproperty
22+
def _unique_id(self):
1823
"""str: The unique identifier of each QSR."""
24+
pass
1925

20-
self._all_possible_relations = ()
26+
@abstractproperty
27+
def _all_possible_relations(self):
2128
"""tuple: All possible relations of a QSR."""
29+
pass
2230

23-
self._dtype = ""
24-
"""str: On what kind of data the QSR operates with, e.g. 'points' or 'bboxes'"""
25-
26-
self._common_dynamic_args = ["qsrs_for"]
27-
"""tuple: Common across all QSRs arguments of `dynamic_args`."""
28-
29-
self._dtype_map = {"points": self._return_points,
30-
"bounding_boxes_2d": self._return_bounding_boxes_2d}
31-
"""dict: Mapping of _dtype to methods."""
31+
@abstractproperty
32+
def _dtype(self):
33+
"""str: On what kind of data the QSR operates with, see self._dtype_map for possible values"""
34+
pass
3235

3336
@abstractmethod
3437
def make_world_qsr_trace(self, world_trace, timestamps, qsr_params, req_params, **kwargs):

qsr_lib/src/qsrlib_qsrs/qsr_arg_prob_relations_distance.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,7 @@
1212

1313

1414
class QSR_Arg_Prob_Relations_Distance(QSR_Arg_Relations_Distance):
15-
def __init__(self, config=None):
15+
def __init__(self):
1616
super(QSR_Arg_Prob_Relations_Distance, self).__init__()
1717
self._unique_id = "argprobd"
1818
self.allowed_value_types = (tuple, list)

qsr_lib/src/qsrlib_qsrs/qsr_arg_relations_distance.py

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -7,12 +7,15 @@
77

88

99
class QSR_Arg_Relations_Distance(QSR_Arg_Relations_Abstractclass):
10+
11+
_unique_id = "argd"
12+
_dtype = "points"
13+
_all_possible_relations = ()
14+
1015
def __init__(self):
1116
super(QSR_Arg_Relations_Distance, self).__init__()
12-
self._unique_id = "argd"
1317
self.allowed_value_types = (int, float)
1418
self.value_sort_key = operator.itemgetter(1) # Sort by threshold
15-
self._dtype = "points"
1619

1720
def _process_qsr_parameters_from_request_parameters(self, req_params, **kwargs):
1821
try:

qsr_lib/src/qsrlib_qsrs/qsr_cardinal_direction_bounding_boxes_centroid_2d.py

Lines changed: 5 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -16,11 +16,13 @@ class QSR_Cardinal_Direction_Bounding_Boxes_Centroid_2D(QSR_Dyadic_1t_Abstractcl
1616
1717
where,\nx1, y2: the xy-coords of the top-left corner of the rectangle\nx2, y2: the xy-coords of the bottom-right corner of the rectangle
1818
"""
19+
20+
_unique_id = "cardir"
21+
_all_possible_relations = ("n", "ne", "e", "se", "s", "sw", "w", "nw", "eq")
22+
_dtype = "bounding_boxes_2d"
23+
1924
def __init__(self):
2025
super(QSR_Cardinal_Direction_Bounding_Boxes_Centroid_2D, self).__init__()
21-
self._unique_id = "cardir"
22-
self._all_possible_relations = ("n", "ne", "e", "se", "s", "sw", "w", "nw", "eq")
23-
self._dtype = "bounding_boxes_2d"
2426

2527
def _compute_qsr(self, data1, data2, qsr_params, **kwargs):
2628
"""Cardinal direction relation

qsr_lib/src/qsrlib_qsrs/qsr_moving_or_stationary.py

Lines changed: 5 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -8,12 +8,13 @@ class QSR_Moving_or_Stationary(QSR_Monadic_2t_Abstractclass):
88
"""Computes moving or stationary relations: 'm': moving, 's': stationary
99
1010
"""
11+
12+
_unique_id = "mos"
13+
_all_possible_relations = ("m", "s")
14+
_dtype = "points"
15+
1116
def __init__(self):
1217
super(QSR_Moving_or_Stationary, self).__init__()
13-
self._unique_id = "mos"
14-
self._all_possible_relations = ("m", "s")
15-
self._dtype = "points"
16-
1718
self.__qsr_params_defaults = {"quantisation_factor": 0.0}
1819

1920
def _process_qsr_parameters_from_request_parameters(self, req_params, **kwargs):

qsr_lib/src/qsrlib_qsrs/qsr_new_mwe.py

Lines changed: 10 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -13,22 +13,23 @@ class QSR_MWE(QSR_Dyadic_1t_Abstractclass):
1313
1414
Some explanation about the QSR. Maybe a reference if it exists.
1515
"""
16+
17+
_unique_id = "mwe"
18+
"""str: Unique identifier name of the QSR."""
19+
20+
_all_possible_relations = ("left", "together", "right")
21+
"""tuple: All possible relations of the QSR."""
22+
23+
_dtype = "points"
24+
"""str: On what kind of data the QSR works with."""
25+
1626
def __init__(self):
1727
"""Constructor.
1828
1929
:return:
2030
"""
2131
super(QSR_MWE, self).__init__()
2232

23-
self._unique_id = "mwe"
24-
"""str: Unique identifier name of the QSR."""
25-
26-
self._all_possible_relations = ("left", "together", "right")
27-
"""tuple: All possible relations of the QSR."""
28-
29-
self._dtype = "points"
30-
"""str: On what kind of data the QSR works with."""
31-
3233
def _compute_qsr(self, data1, data2, qsr_params, **kwargs):
3334
"""Compute QSR value.
3435

qsr_lib/src/qsrlib_qsrs/qsr_qtc_simplified_abstractclass.py

Lines changed: 17 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -30,9 +30,12 @@ class QSR_QTC_Simplified_Abstractclass(QSR_Dyadic_Abstractclass):
3030
__global_unique_id = "qtcs"
3131
__no_state__ = 9.
3232

33+
_unique_id = ""
34+
_all_possible_relations = ()
35+
_dtype = "points"
36+
3337
def __init__(self):
3438
super(QSR_QTC_Simplified_Abstractclass, self).__init__()
35-
self._unique_id = ""
3639
self.qtc_type = ""
3740

3841
self.__qsr_params_defaults= {
@@ -116,9 +119,9 @@ def _validate_qtc_sequence(self, qtc):
116119
for j1 in xrange(0, len(qtc[i,:])-1):
117120
for j2 in xrange(j1+1, len(insert)):
118121
if np.sum(np.abs(qtc[i-1,[j1,j2]])) == 1 \
119-
and np.sum(np.abs(insert[[j1,j2]])) == 1:
122+
and np.sum(np.abs(insert[[j1,j2]])) == 1:
120123
if np.nanmax(np.abs(qtc[i-1,[j1,j2]] - insert[[j1,j2]])) > 0 \
121-
and np.sum(qtc[i-1,[j1,j2]] - insert[[j1,j2]]) != 1:
124+
and np.sum(qtc[i-1,[j1,j2]] - insert[[j1,j2]]) != 1:
122125
insert[[j1,j2]] = 0
123126

124127
#print insert
@@ -222,16 +225,16 @@ def _create_qtc_representation(self, pos_k, pos_l, quantisation_factor=0):
222225
self._test_constraint(
223226
pos_l,
224227
np.array([ # Needs to be turned around to determine correct side
225-
[trans_RL_l[1,0],trans_RL_l[1,1]],
226-
[trans_RL_l[0,0],trans_RL_l[0,1]]
227-
]),
228+
[trans_RL_l[1,0],trans_RL_l[1,1]],
229+
[trans_RL_l[0,0],trans_RL_l[0,1]]
230+
]),
228231
quantisation_factor=quantisation_factor),
229232
self._test_constraint(
230233
pos_l,
231234
np.array([ # Needs to be turned around to determine correct side
232-
[RL_ext[1,0],RL_ext[1,1]],
233-
[RL_ext[0,0],RL_ext[0,1]]
234-
]),
235+
[RL_ext[1,0],RL_ext[1,1]],
236+
[RL_ext[0,0],RL_ext[0,1]]
237+
]),
235238
quantisation_factor=quantisation_factor,
236239
constraint="side")
237240
)
@@ -426,11 +429,11 @@ def _postprocess_world_qsr_trace(self, world_qsr_trace, world_trace, world_trace
426429
return World_QSR_Trace(
427430
qsr_type=world_qsr_trace.qsr_type,
428431
trace={t: world_qsr_trace.trace[tqtc]
429-
for t, tqtc in zip(
430-
world_trace.get_sorted_timestamps()[1:],
431-
world_qsr_trace.get_sorted_timestamps()
432-
)
433-
}
432+
for t, tqtc in zip(
433+
world_trace.get_sorted_timestamps()[1:],
434+
world_qsr_trace.get_sorted_timestamps()
435+
)
436+
}
434437
)
435438
else:
436439
return world_qsr_trace

qsr_lib/src/qsrlib_qsrs/qsr_rcc2_rectangle_bounding_boxes_2d.py

Lines changed: 7 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -9,10 +9,15 @@ class QSR_RCC2_Rectangle_Bounding_Boxes_2D(QSR_RCC_Abstractclass):
99
# 'dc' bb1 is disconnected from bb2
1010
# 'c' bb1 is connected to bb2
1111
"""
12+
13+
_unique_id = "rcc2"
14+
"""str: Unique identifier name of the QSR."""
15+
16+
_all_possible_relations = ("dc", "c")
17+
"""tuple: All possible relations of the QSR."""
18+
1219
def __init__(self):
1320
super(QSR_RCC2_Rectangle_Bounding_Boxes_2D, self).__init__()
14-
self._unique_id = "rcc2"
15-
self._all_possible_relations = ("dc", "c")
1621

1722
def _convert_to_requested_rcc_type(self, qsr):
1823
return qsr if qsr == "dc" else "c"

qsr_lib/src/qsrlib_qsrs/qsr_rcc3_rectangle_bounding_boxes_2d.py

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -10,10 +10,12 @@ class QSR_RCC3_Rectangle_Bounding_Boxes_2D(QSR_RCC_Abstractclass):
1010
# 'po' bb1 partially overlaps bb2
1111
# 'o' bb1 is occluded or part of bb2
1212
"""
13+
14+
_unique_id = "rcc3"
15+
_all_possible_relations = ("dc", "po", "o")
16+
1317
def __init__(self):
1418
super(QSR_RCC3_Rectangle_Bounding_Boxes_2D, self).__init__()
15-
self._unique_id = "rcc3"
16-
self._all_possible_relations = ("dc", "po", "o")
1719

1820
def _convert_to_requested_rcc_type(self, qsr):
1921
qsr = qsr.replace("ec", "po")

qsr_lib/src/qsrlib_qsrs/qsr_rcc8_rectangle_bounding_boxes_2d.py

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -15,10 +15,12 @@ class QSR_RCC8_Rectangle_Bounding_Boxes_2D(QSR_RCC_Abstractclass):
1515
# 'tppi' bb2 is a tangential proper part of bb1
1616
# 'ntppi' bb2 is a non-tangential proper part of bb1
1717
"""
18+
19+
_unique_id = "rcc8"
20+
_all_possible_relations = ("dc", "ec", "po", "eq", "tpp", "ntpp", "tppi", "ntppi")
21+
1822
def __init__(self):
1923
super(QSR_RCC8_Rectangle_Bounding_Boxes_2D, self).__init__()
20-
self._unique_id = "rcc8"
21-
self._all_possible_relations = ("dc", "ec", "po", "eq", "tpp", "ntpp", "tppi", "ntppi")
2224

2325
def _convert_to_requested_rcc_type(self, qsr):
2426
return qsr

0 commit comments

Comments
 (0)