From c1ba9bab0a48100aa3f81286a2015c5112bb1f9f Mon Sep 17 00:00:00 2001 From: Francisco Moretti Date: Thu, 17 Oct 2019 09:09:54 -0300 Subject: [PATCH 01/16] fix check segment intersection with obstacle The previous method only worked because the step that checked collision from a point of the line to obstacles was the same as the minimum obstacle radius. If the obstacle radius is very small a great amount of steps would be required. Thus It's better to check the distance from the segment to the obstacles directly and compare with obstacle radius Now there is no need to have two check functions. --- .../InformedRRTStar/informed_rrt_star.py | 52 ++++++++++--------- 1 file changed, 28 insertions(+), 24 deletions(-) diff --git a/PathPlanning/InformedRRTStar/informed_rrt_star.py b/PathPlanning/InformedRRTStar/informed_rrt_star.py index 4a32801d..b9769bea 100644 --- a/PathPlanning/InformedRRTStar/informed_rrt_star.py +++ b/PathPlanning/InformedRRTStar/informed_rrt_star.py @@ -74,10 +74,9 @@ class InformedRRTStar: newNode = self.get_new_node(theta, nind, nearestNode) d = self.line_cost(nearestNode, newNode) - isCollision = self.collision_check(newNode, self.obstacle_list) - isCollisionEx = self.check_collision_extend(nearestNode, theta, d) + isCollision = self.check_collision(nearestNode, theta, d) - if isCollision and isCollisionEx: + if isCollision: nearInds = self.find_near_nodes(newNode) newNode = self.choose_parent(newNode, nearInds) @@ -110,7 +109,7 @@ class InformedRRTStar: dy = newNode.y - self.node_list[i].y d = math.sqrt(dx ** 2 + dy ** 2) theta = math.atan2(dy, dx) - if self.check_collision_extend(self.node_list[i], theta, d): + if self.check_collision(self.node_list[i], theta, d): dList.append(self.node_list[i].cost + d) else: dList.append(float('inf')) @@ -194,17 +193,6 @@ class InformedRRTStar: minIndex = dList.index(min(dList)) return minIndex - @staticmethod - def collision_check(newNode, obstacleList): - for (ox, oy, size) in obstacleList: - dx = ox - newNode.x - dy = oy - newNode.y - d = dx * dx + dy * dy - if d <= 1.1 * size ** 2: - return False # collision - - return True # safe - def get_new_node(self, theta, nind, nearestNode): newNode = copy.deepcopy(nearestNode) @@ -234,19 +222,35 @@ class InformedRRTStar: if nearNode.cost > scost: theta = math.atan2(newNode.y - nearNode.y, newNode.x - nearNode.x) - if self.check_collision_extend(nearNode, theta, d): + if self.check_collision(nearNode, theta, d): nearNode.parent = n_node - 1 nearNode.cost = scost + + @staticmethod + def distance_squared_point_to_segment(v, w, p): + # Return minimum distance between line segment vw and point p + if (np.array_equal(v, w)): + return (p-v).dot(p-v) # v == w case + l2 = (w-v).dot(w-v) # i.e. |w-v|^2 - avoid a sqrt + # Consider the line extending the segment, parameterized as v + t (w - v). + # We find projection of point p onto the line. + # It falls where t = [(p-v) . (w-v)] / |w-v|^2 + # We clamp t from [0,1] to handle points outside the segment vw. + t = max(0, min(1, (p - v).dot(w - v) / l2)) + projection = v + t * (w - v) # Projection falls on the segment + return (p-projection).dot(p-projection) - def check_collision_extend(self, nearNode, theta, d): + def check_collision(self, nearNode, theta, d): tmpNode = copy.deepcopy(nearNode) - - for i in range(int(d / self.expand_dis)): - tmpNode.x += self.expand_dis * math.cos(theta) - tmpNode.y += self.expand_dis * math.sin(theta) - if not self.collision_check(tmpNode, self.obstacle_list): - return False - + endx = tmpNode.x + math.cos(theta)*d + endy = tmpNode.y + math.sin(theta)*d + for (ox, oy, size) in self.obstacle_list: + dd = self.distance_squared_point_to_segment( + np.array([tmpNode.x, tmpNode.y]), + np.array([endx, endy]), + np.array([ox, oy])) + if dd <= 1.1 * size**2: + return False # collision return True def get_final_course(self, lastIndex): From b2d65f277ec9d7a122baaec7d2bf4a4b77c5d6a8 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?G=C3=B6ktu=C4=9F=20Karaka=C5=9Fl=C4=B1?= <20567087+goktug97@users.noreply.github.com> Date: Sat, 26 Oct 2019 09:11:23 +0300 Subject: [PATCH 02/16] change resampling function to match with the book - changed resampling function so that it chooses random number once for the starting point. - condition check is moved from the inside of the resampling function to the outside of the function, this way the purpose of the function is much clear. Instead "resampling" every iteration, resample if the condition holds. --- .../particle_filter/particle_filter.py | 30 +++++++++---------- 1 file changed, 14 insertions(+), 16 deletions(-) diff --git a/Localization/particle_filter/particle_filter.py b/Localization/particle_filter/particle_filter.py index 6643116f..0ebb5fc3 100644 --- a/Localization/particle_filter/particle_filter.py +++ b/Localization/particle_filter/particle_filter.py @@ -128,8 +128,9 @@ def pf_localization(px, pw, z, u): xEst = px.dot(pw.T) PEst = calc_covariance(xEst, px, pw) - px, pw = re_sampling(px, pw) - + N_eff = 1.0 / (pw.dot(pw.T))[0, 0] # Effective particle number + if N_eff < NTh: + px, pw = re_sampling(px, pw) return xEst, PEst, px, pw @@ -138,21 +139,18 @@ def re_sampling(px, pw): low variance re-sampling """ - N_eff = 1.0 / (pw.dot(pw.T))[0, 0] # Effective particle number - if N_eff < NTh: - w_cum = np.cumsum(pw) - base = np.cumsum(pw * 0.0 + 1 / NP) - 1 / NP - re_sample_id = base + np.random.rand(base.shape[0]) / NP + w_cum = np.cumsum(pw) + base = np.arange(0.0, 1.0, 1/NP) + re_sample_id = base + np.random.uniform(0, 1/NP) + indexes = [] + ind = 0 + for ip in range(NP): + while re_sample_id[ip] > w_cum[ind]: + ind += 1 + indexes.append(ind) - indexes = [] - ind = 0 - for ip in range(NP): - while re_sample_id[ip] > w_cum[ind]: - ind += 1 - indexes.append(ind) - - px = px[:, indexes] - pw = np.zeros((1, NP)) + 1.0 / NP # init weight + px = px[:, indexes] + pw = np.zeros((1, NP)) + 1.0 / NP # init weight return px, pw From 342e671b34f7cced14388b3b33fc4c4dd7dd119f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?G=C3=B6ktu=C4=9F=20Karaka=C5=9Fl=C4=B1?= <20567087+goktug97@users.noreply.github.com> Date: Fri, 25 Oct 2019 15:30:16 +0300 Subject: [PATCH 03/16] optimize nearest_neighbor_assosiation - vectorize distance calculation - append authors --- .../iterative_closest_point.py | 24 +++++++------------ 1 file changed, 8 insertions(+), 16 deletions(-) diff --git a/SLAM/iterative_closest_point/iterative_closest_point.py b/SLAM/iterative_closest_point/iterative_closest_point.py index 73651d8e..ec81bb12 100644 --- a/SLAM/iterative_closest_point/iterative_closest_point.py +++ b/SLAM/iterative_closest_point/iterative_closest_point.py @@ -1,6 +1,6 @@ """ Iterative Closest Point (ICP) SLAM example -author: Atsushi Sakai (@Atsushi_twi) +author: Atsushi Sakai (@Atsushi_twi), Göktuğ Karakaşlı """ import math @@ -39,7 +39,7 @@ def ICP_matching(ppoints, cpoints): plt.plot(cpoints[0, :], cpoints[1, :], ".b") plt.plot(0.0, 0.0, "xr") plt.axis("equal") - plt.pause(1.0) + plt.pause(0.1) inds, error = nearest_neighbor_assosiation(ppoints, cpoints) Rt, Tt = SVD_motion_estimation(ppoints[:, inds], cpoints) @@ -93,18 +93,10 @@ def nearest_neighbor_assosiation(ppoints, cpoints): error = sum(d) # calc index with nearest neighbor assosiation - inds = [] - for i in range(cpoints.shape[1]): - minid = -1 - mind = float("inf") - for ii in range(ppoints.shape[1]): - d = np.linalg.norm(ppoints[:, ii] - cpoints[:, i]) - - if mind >= d: - mind = d - minid = ii - - inds.append(minid) + d = np.linalg.norm( + np.repeat(cpoints, ppoints.shape[1], axis=1) - np.tile(ppoints, (1, + cpoints.shape[1])), axis=0) + inds = np.argmin(d.reshape(cpoints.shape[1], ppoints.shape[1]), axis=1) return inds, error @@ -130,7 +122,7 @@ def main(): print(__file__ + " start!!") # simulation parameters - nPoint = 10 + nPoint = 1000 fieldLength = 50.0 motion = [0.5, 2.0, np.deg2rad(-10.0)] # movement [x[m],y[m],yaw[deg]] @@ -156,4 +148,4 @@ def main(): if __name__ == '__main__': - main() \ No newline at end of file + main() From 97570de50c222c3362dfda765fd951f37cfb900f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?G=C3=B6ktu=C4=9F=20Karaka=C5=9Fl=C4=B1?= <20567087+goktug97@users.noreply.github.com> Date: Wed, 23 Oct 2019 10:14:14 +0300 Subject: [PATCH 04/16] Fix wrong rotation direction - The obstacle rotation for the rectangle obstacle calculation is wrong. It should be positive instead of negative. --- PathPlanning/DynamicWindowApproach/dynamic_window_approach.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py index c2a8674a..c8a44349 100644 --- a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py +++ b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py @@ -2,7 +2,7 @@ Mobile robot motion planning sample with Dynamic Window Approach -author: Atsushi Sakai (@Atsushi_twi), Goktug Karakasli +author: Atsushi Sakai (@Atsushi_twi), Göktuğ Karakaşlı """ @@ -172,7 +172,7 @@ def calc_obstacle_cost(trajectory, ob, config): rot = np.transpose(rot, [2, 0, 1]) local_ob = ob[:, None] - trajectory[:, 0:2] local_ob = local_ob.reshape(-1, local_ob.shape[-1]) - local_ob = np.array([local_ob @ -x for x in rot]) + local_ob = np.array([local_ob @ x for x in rot]) local_ob = local_ob.reshape(-1, local_ob.shape[-1]) upper_check = local_ob[:, 0] <= config.robot_length / 2 right_check = local_ob[:, 1] <= config.robot_width / 2 From 49ce57d6f8de1265eb1e578dd0f069c6b7a56ca6 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 27 Oct 2019 17:59:08 +0900 Subject: [PATCH 05/16] Code cleanup. --- .../iterative_closest_point.py | 57 +++++++++---------- tests/test_LQR_planner.py | 4 +- 2 files changed, 30 insertions(+), 31 deletions(-) diff --git a/SLAM/iterative_closest_point/iterative_closest_point.py b/SLAM/iterative_closest_point/iterative_closest_point.py index ec81bb12..3512ef97 100644 --- a/SLAM/iterative_closest_point/iterative_closest_point.py +++ b/SLAM/iterative_closest_point/iterative_closest_point.py @@ -4,22 +4,23 @@ author: Atsushi Sakai (@Atsushi_twi), Göktuğ Karakaşlı """ import math -import numpy as np + import matplotlib.pyplot as plt +import numpy as np # ICP parameters EPS = 0.0001 -MAXITER = 100 +MAX_ITER = 100 show_animation = True -def ICP_matching(ppoints, cpoints): +def icp_matching(previous_points, current_points): """ Iterative Closest Point matching - input - ppoints: 2D points in the previous frame - cpoints: 2D points in the current frame + previous_points: 2D points in the previous frame + current_points: 2D points in the current frame - output R: Rotation matrix T: Translation vector @@ -35,17 +36,17 @@ def ICP_matching(ppoints, cpoints): if show_animation: # pragma: no cover plt.cla() - plt.plot(ppoints[0, :], ppoints[1, :], ".r") - plt.plot(cpoints[0, :], cpoints[1, :], ".b") + plt.plot(previous_points[0, :], previous_points[1, :], ".r") + plt.plot(current_points[0, :], current_points[1, :], ".b") plt.plot(0.0, 0.0, "xr") plt.axis("equal") plt.pause(0.1) - inds, error = nearest_neighbor_assosiation(ppoints, cpoints) - Rt, Tt = SVD_motion_estimation(ppoints[:, inds], cpoints) + indexes, error = nearest_neighbor_association(previous_points, current_points) + Rt, Tt = svd_motion_estimation(previous_points[:, indexes], current_points) # update current points - cpoints = (Rt @ cpoints) + Tt[:, np.newaxis] + current_points = (Rt @ current_points) + Tt[:, np.newaxis] H = update_homogeneous_matrix(H, Rt, Tt) @@ -56,7 +57,7 @@ def ICP_matching(ppoints, cpoints): if dError <= EPS: print("Converge", error, dError, count) break - elif MAXITER <= count: + elif MAX_ITER <= count: print("Not Converge...", error, dError, count) break @@ -85,31 +86,29 @@ def update_homogeneous_matrix(Hin, R, T): return Hin @ H -def nearest_neighbor_assosiation(ppoints, cpoints): +def nearest_neighbor_association(previous_points, current_points): # calc the sum of residual errors - dcpoints = ppoints - cpoints - d = np.linalg.norm(dcpoints, axis=0) + delta_points = previous_points - current_points + d = np.linalg.norm(delta_points, axis=0) error = sum(d) # calc index with nearest neighbor assosiation - d = np.linalg.norm( - np.repeat(cpoints, ppoints.shape[1], axis=1) - np.tile(ppoints, (1, - cpoints.shape[1])), axis=0) - inds = np.argmin(d.reshape(cpoints.shape[1], ppoints.shape[1]), axis=1) + d = np.linalg.norm(np.repeat(current_points, previous_points.shape[1], axis=1) + - np.tile(previous_points, (1, current_points.shape[1])), axis=0) + indexes = np.argmin(d.reshape(current_points.shape[1], previous_points.shape[1]), axis=1) - return inds, error + return indexes, error -def SVD_motion_estimation(ppoints, cpoints): +def svd_motion_estimation(previous_points, current_points): + pm = np.mean(previous_points, axis=1) + cm = np.mean(current_points, axis=1) - pm = np.mean(ppoints, axis=1) - cm = np.mean(cpoints, axis=1) + p_shift = previous_points - pm[:, np.newaxis] + c_shift = current_points - cm[:, np.newaxis] - pshift = ppoints - pm[:, np.newaxis] - cshift = cpoints - cm[:, np.newaxis] - - W = cshift @ pshift.T + W = c_shift @ p_shift.T u, s, vh = np.linalg.svd(W) R = (u @ vh).T @@ -133,16 +132,16 @@ def main(): # previous points px = (np.random.rand(nPoint) - 0.5) * fieldLength py = (np.random.rand(nPoint) - 0.5) * fieldLength - ppoints = np.vstack((px, py)) + previous_points = np.vstack((px, py)) # current points cx = [math.cos(motion[2]) * x - math.sin(motion[2]) * y + motion[0] for (x, y) in zip(px, py)] cy = [math.sin(motion[2]) * x + math.cos(motion[2]) * y + motion[1] for (x, y) in zip(px, py)] - cpoints = np.vstack((cx, cy)) + current_points = np.vstack((cx, cy)) - R, T = ICP_matching(ppoints, cpoints) + R, T = icp_matching(previous_points, current_points) print("R:", R) print("T:", T) diff --git a/tests/test_LQR_planner.py b/tests/test_LQR_planner.py index 5ece27f8..2bcf828c 100644 --- a/tests/test_LQR_planner.py +++ b/tests/test_LQR_planner.py @@ -1,6 +1,6 @@ +import sys from unittest import TestCase -import sys sys.path.append("./PathPlanning/LQRPlanner") from PathPlanning.LQRPlanner import LQRplanner as m @@ -11,5 +11,5 @@ print(__file__) class Test(TestCase): def test1(self): - m.show_animation = False + m.SHOW_ANIMATION = False m.main() From 3f14311cc54cb071b530a03b7a0245a61987c300 Mon Sep 17 00:00:00 2001 From: Francisco Moretti Date: Sun, 3 Nov 2019 12:07:56 -0300 Subject: [PATCH 06/16] correct variable name --- PathPlanning/InformedRRTStar/informed_rrt_star.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/PathPlanning/InformedRRTStar/informed_rrt_star.py b/PathPlanning/InformedRRTStar/informed_rrt_star.py index b9769bea..98a239ab 100644 --- a/PathPlanning/InformedRRTStar/informed_rrt_star.py +++ b/PathPlanning/InformedRRTStar/informed_rrt_star.py @@ -74,9 +74,9 @@ class InformedRRTStar: newNode = self.get_new_node(theta, nind, nearestNode) d = self.line_cost(nearestNode, newNode) - isCollision = self.check_collision(nearestNode, theta, d) + noCollision = self.check_collision(nearestNode, theta, d) - if isCollision: + if noCollision: nearInds = self.find_near_nodes(newNode) newNode = self.choose_parent(newNode, nearInds) From 178dca3e343749b9e3ec3d1fda7a89f464532cda Mon Sep 17 00:00:00 2001 From: Francisco Moretti Date: Sun, 3 Nov 2019 12:12:53 -0300 Subject: [PATCH 07/16] add collision check to node near to goal --- .../InformedRRTStar/informed_rrt_star.py | 21 ++++++++++++------- 1 file changed, 13 insertions(+), 8 deletions(-) diff --git a/PathPlanning/InformedRRTStar/informed_rrt_star.py b/PathPlanning/InformedRRTStar/informed_rrt_star.py index 98a239ab..a8352bc0 100644 --- a/PathPlanning/InformedRRTStar/informed_rrt_star.py +++ b/PathPlanning/InformedRRTStar/informed_rrt_star.py @@ -84,6 +84,7 @@ class InformedRRTStar: self.rewire(newNode, nearInds) if self.is_near_goal(newNode): + if self.check_segment_collision(newNode.x, newNode.y, self.goal.x , self.goal.y): solutionSet.add(newNode) lastIndex = len(self.node_list) - 1 tempPath = self.get_final_course(lastIndex) @@ -240,18 +241,22 @@ class InformedRRTStar: projection = v + t * (w - v) # Projection falls on the segment return (p-projection).dot(p-projection) + def check_segment_collision(self, x1, y1, x2, y2): + for (ox, oy, size) in self.obstacle_list: + dd = self.distance_squared_point_to_segment( + np.array([x1, y1]), + np.array([x2, y2]), + np.array([ox, oy])) + if dd <= size**2: + return False # collision + return True + + def check_collision(self, nearNode, theta, d): tmpNode = copy.deepcopy(nearNode) endx = tmpNode.x + math.cos(theta)*d endy = tmpNode.y + math.sin(theta)*d - for (ox, oy, size) in self.obstacle_list: - dd = self.distance_squared_point_to_segment( - np.array([tmpNode.x, tmpNode.y]), - np.array([endx, endy]), - np.array([ox, oy])) - if dd <= 1.1 * size**2: - return False # collision - return True + return self.check_segment_collision(tmpNode.x, tmpNode.y, endx, endy) def get_final_course(self, lastIndex): path = [[self.goal.x, self.goal.y]] From 3e5cad819247edd892ae7f8f0192170e8a4c31bd Mon Sep 17 00:00:00 2001 From: Francisco Moretti Date: Sun, 3 Nov 2019 12:23:48 -0300 Subject: [PATCH 08/16] fix indentation --- PathPlanning/InformedRRTStar/informed_rrt_star.py | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/PathPlanning/InformedRRTStar/informed_rrt_star.py b/PathPlanning/InformedRRTStar/informed_rrt_star.py index a8352bc0..62a94064 100644 --- a/PathPlanning/InformedRRTStar/informed_rrt_star.py +++ b/PathPlanning/InformedRRTStar/informed_rrt_star.py @@ -85,13 +85,13 @@ class InformedRRTStar: if self.is_near_goal(newNode): if self.check_segment_collision(newNode.x, newNode.y, self.goal.x , self.goal.y): - solutionSet.add(newNode) - lastIndex = len(self.node_list) - 1 - tempPath = self.get_final_course(lastIndex) - tempPathLen = self.get_path_len(tempPath) - if tempPathLen < pathLen: - path = tempPath - cBest = tempPathLen + solutionSet.add(newNode) + lastIndex = len(self.node_list) - 1 + tempPath = self.get_final_course(lastIndex) + tempPathLen = self.get_path_len(tempPath) + if tempPathLen < pathLen: + path = tempPath + cBest = tempPathLen if animation: self.draw_graph(xCenter=xCenter, From 8b31c2bdf0cd1672f2282509e279540f76c2ef3a Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 17 Nov 2019 10:25:24 +0900 Subject: [PATCH 09/16] Create greetings.yml --- .github/workflows/greetings.yml | 13 +++++++++++++ 1 file changed, 13 insertions(+) create mode 100644 .github/workflows/greetings.yml diff --git a/.github/workflows/greetings.yml b/.github/workflows/greetings.yml new file mode 100644 index 00000000..3da4a694 --- /dev/null +++ b/.github/workflows/greetings.yml @@ -0,0 +1,13 @@ +name: Greetings + +on: [pull_request, issues] + +jobs: + greeting: + runs-on: ubuntu-latest + steps: + - uses: actions/first-interaction@v1 + with: + repo-token: ${{ secrets.GITHUB_TOKEN }} + issue-message: 'Message that will be displayed on users'' This is first issue for you on this project' + pr-message: 'Message that will be displayed on users'' This is first pr for you on this project' From 25ea5eb6c5a896350e6cd2c3ab2377ea2e9c1daa Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 17 Nov 2019 10:34:19 +0900 Subject: [PATCH 10/16] Create pythonpackage.yml --- .github/workflows/pythonpackage.yml | 33 +++++++++++++++++++++++++++++ 1 file changed, 33 insertions(+) create mode 100644 .github/workflows/pythonpackage.yml diff --git a/.github/workflows/pythonpackage.yml b/.github/workflows/pythonpackage.yml new file mode 100644 index 00000000..901eb4c6 --- /dev/null +++ b/.github/workflows/pythonpackage.yml @@ -0,0 +1,33 @@ +name: Python package + +on: [push] + +jobs: + build: + + runs-on: ubuntu-latest + strategy: + max-parallel: 4 + matrix: + python-version: [3.5, 3.6, 3.7] + + steps: + - uses: actions/checkout@v1 + - name: Set up Python ${{ matrix.python-version }} + uses: actions/setup-python@v1 + with: + python-version: ${{ matrix.python-version }} + - name: Install dependencies + run: | + python -m pip install --upgrade pip + pip install -r requirements.txt + - name: Lint with flake8 + run: | + pip install flake8 + # stop the build if there are Python syntax errors or undefined names + flake8 . --count --select=E9,F63,F7,F82 --show-source --statistics + # exit-zero treats all errors as warnings. The GitHub editor is 127 chars wide + flake8 . --count --exit-zero --max-complexity=10 --max-line-length=127 --statistics + - name: Test with pytest + run: | + runtests.sh From 8877bc1a42d7853d949f00794385a16b488b3292 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 17 Nov 2019 10:41:28 +0900 Subject: [PATCH 11/16] Update pythonpackage.yml --- .github/workflows/pythonpackage.yml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/.github/workflows/pythonpackage.yml b/.github/workflows/pythonpackage.yml index 901eb4c6..c49c61de 100644 --- a/.github/workflows/pythonpackage.yml +++ b/.github/workflows/pythonpackage.yml @@ -28,6 +28,6 @@ jobs: flake8 . --count --select=E9,F63,F7,F82 --show-source --statistics # exit-zero treats all errors as warnings. The GitHub editor is 127 chars wide flake8 . --count --exit-zero --max-complexity=10 --max-line-length=127 --statistics - - name: Test with pytest - run: | - runtests.sh + - name: Test + run: runtests.sh + shell: bash From 4d9ff51f27a11dbf615b5755781a3e1e961bb5a8 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 17 Nov 2019 12:00:00 +0900 Subject: [PATCH 12/16] Update pythonpackage.yml --- .github/workflows/pythonpackage.yml | 3 +++ 1 file changed, 3 insertions(+) diff --git a/.github/workflows/pythonpackage.yml b/.github/workflows/pythonpackage.yml index c49c61de..b9f0adb8 100644 --- a/.github/workflows/pythonpackage.yml +++ b/.github/workflows/pythonpackage.yml @@ -28,6 +28,9 @@ jobs: flake8 . --count --select=E9,F63,F7,F82 --show-source --statistics # exit-zero treats all errors as warnings. The GitHub editor is 127 chars wide flake8 . --count --exit-zero --max-complexity=10 --max-line-length=127 --statistics + - name: Test1 + run: ls + shell: bash - name: Test run: runtests.sh shell: bash From ecdff00fa2ee0d870b0c4b01fd2c92c52389ce21 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 17 Nov 2019 13:15:57 +0900 Subject: [PATCH 13/16] Update pythonpackage.yml --- .github/workflows/pythonpackage.yml | 6 +----- 1 file changed, 1 insertion(+), 5 deletions(-) diff --git a/.github/workflows/pythonpackage.yml b/.github/workflows/pythonpackage.yml index b9f0adb8..4d6e3d3b 100644 --- a/.github/workflows/pythonpackage.yml +++ b/.github/workflows/pythonpackage.yml @@ -28,9 +28,5 @@ jobs: flake8 . --count --select=E9,F63,F7,F82 --show-source --statistics # exit-zero treats all errors as warnings. The GitHub editor is 127 chars wide flake8 . --count --exit-zero --max-complexity=10 --max-line-length=127 --statistics - - name: Test1 - run: ls - shell: bash - name: Test - run: runtests.sh - shell: bash + run: bash runtests.sh From 27b6e19ea6f9d4b4e08b23b5db305e79a624e6bf Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 17 Nov 2019 13:21:14 +0900 Subject: [PATCH 14/16] Update pythonpackage.yml --- .github/workflows/pythonpackage.yml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/.github/workflows/pythonpackage.yml b/.github/workflows/pythonpackage.yml index 4d6e3d3b..fbac68ac 100644 --- a/.github/workflows/pythonpackage.yml +++ b/.github/workflows/pythonpackage.yml @@ -28,5 +28,7 @@ jobs: flake8 . --count --select=E9,F63,F7,F82 --show-source --statistics # exit-zero treats all errors as warnings. The GitHub editor is 127 chars wide flake8 . --count --exit-zero --max-complexity=10 --max-line-length=127 --statistics + - name: install coverage + run: pip insall coverage - name: Test run: bash runtests.sh From 157664857b9eb12181e1405c28b18928d7120a59 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 17 Nov 2019 13:23:30 +0900 Subject: [PATCH 15/16] Update pythonpackage.yml --- .github/workflows/pythonpackage.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/pythonpackage.yml b/.github/workflows/pythonpackage.yml index fbac68ac..fc708457 100644 --- a/.github/workflows/pythonpackage.yml +++ b/.github/workflows/pythonpackage.yml @@ -29,6 +29,6 @@ jobs: # exit-zero treats all errors as warnings. The GitHub editor is 127 chars wide flake8 . --count --exit-zero --max-complexity=10 --max-line-length=127 --statistics - name: install coverage - run: pip insall coverage + run: pip install coverage - name: Test run: bash runtests.sh From 3333b34ce215b0287073fd250aa0c2813ed36e48 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 17 Nov 2019 13:33:50 +0900 Subject: [PATCH 16/16] Update pythonpackage.yml --- .github/workflows/pythonpackage.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/pythonpackage.yml b/.github/workflows/pythonpackage.yml index fc708457..a3203ff1 100644 --- a/.github/workflows/pythonpackage.yml +++ b/.github/workflows/pythonpackage.yml @@ -9,7 +9,7 @@ jobs: strategy: max-parallel: 4 matrix: - python-version: [3.5, 3.6, 3.7] + python-version: [3.6, 3.7] steps: - uses: actions/checkout@v1