Skip to content

Commit 8b3c4aa

Browse files
authored
Merge pull request #135 from project-neon/docs/real_life_in_code_documentation
Docs/real life in code documentation
2 parents 623c4ee + 943a9a9 commit 8b3c4aa

File tree

4 files changed

+168
-6
lines changed

4 files changed

+168
-6
lines changed

algorithms/limit_cycle/limit_cycle.py

Lines changed: 31 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -27,9 +27,11 @@ def filter_func(a, b, c, r, t, o):
2727
class LimitCycle(object):
2828
def __init__(self, match):
2929
'''
30-
- obstacles: list of the obstacles, not sorted yet
31-
- target_is_ball: if the ball is the target, two virtual obstacles are added
32-
to make the robot head to the goal when arriving
30+
Constructor of the Limit Cycle class
31+
32+
Parameters
33+
----------
34+
obstacles [list(Obstacle)] : list of the obstacles, not sorted yet
3335
'''
3436
self.match = match
3537
self.robot = None
@@ -46,9 +48,25 @@ def __init__(self, match):
4648
self.field_w, self.field_h = self.match.game.field.get_dimensions()
4749

4850
def set_target(self, target):
51+
'''
52+
Defines the target position
53+
54+
Parameters
55+
----------
56+
target (tuple[int, int]): target x and y coordinates
57+
'''
58+
4959
self.target = Target(*target)
5060

5161
def add_obstacle(self, obstacle: Obstacle):
62+
'''
63+
Add an obstacle to the 'obstacles' list
64+
65+
Parameters
66+
----------
67+
obstacle Obstacle(int, int, int, bool): obstacle x and y position, its radius and a 'force_clockwise' property
68+
'''
69+
5270
self.obstacles.append(Obstacle(*obstacle))
5371

5472
def contour(self, a, b, c, obstacle: Obstacle, fitness):
@@ -79,6 +97,15 @@ def contour(self, a, b, c, obstacle: Obstacle, fitness):
7997
return (self.robot.x + self.dt*ddx, self.robot.y + self.dt*ddy)
8098

