Skip to content

Commit 4880986

Browse files
committed
fix code for coveralls
1 parent 1119587 commit 4880986

File tree

24 files changed

+122
-122
lines changed

24 files changed

+122
-122
lines changed

AerialNavigation/drone_3d_trajectory_following/Quadrotor.py

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -51,12 +51,12 @@ def transformation_matrix(self):
5151
yaw = self.yaw
5252
return np.array(
5353
[[cos(yaw) * cos(pitch), -sin(yaw) * cos(roll) + cos(yaw) * sin(pitch) * sin(roll), sin(yaw) * sin(roll) + cos(yaw) * sin(pitch) * cos(roll), x],
54-
[sin(yaw) * cos(pitch), cos(yaw) * cos(roll) + sin(yaw) * sin(pitch) *
55-
sin(roll), -cos(yaw) * sin(roll) + sin(yaw) * sin(pitch) * cos(roll), y],
54+
[sin(yaw) * cos(pitch), cos(yaw) * cos(roll) + sin(yaw) * sin(pitch)
55+
* sin(roll), -cos(yaw) * sin(roll) + sin(yaw) * sin(pitch) * cos(roll), y],
5656
[-sin(pitch), cos(pitch) * sin(roll), cos(pitch) * cos(yaw), z]
5757
])
5858

59-
def plot(self):
59+
def plot(self): # pragma: no cover
6060
T = self.transformation_matrix()
6161

6262
p1_t = np.matmul(T, self.p1)

AerialNavigation/rocket_powered_landing/rocket_powered_landing.py

