@ -17,7 +17,8 @@ else: 
			
		
	
		
		
			
				
					
					LAT_MPC_DIR  =  os . path . dirname ( os . path . abspath ( __file__ ) ) LAT_MPC_DIR  =  os . path . dirname ( os . path . abspath ( __file__ ) )  
			
		
	
		
		
			
				
					
					EXPORT_DIR  =  os . path . join ( LAT_MPC_DIR ,  " c_generated_code " ) EXPORT_DIR  =  os . path . join ( LAT_MPC_DIR ,  " c_generated_code " )  
			
		
	
		
		
			
				
					
					JSON_FILE  =  " acados_ocp_lat.json " JSON_FILE  =  " acados_ocp_lat.json "  
			
		
	
		
		
			
				
					
					X_DIM  =  6 X_DIM  =  4  
			
				
				
			
		
	
		
		
	
		
		
			
				
					
					P_DIM  =  2  
			
		
	
		
		
			
				
					
					
 
			
		
	
		
		
			
				
					
					def  gen_lat_model ( ) : def  gen_lat_model ( ) :  
			
		
	
		
		
			
				
					
					  model  =  AcadosModel ( )    model  =  AcadosModel ( )   
			
		
	
	
		
		
			
				
					
						
						
						
							
								 
						
					 
					@ -28,9 +29,12 @@ def gen_lat_model(): 
			
		
	
		
		
			
				
					
					  y_ego  =  SX . sym ( ' y_ego ' )    y_ego  =  SX . sym ( ' y_ego ' )   
			
		
	
		
		
			
				
					
					  psi_ego  =  SX . sym ( ' psi_ego ' )    psi_ego  =  SX . sym ( ' psi_ego ' )   
			
		
	
		
		
			
				
					
					  curv_ego  =  SX . sym ( ' curv_ego ' )    curv_ego  =  SX . sym ( ' curv_ego ' )   
			
		
	
		
		
			
				
					
					  model . x  =  vertcat ( x_ego ,  y_ego ,  psi_ego ,  curv_ego )   
			
		
	
		
		
			
				
					
					
 
			
		
	
		
		
			
				
					
					  # parameters   
			
		
	
		
		
			
				
					
					  v_ego  =  SX . sym ( ' v_ego ' )    v_ego  =  SX . sym ( ' v_ego ' )   
			
		
	
		
		
			
				
					
					  rotation_radius  =  SX . sym ( ' rotation_radius ' )    rotation_radius  =  SX . sym ( ' rotation_radius ' )   
			
		
	
		
		
			
				
					
					  model . x  =  vertcat ( x_ego ,  y_ego ,  psi_ego ,  curv_ego ,  v_ego ,  rotation_radius )    model . p =  vertcat ( v_ego ,  rotation_radius )   
			
				
				
			
		
	
		
		
	
		
		
			
				
					
					
 
			
		
	
		
		
			
				
					
					  # controls    # controls   
			
		
	
		
		
			
				
					
					  curv_rate  =  SX . sym ( ' curv_rate ' )    curv_rate  =  SX . sym ( ' curv_rate ' )   
			
		
	
	
		
		
			
				
					
						
						
						
							
								 
						
					 
					@ -41,18 +45,14 @@ def gen_lat_model(): 
			
		
	
		
		
			
				
					
					  y_ego_dot  =  SX . sym ( ' y_ego_dot ' )    y_ego_dot  =  SX . sym ( ' y_ego_dot ' )   
			
		
	
		
		
			
				
					
					  psi_ego_dot  =  SX . sym ( ' psi_ego_dot ' )    psi_ego_dot  =  SX . sym ( ' psi_ego_dot ' )   
			
		
	
		
		
			
				
					
					  curv_ego_dot  =  SX . sym ( ' curv_ego_dot ' )    curv_ego_dot  =  SX . sym ( ' curv_ego_dot ' )   
			
		
	
		
		
			
				
					
					  v_ego_dot  =  SX . sym ( ' v_ego_dot ' )  
 
			
				
				
			
		
	
		
		
			
				
					
					  rotation_radius_dot  =  SX . sym ( ' rotation_radius_dot ' )    model . xdot  =  vertcat ( x_ego_dot ,  y_ego_dot ,  psi_ego_dot ,  curv_ego_dot )   
			
				
				
			
		
	
		
		
			
				
					
					  model . xdot  =  vertcat ( x_ego_dot ,  y_ego_dot ,  psi_ego_dot ,  curv_ego_dot ,   
			
		
	
		
		
			
				
					
					                       v_ego_dot ,  rotation_radius_dot )   
			
		
	
		
		
	
		
		
	
		
		
			
				
					
					
 
			
		
	
		
		
			
				
					
					  # dynamics model    # dynamics model   
			
		
	
		
		
			
				
					
					  f_expl  =  vertcat ( v_ego  *  cos ( psi_ego )  -  rotation_radius  *  sin ( psi_ego )  *  ( v_ego  *  curv_ego ) ,    f_expl  =  vertcat ( v_ego  *  cos ( psi_ego )  -  rotation_radius  *  sin ( psi_ego )  *  ( v_ego  *  curv_ego ) ,   
			
		
	
		
		
			
				
					
					                   v_ego  *  sin ( psi_ego )  +  rotation_radius  *  cos ( psi_ego )  *  ( v_ego  *  curv_ego ) ,                     v_ego  *  sin ( psi_ego )  +  rotation_radius  *  cos ( psi_ego )  *  ( v_ego  *  curv_ego ) ,   
			
		
	
		
		
			
				
					
					                   v_ego  *  curv_ego ,                     v_ego  *  curv_ego ,   
			
		
	
		
		
			
				
					
					                   curv_rate ,                     curv_rate )   
			
				
				
			
		
	
		
		
			
				
					
					                   0.0 ,   
			
		
	
		
		
			
				
					
					                   0.0 )   
			
		
	
		
		
	
		
		
			
				
					
					  model . f_impl_expr  =  model . xdot  -  f_expl    model . f_impl_expr  =  model . xdot  -  f_expl   
			
		
	
		
		
			
				
					
					  model . f_expl_expr  =  f_expl    model . f_expl_expr  =  f_expl   
			
		
	
		
		
			
				
					
					  return  model    return  model   
			
		
	
	
		
		
			
				
					
						
							
								 
						
						
							
								 
						
						
					 
					@ -79,8 +79,9 @@ def gen_lat_mpc_solver(): 
			
		
	
		
		
			
				
					
					
 
			
		
	
		
		
			
				
					
					  y_ego ,  psi_ego  =  ocp . model . x [ 1 ] ,  ocp . model . x [ 2 ]    y_ego ,  psi_ego  =  ocp . model . x [ 1 ] ,  ocp . model . x [ 2 ]   
			
		
	
		
		
			
				
					
					  curv_rate  =  ocp . model . u [ 0 ]    curv_rate  =  ocp . model . u [ 0 ]   
			
		
	
		
		
			
				
					
					  v_ego  =  ocp . model . x [ 4 ]    v_ego  =  ocp . model . p [ 0 ]   
			
				
				
			
		
	
		
		
	
		
		
			
				
					
					
 
			
		
	
		
		
			
				
					
					  ocp . parameter_values  =  np . zeros ( ( P_DIM ,  ) )   
			
		
	
		
		
			
				
					
					
 
			
		
	
		
		
			
				
					
					  ocp . cost . yref  =  np . zeros ( ( 3 ,  ) )    ocp . cost . yref  =  np . zeros ( ( 3 ,  ) )   
			
		
	
		
		
			
				
					
					  ocp . cost . yref_e  =  np . zeros ( ( 2 ,  ) )    ocp . cost . yref_e  =  np . zeros ( ( 2 ,  ) )   
			
		
	
	
		
		
			
				
					
						
						
						
							
								 
						
					 
					@ -96,7 +97,7 @@ def gen_lat_mpc_solver(): 
			
		
	
		
		
			
				
					
					  ocp . constraints . idxbx  =  np . array ( [ 2 , 3 ] )    ocp . constraints . idxbx  =  np . array ( [ 2 , 3 ] )   
			
		
	
		
		
			
				
					
					  ocp . constraints . ubx  =  np . array ( [ np . radians ( 90 ) ,  np . radians ( 50 ) ] )    ocp . constraints . ubx  =  np . array ( [ np . radians ( 90 ) ,  np . radians ( 50 ) ] )   
			
		
	
		
		
			
				
					
					  ocp . constraints . lbx  =  np . array ( [ - np . radians ( 90 ) ,  - np . radians ( 50 ) ] )    ocp . constraints . lbx  =  np . array ( [ - np . radians ( 90 ) ,  - np . radians ( 50 ) ] )   
			
		
	
		
		
			
				
					
					  x0  =  np . array ( [ 0.0 ,  0.0 ,  0.0 ,  0.0 ,  0.0 ,  0.0 ] )    x0  =  np . zeros ( ( X_DIM , ) )   
			
				
				
			
		
	
		
		
	
		
		
			
				
					
					  ocp . constraints . x0  =  x0    ocp . constraints . x0  =  x0   
			
		
	
		
		
			
				
					
					
 
			
		
	
		
		
			
				
					
					  ocp . solver_options . qp_solver  =  ' PARTIAL_CONDENSING_HPIPM '    ocp . solver_options . qp_solver  =  ' PARTIAL_CONDENSING_HPIPM '   
			
		
	
	
		
		
			
				
					
						
						
						
							
								 
						
					 
					@ -104,7 +105,7 @@ def gen_lat_mpc_solver(): 
			
		
	
		
		
			
				
					
					  ocp . solver_options . integrator_type  =  ' ERK '    ocp . solver_options . integrator_type  =  ' ERK '   
			
		
	
		
		
			
				
					
					  ocp . solver_options . nlp_solver_type  =  ' SQP_RTI '    ocp . solver_options . nlp_solver_type  =  ' SQP_RTI '   
			
		
	
		
		
			
				
					
					  ocp . solver_options . qp_solver_iter_max  =  1    ocp . solver_options . qp_solver_iter_max  =  1   
			
		
	
		
		
			
				
					
					  ocp . solver_options . qp_solver_cond_N  =  N / / 4    ocp . solver_options . qp_solver_cond_N  =  1   
			
				
				
			
		
	
		
		
	
		
		
			
				
					
					
 
			
		
	
		
		
			
				
					
					  # set prediction horizon    # set prediction horizon   
			
		
	
		
		
			
				
					
					  ocp . solver_options . tf  =  Tf    ocp . solver_options . tf  =  Tf   
			
		
	
	
		
		
			
				
					
						
						
						
							
								 
						
					 
					@ -130,6 +131,7 @@ class LateralMpc(): 
			
		
	
		
		
			
				
					
					    # Somehow needed for stable init      # Somehow needed for stable init   
			
		
	
		
		
			
				
					
					    for  i  in  range ( N + 1 ) :      for  i  in  range ( N + 1 ) :   
			
		
	
		
		
			
				
					
					      self . solver . set ( i ,  ' x ' ,  np . zeros ( X_DIM ) )        self . solver . set ( i ,  ' x ' ,  np . zeros ( X_DIM ) )   
			
		
	
		
		
			
				
					
					      self . solver . set ( i ,  ' p ' ,  np . zeros ( P_DIM ) )   
			
		
	
		
		
			
				
					
					    self . solver . constraints_set ( 0 ,  " lbx " ,  x0 )      self . solver . constraints_set ( 0 ,  " lbx " ,  x0 )   
			
		
	
		
		
			
				
					
					    self . solver . constraints_set ( 0 ,  " ubx " ,  x0 )      self . solver . constraints_set ( 0 ,  " ubx " ,  x0 )   
			
		
	
		
		
			
				
					
					    self . solver . solve ( )      self . solver . solve ( )   
			
		
	
	
		
		
			
				
					
						
						
						
							
								 
						
					 
					@ -144,14 +146,19 @@ class LateralMpc(): 
			
		
	
		
		
			
				
					
					    #TODO hacky weights to keep behavior the same      #TODO hacky weights to keep behavior the same   
			
		
	
		
		
			
				
					
					    self . solver . cost_set ( N ,  ' W ' ,  ( 3 / 20. ) * W [ : 2 , : 2 ] )      self . solver . cost_set ( N ,  ' W ' ,  ( 3 / 20. ) * W [ : 2 , : 2 ] )   
			
		
	
		
		
			
				
					
					
 
			
		
	
		
		
			
				
					
					  def  run ( self ,  x0 ,  v_ego ,  car_rotation_radius ,  y_pts ,  heading_pts ) :    def  run ( self ,  x0 ,  p ,  y_pts ,  heading_pts ) :   
			
				
				
			
		
	
		
		
	
		
		
			
				
					
					    x0_cp  =  np . copy ( x0 )      x0_cp  =  np . copy ( x0 )   
			
		
	
		
		
			
				
					
					    p_cp  =  np . copy ( p )   
			
		
	
		
		
			
				
					
					    self . solver . constraints_set ( 0 ,  " lbx " ,  x0_cp )      self . solver . constraints_set ( 0 ,  " lbx " ,  x0_cp )   
			
		
	
		
		
			
				
					
					    self . solver . constraints_set ( 0 ,  " ubx " ,  x0_cp )      self . solver . constraints_set ( 0 ,  " ubx " ,  x0_cp )   
			
		
	
		
		
			
				
					
					    self . yref [ : , 0 ]  =  y_pts      self . yref [ : , 0 ]  =  y_pts   
			
		
	
		
		
			
				
					
					    v_ego  =  p_cp [ 0 ]   
			
		
	
		
		
			
				
					
					    # rotation_radius = p_cp[1]   
			
		
	
		
		
			
				
					
					    self . yref [ : , 1 ]  =  heading_pts * ( v_ego + 5.0 )      self . yref [ : , 1 ]  =  heading_pts * ( v_ego + 5.0 )   
			
		
	
		
		
			
				
					
					    for  i  in  range ( N ) :      for  i  in  range ( N ) :   
			
		
	
		
		
			
				
					
					      self . solver . cost_set ( i ,  " yref " ,  self . yref [ i ] )        self . solver . cost_set ( i ,  " yref " ,  self . yref [ i ] )   
			
		
	
		
		
			
				
					
					      self . solver . set ( i ,  " p " ,  p_cp )   
			
		
	
		
		
			
				
					
					    self . solver . set ( N ,  " p " ,  p_cp )   
			
		
	
		
		
			
				
					
					    self . solver . cost_set ( N ,  " yref " ,  self . yref [ N ] [ : 2 ] )      self . solver . cost_set ( N ,  " yref " ,  self . yref [ N ] [ : 2 ] )   
			
		
	
		
		
			
				
					
					
 
			
		
	
		
		
			
				
					
					    t  =  sec_since_boot ( )      t  =  sec_since_boot ( )