8199
def compute(self, robot, fitness=15):
100+
'''
101+
Runs the Limit Cycle algorithm
102+
103+
Parameters
104+
----------
105+
robot Robot: robot entity from match
106+
fitness int: parameter to increase/decrease the 'fitness' of the trajectory
107+
'''
108+
82109
self.robot = robot
83110
'''
84111
a, b and c are the indexes of a linear equation: a*x + b*y + c = 0
@@ -99,7 +126,7 @@ def compute(self, robot, fitness=15):
99126
self.obstacles.sort(key=lambda o: math.sqrt((o.x - self.robot.x)**2 + (o.y - self.robot.y)**2))
100127

101128
'''
102-
here we have the conditional, if there are obstacles to contour we do so, else we go to the target
129+
here we have the conditional, if there are obstacles to contour we do so, else we go straight to the target
103130
'''
104131
if len(self.obstacles) > 0:
105132
return self.contour(a, b, c, self.obstacles[0], fitness)

algorithms/univector_field/univector_field.py

Lines changed: 51 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -23,7 +23,23 @@ def reduce_angle(ang):
2323
np_reduce_angle = np.vectorize(reduce_angle)
2424

2525
class UnivectorField:
26+
"""
27+
An implementation of the uni vector field path planning algotithm
28+
29+
The UnivectorField will generate vector that guides a given point to the target so that it gets there with an angle
30+
directed at the guiding point. This algorithm is also capable of contouring obstacles and generating a rectangle
31+
behind the target where the vectors have the save directions as the target-guide vector.
32+
"""
33+
2634
def __init__(self, n, rect_size, plot=False, path=''):
35+
"""Inits UnivectorField class.
36+
37+
Parameters
38+
----------
39+
n: Constant the related to how much the path will avoid hitting the target from the wrong direction
40+
rect_size: the base side size of the rectangle behind the target where all the vectors are the same
41+
angle of the target-guide line
42+
"""
2743
self.obstacles = []
2844
self.N = n
2945
self.delta_g = rect_size
@@ -37,18 +53,40 @@ def set_target(self, g, r):
3753
3854
Parameters
3955
----------
40-
g (tuple[int, int]): target x and y coordinates
41-
r (tuple[int, int]): guide point x and y coordinates
56+
g (tuple[float, float]): target x and y coordinates
57+
r (tuple[float, float]): guide point x and y coordinates
4258
"""
4359

4460
self.g = g
4561
self.r = r
4662

4763
def add_obstacle(self, p, r0, m):
64+
"""
65+
Add one obstacle
66+
67+
Parameters
68+
----------
69+
p (tuple[float, float]): obstacle center x and y coordinates
70+
r0 (float): obstacle radius
71+
m (float): obstacle margin (distance the path will avoid)
72+
73+
Return
74+
----------
75+
obstacle (obstacle): the obstacle object
76+
"""
77+
4878
self.obstacles.append(Obstacle(p, r0, m, m + r0))
4979
return self.obstacles[-1]
5080

5181
def del_obstacle(self, *args, all=False):
82+
"""
83+
Delete any amount of obstacles
84+
85+
Parameters
86+
----------
87+
*args (list[obstacles]): one or more obstacle to be deleted
88+
all (bool): whether to delete all obstacles
89+
"""
5290
if all:
5391
self.obstacles = []
5492
return
@@ -78,6 +116,17 @@ def __call__(self, p):
78116
return self.compute(p)
79117

80118
def compute(self, p):
119+
"""
120+
Calculate the angle for the given position
121+
122+
Parameters
123+
----------
124+
p (tuple[float, float]): the position for which the angle will be calculated
125+
126+
Return
127+
----------
128+
angle (float): the angle of the vector in the field at the given position
129+
"""
81130
behind_angle = None
82131

83132
ang_pr = angle_between(p, self.r)

controller/PID_control.py

Lines changed: 56 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,33 @@ def angle_adjustment(angle):
1313

1414

1515
class PID_control(object):
16+
"""
17+
An implementation of the PID controller on linear and angular speed
18+
19+
The PID_control will receive a target position (x, y) and calculate the angular speed needed to reach the target
20+
angle (ensure that the robot angle is in the direction of the target) using the PID algorithm. It will also
21+
calculate the linear speed based on the distance from the robot and the target using a P algorithm.
22+
23+
Attributes
24+
----------
25+
K_RHO : float
26+
the linear Kp value
27+
KP : float
28+
the angular Kp value
29+
KD : float
30+
the angular Kd value
31+
KI : float
32+
the angular Ki value
33+
V_MAX : int
34+
the maximum linear speed
35+
V_MIN : int
36+
the minimum linear speed
37+
W_MAX : int
38+
the maximum angular speed
39+
TWO_SIDES: bool
40+
whether the controller will consider the robot as having two equal sides or only one
41+
"""
42+
1643
CONSTANTS = {
1744
'simulation': {
1845
# Control params
@@ -69,6 +96,13 @@ def __init__(self, robot, default_fps=60, **kwargs):
6996
self.last_ki = self.KI
7097

7198
def set_desired(self, vector):
99+
"""
100+
Defines the target position
101+
102+
Parameters
103+
----------
104+
vector (tuple[float, float]): target x and y coordinates
105+
"""
72106
self.desired = vector
73107

74108
def _update_fps(self):
@@ -125,6 +159,28 @@ def update(self):
125159

126160

127161
class PID_W_control(PID_control):
162+
"""
163+
An implementation of the PID controller on the angular speed
164+
165+
The PID_control will receive a target position (x, y) and calculate the angular speed needed to reach the target
166+
angle (ensure that the robot angle is in the direction of the target) using the PID algorithm. It will set the robot
167+
linear speed as the maximum all times.
168+
169+
Attributes
170+
----------
171+
KP : float
172+
the angular Kp value
173+
KD : float
174+
the angular Kd value
175+
KI : float
176+
the angular Ki value
177+
V_MAX : int
178+
the maximum linear speed
179+
W_MAX : int
180+
the maximum angular speed
181+
TWO_SIDES: bool
182+
whether the controller will consider the robot as having two equal sides or only one
183+
"""
128184

129185
def update(self):
130186
v, w = super()._update()

controller/uni_controller.py

Lines changed: 30 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -8,6 +8,28 @@
88
"""
99

1010
class UniController(object):
11+
"""
12+
An implementation of the Uni controller specified on the soccer robotics article
13+
14+
The UniController will receive a desired angle for the robot current position, the desired angle for the position in
15+
front of the robot and along with the current robot angle it will calculate the robot angular and linear speed. it
16+
can also be set through the control_speed parameter to slow down when near the target position.
17+
18+
Attributes
19+
----------
20+
K_P : float
21+
the linear Kp value
22+
control_speed : bool
23+
whether the controller will use the P control for linear speed
24+
V_M : int
25+
the maximum linear speed
26+
K_W : float
27+
a positive constant
28+
R_M : int
29+
the maximum turn (v*w)
30+
target: tuple[float, float]
31+
the target position used for calculating the linear speed P
32+
"""
1133

1234
CONSTANTS = {
1335
'simulation': {
@@ -95,6 +117,14 @@ def control(self):
95117
return v, w
96118

97119
def set_desired(self, desired):
120+
"""
121+
Defines the target angles
122+
123+
Parameters
124+
----------
125+
desired (tuple[float, float]): the desired angle in the current position and in the desired angle in
126+
front of the robot
127+
"""
98128
self.theta_d = desired[0]
99129
self.theta_f = desired[1]
100130

0 commit comments

Comments
 (0)