using pathlib based local module import (#722)

* using pathlib based local module import

* remove unused import
This commit is contained in:
Atsushi Sakai
2022-09-11 07:21:37 +09:00
committed by GitHub
parent 1ff3095c14
commit 76b0d04a3c
39 changed files with 142 additions and 245 deletions

View File

@@ -1,4 +1,3 @@
import os
import sys import sys
import pathlib
sys.path.append(os.path.dirname(os.path.abspath(__file__))) sys.path.append(str(pathlib.Path(__file__).parent))

View File

@@ -1,3 +1,3 @@
import sys import sys
import os import pathlib
sys.path.append(os.path.dirname(os.path.abspath(__file__))) sys.path.append(str(pathlib.Path(__file__).parent))

View File

@@ -5,11 +5,11 @@ Author: Daniel Ingram (daniel-s-ingram)
Atsushi Sakai (@Atsushi_twi) Atsushi Sakai (@Atsushi_twi)
""" """
import numpy as np
import sys import sys
from pathlib import Path from pathlib import Path
sys.path.append(str(Path(__file__).parent.parent.parent)) sys.path.append(str(Path(__file__).parent.parent.parent))
import numpy as np
from ArmNavigation.n_joint_arm_to_point_control.NLinkArm import NLinkArm from ArmNavigation.n_joint_arm_to_point_control.NLinkArm import NLinkArm
# Simulation parameters # Simulation parameters

View File

@@ -3,18 +3,15 @@ RRT* path planner for a seven joint arm
Author: Mahyar Abdeetedal (mahyaret) Author: Mahyar Abdeetedal (mahyaret)
""" """
import math import math
import os
import sys
import random import random
import numpy as np import numpy as np
from mpl_toolkits import mplot3d from mpl_toolkits import mplot3d
import matplotlib.pyplot as plt import matplotlib.pyplot as plt
sys.path.append(os.path.dirname(os.path.abspath(__file__)) + import sys
"/../n_joint_arm_3d/") import pathlib
try: sys.path.append(str(pathlib.Path(__file__).parent.parent))
from NLinkArm3d import NLinkArm
except ImportError: from n_joint_arm_3d.NLinkArm3d import NLinkArm
raise
show_animation = True show_animation = True
verbose = False verbose = False

View File

@@ -9,10 +9,9 @@ Ensemble Kalman filtering
(https://rmets.onlinelibrary.wiley.com/doi/10.1256/qj.05.135) (https://rmets.onlinelibrary.wiley.com/doi/10.1256/qj.05.135)
""" """
import sys import sys
import os import pathlib
sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../utils/") sys.path.append(str(pathlib.Path(__file__).parent.parent.parent))
import math import math
import matplotlib.pyplot as plt import matplotlib.pyplot as plt

View File

@@ -5,10 +5,9 @@ Extended kalman filter (EKF) localization sample
author: Atsushi Sakai (@Atsushi_twi) author: Atsushi Sakai (@Atsushi_twi)
""" """
import sys import sys
import os import pathlib
sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../utils/") sys.path.append(str(pathlib.Path(__file__).parent.parent.parent))
import math import math
import matplotlib.pyplot as plt import matplotlib.pyplot as plt

View File

@@ -6,8 +6,8 @@ author: Atsushi Sakai (@Atsushi_twi)
""" """
import sys import sys
import os import pathlib
sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../utils/") sys.path.append(str(pathlib.Path(__file__).parent.parent.parent))
import math import math

View File

@@ -7,8 +7,8 @@ author: Atsushi Sakai (@Atsushi_twi)
""" """
import sys import sys
import os import pathlib
sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../utils/") sys.path.append(str(pathlib.Path(__file__).parent.parent.parent))
import math import math

View File

@@ -1,4 +1,3 @@
import os
import sys import sys
import pathlib
sys.path.append(os.path.dirname(os.path.abspath(__file__))) sys.path.append(str(pathlib.Path(__file__).parent))

View File

@@ -13,9 +13,8 @@ efficient-l-shape-fitting-for-vehicle-detection-using-laser-scanners/
""" """
import sys import sys
import os import pathlib
sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../utils/") sys.path.append(str(pathlib.Path(__file__).parent.parent.parent))
import matplotlib.pyplot as plt import matplotlib.pyplot as plt
import numpy as np import numpy as np

View File

@@ -6,8 +6,8 @@ author: Atsushi Sakai
""" """
import sys import sys
import os import pathlib
sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../utils/") sys.path.append(str(pathlib.Path(__file__).parent.parent.parent))
import numpy as np import numpy as np
import matplotlib.pyplot as plt import matplotlib.pyplot as plt

View File

@@ -5,27 +5,17 @@ Path planning Sample Code with Closed loop RRT for car like robot.
author: AtsushiSakai(@Atsushi_twi) author: AtsushiSakai(@Atsushi_twi)
""" """
import os
import sys
import matplotlib.pyplot as plt import matplotlib.pyplot as plt
import numpy as np import numpy as np
sys.path.append(os.path.dirname(os.path.abspath(__file__))) import sys
import pathlib
sys.path.append(str(pathlib.Path(__file__).parent.parent))
import pure_pursuit from ClosedLoopRRTStar import pure_pursuit
import unicycle_model from ClosedLoopRRTStar import unicycle_model
from ReedsSheppPath import reeds_shepp_path_planning
sys.path.append(os.path.dirname( from RRTStarReedsShepp.rrt_star_reeds_shepp import RRTStarReedsShepp
os.path.abspath(__file__)) + "/../ReedsSheppPath/")
sys.path.append(os.path.dirname(
os.path.abspath(__file__)) + "/../RRTStarReedsShepp/")
try:
import reeds_shepp_path_planning
from rrt_star_reeds_shepp import RRTStarReedsShepp
except ImportError:
raise
show_animation = True show_animation = True

View File

@@ -10,7 +10,11 @@ import math
import matplotlib.pyplot as plt import matplotlib.pyplot as plt
import numpy as np import numpy as np
import unicycle_model import sys
import pathlib
sys.path.append(str(pathlib.Path(__file__).parent.parent))
from ClosedLoopRRTStar import unicycle_model
Kp = 2.0 # speed propotional gain Kp = 2.0 # speed propotional gain
Lf = 0.5 # look-ahead distance Lf = 0.5 # look-ahead distance

View File

@@ -6,9 +6,8 @@ author Atsushi Sakai(@Atsushi_twi)
""" """
import sys import sys
import os import pathlib
sys.path.append(str(pathlib.Path(__file__).parent.parent.parent))
sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../utils/")
from math import sin, cos, atan2, sqrt, acos, pi, hypot from math import sin, cos, atan2, sqrt, acos, pi, hypot
import numpy as np import numpy as np

View File

@@ -16,14 +16,10 @@ import numpy as np
import matplotlib.pyplot as plt import matplotlib.pyplot as plt
from matplotlib.collections import LineCollection from matplotlib.collections import LineCollection
import sys import sys
import os import pathlib
sys.path.append(os.path.dirname(os.path.abspath(__file__)) + sys.path.append(str(pathlib.Path(__file__).parent.parent))
"/../Eta3SplinePath")
try: from Eta3SplinePath.eta3_spline_path import Eta3Path, Eta3PathSegment
from eta3_spline_path import Eta3Path, Eta3PathSegment
except ImportError:
raise
show_animation = True show_animation = True

View File

@@ -19,18 +19,12 @@ import matplotlib.pyplot as plt
import copy import copy
import math import math
import sys import sys
import os import pathlib
sys.path.append(str(pathlib.Path(__file__).parent.parent))
sys.path.append(os.path.dirname(os.path.abspath(__file__)) + from QuinticPolynomialsPlanner.quintic_polynomials_planner import \
"/../QuinticPolynomialsPlanner/") QuinticPolynomial
sys.path.append(os.path.dirname(os.path.abspath(__file__)) + from CubicSpline import cubic_spline_planner
"/../CubicSpline/")
try:
from quintic_polynomials_planner import QuinticPolynomial
import cubic_spline_planner
except ImportError:
raise
SIM_LOOP = 500 SIM_LOOP = 500

View File

@@ -4,25 +4,16 @@ Grid based sweep planner
author: Atsushi Sakai author: Atsushi Sakai
""" """
import sys
import os
sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../utils/")
import math import math
from enum import IntEnum from enum import IntEnum
import numpy as np import numpy as np
import matplotlib.pyplot as plt import matplotlib.pyplot as plt
import sys
import pathlib
sys.path.append(str(pathlib.Path(__file__).parent.parent.parent))
from utils.angle import rot_mat_2d from utils.angle import rot_mat_2d
from Mapping.grid_map_lib.grid_map_lib import GridMap
sys.path.append(os.path.dirname(os.path.abspath(__file__)) +
"/../../Mapping/")
try:
from grid_map_lib.grid_map_lib import GridMap
except ImportError:
raise
do_animation = True do_animation = True

View File

@@ -7,8 +7,9 @@ author: Zheng Zh (@Zhengzh)
""" """
import sys import sys
import os import pathlib
sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../utils/") root_dir = pathlib.Path(__file__).parent.parent.parent
sys.path.append(str(root_dir))
from math import cos, sin, tan, pi from math import cos, sin, tan, pi
@@ -76,7 +77,7 @@ def plot_arrow(x, y, yaw, length=1.0, width=0.5, fc="r", ec="k"):
def plot_car(x, y, yaw): def plot_car(x, y, yaw):
car_color = '-k' car_color = '-k'
c, s = cos(yaw), sin(yaw) c, s = cos(yaw), sin(yaw)
rot = Rot.from_euler('z', -yaw).as_matrix()[0:2, 0:2] rot = rot_mat_2d(-yaw)
car_outline_x, car_outline_y = [], [] car_outline_x, car_outline_y = [], []
for rx, ry in zip(VRX, VRY): for rx, ry in zip(VRX, VRY):
converted_xy = np.stack([rx, ry]).T @ rot converted_xy = np.stack([rx, ry]).T @ rot

View File

@@ -8,22 +8,16 @@ author: Zheng Zh (@Zhengzh)
import heapq import heapq
import math import math
import os
import sys
import matplotlib.pyplot as plt import matplotlib.pyplot as plt
import numpy as np import numpy as np
from scipy.spatial import cKDTree from scipy.spatial import cKDTree
import sys
import pathlib
sys.path.append(str(pathlib.Path(__file__).parent.parent))
sys.path.append(os.path.dirname(os.path.abspath(__file__)) from dynamic_programming_heuristic import calc_distance_heuristic
+ "/../ReedsSheppPath") from ReedsSheppPath import reeds_shepp_path_planning as rs
try: from car import move, check_car_collision, MAX_STEER, WB, plot_car, BUBBLE_R
from dynamic_programming_heuristic import calc_distance_heuristic
import reeds_shepp_path_planning as rs
from car import move, check_car_collision, MAX_STEER, WB, plot_car,\
BUBBLE_R
except Exception:
raise
XY_GRID_RESOLUTION = 2.0 # [m] XY_GRID_RESOLUTION = 2.0 # [m]
YAW_GRID_RESOLUTION = np.deg2rad(15.0) # [rad] YAW_GRID_RESOLUTION = np.deg2rad(15.0) # [rad]

View File

@@ -10,8 +10,8 @@ https://arxiv.org/pdf/1404.2334.pdf
""" """
import sys import sys
import os import pathlib
sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../utils/") sys.path.append(str(pathlib.Path(__file__).parent.parent.parent))
import copy import copy
import math import math

View File

@@ -7,21 +7,15 @@ author: AtsushiSakai(@Atsushi_twi)
""" """
import copy import copy
import math import math
import os
import random import random
import sys
import matplotlib.pyplot as plt import matplotlib.pyplot as plt
import numpy as np import numpy as np
import sys
import pathlib
sys.path.append(str(pathlib.Path(__file__).parent.parent))
sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../LQRPlanner/") from LQRPlanner.lqr_planner import LQRPlanner
sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../RRTStar/") from RRTStar.rrt_star import RRTStar
try:
from LQRplanner import LQRPlanner
from rrt_star import RRTStar
except ImportError:
raise
show_animation = True show_animation = True

View File

@@ -7,11 +7,14 @@ author: Atsushi Sakai(@Atsushi_twi)
""" """
import math import math
import matplotlib.pyplot as plt import matplotlib.pyplot as plt
import numpy as np import numpy as np
import sys
import pathlib
path_planning_dir = pathlib.Path(__file__).parent.parent
sys.path.append(str(path_planning_dir))
import motion_model import ModelPredictiveTrajectoryGenerator.motion_model as motion_model
# optimization parameter # optimization parameter
max_iter = 100 max_iter = 100

View File

@@ -7,18 +7,13 @@ Path planning Sample Code with RRT with path smoothing
""" """
import math import math
import os
import random import random
import sys
import matplotlib.pyplot as plt import matplotlib.pyplot as plt
import sys
import pathlib
sys.path.append(str(pathlib.Path(__file__).parent))
sys.path.append(os.path.dirname(os.path.abspath(__file__))) from rrt import RRT
try:
from rrt import RRT
except ImportError:
raise
show_animation = True show_animation = True

View File

@@ -28,12 +28,11 @@ Rojas (rafaelrojasmiliani@gmail.com)
import math import math
import random import random
from sobol import sobol_quasirand
import sys
import matplotlib.pyplot as plt import matplotlib.pyplot as plt
import numpy as np import numpy as np
from sobol import sobol_quasirand
show_animation = True show_animation = True

View File

@@ -6,23 +6,17 @@ author: AtsushiSakai(@Atsushi_twi)
""" """
import copy import copy
import math import math
import os
import random import random
import sys
import matplotlib.pyplot as plt
import numpy as np import numpy as np
import matplotlib.pyplot as plt
import sys
import pathlib
sys.path.append(str(pathlib.Path(__file__).parent.parent.parent)) # root dir
sys.path.append(str(pathlib.Path(__file__).parent.parent))
sys.path.append(os.path.dirname(os.path.abspath(__file__)) + from RRT.rrt import RRT
"/../DubinsPath/") from DubinsPath import dubins_path_planner
sys.path.append(os.path.dirname(os.path.abspath(__file__)) + from utils.plot import plot_arrow
"/../RRT/")
try:
from rrt import RRT
import dubins_path_planner
except ImportError:
raise
show_animation = True show_animation = True
@@ -130,10 +124,8 @@ class RRTDubins(RRT):
plt.pause(0.01) plt.pause(0.01)
def plot_start_goal_arrow(self): # pragma: no cover def plot_start_goal_arrow(self): # pragma: no cover
dubins_path_planner.plot_arrow( plot_arrow(self.start.x, self.start.y, self.start.yaw)
self.start.x, self.start.y, self.start.yaw) plot_arrow(self.end.x, self.end.y, self.end.yaw)
dubins_path_planner.plot_arrow(
self.end.x, self.end.y, self.end.yaw)
def steer(self, from_node, to_node): def steer(self, from_node, to_node):
@@ -214,6 +206,7 @@ class RRTDubins(RRT):
def main(): def main():
print("Start " + __file__) print("Start " + __file__)
# ====Search Path with RRT==== # ====Search Path with RRT====
obstacleList = [ obstacleList = [

View File

@@ -7,17 +7,12 @@ author: Atsushi Sakai(@Atsushi_twi)
""" """
import math import math
import os
import sys import sys
import matplotlib.pyplot as plt import matplotlib.pyplot as plt
import pathlib
sys.path.append(str(pathlib.Path(__file__).parent.parent))
sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../RRT/") from RRT.rrt import RRT
try:
from rrt import RRT
except ImportError:
raise
show_animation = True show_animation = True
@@ -59,6 +54,7 @@ class RRTStar(RRT):
self.connect_circle_dist = connect_circle_dist self.connect_circle_dist = connect_circle_dist
self.goal_node = self.Node(goal[0], goal[1]) self.goal_node = self.Node(goal[0], goal[1])
self.search_until_max_iter = search_until_max_iter self.search_until_max_iter = search_until_max_iter
self.node_list = []
def planning(self, animation=True): def planning(self, animation=True):
""" """

View File

@@ -4,26 +4,19 @@ Path planning Sample Code with RRT and Dubins path
author: AtsushiSakai(@Atsushi_twi) author: AtsushiSakai(@Atsushi_twi)
""" """
import copy import copy
import math import math
import os
import random import random
import sys
import matplotlib.pyplot as plt import matplotlib.pyplot as plt
import numpy as np import numpy as np
import sys
import pathlib
sys.path.append(str(pathlib.Path(__file__).parent.parent.parent)) # root dir
sys.path.append(str(pathlib.Path(__file__).parent.parent))
sys.path.append(os.path.dirname(os.path.abspath(__file__)) + from DubinsPath import dubins_path_planner
"/../DubinsPath/") from RRTStar.rrt_star import RRTStar
sys.path.append(os.path.dirname(os.path.abspath(__file__)) + from utils.plot import plot_arrow
"/../RRTStar/")
try:
import dubins_path_planner
from rrt_star import RRTStar
except ImportError:
raise
show_animation = True show_animation = True
@@ -136,10 +129,8 @@ class RRTStarDubins(RRTStar):
plt.pause(0.01) plt.pause(0.01)
def plot_start_goal_arrow(self): def plot_start_goal_arrow(self):
dubins_path_planner.plot_arrow( plot_arrow(self.start.x, self.start.y, self.start.yaw)
self.start.x, self.start.y, self.start.yaw) plot_arrow(self.end.x, self.end.y, self.end.yaw)
dubins_path_planner.plot_arrow(
self.end.x, self.end.y, self.end.yaw)
def steer(self, from_node, to_node): def steer(self, from_node, to_node):

View File

@@ -7,23 +7,15 @@ author: AtsushiSakai(@Atsushi_twi)
""" """
import copy import copy
import math import math
import os
import random import random
import sys import sys
import pathlib
import matplotlib.pyplot as plt import matplotlib.pyplot as plt
import numpy as np import numpy as np
sys.path.append(str(pathlib.Path(__file__).parent.parent))
sys.path.append(os.path.dirname(os.path.abspath(__file__)) + from ReedsSheppPath import reeds_shepp_path_planning
"/../ReedsSheppPath/") from RRTStar.rrt_star import RRTStar
sys.path.append(os.path.dirname(os.path.abspath(__file__)) +
"/../RRTStar/")
try:
import reeds_shepp_path_planning
from rrt_star import RRTStar
except ImportError:
raise
show_animation = True show_animation = True

View File

@@ -4,11 +4,16 @@ State lattice planner with model predictive trajectory generator
author: Atsushi Sakai (@Atsushi_twi) author: Atsushi Sakai (@Atsushi_twi)
- lookuptable.csv is generated with this script: https://github.com/AtsushiSakai/PythonRobotics/blob/master/PathPlanning/ModelPredictiveTrajectoryGenerator/lookuptable_generator.py - lookuptable.csv is generated with this script:
https://github.com/AtsushiSakai/PythonRobotics/blob/master/PathPlanning
/ModelPredictiveTrajectoryGenerator/lookuptable_generator.py
Ref: Ref:
- State Space Sampling of Feasible Motions for High-Performance Mobile Robot Navigation in Complex Environments http://citeseerx.ist.psu.edu/viewdoc/download?doi=10.1.1.187.8210&rep=rep1&type=pdf - State Space Sampling of Feasible Motions for High-Performance Mobile Robot
Navigation in Complex Environments
http://citeseerx.ist.psu.edu/viewdoc/download?doi=10.1.1.187.8210&rep=rep1
&type=pdf
""" """
import sys import sys
@@ -17,17 +22,11 @@ from matplotlib import pyplot as plt
import numpy as np import numpy as np
import math import math
import pandas as pd import pandas as pd
import pathlib
sys.path.append(str(pathlib.Path(__file__).parent.parent))
sys.path.append(os.path.dirname(os.path.abspath(__file__)) import ModelPredictiveTrajectoryGenerator.trajectory_generator as planner
+ "/../ModelPredictiveTrajectoryGenerator/") import ModelPredictiveTrajectoryGenerator.motion_model as motion_model
try:
import model_predictive_trajectory_generator as planner
import motion_model
except ImportError:
raise
table_path = os.path.dirname(os.path.abspath(__file__)) + "/lookuptable.csv" table_path = os.path.dirname(os.path.abspath(__file__)) + "/lookuptable.csv"

View File

@@ -6,17 +6,15 @@ author: Atsushi Sakai (@Atsushi_twi)
""" """
import os
import sys import sys
import math import math
import numpy as np import numpy as np
import matplotlib.pyplot as plt import matplotlib.pyplot as plt
import pathlib
sys.path.append(str(pathlib.Path(__file__).parent.parent))
from PathPlanning.VisibilityRoadMap.geometry import Geometry from VisibilityRoadMap.geometry import Geometry
from VoronoiRoadMap.dijkstra_search import DijkstraSearch
sys.path.append(os.path.dirname(os.path.abspath(__file__)) +
"/../VoronoiRoadMap/")
from dijkstra_search import DijkstraSearch
show_animation = True show_animation = True

View File

@@ -1,4 +0,0 @@
import os
import sys
sys.path.append(os.path.dirname(os.path.abspath(__file__)))

View File

@@ -9,8 +9,12 @@ author: Atsushi Sakai (@Atsushi_twi)
import math import math
import numpy as np import numpy as np
import matplotlib.pyplot as plt import matplotlib.pyplot as plt
from dijkstra_search import DijkstraSearch
from scipy.spatial import cKDTree, Voronoi from scipy.spatial import cKDTree, Voronoi
import sys
import pathlib
sys.path.append(str(pathlib.Path(__file__).parent.parent))
from VoronoiRoadMap.dijkstra_search import DijkstraSearch
show_animation = True show_animation = True

View File

@@ -7,19 +7,13 @@ author Atsushi Sakai (@Atsushi_twi)
""" """
import math import math
import sys import sys
import os
import matplotlib.pyplot as plt import matplotlib.pyplot as plt
import numpy as np import numpy as np
import scipy.linalg as la import scipy.linalg as la
import pathlib
sys.path.append(str(pathlib.Path(__file__).parent.parent.parent))
sys.path.append(os.path.dirname(os.path.abspath(__file__)) + from PathPlanning.CubicSpline import cubic_spline_planner
"/../../PathPlanning/CubicSpline/")
try:
import cubic_spline_planner
except ImportError:
raise
# === Parameters ===== # === Parameters =====

View File

@@ -10,16 +10,10 @@ import matplotlib.pyplot as plt
import math import math
import numpy as np import numpy as np
import sys import sys
import os import pathlib
sys.path.append(str(pathlib.Path(__file__).parent.parent.parent))
sys.path.append(os.path.dirname(os.path.abspath(__file__)) +
"/../../PathPlanning/CubicSpline/")
try:
import cubic_spline_planner
except:
raise
from PathPlanning.CubicSpline import cubic_spline_planner
Kp = 1.0 # speed proportional gain Kp = 1.0 # speed proportional gain
@@ -29,7 +23,7 @@ R = np.eye(1)
# parameters # parameters
dt = 0.1 # time tick[s] dt = 0.1 # time tick[s]
L = 0.5 # Wheel base of the vehicle [m] L = 0.5 # Wheelbase of the vehicle [m]
max_steer = np.deg2rad(45.0) # maximum steering angle[rad] max_steer = np.deg2rad(45.0) # maximum steering angle[rad]
show_animation = True show_animation = True

View File

@@ -10,16 +10,10 @@ import cvxpy
import math import math
import numpy as np import numpy as np
import sys import sys
import os import pathlib
sys.path.append(str(pathlib.Path(__file__).parent.parent.parent))
sys.path.append(os.path.dirname(os.path.abspath(__file__)) +
"/../../PathPlanning/CubicSpline/")
try:
import cubic_spline_planner
except:
raise
from PathPlanning.CubicSpline import cubic_spline_planner
NX = 4 # x = x, y, v, yaw NX = 4 # x = x, y, v, yaw
NU = 2 # a = [accel, steer] NU = 2 # a = [accel, steer]

View File

@@ -12,16 +12,10 @@ Ref:
import numpy as np import numpy as np
import matplotlib.pyplot as plt import matplotlib.pyplot as plt
import sys import sys
import os import pathlib
sys.path.append(str(pathlib.Path(__file__).parent.parent.parent))
sys.path.append(os.path.dirname(os.path.abspath(__file__)) +
"/../../PathPlanning/CubicSpline/")
try:
import cubic_spline_planner
except:
raise
from PathPlanning.CubicSpline import cubic_spline_planner
k = 0.5 # control gain k = 0.5 # control gain
Kp = 1.0 # speed proportional gain Kp = 1.0 # speed proportional gain

View File

@@ -11,8 +11,8 @@ Ref
""" """
import sys import sys
import os import pathlib
sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../utils/") sys.path.append(str(pathlib.Path(__file__).parent.parent.parent))
import copy import copy
import itertools import itertools

View File

@@ -1,5 +1,5 @@
import conftest # Add root path to sys.path import conftest # Add root path to sys.path
from PathPlanning.LQRPlanner import LQRplanner as m from PathPlanning.LQRPlanner import lqr_planner as m
def test_1(): def test_1():