diff --git a/.old/cte/mpc_demo/cvxpy_mpc.py b/.old/cte/mpc_demo/cvxpy_mpc.py new file mode 100755 index 0000000..0a3da8d --- /dev/null +++ b/.old/cte/mpc_demo/cvxpy_mpc.py @@ -0,0 +1,104 @@ +import numpy as np +np.seterr(divide='ignore', invalid='ignore') + +from scipy.integrate import odeint +from scipy.interpolate import interp1d +import cvxpy as cp + +from utils import road_curve, f, df + +from mpc_config import Params +P=Params() + +def get_linear_model(x_bar,u_bar): + """ + """ + + x = x_bar[0] + y = x_bar[1] + theta = x_bar[2] + + v = u_bar[0] + w = u_bar[1] + + A = np.zeros((P.N,P.N)) + A[0,2]=-v*np.sin(theta) + A[1,2]=v*np.cos(theta) + A_lin=np.eye(P.N)+P.dt*A + + B = np.zeros((P.N,P.M)) + B[0,0]=np.cos(theta) + B[1,0]=np.sin(theta) + B[2,1]=1 + B_lin=P.dt*B + + f_xu=np.array([v*np.cos(theta),v*np.sin(theta),w]).reshape(P.N,1) + C_lin = P.dt*(f_xu - np.dot(A,x_bar.reshape(P.N,1)) - np.dot(B,u_bar.reshape(P.M,1))) + + return A_lin,B_lin,C_lin + + +def optimize(state,u_bar,track): + ''' + :param state: + :param u_bar: + :param track: + :returns: + ''' + + MAX_SPEED = 1.25 + MIN_SPEED = 0.75 + MAX_STEER_SPEED = 1.57/2 + + # compute polynomial coefficients of the track + K=road_curve(state,track) + + # dynamics starting state w.r.t vehicle frame + x_bar=np.zeros((P.N,P.T+1)) + + #prediction for linearization of costrains + for t in range (1,P.T+1): + xt=x_bar[:,t-1].reshape(P.N,1) + ut=u_bar[:,t-1].reshape(P.M,1) + A,B,C=get_linear_model(xt,ut) + xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C) + x_bar[:,t]= xt_plus_one + + #CVXPY Linear MPC problem statement + cost = 0 + constr = [] + x = cp.Variable((P.N, P.T+1)) + u = cp.Variable((P.M, P.T)) + + for t in range(P.T): + + #cost += 30*cp.sum_squares(x[2,t]-np.arctan(df(x_bar[0,t],K))) # psi + cost += 50*cp.sum_squares(x[2,t]-np.arctan2(df(x_bar[0,t],K),x_bar[0,t])) # psi + cost += 20*cp.sum_squares(f(x_bar[0,t],K)-x[1,t]) # cte + + # Actuation rate of change + if t < (P.T - 1): + cost += cp.quad_form(u[:, t + 1] - u[:, t], 100*np.eye(P.M)) + + # Actuation effort + cost += cp.quad_form( u[:, t],1*np.eye(P.M)) + + # Kinrmatics Constrains (Linearized model) + A,B,C=get_linear_model(x_bar[:,t],u_bar[:,t]) + constr += [x[:,t+1] == A@x[:,t] + B@u[:,t] + C.flatten()] + + # sums problem objectives and concatenates constraints. + constr += [x[:,0] == x_bar[:,0]] #<--watch out the start condition + constr += [u[0, :] <= MAX_SPEED] + constr += [u[0, :] >= MIN_SPEED] + constr += [cp.abs(u[1, :]) <= MAX_STEER_SPEED] + + # Solve + prob = cp.Problem(cp.Minimize(cost), constr) + solution = prob.solve(solver=cp.OSQP, verbose=False) + + #retrieved optimized U and assign to u_bar to linearize in next step + u_bar=np.vstack((np.array(u.value[0, :]).flatten(), + (np.array(u.value[1, :]).flatten()))) + + return u_bar diff --git a/mpc_demo/data/checker_blue.png b/.old/cte/mpc_demo/data/checker_blue.png similarity index 100% rename from mpc_demo/data/checker_blue.png rename to .old/cte/mpc_demo/data/checker_blue.png diff --git a/mpc_demo/data/plane.mtl b/.old/cte/mpc_demo/data/plane.mtl similarity index 100% rename from mpc_demo/data/plane.mtl rename to .old/cte/mpc_demo/data/plane.mtl diff --git a/mpc_demo/data/plane.obj b/.old/cte/mpc_demo/data/plane.obj similarity index 100% rename from mpc_demo/data/plane.obj rename to .old/cte/mpc_demo/data/plane.obj diff --git a/mpc_demo/data/plane.urdf b/.old/cte/mpc_demo/data/plane.urdf similarity index 100% rename from mpc_demo/data/plane.urdf rename to .old/cte/mpc_demo/data/plane.urdf diff --git a/mpc_demo/data/turtlebot.urdf b/.old/cte/mpc_demo/data/turtlebot.urdf similarity index 100% rename from mpc_demo/data/turtlebot.urdf rename to .old/cte/mpc_demo/data/turtlebot.urdf diff --git a/mpc_demo/data/turtlebot/kobuki_description/meshes/images/main_body.jpg b/.old/cte/mpc_demo/data/turtlebot/kobuki_description/meshes/images/main_body.jpg similarity index 100% rename from mpc_demo/data/turtlebot/kobuki_description/meshes/images/main_body.jpg rename to .old/cte/mpc_demo/data/turtlebot/kobuki_description/meshes/images/main_body.jpg diff --git a/mpc_demo/data/turtlebot/kobuki_description/meshes/images/wheel.jpg b/.old/cte/mpc_demo/data/turtlebot/kobuki_description/meshes/images/wheel.jpg similarity index 100% rename from mpc_demo/data/turtlebot/kobuki_description/meshes/images/wheel.jpg rename to .old/cte/mpc_demo/data/turtlebot/kobuki_description/meshes/images/wheel.jpg diff --git a/mpc_demo/data/turtlebot/kobuki_description/meshes/main_body.dae b/.old/cte/mpc_demo/data/turtlebot/kobuki_description/meshes/main_body.dae similarity index 100% rename from mpc_demo/data/turtlebot/kobuki_description/meshes/main_body.dae rename to .old/cte/mpc_demo/data/turtlebot/kobuki_description/meshes/main_body.dae diff --git a/mpc_demo/data/turtlebot/kobuki_description/meshes/wheel.dae b/.old/cte/mpc_demo/data/turtlebot/kobuki_description/meshes/wheel.dae similarity index 100% rename from mpc_demo/data/turtlebot/kobuki_description/meshes/wheel.dae rename to .old/cte/mpc_demo/data/turtlebot/kobuki_description/meshes/wheel.dae diff --git a/mpc_demo/data/turtlebot/turtlebot_description/meshes/sensors/asus_xtion_pro_live.dae b/.old/cte/mpc_demo/data/turtlebot/turtlebot_description/meshes/sensors/asus_xtion_pro_live.dae similarity index 100% rename from mpc_demo/data/turtlebot/turtlebot_description/meshes/sensors/asus_xtion_pro_live.dae rename to .old/cte/mpc_demo/data/turtlebot/turtlebot_description/meshes/sensors/asus_xtion_pro_live.dae diff --git a/mpc_demo/data/turtlebot/turtlebot_description/meshes/sensors/asus_xtion_pro_live.png b/.old/cte/mpc_demo/data/turtlebot/turtlebot_description/meshes/sensors/asus_xtion_pro_live.png similarity index 100% rename from mpc_demo/data/turtlebot/turtlebot_description/meshes/sensors/asus_xtion_pro_live.png rename to .old/cte/mpc_demo/data/turtlebot/turtlebot_description/meshes/sensors/asus_xtion_pro_live.png diff --git a/mpc_demo/data/turtlebot/turtlebot_description/meshes/sensors/kinect.dae b/.old/cte/mpc_demo/data/turtlebot/turtlebot_description/meshes/sensors/kinect.dae similarity index 100% rename from mpc_demo/data/turtlebot/turtlebot_description/meshes/sensors/kinect.dae rename to .old/cte/mpc_demo/data/turtlebot/turtlebot_description/meshes/sensors/kinect.dae diff --git a/mpc_demo/data/turtlebot/turtlebot_description/meshes/sensors/kinect.jpg b/.old/cte/mpc_demo/data/turtlebot/turtlebot_description/meshes/sensors/kinect.jpg similarity index 100% rename from mpc_demo/data/turtlebot/turtlebot_description/meshes/sensors/kinect.jpg rename to .old/cte/mpc_demo/data/turtlebot/turtlebot_description/meshes/sensors/kinect.jpg diff --git a/mpc_demo/data/turtlebot/turtlebot_description/meshes/sensors/kinect.tga b/.old/cte/mpc_demo/data/turtlebot/turtlebot_description/meshes/sensors/kinect.tga similarity index 100% rename from mpc_demo/data/turtlebot/turtlebot_description/meshes/sensors/kinect.tga rename to .old/cte/mpc_demo/data/turtlebot/turtlebot_description/meshes/sensors/kinect.tga diff --git a/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/_DS_Store b/.old/cte/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/_DS_Store similarity index 100% rename from mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/_DS_Store rename to .old/cte/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/_DS_Store diff --git a/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/images/1f_pole.jpg b/.old/cte/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/images/1f_pole.jpg similarity index 100% rename from mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/images/1f_pole.jpg rename to .old/cte/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/images/1f_pole.jpg diff --git a/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/images/1f_stack.jpg b/.old/cte/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/images/1f_stack.jpg similarity index 100% rename from mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/images/1f_stack.jpg rename to .old/cte/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/images/1f_stack.jpg diff --git a/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/images/2f_pole.jpg b/.old/cte/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/images/2f_pole.jpg similarity index 100% rename from mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/images/2f_pole.jpg rename to .old/cte/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/images/2f_pole.jpg diff --git a/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/images/2f_stack.jpg b/.old/cte/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/images/2f_stack.jpg similarity index 100% rename from mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/images/2f_stack.jpg rename to .old/cte/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/images/2f_stack.jpg diff --git a/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/images/3f_pole.jpg b/.old/cte/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/images/3f_pole.jpg similarity index 100% rename from mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/images/3f_pole.jpg rename to .old/cte/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/images/3f_pole.jpg diff --git a/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/images/3f_stack.jpg b/.old/cte/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/images/3f_stack.jpg similarity index 100% rename from mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/images/3f_stack.jpg rename to .old/cte/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/images/3f_stack.jpg diff --git a/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/images/3f_stack1.jpg b/.old/cte/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/images/3f_stack1.jpg similarity index 100% rename from mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/images/3f_stack1.jpg rename to .old/cte/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/images/3f_stack1.jpg diff --git a/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/images/kinect_pole.jpg b/.old/cte/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/images/kinect_pole.jpg similarity index 100% rename from mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/images/kinect_pole.jpg rename to .old/cte/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/images/kinect_pole.jpg diff --git a/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/images/kinect_pole_old.jpg b/.old/cte/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/images/kinect_pole_old.jpg similarity index 100% rename from mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/images/kinect_pole_old.jpg rename to .old/cte/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/images/kinect_pole_old.jpg diff --git a/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/plate_bottom.dae b/.old/cte/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/plate_bottom.dae similarity index 100% rename from mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/plate_bottom.dae rename to .old/cte/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/plate_bottom.dae diff --git a/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/plate_middle.dae b/.old/cte/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/plate_middle.dae similarity index 100% rename from mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/plate_middle.dae rename to .old/cte/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/plate_middle.dae diff --git a/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/plate_top.dae b/.old/cte/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/plate_top.dae similarity index 100% rename from mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/plate_top.dae rename to .old/cte/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/plate_top.dae diff --git a/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/pole_bottom.dae b/.old/cte/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/pole_bottom.dae similarity index 100% rename from mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/pole_bottom.dae rename to .old/cte/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/pole_bottom.dae diff --git a/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/pole_kinect.dae b/.old/cte/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/pole_kinect.dae similarity index 100% rename from mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/pole_kinect.dae rename to .old/cte/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/pole_kinect.dae diff --git a/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/pole_middle.dae b/.old/cte/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/pole_middle.dae similarity index 100% rename from mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/pole_middle.dae rename to .old/cte/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/pole_middle.dae diff --git a/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/pole_top.dae b/.old/cte/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/pole_top.dae similarity index 100% rename from mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/pole_top.dae rename to .old/cte/mpc_demo/data/turtlebot/turtlebot_description/meshes/stacks/hexagons/pole_top.dae diff --git a/.old/cte/mpc_demo/mpc_config.py b/.old/cte/mpc_demo/mpc_config.py new file mode 100644 index 0000000..9b85c5b --- /dev/null +++ b/.old/cte/mpc_demo/mpc_config.py @@ -0,0 +1,6 @@ +class Params(): + def __init__(self): + self.N = 3 #number of state variables + self.M = 2 #number of control variables + self.T = 20 #Prediction Horizon + self.dt = 0.25 #discretization step diff --git a/.old/cte/mpc_demo/mpc_demo_nosim.py b/.old/cte/mpc_demo/mpc_demo_nosim.py new file mode 100755 index 0000000..a3704c9 --- /dev/null +++ b/.old/cte/mpc_demo/mpc_demo_nosim.py @@ -0,0 +1,207 @@ +#! /usr/bin/env python + +import numpy as np +import matplotlib.pyplot as plt +from matplotlib import animation + +from utils import compute_path_from_wp +from cvxpy_mpc import optimize + +import sys +import time + +# Robot Starting position +SIM_START_X=0 +SIM_START_Y=0.5 +SIM_START_H=0 + +from mpc_config import Params +P=Params() + +# Classes +class MPC(): + + def __init__(self): + + # State for the robot mathematical model [x,y,heading] + self.state = [SIM_START_X, SIM_START_Y, SIM_START_H] + + self.opt_u = np.zeros((P.M,P.T)) + self.opt_u[0,:] = 1 #m/s + self.opt_u[1,:] = np.radians(0) #rad/s + + # Interpolated Path to follow given waypoints + #self.path = compute_path_from_wp([0,10,12,2,4,14],[0,0,2,10,12,12]) + self.path = compute_path_from_wp([0,3,4,6,10,13], + [0,0,2,4,3,3],1) + + # Sim help vars + self.sim_time=0 + self.x_history=[] + self.y_history=[] + self.h_history=[] + self.v_history=[] + self.w_history=[] + self.predicted=None + + #Initialise plot + plt.style.use("ggplot") + self.fig = plt.figure() + plt.ion() + plt.show() + + def predict_motion(self): + ''' + ''' + predicted=np.zeros(self.opt_u.shape) + x=self.state[0] + y=self.state[1] + th=self.state[2] + for idx,v,w in zip(range(len(self.opt_u[0,:])),self.opt_u[0,:],self.opt_u[1,:]): + x = x+v*np.cos(th)*P.dt + y = y+v*np.sin(th)*P.dt + th= th +w*P.dt + predicted[0,idx]=x + predicted[1,idx]=y + + self.predicted = predicted + + def run(self): + ''' + ''' + + while 1: + if self.state is not None: + + if np.sqrt((self.state[0]-self.path[0,-1])**2+(self.state[1]-self.path[1,-1])**2)<1: + print("Success! Goal Reached") + return + + #optimization loop + start=time.time() + self.opt_u = optimize(self.state, + self.opt_u, + self.path) + + # print("CVXPY Optimization Time: {:.4f}s".format(time.time()-start)) + + self.update_sim(self.opt_u[0,1],self.opt_u[1,1]) + self.predict_motion() + self.plot_sim() + + def update_sim(self,lin_v,ang_v): + ''' + Updates state. + + :param lin_v: float + :param ang_v: float + ''' + + self.state[0] = self.state[0] +lin_v*np.cos(self.state[2])*P.dt + self.state[1] = self.state[1] +lin_v*np.sin(self.state[2])*P.dt + self.state[2] = self.state[2] +ang_v*P.dt + + def plot_sim(self): + + self.sim_time = self.sim_time+P.dt + self.x_history.append(self.state[0]) + self.y_history.append(self.state[1]) + self.h_history.append(self.state[2]) + self.v_history.append(self.opt_u[0,1]) + self.w_history.append(self.opt_u[1,1]) + + plt.clf() + + grid = plt.GridSpec(2, 3) + + plt.subplot(grid[0:2, 0:2]) + plt.title("MPC Simulation \n" + "Simulation elapsed time {}s".format(self.sim_time)) + + plt.plot(self.path[0,:],self.path[1,:], c='tab:orange', + marker=".", + label="reference track") + + plt.plot(self.x_history, self.y_history, c='tab:blue', + marker=".", + alpha=0.5, + label="vehicle trajectory") + + if self.predicted is not None: + plt.plot(self.predicted[0,:], self.predicted[1,:], c='tab:green', + marker=".", + alpha=0.5, + label="mpc opt trajectory") + + # plt.plot(self.x_history[-1], self.y_history[-1], c='tab:blue', + # marker=".", + # markersize=12, + # label="vehicle position") + # plt.arrow(self.x_history[-1], + # self.y_history[-1], + # np.cos(self.h_history[-1]), + # np.sin(self.h_history[-1]), + # color='tab:blue', + # width=0.2, + # head_length=0.5, + # label="heading") + + plot_car(self.x_history[-1], self.y_history[-1], self.h_history[-1]) + + plt.ylabel('map y') + plt.yticks(np.arange(min(self.path[1,:])-1., max(self.path[1,:]+1.)+1, 1.0)) + plt.xlabel('map x') + plt.xticks(np.arange(min(self.path[0,:])-1., max(self.path[0,:]+1.)+1, 1.0)) + plt.axis("equal") + #plt.legend() + + plt.subplot(grid[0, 2]) + #plt.title("Linear Velocity {} m/s".format(self.v_history[-1])) + plt.plot(self.v_history,c='tab:orange') + locs, _ = plt.xticks() + plt.xticks(locs[1:], locs[1:]*P.dt) + plt.ylabel('v(t) [m/s]') + plt.xlabel('t [s]') + + plt.subplot(grid[1, 2]) + #plt.title("Angular Velocity {} m/s".format(self.w_history[-1])) + plt.plot(np.degrees(self.w_history),c='tab:orange') + plt.ylabel('w(t) [deg/s]') + locs, _ = plt.xticks() + plt.xticks(locs[1:], locs[1:]*P.dt) + plt.xlabel('t [s]') + + plt.tight_layout() + + plt.draw() + plt.pause(0.1) + + +def plot_car(x, y, yaw): + LENGTH = 1.0 # [m] + WIDTH = 0.5 # [m] + OFFSET = LENGTH/2 # [m] + + outline = np.array([[-OFFSET, (LENGTH - OFFSET), (LENGTH - OFFSET), -OFFSET, -OFFSET], + [WIDTH / 2, WIDTH / 2, - WIDTH / 2, -WIDTH / 2, WIDTH / 2]]) + + Rotm = np.array([[np.cos(yaw), np.sin(yaw)], + [-np.sin(yaw), np.cos(yaw)]]) + + outline = (outline.T.dot(Rotm)).T + + outline[0, :] += x + outline[1, :] += y + + plt.plot(np.array(outline[0, :]).flatten(), np.array(outline[1, :]).flatten(), 'tab:blue') + + + +def do_sim(): + sim=MPC() + try: + sim.run() + except Exception as e: + sys.exit(e) + +if __name__ == '__main__': + do_sim() diff --git a/.old/cte/mpc_demo/mpc_demo_pybullet.py b/.old/cte/mpc_demo/mpc_demo_pybullet.py new file mode 100644 index 0000000..910bf88 --- /dev/null +++ b/.old/cte/mpc_demo/mpc_demo_pybullet.py @@ -0,0 +1,108 @@ +import numpy as np +import matplotlib.pyplot as plt +from matplotlib import animation + +from utils import compute_path_from_wp +from cvxpy_mpc import optimize + +from mpc_config import Params +P=Params() + +import sys +import time + +import pybullet as p +import time + +def get_state(robotId): + """ + """ + robPos, robOrn = p.getBasePositionAndOrientation(robotId) + linVel,angVel = p.getBaseVelocity(robotId) + + return[robPos[0], robPos[1], p.getEulerFromQuaternion(robOrn)[2]] + +def set_ctrl(robotId,v,w): + """ + """ + L= 0.354 + R= 0.076/2 + + rightWheelVelocity= (2*v+w*L)/(2*R) + leftWheelVelocity = (2*v-w*L)/(2*R) + + p.setJointMotorControl2(robotId,0,p.VELOCITY_CONTROL,targetVelocity=leftWheelVelocity,force=1000) + p.setJointMotorControl2(robotId,1,p.VELOCITY_CONTROL,targetVelocity=rightWheelVelocity,force=1000) + +def plot(path,x_history,y_history): + """ + """ + plt.style.use("ggplot") + plt.figure() + plt.title("MPC Tracking Results") + + plt.plot(path[0,:],path[1,:], c='tab:orange',marker=".",label="reference track") + plt.plot(x_history, y_history, c='tab:blue',marker=".",alpha=0.5,label="vehicle trajectory") + plt.axis("equal") + plt.legend() + plt.show() + +def run_sim(): + """ + """ + p.connect(p.GUI) + + start_offset = [0,2,0] + start_orientation = p.getQuaternionFromEuler([0,0,0]) + turtle = p.loadURDF("turtlebot.urdf",start_offset, start_orientation) + plane = p.loadURDF("plane.urdf") + + p.setRealTimeSimulation(1) + p.setGravity(0,0,-10) + + # MPC time step + P.dt = 0.25 + + opt_u = np.zeros((P.M,P.T)) + opt_u[0,:] = 1 #m/s + opt_u[1,:] = np.radians(0) #rad/s + + # Interpolated Path to follow given waypoints + path = compute_path_from_wp([0,3,4,6,10,13], + [0,0,2,4,3,3],1) + + for x_,y_ in zip(path[0,:],path[1,:]): + p.addUserDebugLine([x_,y_,0],[x_,y_,0.33],[0,0,1]) + + x_history=[] + y_history=[] + + while (1): + + state = get_state(turtle) + x_history.append(state[0]) + y_history.append(state[1]) + + #track path in bullet + p.addUserDebugLine([state[0],state[1],0],[state[0],state[1],0.5],[1,0,0]) + + if np.sqrt((state[0]-path[0,-1])**2+(state[1]-path[1,-1])**2)<1: + print("Success! Goal Reached") + set_ctrl(turtle,0,0) + plot(path,x_history,y_history) + p.disconnect() + return + + #optimization loop + start=time.time() + opt_u = optimize(state,opt_u,path) + elapsed=time.time()-start + print("CVXPY Optimization Time: {:.4f}s".format(elapsed)) + + set_ctrl(turtle,opt_u[0,1],opt_u[1,1]) + + if P.dt-elapsed>0: + time.sleep(P.dt-elapsed) + +if __name__ == '__main__': + run_sim() diff --git a/.old/cte/mpc_demo/utils.py b/.old/cte/mpc_demo/utils.py new file mode 100755 index 0000000..f952e0b --- /dev/null +++ b/.old/cte/mpc_demo/utils.py @@ -0,0 +1,84 @@ +import numpy as np +from scipy.interpolate import interp1d + +def compute_path_from_wp(start_xp, start_yp, step = 0.1): + """ + """ + final_xp=[] + final_yp=[] + delta = step #[m] + + for idx in range(len(start_xp)-1): + section_len = np.sum(np.sqrt(np.power(np.diff(start_xp[idx:idx+2]),2)+np.power(np.diff(start_yp[idx:idx+2]),2))) + + interp_range = np.linspace(0,1,np.floor(section_len/delta).astype(int)) + + fx=interp1d(np.linspace(0,1,2),start_xp[idx:idx+2],kind=1) + fy=interp1d(np.linspace(0,1,2),start_yp[idx:idx+2],kind=1) + + final_xp=np.append(final_xp,fx(interp_range)) + final_yp=np.append(final_yp,fy(interp_range)) + + return np.vstack((final_xp,final_yp)) + +def get_nn_idx(state,path): + """ + """ + dx = state[0]-path[0,:] + dy = state[1]-path[1,:] + dist = np.sqrt(dx**2 + dy**2) + nn_idx = np.argmin(dist) + + try: + v = [path[0,nn_idx+1] - path[0,nn_idx], + path[1,nn_idx+1] - path[1,nn_idx]] + v /= np.linalg.norm(v) + + d = [path[0,nn_idx] - state[0], + path[1,nn_idx] - state[1]] + + if np.dot(d,v) > 0: + target_idx = nn_idx + else: + target_idx = nn_idx+1 + + except IndexError as e: + target_idx = nn_idx + + return target_idx + +def road_curve(state,track): + """ + """ + + POLY_RANK = 3 + + #given vehicle pos find lookahead waypoints + nn_idx=get_nn_idx(state,track)-1 + LOOKAHED = POLY_RANK + 1 + lk_wp=track[:,nn_idx:nn_idx+LOOKAHED] + + #trasform lookahead waypoints to vehicle ref frame + dx = lk_wp[0,:] - state[0] + dy = lk_wp[1,:] - state[1] + + wp_vehicle_frame = np.vstack(( dx * np.cos(-state[2]) - dy * np.sin(-state[2]), + dy * np.cos(-state[2]) + dx * np.sin(-state[2]) )) + + #fit poly + return np.polyfit(wp_vehicle_frame[0,:], wp_vehicle_frame[1,:], POLY_RANK, rcond=None, full=False, w=None, cov=False) + +def f(x,coeff): + """ + """ + return round(coeff[0]*x**3 + coeff[1]*x**2 + coeff[2]*x**1 + coeff[3]*x**0,6) + +# def f(x,coeff): +# return round(coeff[0]*x**5+coeff[1]*x**4+coeff[2]*x**3+coeff[3]*x**2+coeff[4]*x**1+coeff[5]*x**0,6) + +def df(x,coeff): + """ + """ + return round(3*coeff[0]*x**2 + 2*coeff[1]*x**1 + coeff[2]*x**0,6) +# def df(x,coeff): +# return round(5*coeff[0]*x**4 + 4*coeff[1]*x**3 +3*coeff[2]*x**2 + 2*coeff[3]*x**1 + coeff[4]*x**0,6) diff --git a/notebooks/MPC_cte_cvxpy.ipynb b/.old/cte/notebooks/MPC_cte_cvxpy.ipynb similarity index 100% rename from notebooks/MPC_cte_cvxpy.ipynb rename to .old/cte/notebooks/MPC_cte_cvxpy.ipynb diff --git a/notebooks/MPC_cte_scipy.ipynb b/.old/cte/notebooks/MPC_cte_scipy.ipynb similarity index 100% rename from notebooks/MPC_cte_scipy.ipynb rename to .old/cte/notebooks/MPC_cte_scipy.ipynb diff --git a/.old/cte/notebooks/img/fitted_poly.png b/.old/cte/notebooks/img/fitted_poly.png new file mode 100644 index 0000000..2ce0e93 Binary files /dev/null and b/.old/cte/notebooks/img/fitted_poly.png differ diff --git a/.old/cte/notebooks/img/mpc_block_diagram.png b/.old/cte/notebooks/img/mpc_block_diagram.png new file mode 100644 index 0000000..7f322d1 Binary files /dev/null and b/.old/cte/notebooks/img/mpc_block_diagram.png differ diff --git a/.old/cte/notebooks/img/mpc_t.png b/.old/cte/notebooks/img/mpc_t.png new file mode 100644 index 0000000..8ed78b4 Binary files /dev/null and b/.old/cte/notebooks/img/mpc_t.png differ diff --git a/mpc_demo/cvxpy_mpc.py b/mpc_demo/cvxpy_mpc.py index 0a3da8d..c14c8a5 100755 --- a/mpc_demo/cvxpy_mpc.py +++ b/mpc_demo/cvxpy_mpc.py @@ -13,32 +13,36 @@ P=Params() def get_linear_model(x_bar,u_bar): """ """ + L=0.3 x = x_bar[0] y = x_bar[1] - theta = x_bar[2] + v = x_bar[2] + theta = x_bar[3] - v = u_bar[0] - w = u_bar[1] + a = u_bar[0] + delta = u_bar[1] A = np.zeros((P.N,P.N)) - A[0,2]=-v*np.sin(theta) - A[1,2]=v*np.cos(theta) + A[0,2]=np.cos(theta) + A[0,3]=-v*np.sin(theta) + A[1,2]=np.sin(theta) + A[1,3]=v*np.cos(theta) + A[3,2]=v*np.tan(delta)/L A_lin=np.eye(P.N)+P.dt*A B = np.zeros((P.N,P.M)) - B[0,0]=np.cos(theta) - B[1,0]=np.sin(theta) - B[2,1]=1 + B[2,0]=1 + B[3,1]=v/(L*np.cos(delta)**2) B_lin=P.dt*B - f_xu=np.array([v*np.cos(theta),v*np.sin(theta),w]).reshape(P.N,1) + f_xu=np.array([v*np.cos(theta), v*np.sin(theta), a,v*np.tan(delta)/L]).reshape(P.N,1) C_lin = P.dt*(f_xu - np.dot(A,x_bar.reshape(P.N,1)) - np.dot(B,u_bar.reshape(P.M,1))) - return A_lin,B_lin,C_lin + return np.round(A_lin,4), np.round(B_lin,4), np.round(C_lin,4) -def optimize(state,u_bar,track): +def optimize(state,u_bar,track,ref_vel=1.): ''' :param state: :param u_bar: @@ -47,14 +51,15 @@ def optimize(state,u_bar,track): ''' MAX_SPEED = 1.25 - MIN_SPEED = 0.75 - MAX_STEER_SPEED = 1.57/2 + MAX_STEER = 1.57/2 + MAX_ACC = 1.0 # compute polynomial coefficients of the track K=road_curve(state,track) # dynamics starting state w.r.t vehicle frame x_bar=np.zeros((P.N,P.T+1)) + x_bar[2,0]=state[2] #prediction for linearization of costrains for t in range (1,P.T+1): @@ -72,16 +77,16 @@ def optimize(state,u_bar,track): for t in range(P.T): - #cost += 30*cp.sum_squares(x[2,t]-np.arctan(df(x_bar[0,t],K))) # psi - cost += 50*cp.sum_squares(x[2,t]-np.arctan2(df(x_bar[0,t],K),x_bar[0,t])) # psi + cost += 30*cp.sum_squares(x[3,t]-np.arctan(df(x_bar[0,t],K))) # psi cost += 20*cp.sum_squares(f(x_bar[0,t],K)-x[1,t]) # cte + cost += 10*cp.sum_squares(ref_vel-x[2,t]) # desired v # Actuation rate of change if t < (P.T - 1): - cost += cp.quad_form(u[:, t + 1] - u[:, t], 100*np.eye(P.M)) + cost += cp.quad_form(u[:, t + 1] - u[:, t], 10*np.eye(P.M)) # Actuation effort - cost += cp.quad_form( u[:, t],1*np.eye(P.M)) + cost += cp.quad_form( u[:, t],10*np.eye(P.M)) # Kinrmatics Constrains (Linearized model) A,B,C=get_linear_model(x_bar[:,t],u_bar[:,t]) @@ -89,9 +94,10 @@ def optimize(state,u_bar,track): # sums problem objectives and concatenates constraints. constr += [x[:,0] == x_bar[:,0]] #<--watch out the start condition - constr += [u[0, :] <= MAX_SPEED] - constr += [u[0, :] >= MIN_SPEED] - constr += [cp.abs(u[1, :]) <= MAX_STEER_SPEED] + constr += [x[2, :] <= MAX_SPEED] + constr += [x[2, :] >= 0.0] + constr += [cp.abs(u[0, :]) <= MAX_ACC] + constr += [cp.abs(u[1, :]) <= MAX_STEER] # Solve prob = cp.Problem(cp.Minimize(cost), constr) diff --git a/mpc_demo/mpc_config.py b/mpc_demo/mpc_config.py index 9b85c5b..a97a79c 100644 --- a/mpc_demo/mpc_config.py +++ b/mpc_demo/mpc_config.py @@ -1,6 +1,6 @@ class Params(): def __init__(self): - self.N = 3 #number of state variables + self.N = 4 #number of state variables self.M = 2 #number of control variables - self.T = 20 #Prediction Horizon + self.T = 10 #Prediction Horizon self.dt = 0.25 #discretization step diff --git a/mpc_demo/mpc_demo_nosim.py b/mpc_demo/mpc_demo_nosim.py index a3704c9..cf24f90 100755 --- a/mpc_demo/mpc_demo_nosim.py +++ b/mpc_demo/mpc_demo_nosim.py @@ -11,9 +11,11 @@ import sys import time # Robot Starting position -SIM_START_X=0 +SIM_START_X=0. SIM_START_Y=0.5 -SIM_START_H=0 +SIM_START_V=0. +SIM_START_H=0. +L=0.3 from mpc_config import Params P=Params() @@ -24,24 +26,25 @@ class MPC(): def __init__(self): # State for the robot mathematical model [x,y,heading] - self.state = [SIM_START_X, SIM_START_Y, SIM_START_H] + self.state = [SIM_START_X, SIM_START_Y, SIM_START_V, SIM_START_H] self.opt_u = np.zeros((P.M,P.T)) - self.opt_u[0,:] = 1 #m/s + self.opt_u[0,:] = 0.5 #m/ss self.opt_u[1,:] = np.radians(0) #rad/s # Interpolated Path to follow given waypoints #self.path = compute_path_from_wp([0,10,12,2,4,14],[0,0,2,10,12,12]) - self.path = compute_path_from_wp([0,3,4,6,10,13], - [0,0,2,4,3,3],1) + self.path = compute_path_from_wp([0,3,4,6,10,12,14,6,1,0], + [0,0,2,4,3,3,-2,-6,-2,-2],1) # Sim help vars self.sim_time=0 self.x_history=[] self.y_history=[] - self.h_history=[] self.v_history=[] - self.w_history=[] + self.h_history=[] + self.a_history=[] + self.d_history=[] self.predicted=None #Initialise plot @@ -56,11 +59,15 @@ class MPC(): predicted=np.zeros(self.opt_u.shape) x=self.state[0] y=self.state[1] - th=self.state[2] - for idx,v,w in zip(range(len(self.opt_u[0,:])),self.opt_u[0,:],self.opt_u[1,:]): + v=self.state[2] + th=self.state[3] + + for idx,a,delta in zip(range(len(self.opt_u[0,:])),self.opt_u[0,:],self.opt_u[1,:]): x = x+v*np.cos(th)*P.dt y = y+v*np.sin(th)*P.dt - th= th +w*P.dt + v = v+a*P.dt + th = th + v*np.tan(delta)/L*P.dt + predicted[0,idx]=x predicted[1,idx]=y @@ -73,7 +80,7 @@ class MPC(): while 1: if self.state is not None: - if np.sqrt((self.state[0]-self.path[0,-1])**2+(self.state[1]-self.path[1,-1])**2)<1: + if np.sqrt((self.state[0]-self.path[0,-1])**2+(self.state[1]-self.path[1,-1])**2)<0.5: print("Success! Goal Reached") return @@ -89,7 +96,7 @@ class MPC(): self.predict_motion() self.plot_sim() - def update_sim(self,lin_v,ang_v): + def update_sim(self,acc,steer): ''' Updates state. @@ -97,18 +104,20 @@ class MPC(): :param ang_v: float ''' - self.state[0] = self.state[0] +lin_v*np.cos(self.state[2])*P.dt - self.state[1] = self.state[1] +lin_v*np.sin(self.state[2])*P.dt - self.state[2] = self.state[2] +ang_v*P.dt + self.state[0] = self.state[0] +self.state[2]*np.cos(self.state[3])*P.dt + self.state[1] = self.state[1] +self.state[2]*np.sin(self.state[3])*P.dt + self.state[2] = self.state[2] +acc*P.dt + self.state[3] = self.state[3] + self.state[2]*np.tan(steer)/L*P.dt def plot_sim(self): self.sim_time = self.sim_time+P.dt self.x_history.append(self.state[0]) self.y_history.append(self.state[1]) - self.h_history.append(self.state[2]) - self.v_history.append(self.opt_u[0,1]) - self.w_history.append(self.opt_u[1,1]) + self.v_history.append(self.state[2]) + self.h_history.append(self.state[3]) + self.a_history.append(self.opt_u[0,1]) + self.d_history.append(self.opt_u[1,1]) plt.clf() @@ -156,16 +165,16 @@ class MPC(): plt.subplot(grid[0, 2]) #plt.title("Linear Velocity {} m/s".format(self.v_history[-1])) - plt.plot(self.v_history,c='tab:orange') + plt.plot(self.a_history,c='tab:orange') locs, _ = plt.xticks() plt.xticks(locs[1:], locs[1:]*P.dt) - plt.ylabel('v(t) [m/s]') + plt.ylabel('a(t) [m/ss]') plt.xlabel('t [s]') plt.subplot(grid[1, 2]) #plt.title("Angular Velocity {} m/s".format(self.w_history[-1])) - plt.plot(np.degrees(self.w_history),c='tab:orange') - plt.ylabel('w(t) [deg/s]') + plt.plot(np.degrees(self.d_history),c='tab:orange') + plt.ylabel('w(t) [deg]') locs, _ = plt.xticks() plt.xticks(locs[1:], locs[1:]*P.dt) plt.xlabel('t [s]') @@ -177,9 +186,9 @@ class MPC(): def plot_car(x, y, yaw): - LENGTH = 1.0 # [m] - WIDTH = 0.5 # [m] - OFFSET = LENGTH/2 # [m] + LENGTH = 0.3 # [m] + WIDTH = 0.1 # [m] + OFFSET = LENGTH # [m] outline = np.array([[-OFFSET, (LENGTH - OFFSET), (LENGTH - OFFSET), -OFFSET, -OFFSET], [WIDTH / 2, WIDTH / 2, - WIDTH / 2, -WIDTH / 2, WIDTH / 2]]) diff --git a/racecar/checker_blue.png b/mpc_demo/racecar/checker_blue.png similarity index 100% rename from racecar/checker_blue.png rename to mpc_demo/racecar/checker_blue.png diff --git a/racecar/f10_racecar/differential/diff_arm.stl b/mpc_demo/racecar/f10_racecar/differential/diff_arm.stl similarity index 100% rename from racecar/f10_racecar/differential/diff_arm.stl rename to mpc_demo/racecar/f10_racecar/differential/diff_arm.stl diff --git a/racecar/f10_racecar/differential/diff_carrier.stl b/mpc_demo/racecar/f10_racecar/differential/diff_carrier.stl similarity index 100% rename from racecar/f10_racecar/differential/diff_carrier.stl rename to mpc_demo/racecar/f10_racecar/differential/diff_carrier.stl diff --git a/racecar/f10_racecar/differential/diff_carrier_cover.stl b/mpc_demo/racecar/f10_racecar/differential/diff_carrier_cover.stl similarity index 100% rename from racecar/f10_racecar/differential/diff_carrier_cover.stl rename to mpc_demo/racecar/f10_racecar/differential/diff_carrier_cover.stl diff --git a/racecar/f10_racecar/differential/diff_leftshaft.stl b/mpc_demo/racecar/f10_racecar/differential/diff_leftshaft.stl similarity index 100% rename from racecar/f10_racecar/differential/diff_leftshaft.stl rename to mpc_demo/racecar/f10_racecar/differential/diff_leftshaft.stl diff --git a/racecar/f10_racecar/differential/diff_motor_cover.stl b/mpc_demo/racecar/f10_racecar/differential/diff_motor_cover.stl similarity index 100% rename from racecar/f10_racecar/differential/diff_motor_cover.stl rename to mpc_demo/racecar/f10_racecar/differential/diff_motor_cover.stl diff --git a/racecar/f10_racecar/differential/diff_pinion.stl b/mpc_demo/racecar/f10_racecar/differential/diff_pinion.stl similarity index 100% rename from racecar/f10_racecar/differential/diff_pinion.stl rename to mpc_demo/racecar/f10_racecar/differential/diff_pinion.stl diff --git a/racecar/f10_racecar/differential/diff_rightshaft.stl b/mpc_demo/racecar/f10_racecar/differential/diff_rightshaft.stl similarity index 100% rename from racecar/f10_racecar/differential/diff_rightshaft.stl rename to mpc_demo/racecar/f10_racecar/differential/diff_rightshaft.stl diff --git a/racecar/f10_racecar/differential/diff_ring.stl b/mpc_demo/racecar/f10_racecar/differential/diff_ring.stl similarity index 100% rename from racecar/f10_racecar/differential/diff_ring.stl rename to mpc_demo/racecar/f10_racecar/differential/diff_ring.stl diff --git a/racecar/f10_racecar/differential/diff_ring.urdf b/mpc_demo/racecar/f10_racecar/differential/diff_ring.urdf similarity index 100% rename from racecar/f10_racecar/differential/diff_ring.urdf rename to mpc_demo/racecar/f10_racecar/differential/diff_ring.urdf diff --git a/racecar/f10_racecar/differential/diff_side.stl b/mpc_demo/racecar/f10_racecar/differential/diff_side.stl similarity index 100% rename from racecar/f10_racecar/differential/diff_side.stl rename to mpc_demo/racecar/f10_racecar/differential/diff_side.stl diff --git a/racecar/f10_racecar/differential/diff_spider.stl b/mpc_demo/racecar/f10_racecar/differential/diff_spider.stl similarity index 100% rename from racecar/f10_racecar/differential/diff_spider.stl rename to mpc_demo/racecar/f10_racecar/differential/diff_spider.stl diff --git a/racecar/f10_racecar/differential/diff_spider_shaft.stl b/mpc_demo/racecar/f10_racecar/differential/diff_spider_shaft.stl similarity index 100% rename from racecar/f10_racecar/differential/diff_spider_shaft.stl rename to mpc_demo/racecar/f10_racecar/differential/diff_spider_shaft.stl diff --git a/racecar/f10_racecar/differential/diff_stand.stl b/mpc_demo/racecar/f10_racecar/differential/diff_stand.stl similarity index 100% rename from racecar/f10_racecar/differential/diff_stand.stl rename to mpc_demo/racecar/f10_racecar/differential/diff_stand.stl diff --git a/racecar/f10_racecar/differential/modelorigin.txt b/mpc_demo/racecar/f10_racecar/differential/modelorigin.txt similarity index 100% rename from racecar/f10_racecar/differential/modelorigin.txt rename to mpc_demo/racecar/f10_racecar/differential/modelorigin.txt diff --git a/racecar/f10_racecar/meshes/barca_track.mtl b/mpc_demo/racecar/f10_racecar/meshes/barca_track.mtl similarity index 100% rename from racecar/f10_racecar/meshes/barca_track.mtl rename to mpc_demo/racecar/f10_racecar/meshes/barca_track.mtl diff --git a/racecar/f10_racecar/meshes/barca_track.obj b/mpc_demo/racecar/f10_racecar/meshes/barca_track.obj similarity index 100% rename from racecar/f10_racecar/meshes/barca_track.obj rename to mpc_demo/racecar/f10_racecar/meshes/barca_track.obj diff --git a/racecar/f10_racecar/meshes/barca_track.sdf b/mpc_demo/racecar/f10_racecar/meshes/barca_track.sdf similarity index 100% rename from racecar/f10_racecar/meshes/barca_track.sdf rename to mpc_demo/racecar/f10_racecar/meshes/barca_track.sdf diff --git a/racecar/f10_racecar/meshes/chassis.STL b/mpc_demo/racecar/f10_racecar/meshes/chassis.STL similarity index 100% rename from racecar/f10_racecar/meshes/chassis.STL rename to mpc_demo/racecar/f10_racecar/meshes/chassis.STL diff --git a/racecar/f10_racecar/meshes/chassis.dae b/mpc_demo/racecar/f10_racecar/meshes/chassis.dae similarity index 100% rename from racecar/f10_racecar/meshes/chassis.dae rename to mpc_demo/racecar/f10_racecar/meshes/chassis.dae diff --git a/racecar/f10_racecar/meshes/chassis_differential.STL b/mpc_demo/racecar/f10_racecar/meshes/chassis_differential.STL similarity index 100% rename from racecar/f10_racecar/meshes/chassis_differential.STL rename to mpc_demo/racecar/f10_racecar/meshes/chassis_differential.STL diff --git a/racecar/f10_racecar/meshes/checker_blue.png b/mpc_demo/racecar/f10_racecar/meshes/checker_blue.png similarity index 100% rename from racecar/f10_racecar/meshes/checker_blue.png rename to mpc_demo/racecar/f10_racecar/meshes/checker_blue.png diff --git a/racecar/f10_racecar/meshes/cone.dae b/mpc_demo/racecar/f10_racecar/meshes/cone.dae similarity index 100% rename from racecar/f10_racecar/meshes/cone.dae rename to mpc_demo/racecar/f10_racecar/meshes/cone.dae diff --git a/racecar/f10_racecar/meshes/cone.mtl b/mpc_demo/racecar/f10_racecar/meshes/cone.mtl similarity index 100% rename from racecar/f10_racecar/meshes/cone.mtl rename to mpc_demo/racecar/f10_racecar/meshes/cone.mtl diff --git a/racecar/f10_racecar/meshes/cone.obj b/mpc_demo/racecar/f10_racecar/meshes/cone.obj similarity index 100% rename from racecar/f10_racecar/meshes/cone.obj rename to mpc_demo/racecar/f10_racecar/meshes/cone.obj diff --git a/racecar/f10_racecar/meshes/hokuyo.dae b/mpc_demo/racecar/f10_racecar/meshes/hokuyo.dae similarity index 100% rename from racecar/f10_racecar/meshes/hokuyo.dae rename to mpc_demo/racecar/f10_racecar/meshes/hokuyo.dae diff --git a/racecar/f10_racecar/meshes/hokuyo.mtl b/mpc_demo/racecar/f10_racecar/meshes/hokuyo.mtl similarity index 100% rename from racecar/f10_racecar/meshes/hokuyo.mtl rename to mpc_demo/racecar/f10_racecar/meshes/hokuyo.mtl diff --git a/racecar/f10_racecar/meshes/hokuyo.obj b/mpc_demo/racecar/f10_racecar/meshes/hokuyo.obj similarity index 100% rename from racecar/f10_racecar/meshes/hokuyo.obj rename to mpc_demo/racecar/f10_racecar/meshes/hokuyo.obj diff --git a/racecar/f10_racecar/meshes/left_front_wheel.STL b/mpc_demo/racecar/f10_racecar/meshes/left_front_wheel.STL similarity index 100% rename from racecar/f10_racecar/meshes/left_front_wheel.STL rename to mpc_demo/racecar/f10_racecar/meshes/left_front_wheel.STL diff --git a/racecar/f10_racecar/meshes/left_front_wheel.dae b/mpc_demo/racecar/f10_racecar/meshes/left_front_wheel.dae similarity index 100% rename from racecar/f10_racecar/meshes/left_front_wheel.dae rename to mpc_demo/racecar/f10_racecar/meshes/left_front_wheel.dae diff --git a/racecar/f10_racecar/meshes/left_front_wheel.mtl b/mpc_demo/racecar/f10_racecar/meshes/left_front_wheel.mtl similarity index 100% rename from racecar/f10_racecar/meshes/left_front_wheel.mtl rename to mpc_demo/racecar/f10_racecar/meshes/left_front_wheel.mtl diff --git a/racecar/f10_racecar/meshes/left_front_wheel.obj b/mpc_demo/racecar/f10_racecar/meshes/left_front_wheel.obj similarity index 100% rename from racecar/f10_racecar/meshes/left_front_wheel.obj rename to mpc_demo/racecar/f10_racecar/meshes/left_front_wheel.obj diff --git a/racecar/f10_racecar/meshes/left_rear_wheel.STL b/mpc_demo/racecar/f10_racecar/meshes/left_rear_wheel.STL similarity index 100% rename from racecar/f10_racecar/meshes/left_rear_wheel.STL rename to mpc_demo/racecar/f10_racecar/meshes/left_rear_wheel.STL diff --git a/racecar/f10_racecar/meshes/left_rear_wheel.dae b/mpc_demo/racecar/f10_racecar/meshes/left_rear_wheel.dae similarity index 100% rename from racecar/f10_racecar/meshes/left_rear_wheel.dae rename to mpc_demo/racecar/f10_racecar/meshes/left_rear_wheel.dae diff --git a/racecar/f10_racecar/meshes/left_rear_wheel.mtl b/mpc_demo/racecar/f10_racecar/meshes/left_rear_wheel.mtl similarity index 100% rename from racecar/f10_racecar/meshes/left_rear_wheel.mtl rename to mpc_demo/racecar/f10_racecar/meshes/left_rear_wheel.mtl diff --git a/racecar/f10_racecar/meshes/left_rear_wheel.obj b/mpc_demo/racecar/f10_racecar/meshes/left_rear_wheel.obj similarity index 100% rename from racecar/f10_racecar/meshes/left_rear_wheel.obj rename to mpc_demo/racecar/f10_racecar/meshes/left_rear_wheel.obj diff --git a/racecar/f10_racecar/meshes/left_steering_hinge.STL b/mpc_demo/racecar/f10_racecar/meshes/left_steering_hinge.STL similarity index 100% rename from racecar/f10_racecar/meshes/left_steering_hinge.STL rename to mpc_demo/racecar/f10_racecar/meshes/left_steering_hinge.STL diff --git a/racecar/f10_racecar/meshes/left_steering_hinge.dae b/mpc_demo/racecar/f10_racecar/meshes/left_steering_hinge.dae similarity index 100% rename from racecar/f10_racecar/meshes/left_steering_hinge.dae rename to mpc_demo/racecar/f10_racecar/meshes/left_steering_hinge.dae diff --git a/racecar/f10_racecar/meshes/parking_1.dae b/mpc_demo/racecar/f10_racecar/meshes/parking_1.dae similarity index 100% rename from racecar/f10_racecar/meshes/parking_1.dae rename to mpc_demo/racecar/f10_racecar/meshes/parking_1.dae diff --git a/racecar/f10_racecar/meshes/part0.obj b/mpc_demo/racecar/f10_racecar/meshes/part0.obj similarity index 100% rename from racecar/f10_racecar/meshes/part0.obj rename to mpc_demo/racecar/f10_racecar/meshes/part0.obj diff --git a/racecar/f10_racecar/meshes/part1.obj b/mpc_demo/racecar/f10_racecar/meshes/part1.obj similarity index 100% rename from racecar/f10_racecar/meshes/part1.obj rename to mpc_demo/racecar/f10_racecar/meshes/part1.obj diff --git a/racecar/f10_racecar/meshes/part2.obj b/mpc_demo/racecar/f10_racecar/meshes/part2.obj similarity index 100% rename from racecar/f10_racecar/meshes/part2.obj rename to mpc_demo/racecar/f10_racecar/meshes/part2.obj diff --git a/racecar/f10_racecar/meshes/part3.obj b/mpc_demo/racecar/f10_racecar/meshes/part3.obj similarity index 100% rename from racecar/f10_racecar/meshes/part3.obj rename to mpc_demo/racecar/f10_racecar/meshes/part3.obj diff --git a/racecar/f10_racecar/meshes/part4.obj b/mpc_demo/racecar/f10_racecar/meshes/part4.obj similarity index 100% rename from racecar/f10_racecar/meshes/part4.obj rename to mpc_demo/racecar/f10_racecar/meshes/part4.obj diff --git a/racecar/f10_racecar/meshes/part5.obj b/mpc_demo/racecar/f10_racecar/meshes/part5.obj similarity index 100% rename from racecar/f10_racecar/meshes/part5.obj rename to mpc_demo/racecar/f10_racecar/meshes/part5.obj diff --git a/racecar/f10_racecar/meshes/part6.mtl b/mpc_demo/racecar/f10_racecar/meshes/part6.mtl similarity index 100% rename from racecar/f10_racecar/meshes/part6.mtl rename to mpc_demo/racecar/f10_racecar/meshes/part6.mtl diff --git a/racecar/f10_racecar/meshes/part6.obj b/mpc_demo/racecar/f10_racecar/meshes/part6.obj similarity index 100% rename from racecar/f10_racecar/meshes/part6.obj rename to mpc_demo/racecar/f10_racecar/meshes/part6.obj diff --git a/racecar/f10_racecar/meshes/porto_race_track.DAE b/mpc_demo/racecar/f10_racecar/meshes/porto_race_track.DAE similarity index 100% rename from racecar/f10_racecar/meshes/porto_race_track.DAE rename to mpc_demo/racecar/f10_racecar/meshes/porto_race_track.DAE diff --git a/racecar/f10_racecar/meshes/right_front_wheel.STL b/mpc_demo/racecar/f10_racecar/meshes/right_front_wheel.STL similarity index 100% rename from racecar/f10_racecar/meshes/right_front_wheel.STL rename to mpc_demo/racecar/f10_racecar/meshes/right_front_wheel.STL diff --git a/racecar/f10_racecar/meshes/right_front_wheel.dae b/mpc_demo/racecar/f10_racecar/meshes/right_front_wheel.dae similarity index 100% rename from racecar/f10_racecar/meshes/right_front_wheel.dae rename to mpc_demo/racecar/f10_racecar/meshes/right_front_wheel.dae diff --git a/racecar/f10_racecar/meshes/right_front_wheel.mtl b/mpc_demo/racecar/f10_racecar/meshes/right_front_wheel.mtl similarity index 100% rename from racecar/f10_racecar/meshes/right_front_wheel.mtl rename to mpc_demo/racecar/f10_racecar/meshes/right_front_wheel.mtl diff --git a/racecar/f10_racecar/meshes/right_front_wheel.obj b/mpc_demo/racecar/f10_racecar/meshes/right_front_wheel.obj similarity index 100% rename from racecar/f10_racecar/meshes/right_front_wheel.obj rename to mpc_demo/racecar/f10_racecar/meshes/right_front_wheel.obj diff --git a/racecar/f10_racecar/meshes/right_rear_wheel.STL b/mpc_demo/racecar/f10_racecar/meshes/right_rear_wheel.STL similarity index 100% rename from racecar/f10_racecar/meshes/right_rear_wheel.STL rename to mpc_demo/racecar/f10_racecar/meshes/right_rear_wheel.STL diff --git a/racecar/f10_racecar/meshes/right_rear_wheel.dae b/mpc_demo/racecar/f10_racecar/meshes/right_rear_wheel.dae similarity index 100% rename from racecar/f10_racecar/meshes/right_rear_wheel.dae rename to mpc_demo/racecar/f10_racecar/meshes/right_rear_wheel.dae diff --git a/racecar/f10_racecar/meshes/right_rear_wheel.mtl b/mpc_demo/racecar/f10_racecar/meshes/right_rear_wheel.mtl similarity index 100% rename from racecar/f10_racecar/meshes/right_rear_wheel.mtl rename to mpc_demo/racecar/f10_racecar/meshes/right_rear_wheel.mtl diff --git a/racecar/f10_racecar/meshes/right_rear_wheel.obj b/mpc_demo/racecar/f10_racecar/meshes/right_rear_wheel.obj similarity index 100% rename from racecar/f10_racecar/meshes/right_rear_wheel.obj rename to mpc_demo/racecar/f10_racecar/meshes/right_rear_wheel.obj diff --git a/racecar/f10_racecar/meshes/right_steering_hinge.STL b/mpc_demo/racecar/f10_racecar/meshes/right_steering_hinge.STL similarity index 100% rename from racecar/f10_racecar/meshes/right_steering_hinge.STL rename to mpc_demo/racecar/f10_racecar/meshes/right_steering_hinge.STL diff --git a/racecar/f10_racecar/meshes/right_steering_hinge.dae b/mpc_demo/racecar/f10_racecar/meshes/right_steering_hinge.dae similarity index 100% rename from racecar/f10_racecar/meshes/right_steering_hinge.dae rename to mpc_demo/racecar/f10_racecar/meshes/right_steering_hinge.dae diff --git a/racecar/f10_racecar/meshes/road.png b/mpc_demo/racecar/f10_racecar/meshes/road.png similarity index 100% rename from racecar/f10_racecar/meshes/road.png rename to mpc_demo/racecar/f10_racecar/meshes/road.png diff --git a/racecar/f10_racecar/meshes/walker_racecourse.dae b/mpc_demo/racecar/f10_racecar/meshes/walker_racecourse.dae similarity index 100% rename from racecar/f10_racecar/meshes/walker_racecourse.dae rename to mpc_demo/racecar/f10_racecar/meshes/walker_racecourse.dae diff --git a/racecar/f10_racecar/meshes/wheel.jpg b/mpc_demo/racecar/f10_racecar/meshes/wheel.jpg similarity index 100% rename from racecar/f10_racecar/meshes/wheel.jpg rename to mpc_demo/racecar/f10_racecar/meshes/wheel.jpg diff --git a/racecar/f10_racecar/racecar.urdf b/mpc_demo/racecar/f10_racecar/racecar.urdf similarity index 100% rename from racecar/f10_racecar/racecar.urdf rename to mpc_demo/racecar/f10_racecar/racecar.urdf diff --git a/racecar/f10_racecar/racecar_differential.urdf b/mpc_demo/racecar/f10_racecar/racecar_differential.urdf similarity index 100% rename from racecar/f10_racecar/racecar_differential.urdf rename to mpc_demo/racecar/f10_racecar/racecar_differential.urdf diff --git a/racecar/plane.mtl b/mpc_demo/racecar/plane.mtl similarity index 100% rename from racecar/plane.mtl rename to mpc_demo/racecar/plane.mtl diff --git a/racecar/plane.obj b/mpc_demo/racecar/plane.obj similarity index 100% rename from racecar/plane.obj rename to mpc_demo/racecar/plane.obj diff --git a/racecar/plane.urdf b/mpc_demo/racecar/plane.urdf similarity index 100% rename from racecar/plane.urdf rename to mpc_demo/racecar/plane.urdf diff --git a/racecar/racecar.py b/mpc_demo/racecar/racecar.py similarity index 100% rename from racecar/racecar.py rename to mpc_demo/racecar/racecar.py diff --git a/mpc_demo/utils.py b/mpc_demo/utils.py index f952e0b..03b6a9f 100755 --- a/mpc_demo/utils.py +++ b/mpc_demo/utils.py @@ -62,8 +62,8 @@ def road_curve(state,track): dx = lk_wp[0,:] - state[0] dy = lk_wp[1,:] - state[1] - wp_vehicle_frame = np.vstack(( dx * np.cos(-state[2]) - dy * np.sin(-state[2]), - dy * np.cos(-state[2]) + dx * np.sin(-state[2]) )) + wp_vehicle_frame = np.vstack(( dx * np.cos(-state[3]) - dy * np.sin(-state[3]), + dy * np.cos(-state[3]) + dx * np.sin(-state[3]) )) #fit poly return np.polyfit(wp_vehicle_frame[0,:], wp_vehicle_frame[1,:], POLY_RANK, rcond=None, full=False, w=None, cov=False) diff --git a/notebooks/MPC_racecar.ipynb b/notebooks/MPC_racecar.ipynb index 5669c03..8097591 100644 --- a/notebooks/MPC_racecar.ipynb +++ b/notebooks/MPC_racecar.ipynb @@ -828,7 +828,7 @@ }, { "cell_type": "code", - "execution_count": 37, + "execution_count": 50, "metadata": {}, "outputs": [ { @@ -837,17 +837,7 @@ "text": [ ":29: RuntimeWarning: invalid value encountered in true_divide\n", " v /= np.linalg.norm(v)\n", - ":34: RankWarning: Polyfit may be poorly conditioned\n", - " K=road_curve(x_sim[:,sim_time],track)\n", - ":34: RankWarning: Polyfit may be poorly conditioned\n", - " K=road_curve(x_sim[:,sim_time],track)\n", - ":34: RankWarning: Polyfit may be poorly conditioned\n", - " K=road_curve(x_sim[:,sim_time],track)\n", - ":34: RankWarning: Polyfit may be poorly conditioned\n", - " K=road_curve(x_sim[:,sim_time],track)\n", - ":34: RankWarning: Polyfit may be poorly conditioned\n", - " K=road_curve(x_sim[:,sim_time],track)\n", - ":34: RankWarning: Polyfit may be poorly conditioned\n", + ":34: RankWarning: Polyfit may be poorly conditioned\n", " K=road_curve(x_sim[:,sim_time],track)\n" ] }, @@ -855,18 +845,18 @@ "name": "stdout", "output_type": "stream", "text": [ - "CVXPY Optimization Time: Avrg: 0.2258s Max: 0.3213s Min: 0.2024s\n" + "CVXPY Optimization Time: Avrg: 0.2259s Max: 0.3524s Min: 0.2046s\n" ] } ], "source": [ - "track = compute_path_from_wp([0,3,4,6,10,13],\n", - " [0,0,2,4,3,3],0.5)\n", + "track = compute_path_from_wp([0,3,4,6,10,12,14,6,1,0],\n", + " [0,0,2,4,3,3,-2,-6,-2,-2],0.5)\n", "\n", "# track = compute_path_from_wp([0,5,7.5,10,12,13,13,10],\n", "# [0,0,2.5,2.5,0,0,5,10],0.5)\n", "\n", - "sim_duration = 80 #time steps\n", + "sim_duration = 175 #time steps\n", "opt_time=[]\n", "\n", "x_sim = np.zeros((N,sim_duration))\n", @@ -965,12 +955,12 @@ }, { "cell_type": "code", - "execution_count": 38, + "execution_count": 51, "metadata": {}, "outputs": [ { "data": { - "image/png": "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\n", + "image/png": "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\n", "text/plain": [ "
" ]