Lines changed: 43 additions & 43 deletions
Original file line numberDiff line numberDiff line change
@@ -129,12 +129,12 @@ def f_func(self, x, u):
129129
[vx],
130130
[vy],
131131
[vz],
132-
[(-1.0 * m - ux * (2 * q2**2 + 2 * q3**2 - 1) - 2 * uy *
133-
(q0 * q3 - q1 * q2) + 2 * uz * (q0 * q2 + q1 * q3)) / m],
134-
[(2 * ux * (q0 * q3 + q1 * q2) - uy * (2 * q1**2 +
135-
2 * q3**2 - 1) - 2 * uz * (q0 * q1 - q2 * q3)) / m],
136-
[(-2 * ux * (q0 * q2 - q1 * q3) + 2 * uy *
137-
(q0 * q1 + q2 * q3) - uz * (2 * q1**2 + 2 * q2**2 - 1)) / m],
132+
[(-1.0 * m - ux * (2 * q2**2 + 2 * q3**2 - 1) - 2 * uy
133+
* (q0 * q3 - q1 * q2) + 2 * uz * (q0 * q2 + q1 * q3)) / m],
134+
[(2 * ux * (q0 * q3 + q1 * q2) - uy * (2 * q1**2
135+
+ 2 * q3**2 - 1) - 2 * uz * (q0 * q1 - q2 * q3)) / m],
136+
[(-2 * ux * (q0 * q2 - q1 * q3) + 2 * uy
137+
* (q0 * q1 + q2 * q3) - uz * (2 * q1**2 + 2 * q2**2 - 1)) / m],
138138
[-0.5 * q1 * wx - 0.5 * q2 * wy - 0.5 * q3 * wz],
139139
[0.5 * q0 * wx + 0.5 * q2 * wz - 0.5 * q3 * wy],
140140
[0.5 * q0 * wy - 0.5 * q1 * wz + 0.5 * q3 * wx],
@@ -154,12 +154,12 @@ def A_func(self, x, u):
154154
[0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0],
155155
[0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0],
156156
[0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0],
157-
[(ux * (2 * q2**2 + 2 * q3**2 - 1) + 2 * uy * (q0 * q3 - q1 * q2) - 2 * uz * (q0 * q2 + q1 * q3)) / m**2, 0, 0, 0, 0, 0, 0, 2 * (q2 * uz -
158-
q3 * uy) / m, 2 * (q2 * uy + q3 * uz) / m, 2 * (q0 * uz + q1 * uy - 2 * q2 * ux) / m, 2 * (-q0 * uy + q1 * uz - 2 * q3 * ux) / m, 0, 0, 0],
159-
[(-2 * ux * (q0 * q3 + q1 * q2) + uy * (2 * q1**2 + 2 * q3**2 - 1) + 2 * uz * (q0 * q1 - q2 * q3)) / m**2, 0, 0, 0, 0, 0, 0, 2 * (-q1 * uz +
160-
q3 * ux) / m, 2 * (-q0 * uz - 2 * q1 * uy + q2 * ux) / m, 2 * (q1 * ux + q3 * uz) / m, 2 * (q0 * ux + q2 * uz - 2 * q3 * uy) / m, 0, 0, 0],
161-
[(2 * ux * (q0 * q2 - q1 * q3) - 2 * uy * (q0 * q1 + q2 * q3) + uz * (2 * q1**2 + 2 * q2**2 - 1)) / m**2, 0, 0, 0, 0, 0, 0, 2 * (q1 * uy -
162-
q2 * ux) / m, 2 * (q0 * uy - 2 * q1 * uz + q3 * ux) / m, 2 * (-q0 * ux - 2 * q2 * uz + q3 * uy) / m, 2 * (q1 * ux + q2 * uy) / m, 0, 0, 0],
157+
[(ux * (2 * q2**2 + 2 * q3**2 - 1) + 2 * uy * (q0 * q3 - q1 * q2) - 2 * uz * (q0 * q2 + q1 * q3)) / m**2, 0, 0, 0, 0, 0, 0, 2 * (q2 * uz
158+
- q3 * uy) / m, 2 * (q2 * uy + q3 * uz) / m, 2 * (q0 * uz + q1 * uy - 2 * q2 * ux) / m, 2 * (-q0 * uy + q1 * uz - 2 * q3 * ux) / m, 0, 0, 0],
159+
[(-2 * ux * (q0 * q3 + q1 * q2) + uy * (2 * q1**2 + 2 * q3**2 - 1) + 2 * uz * (q0 * q1 - q2 * q3)) / m**2, 0, 0, 0, 0, 0, 0, 2 * (-q1 * uz
160+
+ q3 * ux) / m, 2 * (-q0 * uz - 2 * q1 * uy + q2 * ux) / m, 2 * (q1 * ux + q3 * uz) / m, 2 * (q0 * ux + q2 * uz - 2 * q3 * uy) / m, 0, 0, 0],
161+
[(2 * ux * (q0 * q2 - q1 * q3) - 2 * uy * (q0 * q1 + q2 * q3) + uz * (2 * q1**2 + 2 * q2**2 - 1)) / m**2, 0, 0, 0, 0, 0, 0, 2 * (q1 * uy
162+
- q2 * ux) / m, 2 * (q0 * uy - 2 * q1 * uz + q3 * ux) / m, 2 * (-q0 * ux - 2 * q2 * uz + q3 * uy) / m, 2 * (q1 * ux + q2 * uy) / m, 0, 0, 0],
163163
[0, 0, 0, 0, 0, 0, 0, 0, -0.5 * wx, -0.5 * wy,
164164
- 0.5 * wz, -0.5 * q1, -0.5 * q2, -0.5 * q3],
165165
[0, 0, 0, 0, 0, 0, 0, 0.5 * wx, 0, 0.5 * wz,
@@ -184,12 +184,12 @@ def B_func(self, x, u):
184184
[0, 0, 0],
185185
[0, 0, 0],
186186
[0, 0, 0],
187-
[(-2 * q2**2 - 2 * q3**2 + 1) / m, 2 *
188-
(-q0 * q3 + q1 * q2) / m, 2 * (q0 * q2 + q1 * q3) / m],
189-
[2 * (q0 * q3 + q1 * q2) / m, (-2 * q1**2 - 2 *
190-
q3**2 + 1) / m, 2 * (-q0 * q1 + q2 * q3) / m],
191-
[2 * (-q0 * q2 + q1 * q3) / m, 2 * (q0 * q1 + q2 * q3) /
192-
m, (-2 * q1**2 - 2 * q2**2 + 1) / m],
187+
[(-2 * q2**2 - 2 * q3**2 + 1) / m, 2
188+
* (-q0 * q3 + q1 * q2) / m, 2 * (q0 * q2 + q1 * q3) / m],
189+
[2 * (q0 * q3 + q1 * q2) / m, (-2 * q1**2 - 2
190+
* q3**2 + 1) / m, 2 * (-q0 * q1 + q2 * q3) / m],
191+
[2 * (-q0 * q2 + q1 * q3) / m, 2 * (q0 * q1 + q2 * q3)
192+
/ m, (-2 * q1**2 - 2 * q2**2 + 1) / m],
193193
[0, 0, 0],
194194
[0, 0, 0],
195195
[0, 0, 0],
@@ -227,12 +227,12 @@ def skew(self, v):
227227

228228
def dir_cosine(self, q):
229229
return np.matrix([
230-
[1 - 2 * (q[2] ** 2 + q[3] ** 2), 2 * (q[1] * q[2] +
231-
q[0] * q[3]), 2 * (q[1] * q[3] - q[0] * q[2])],
232-
[2 * (q[1] * q[2] - q[0] * q[3]), 1 - 2 *
233-
(q[1] ** 2 + q[3] ** 2), 2 * (q[2] * q[3] + q[0] * q[1])],
234-
[2 * (q[1] * q[3] + q[0] * q[2]), 2 * (q[2] * q[3] -
235-
q[0] * q[1]), 1 - 2 * (q[1] ** 2 + q[2] ** 2)]
230+
[1 - 2 * (q[2] ** 2 + q[3] ** 2), 2 * (q[1] * q[2]
231+
+ q[0] * q[3]), 2 * (q[1] * q[3] - q[0] * q[2])],
232+
[2 * (q[1] * q[2] - q[0] * q[3]), 1 - 2
233+
* (q[1] ** 2 + q[3] ** 2), 2 * (q[2] * q[3] + q[0] * q[1])],
234+
[2 * (q[1] * q[3] + q[0] * q[2]), 2 * (q[2] * q[3]
235+
- q[0] * q[1]), 1 - 2 * (q[1] ** 2 + q[2] ** 2)]
236236
])
237237

238238
def omega(self, w):
@@ -459,16 +459,16 @@ def __init__(self, m, K):
459459
# Dynamics:
460460
# x_t+1 = A_*x_t+B_*U_t+C_*U_T+1*S_*sigma+zbar+nu
461461
constraints += [
462-
self.var['X'][:, k + 1]
463-
== cvxpy.reshape(self.par['A_bar'][:, k], (m.n_x, m.n_x))
464-
* self.var['X'][:, k]
465-
+ cvxpy.reshape(self.par['B_bar'][:, k], (m.n_x, m.n_u))
466-
* self.var['U'][:, k]
467-
+ cvxpy.reshape(self.par['C_bar'][:, k], (m.n_x, m.n_u))
468-
* self.var['U'][:, k + 1]
469-
+ self.par['S_bar'][:, k] * self.var['sigma']
470-
+ self.par['z_bar'][:, k]
471-
+ self.var['nu'][:, k]
462+
self.var['X'][:, k + 1] ==
463+
cvxpy.reshape(self.par['A_bar'][:, k], (m.n_x, m.n_x)) *
464+
self.var['X'][:, k] +
465+
cvxpy.reshape(self.par['B_bar'][:, k], (m.n_x, m.n_u)) *
466+
self.var['U'][:, k] +
467+
cvxpy.reshape(self.par['C_bar'][:, k], (m.n_x, m.n_u)) *
468+
self.var['U'][:, k + 1] +
469+
self.par['S_bar'][:, k] * self.var['sigma'] +
470+
self.par['z_bar'][:, k] +
471+
self.var['nu'][:, k]
472472
for k in range(K - 1)
473473
]
474474

@@ -486,10 +486,10 @@ def __init__(self, m, K):
486486

487487
# Objective:
488488
sc_objective = cvxpy.Minimize(
489-
self.par['weight_sigma'] * self.var['sigma']
490-
+ self.par['weight_nu'] * cvxpy.norm(self.var['nu'], 'inf')
491-
+ self.par['weight_delta'] * self.var['delta_norm']
492-
+ self.par['weight_delta_sigma'] * self.var['sigma_norm']
489+
self.par['weight_sigma'] * self.var['sigma'] +
490+
self.par['weight_nu'] * cvxpy.norm(self.var['nu'], 'inf') +
491+
self.par['weight_delta'] * self.var['delta_norm'] +
492+
self.par['weight_delta_sigma'] * self.var['sigma_norm']
493493
)
494494

495495
objective = sc_objective
@@ -550,8 +550,8 @@ def solve(self, **kwargs):
550550

551551
def axis3d_equal(X, Y, Z, ax):
552552

553-
max_range = np.array([X.max() - X.min(), Y.max() -
554-
Y.min(), Z.max() - Z.min()]).max()
553+
max_range = np.array([X.max() - X.min(), Y.max()
554+
- Y.min(), Z.max() - Z.min()]).max()
555555
Xb = 0.5 * max_range * np.mgrid[-1:2:2, -1:2:2,
556556
- 1:2:2][0].flatten() + 0.5 * (X.max() + X.min())
557557
Yb = 0.5 * max_range * np.mgrid[-1:2:2, -1:2:2,
@@ -563,7 +563,7 @@ def axis3d_equal(X, Y, Z, ax):
563563
ax.plot([xb], [yb], [zb], 'w')
564564

565565

566-
def plot_animation(X, U):
566+
def plot_animation(X, U): # pragma: no cover
567567

568568
fig = plt.figure()
569569
ax = fig.gca(projection='3d')
@@ -582,8 +582,8 @@ def plot_animation(X, U):
582582
CBI = np.array([
583583
[1 - 2 * (qy ** 2 + qz ** 2), 2 * (qx * qy + qw * qz),
584584
2 * (qx * qz - qw * qy)],
585-
[2 * (qx * qy - qw * qz), 1 - 2 *
586-
(qx ** 2 + qz ** 2), 2 * (qy * qz + qw * qx)],
585+
[2 * (qx * qy - qw * qz), 1 - 2
586+
* (qx ** 2 + qz ** 2), 2 * (qy * qz + qw * qx)],
587587
[2 * (qx * qz + qw * qy), 2 * (qy * qz - qw * qx),
588588
1 - 2 * (qx ** 2 + qy ** 2)]
589589
])

ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -241,7 +241,7 @@ def update_points(self):
241241

242242
self.end_effector = np.array(self.points[self.n_links]).T
243243

244-
def plot(self, obstacles=[]):
244+
def plot(self, obstacles=[]): # pragma: no cover
245245
plt.cla()
246246

247247
for obstacle in obstacles:

ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation_2.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -272,7 +272,7 @@ def update_points(self):
272272

273273
self.end_effector = np.array(self.points[self.n_links]).T
274274

275-
def plot(self, myplt, obstacles=[]):
275+
def plot(self, myplt, obstacles=[]): # pragma: no cover
276276
myplt.cla()
277277

278278
for obstacle in obstacles:

ArmNavigation/n_joint_arm_to_point_control/NLinkArm.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -49,7 +49,7 @@ def update_points(self):
4949
if self.show_animation:
5050
self.plot()
5151

52-
def plot(self):
52+
def plot(self): # pragma: no cover
5353
plt.cla()
5454

5555
for i in range(self.n_links + 1):

ArmNavigation/n_joint_arm_to_point_control/n_joint_arm_to_point_control.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -159,5 +159,5 @@ def ang_diff(theta1, theta2):
159159

160160

161161
if __name__ == '__main__':
162-
main()
163-
# animation()
162+
# main()
163+
animation()

ArmNavigation/two_joint_arm_to_point_control/two_joint_arm_to_point_control.py

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -39,8 +39,8 @@ def two_joint_arm(GOAL_TH=0.0, theta1=0.0, theta2=0.0):
3939
try:
4040
theta2_goal = np.arccos(
4141
(x**2 + y**2 - l1**2 - l2**2) / (2 * l1 * l2))
42-
theta1_goal = np.math.atan2(y, x) - np.math.atan2(l2 *
43-
np.sin(theta2_goal), (l1 + l2 * np.cos(theta2_goal)))
42+
theta1_goal = np.math.atan2(y, x) - np.math.atan2(l2
43+
* np.sin(theta2_goal), (l1 + l2 * np.cos(theta2_goal)))
4444

4545
if theta1_goal < 0:
4646
theta2_goal = -theta2_goal
@@ -61,7 +61,7 @@ def two_joint_arm(GOAL_TH=0.0, theta1=0.0, theta2=0.0):
6161
return theta1, theta2
6262

6363

64-
def plot_arm(theta1, theta2, x, y):
64+
def plot_arm(theta1, theta2, x, y): # pragma: no cover
6565
shoulder = np.array([0, 0])
6666
elbow = shoulder + np.array([l1 * np.cos(theta1), l1 * np.sin(theta1)])
6767
wrist = elbow + \

Localization/extended_kalman_filter/extended_kalman_filter.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -134,7 +134,7 @@ def ekf_estimation(xEst, PEst, z, u):
134134
return xEst, PEst
135135

136136

137-
def plot_covariance_ellipse(xEst, PEst):
137+
def plot_covariance_ellipse(xEst, PEst): # pragma: no cover
138138
Pxy = PEst[0:2, 0:2]
139139
eigval, eigvec = np.linalg.eig(Pxy)
140140

Localization/particle_filter/particle_filter.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -156,7 +156,7 @@ def resampling(px, pw):
156156
return px, pw
157157

158158

159-
def plot_covariance_ellipse(xEst, PEst):
159+
def plot_covariance_ellipse(xEst, PEst): # pragma: no cover
160160
Pxy = PEst[0:2, 0:2]
161161
eigval, eigvec = np.linalg.eig(Pxy)
162162

Localization/unscented_kalman_filter/unscented_kalman_filter.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -161,7 +161,7 @@ def ukf_estimation(xEst, PEst, z, u, wm, wc, gamma):
161161
return xEst, PEst
162162

163163

164-
def plot_covariance_ellipse(xEst, PEst):
164+
def plot_covariance_ellipse(xEst, PEst): # pragma: no cover
165165
Pxy = PEst[0:2, 0:2]
166166
eigval, eigvec = np.linalg.eig(Pxy)
167167

0 commit comments

Comments
 (0)