Refactor long (#21433)
* refactor * needs casting * tests pass * fix that test * refactor in controls * lets not go crazy * change of names * use constants * better naming * renamed * soft constraints * compile slack variables * rm git conflict * add slack variables * unused * new edition * fcw * fix tests * dividing causes problems * was way too slow * take a step back * byeeee * for another time * bad idxs * little more cpu for cruise mpc * update refs * these limits seem fine * rename * test model timings fails sometimes * add default * save some cpu * Revert "little more cpu for cruise mpc" This reverts commit f0a8163ec90e8dc1eabb3c4a4268ad330d23374d. * Revert "test model timings fails sometimes" This reverts commit d259d845710ed2cbeb28b383e2600476527d4838. * update refs * less cpu * Revert "Revert "test model timings fails sometimes"" This reverts commit e0263050d9929bfc7ee70c9788234541a4a8461c. * Revert "less cpu" This reverts commit 679007472bc2013e7fafb7b17de7a43d6f82359a. * cleanup * not too much until we clean up mpc * more cost on jerk * change ref * add todo * new ref * indentationpull/21458/head^2
parent
cfe97fcc49
commit
be5ddd25cd
54 changed files with 2992 additions and 6188 deletions
@ -1 +1 @@ |
|||||||
Subproject commit 1f5c4aa350c3783f249724e7a4ea0049e4c46a7a |
Subproject commit 1979127659dc7c47c6ad7b8234ff1f6ca93526fc |
@ -0,0 +1,106 @@ |
|||||||
|
import math |
||||||
|
import numpy as np |
||||||
|
from common.numpy_fast import interp |
||||||
|
from common.realtime import sec_since_boot |
||||||
|
from selfdrive.modeld.constants import T_IDXS |
||||||
|
from selfdrive.controls.lib.radar_helpers import _LEAD_ACCEL_TAU |
||||||
|
from selfdrive.controls.lib.lead_mpc_lib import libmpc_py |
||||||
|
from selfdrive.controls.lib.drive_helpers import MPC_COST_LONG, CONTROL_N |
||||||
|
from selfdrive.swaglog import cloudlog |
||||||
|
|
||||||
|
MPC_T = list(np.arange(0,1.,.2)) + list(np.arange(1.,10.6,.6)) |
||||||
|
|
||||||
|
|
||||||
|
class LeadMpc(): |
||||||
|
def __init__(self, mpc_id): |
||||||
|
self.lead_id = mpc_id |
||||||
|
|
||||||
|
self.reset_mpc() |
||||||
|
self.prev_lead_status = False |
||||||
|
self.prev_lead_x = 0.0 |
||||||
|
self.new_lead = False |
||||||
|
|
||||||
|
self.last_cloudlog_t = 0.0 |
||||||
|
self.n_its = 0 |
||||||
|
self.duration = 0 |
||||||
|
self.status = False |
||||||
|
|
||||||
|
def reset_mpc(self): |
||||||
|
ffi, self.libmpc = libmpc_py.get_libmpc(self.lead_id) |
||||||
|
self.libmpc.init(MPC_COST_LONG.TTC, MPC_COST_LONG.DISTANCE, |
||||||
|
MPC_COST_LONG.ACCELERATION, MPC_COST_LONG.JERK) |
||||||
|
|
||||||
|
self.mpc_solution = ffi.new("log_t *") |
||||||
|
self.cur_state = ffi.new("state_t *") |
||||||
|
self.cur_state[0].v_ego = 0 |
||||||
|
self.cur_state[0].a_ego = 0 |
||||||
|
self.a_lead_tau = _LEAD_ACCEL_TAU |
||||||
|
|
||||||
|
def set_cur_state(self, v, a): |
||||||
|
v_safe = max(v, 1e-3) |
||||||
|
a_safe = a |
||||||
|
self.cur_state[0].v_ego = v_safe |
||||||
|
self.cur_state[0].a_ego = a_safe |
||||||
|
|
||||||
|
def update(self, CS, radarstate, v_cruise): |
||||||
|
v_ego = CS.vEgo |
||||||
|
if self.lead_id == 0: |
||||||
|
lead = radarstate.leadOne |
||||||
|
else: |
||||||
|
lead = radarstate.leadOne |
||||||
|
self.status = lead.status and lead.modelProb > .5 |
||||||
|
|
||||||
|
# Setup current mpc state |
||||||
|
self.cur_state[0].x_ego = 0.0 |
||||||
|
|
||||||
|
if lead is not None and lead.status: |
||||||
|
x_lead = lead.dRel |
||||||
|
v_lead = max(0.0, lead.vLead) |
||||||
|
a_lead = lead.aLeadK |
||||||
|
|
||||||
|
if (v_lead < 0.1 or -a_lead / 2.0 > v_lead): |
||||||
|
v_lead = 0.0 |
||||||
|
a_lead = 0.0 |
||||||
|
|
||||||
|
self.a_lead_tau = lead.aLeadTau |
||||||
|
self.new_lead = False |
||||||
|
if not self.prev_lead_status or abs(x_lead - self.prev_lead_x) > 2.5: |
||||||
|
self.libmpc.init_with_simulation(v_ego, x_lead, v_lead, a_lead, self.a_lead_tau) |
||||||
|
self.new_lead = True |
||||||
|
|
||||||
|
self.prev_lead_status = True |
||||||
|
self.prev_lead_x = x_lead |
||||||
|
self.cur_state[0].x_l = x_lead |
||||||
|
self.cur_state[0].v_l = v_lead |
||||||
|
else: |
||||||
|
self.prev_lead_status = False |
||||||
|
# Fake a fast lead car, so mpc keeps running |
||||||
|
self.cur_state[0].x_l = 50.0 |
||||||
|
self.cur_state[0].v_l = v_ego + 10.0 |
||||||
|
a_lead = 0.0 |
||||||
|
self.a_lead_tau = _LEAD_ACCEL_TAU |
||||||
|
|
||||||
|
# Calculate mpc |
||||||
|
t = sec_since_boot() |
||||||
|
self.n_its = self.libmpc.run_mpc(self.cur_state, self.mpc_solution, self.a_lead_tau, a_lead) |
||||||
|
self.v_solution = interp(T_IDXS[:CONTROL_N], MPC_T, self.mpc_solution.v_ego) |
||||||
|
self.a_solution = interp(T_IDXS[:CONTROL_N], MPC_T, self.mpc_solution.a_ego) |
||||||
|
self.duration = int((sec_since_boot() - t) * 1e9) |
||||||
|
|
||||||
|
# Reset if NaN or goes through lead car |
||||||
|
crashing = any(lead - ego < -50 for (lead, ego) in zip(self.mpc_solution[0].x_l, self.mpc_solution[0].x_ego)) |
||||||
|
nans = any(math.isnan(x) for x in self.mpc_solution[0].v_ego) |
||||||
|
backwards = min(self.mpc_solution[0].v_ego) < -0.01 |
||||||
|
|
||||||
|
if ((backwards or crashing) and self.prev_lead_status) or nans: |
||||||
|
if t > self.last_cloudlog_t + 5.0: |
||||||
|
self.last_cloudlog_t = t |
||||||
|
cloudlog.warning("Longitudinal mpc %d reset - backwards: %s crashing: %s nan: %s" % ( |
||||||
|
self.lead_id, backwards, crashing, nans)) |
||||||
|
|
||||||
|
self.libmpc.init(MPC_COST_LONG.TTC, MPC_COST_LONG.DISTANCE, |
||||||
|
MPC_COST_LONG.ACCELERATION, MPC_COST_LONG.JERK) |
||||||
|
self.cur_state[0].v_ego = v_ego |
||||||
|
self.cur_state[0].a_ego = 0.0 |
||||||
|
self.a_mpc = CS.aEgo |
||||||
|
self.prev_lead_status = False |
@ -1,122 +1,66 @@ |
|||||||
import os |
import numpy as np |
||||||
import math |
import math |
||||||
|
|
||||||
import cereal.messaging as messaging |
|
||||||
from selfdrive.swaglog import cloudlog |
from selfdrive.swaglog import cloudlog |
||||||
from common.realtime import sec_since_boot |
from common.realtime import sec_since_boot |
||||||
from selfdrive.controls.lib.radar_helpers import _LEAD_ACCEL_TAU |
from selfdrive.controls.lib.longitudinal_mpc_lib import libmpc_py |
||||||
from selfdrive.controls.lib.longitudinal_mpc import libmpc_py |
from selfdrive.controls.lib.drive_helpers import LON_MPC_N |
||||||
from selfdrive.controls.lib.drive_helpers import MPC_COST_LONG |
from selfdrive.modeld.constants import T_IDXS |
||||||
|
|
||||||
LOG_MPC = os.environ.get('LOG_MPC', False) |
|
||||||
|
|
||||||
|
|
||||||
class LongitudinalMpc(): |
class LongitudinalMpc(): |
||||||
def __init__(self, mpc_id): |
def __init__(self): |
||||||
self.mpc_id = mpc_id |
self.reset_mpc() |
||||||
|
|
||||||
self.setup_mpc() |
|
||||||
self.v_mpc = 0.0 |
|
||||||
self.v_mpc_future = 0.0 |
|
||||||
self.a_mpc = 0.0 |
|
||||||
self.v_cruise = 0.0 |
|
||||||
self.prev_lead_status = False |
|
||||||
self.prev_lead_x = 0.0 |
|
||||||
self.new_lead = False |
|
||||||
|
|
||||||
self.last_cloudlog_t = 0.0 |
self.last_cloudlog_t = 0.0 |
||||||
self.n_its = 0 |
self.ts = list(range(10)) |
||||||
self.duration = 0 |
self.status = True |
||||||
|
self.min_a = -1.2 |
||||||
|
self.max_a = 1.2 |
||||||
|
|
||||||
|
|
||||||
def publish(self, pm): |
def reset_mpc(self): |
||||||
if LOG_MPC: |
self.libmpc = libmpc_py.libmpc |
||||||
qp_iterations = max(0, self.n_its) |
self.libmpc.init(0.0, 1.0, 0.0, 50.0, 10000.0) |
||||||
dat = messaging.new_message('liveLongitudinalMpc') |
|
||||||
dat.liveLongitudinalMpc.xEgo = list(self.mpc_solution[0].x_ego) |
|
||||||
dat.liveLongitudinalMpc.vEgo = list(self.mpc_solution[0].v_ego) |
|
||||||
dat.liveLongitudinalMpc.aEgo = list(self.mpc_solution[0].a_ego) |
|
||||||
dat.liveLongitudinalMpc.xLead = list(self.mpc_solution[0].x_l) |
|
||||||
dat.liveLongitudinalMpc.vLead = list(self.mpc_solution[0].v_l) |
|
||||||
dat.liveLongitudinalMpc.cost = self.mpc_solution[0].cost |
|
||||||
dat.liveLongitudinalMpc.aLeadTau = self.a_lead_tau |
|
||||||
dat.liveLongitudinalMpc.qpIterations = qp_iterations |
|
||||||
dat.liveLongitudinalMpc.mpcId = self.mpc_id |
|
||||||
dat.liveLongitudinalMpc.calculationTime = self.duration |
|
||||||
pm.send('liveLongitudinalMpc', dat) |
|
||||||
|
|
||||||
def setup_mpc(self): |
self.mpc_solution = libmpc_py.ffi.new("log_t *") |
||||||
ffi, self.libmpc = libmpc_py.get_libmpc(self.mpc_id) |
self.cur_state = libmpc_py.ffi.new("state_t *") |
||||||
self.libmpc.init(MPC_COST_LONG.TTC, MPC_COST_LONG.DISTANCE, |
|
||||||
MPC_COST_LONG.ACCELERATION, MPC_COST_LONG.JERK) |
|
||||||
|
|
||||||
self.mpc_solution = ffi.new("log_t *") |
self.cur_state[0].x_ego = 0 |
||||||
self.cur_state = ffi.new("state_t *") |
|
||||||
self.cur_state[0].v_ego = 0 |
self.cur_state[0].v_ego = 0 |
||||||
self.cur_state[0].a_ego = 0 |
self.cur_state[0].a_ego = 0 |
||||||
self.a_lead_tau = _LEAD_ACCEL_TAU |
|
||||||
|
|
||||||
def set_cur_state(self, v, a): |
def set_accel_limits(self, min_a, max_a): |
||||||
self.cur_state[0].v_ego = v |
self.min_a = min_a |
||||||
self.cur_state[0].a_ego = a |
self.max_a = max_a |
||||||
|
|
||||||
def update(self, CS, lead): |
|
||||||
v_ego = CS.vEgo |
|
||||||
|
|
||||||
# Setup current mpc state |
def set_cur_state(self, v, a): |
||||||
|
v_safe = max(v, 1e-2) |
||||||
|
a_safe = min(a, self.max_a - 1e-2) |
||||||
|
a_safe = max(a_safe, self.min_a + 1e-2) |
||||||
self.cur_state[0].x_ego = 0.0 |
self.cur_state[0].x_ego = 0.0 |
||||||
|
self.cur_state[0].v_ego = v_safe |
||||||
|
self.cur_state[0].a_ego = a_safe |
||||||
|
|
||||||
if lead is not None and lead.status: |
def update(self, carstate, model, v_cruise): |
||||||
x_lead = lead.dRel |
v_cruise_clipped = np.clip(v_cruise, self.cur_state[0].v_ego - 10., self.cur_state[0].v_ego + 10.0) |
||||||
v_lead = max(0.0, lead.vLead) |
poss = v_cruise_clipped * np.array(T_IDXS[:LON_MPC_N+1]) |
||||||
a_lead = lead.aLeadK |
speeds = v_cruise_clipped * np.ones(LON_MPC_N+1) |
||||||
|
accels = np.zeros(LON_MPC_N+1) |
||||||
if (v_lead < 0.1 or -a_lead / 2.0 > v_lead): |
|
||||||
v_lead = 0.0 |
|
||||||
a_lead = 0.0 |
|
||||||
|
|
||||||
self.a_lead_tau = lead.aLeadTau |
|
||||||
self.new_lead = False |
|
||||||
if not self.prev_lead_status or abs(x_lead - self.prev_lead_x) > 2.5: |
|
||||||
self.libmpc.init_with_simulation(self.v_mpc, x_lead, v_lead, a_lead, self.a_lead_tau) |
|
||||||
self.new_lead = True |
|
||||||
|
|
||||||
self.prev_lead_status = True |
|
||||||
self.prev_lead_x = x_lead |
|
||||||
self.cur_state[0].x_l = x_lead |
|
||||||
self.cur_state[0].v_l = v_lead |
|
||||||
else: |
|
||||||
self.prev_lead_status = False |
|
||||||
# Fake a fast lead car, so mpc keeps running |
|
||||||
self.cur_state[0].x_l = 50.0 |
|
||||||
self.cur_state[0].v_l = v_ego + 10.0 |
|
||||||
a_lead = 0.0 |
|
||||||
self.a_lead_tau = _LEAD_ACCEL_TAU |
|
||||||
|
|
||||||
# Calculate mpc |
# Calculate mpc |
||||||
t = sec_since_boot() |
self.libmpc.run_mpc(self.cur_state, self.mpc_solution, |
||||||
self.n_its = self.libmpc.run_mpc(self.cur_state, self.mpc_solution, self.a_lead_tau, a_lead) |
list(poss), list(speeds), list(accels), |
||||||
self.duration = int((sec_since_boot() - t) * 1e9) |
self.min_a, self.max_a) |
||||||
|
|
||||||
# Get solution. MPC timestep is 0.2 s, so interpolation to 0.05 s is needed |
self.v_solution = list(self.mpc_solution.v_ego) |
||||||
self.v_mpc = self.mpc_solution[0].v_ego[1] |
self.a_solution = list(self.mpc_solution.a_ego) |
||||||
self.a_mpc = self.mpc_solution[0].a_ego[1] |
|
||||||
self.v_mpc_future = self.mpc_solution[0].v_ego[10] |
|
||||||
|
|
||||||
# Reset if NaN or goes through lead car |
# Reset if NaN or goes through lead car |
||||||
crashing = any(lead - ego < -50 for (lead, ego) in zip(self.mpc_solution[0].x_l, self.mpc_solution[0].x_ego)) |
|
||||||
nans = any(math.isnan(x) for x in self.mpc_solution[0].v_ego) |
nans = any(math.isnan(x) for x in self.mpc_solution[0].v_ego) |
||||||
backwards = min(self.mpc_solution[0].v_ego) < -0.01 |
|
||||||
|
|
||||||
if ((backwards or crashing) and self.prev_lead_status) or nans: |
t = sec_since_boot() |
||||||
|
if nans: |
||||||
if t > self.last_cloudlog_t + 5.0: |
if t > self.last_cloudlog_t + 5.0: |
||||||
self.last_cloudlog_t = t |
self.last_cloudlog_t = t |
||||||
cloudlog.warning("Longitudinal mpc %d reset - backwards: %s crashing: %s nan: %s" % ( |
cloudlog.warning("Longitudinal model mpc reset - nans") |
||||||
self.mpc_id, backwards, crashing, nans)) |
self.reset_mpc() |
||||||
|
|
||||||
self.libmpc.init(MPC_COST_LONG.TTC, MPC_COST_LONG.DISTANCE, |
|
||||||
MPC_COST_LONG.ACCELERATION, MPC_COST_LONG.JERK) |
|
||||||
self.cur_state[0].v_ego = v_ego |
|
||||||
self.cur_state[0].a_ego = 0.0 |
|
||||||
self.v_mpc = v_ego |
|
||||||
self.a_mpc = CS.aEgo |
|
||||||
self.prev_lead_status = False |
|
||||||
|
@ -1,73 +0,0 @@ |
|||||||
import numpy as np |
|
||||||
import math |
|
||||||
|
|
||||||
from selfdrive.swaglog import cloudlog |
|
||||||
from common.realtime import sec_since_boot |
|
||||||
from selfdrive.controls.lib.longitudinal_mpc_model import libmpc_py |
|
||||||
|
|
||||||
|
|
||||||
class LongitudinalMpcModel(): |
|
||||||
def __init__(self): |
|
||||||
|
|
||||||
self.setup_mpc() |
|
||||||
self.v_mpc = 0.0 |
|
||||||
self.v_mpc_future = 0.0 |
|
||||||
self.a_mpc = 0.0 |
|
||||||
self.last_cloudlog_t = 0.0 |
|
||||||
self.ts = list(range(10)) |
|
||||||
|
|
||||||
self.valid = False |
|
||||||
|
|
||||||
def setup_mpc(self, v_ego=0.0): |
|
||||||
self.libmpc = libmpc_py.libmpc |
|
||||||
self.libmpc.init(1.0, 1.0, 1.0, 1.0, 1.0) |
|
||||||
self.libmpc.init_with_simulation(v_ego) |
|
||||||
|
|
||||||
self.mpc_solution = libmpc_py.ffi.new("log_t *") |
|
||||||
self.cur_state = libmpc_py.ffi.new("state_t *") |
|
||||||
|
|
||||||
self.cur_state[0].x_ego = 0 |
|
||||||
self.cur_state[0].v_ego = 0 |
|
||||||
self.cur_state[0].a_ego = 0 |
|
||||||
|
|
||||||
def set_cur_state(self, v, a): |
|
||||||
self.cur_state[0].x_ego = 0.0 |
|
||||||
self.cur_state[0].v_ego = v |
|
||||||
self.cur_state[0].a_ego = a |
|
||||||
|
|
||||||
def update(self, v_ego, a_ego, poss, speeds, accels): |
|
||||||
if len(poss) == 0: |
|
||||||
self.valid = False |
|
||||||
return |
|
||||||
|
|
||||||
x_poly = list(map(float, np.polyfit(self.ts, poss, 3))) |
|
||||||
v_poly = list(map(float, np.polyfit(self.ts, speeds, 3))) |
|
||||||
a_poly = list(map(float, np.polyfit(self.ts, accels, 3))) |
|
||||||
|
|
||||||
# Calculate mpc |
|
||||||
self.libmpc.run_mpc(self.cur_state, self.mpc_solution, x_poly, v_poly, a_poly) |
|
||||||
|
|
||||||
# Get solution. MPC timestep is 0.2 s, so interpolation to 0.05 s is needed |
|
||||||
self.v_mpc = self.mpc_solution[0].v_ego[1] |
|
||||||
self.a_mpc = self.mpc_solution[0].a_ego[1] |
|
||||||
self.v_mpc_future = self.mpc_solution[0].v_ego[10] |
|
||||||
self.valid = True |
|
||||||
|
|
||||||
# Reset if NaN or goes through lead car |
|
||||||
nans = any(math.isnan(x) for x in self.mpc_solution[0].v_ego) |
|
||||||
|
|
||||||
t = sec_since_boot() |
|
||||||
if nans: |
|
||||||
if t > self.last_cloudlog_t + 5.0: |
|
||||||
self.last_cloudlog_t = t |
|
||||||
cloudlog.warning("Longitudinal model mpc reset - backwards") |
|
||||||
|
|
||||||
self.libmpc.init(1.0, 1.0, 1.0, 1.0, 1.0) |
|
||||||
self.libmpc.init_with_simulation(v_ego) |
|
||||||
|
|
||||||
self.cur_state[0].v_ego = v_ego |
|
||||||
self.cur_state[0].a_ego = 0.0 |
|
||||||
|
|
||||||
self.v_mpc = v_ego |
|
||||||
self.a_mpc = a_ego |
|
||||||
self.valid = False |
|
@ -0,0 +1,47 @@ |
|||||||
|
Import('env', 'arch') |
||||||
|
|
||||||
|
cpp_path = [ |
||||||
|
"#", |
||||||
|
"#selfdrive", |
||||||
|
"#phonelibs/acado/include", |
||||||
|
"#phonelibs/acado/include/acado", |
||||||
|
"#phonelibs/qpoases/INCLUDE", |
||||||
|
"#phonelibs/qpoases/INCLUDE/EXTRAS", |
||||||
|
"#phonelibs/qpoases/SRC/", |
||||||
|
"#phonelibs/qpoases", |
||||||
|
"lib_mpc_export", |
||||||
|
] |
||||||
|
|
||||||
|
generated_c = [ |
||||||
|
'lib_mpc_export/acado_auxiliary_functions.c', |
||||||
|
'lib_mpc_export/acado_qpoases_interface.cpp', |
||||||
|
'lib_mpc_export/acado_integrator.c', |
||||||
|
'lib_mpc_export/acado_solver.c', |
||||||
|
] |
||||||
|
|
||||||
|
generated_h = [ |
||||||
|
'lib_mpc_export/acado_common.h', |
||||||
|
'lib_mpc_export/acado_auxiliary_functions.h', |
||||||
|
'lib_mpc_export/acado_qpoases_interface.hpp', |
||||||
|
] |
||||||
|
|
||||||
|
interface_dir = Dir('lib_mpc_export') |
||||||
|
|
||||||
|
SConscript(['#phonelibs/qpoases/SConscript'], variant_dir='lib_qp', exports=['interface_dir']) |
||||||
|
|
||||||
|
if GetOption('mpc_generate'): |
||||||
|
generator_cpp = File('generator.cpp') |
||||||
|
|
||||||
|
acado_libs = [File(f"#phonelibs/acado/{arch}/lib/libacado_toolkit.a"), |
||||||
|
File(f"#phonelibs/acado/{arch}/lib/libacado_casadi.a"), |
||||||
|
File(f"#phonelibs/acado/{arch}/lib/libacado_csparse.a")] |
||||||
|
|
||||||
|
generator = env.Program('generator', generator_cpp, LIBS=acado_libs, CPPPATH=cpp_path, |
||||||
|
CCFLAGS=env['CCFLAGS'] + ["-Wno-deprecated", "-Wno-overloaded-shift-op-parentheses"]) |
||||||
|
|
||||||
|
cmd = f"cd {Dir('.').get_abspath()} && {generator[0].get_abspath()}" |
||||||
|
env.Command(generated_c + generated_h, generator, cmd) |
||||||
|
|
||||||
|
|
||||||
|
mpc_files = ["longitudinal_mpc.c"] + generated_c |
||||||
|
env.SharedLibrary('mpc', mpc_files, LIBS=['m', 'qpoases'], LIBPATH=['lib_qp'], CPPPATH=cpp_path) |
@ -0,0 +1,82 @@ |
|||||||
|
#include <acado_code_generation.hpp> |
||||||
|
#include "selfdrive/common/modeldata.h" |
||||||
|
|
||||||
|
using namespace std; |
||||||
|
|
||||||
|
|
||||||
|
int main( ) |
||||||
|
{ |
||||||
|
USING_NAMESPACE_ACADO |
||||||
|
|
||||||
|
|
||||||
|
DifferentialEquation f; |
||||||
|
|
||||||
|
DifferentialState x_ego, v_ego, a_ego; |
||||||
|
DifferentialState dummy_0; |
||||||
|
OnlineData min_a, max_a; |
||||||
|
|
||||||
|
Control j_ego, accel_slack; |
||||||
|
|
||||||
|
// Equations of motion
|
||||||
|
f << dot(x_ego) == v_ego; |
||||||
|
f << dot(v_ego) == a_ego; |
||||||
|
f << dot(a_ego) == j_ego; |
||||||
|
f << dot(dummy_0) == accel_slack; |
||||||
|
|
||||||
|
// Running cost
|
||||||
|
Function h; |
||||||
|
h << x_ego; |
||||||
|
h << v_ego; |
||||||
|
h << a_ego; |
||||||
|
h << j_ego; |
||||||
|
h << accel_slack; |
||||||
|
|
||||||
|
// Weights are defined in mpc.
|
||||||
|
BMatrix Q(5,5); Q.setAll(true); |
||||||
|
|
||||||
|
// Terminal cost
|
||||||
|
Function hN; |
||||||
|
hN << x_ego; |
||||||
|
hN << v_ego; |
||||||
|
hN << a_ego; |
||||||
|
|
||||||
|
// Weights are defined in mpc.
|
||||||
|
BMatrix QN(3,3); QN.setAll(true); |
||||||
|
|
||||||
|
double T_IDXS_ARR[LON_MPC_N + 1]; |
||||||
|
memcpy(T_IDXS_ARR, T_IDXS, (LON_MPC_N + 1) * sizeof(double)); |
||||||
|
Grid times(LON_MPC_N + 1, T_IDXS_ARR); |
||||||
|
OCP ocp(times); |
||||||
|
ocp.subjectTo(f); |
||||||
|
|
||||||
|
ocp.minimizeLSQ(Q, h); |
||||||
|
ocp.minimizeLSQEndTerm(QN, hN); |
||||||
|
|
||||||
|
ocp.subjectTo( 0.0 <= v_ego); |
||||||
|
ocp.subjectTo( 0.0 <= a_ego - min_a + accel_slack); |
||||||
|
ocp.subjectTo( a_ego - max_a + accel_slack <= 0.0); |
||||||
|
ocp.setNOD(2); |
||||||
|
|
||||||
|
OCPexport mpc(ocp); |
||||||
|
mpc.set( HESSIAN_APPROXIMATION, GAUSS_NEWTON ); |
||||||
|
mpc.set( DISCRETIZATION_TYPE, MULTIPLE_SHOOTING ); |
||||||
|
mpc.set( INTEGRATOR_TYPE, INT_RK4 ); |
||||||
|
mpc.set( NUM_INTEGRATOR_STEPS, 1000); |
||||||
|
mpc.set( MAX_NUM_QP_ITERATIONS, 50); |
||||||
|
mpc.set( CG_USE_VARIABLE_WEIGHTING_MATRIX, YES); |
||||||
|
|
||||||
|
mpc.set( SPARSE_QP_SOLUTION, CONDENSING ); |
||||||
|
mpc.set( QP_SOLVER, QP_QPOASES ); |
||||||
|
mpc.set( HOTSTART_QP, YES ); |
||||||
|
mpc.set( GENERATE_TEST_FILE, NO); |
||||||
|
mpc.set( GENERATE_MAKE_FILE, NO ); |
||||||
|
mpc.set( GENERATE_MATLAB_INTERFACE, NO ); |
||||||
|
mpc.set( GENERATE_SIMULINK_INTERFACE, NO ); |
||||||
|
|
||||||
|
if (mpc.exportCode( "lib_mpc_export" ) != SUCCESSFUL_RETURN) |
||||||
|
exit( EXIT_FAILURE ); |
||||||
|
|
||||||
|
mpc.printDimensionsQP( ); |
||||||
|
|
||||||
|
return EXIT_SUCCESS; |
||||||
|
} |
@ -0,0 +1,250 @@ |
|||||||
|
/*
|
||||||
|
* This file was auto-generated using the ACADO Toolkit. |
||||||
|
*
|
||||||
|
* While ACADO Toolkit is free software released under the terms of |
||||||
|
* the GNU Lesser General Public License (LGPL), the generated code |
||||||
|
* as such remains the property of the user who used ACADO Toolkit |
||||||
|
* to generate this code. In particular, user dependent data of the code |
||||||
|
* do not inherit the GNU LGPL license. On the other hand, parts of the |
||||||
|
* generated code that are a direct copy of source code from the |
||||||
|
* ACADO Toolkit or the software tools it is based on, remain, as derived |
||||||
|
* work, automatically covered by the LGPL license. |
||||||
|
*
|
||||||
|
* ACADO Toolkit is distributed in the hope that it will be useful, |
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of |
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. |
||||||
|
*
|
||||||
|
*/ |
||||||
|
|
||||||
|
|
||||||
|
#include "acado_common.h" |
||||||
|
|
||||||
|
|
||||||
|
void acado_rhs_forw(const real_t* in, real_t* out) |
||||||
|
{ |
||||||
|
const real_t* xd = in; |
||||||
|
const real_t* u = in + 28; |
||||||
|
|
||||||
|
/* Compute outputs: */ |
||||||
|
out[0] = xd[1]; |
||||||
|
out[1] = xd[2]; |
||||||
|
out[2] = u[0]; |
||||||
|
out[3] = u[1]; |
||||||
|
out[4] = xd[8]; |
||||||
|
out[5] = xd[9]; |
||||||
|
out[6] = xd[10]; |
||||||
|
out[7] = xd[11]; |
||||||
|
out[8] = xd[12]; |
||||||
|
out[9] = xd[13]; |
||||||
|
out[10] = xd[14]; |
||||||
|
out[11] = xd[15]; |
||||||
|
out[12] = (real_t)(0.0000000000000000e+00); |
||||||
|
out[13] = (real_t)(0.0000000000000000e+00); |
||||||
|
out[14] = (real_t)(0.0000000000000000e+00); |
||||||
|
out[15] = (real_t)(0.0000000000000000e+00); |
||||||
|
out[16] = (real_t)(0.0000000000000000e+00); |
||||||
|
out[17] = (real_t)(0.0000000000000000e+00); |
||||||
|
out[18] = (real_t)(0.0000000000000000e+00); |
||||||
|
out[19] = (real_t)(0.0000000000000000e+00); |
||||||
|
out[20] = xd[22]; |
||||||
|
out[21] = xd[23]; |
||||||
|
out[22] = xd[24]; |
||||||
|
out[23] = xd[25]; |
||||||
|
out[24] = (real_t)(1.0000000000000000e+00); |
||||||
|
out[25] = (real_t)(0.0000000000000000e+00); |
||||||
|
out[26] = (real_t)(0.0000000000000000e+00); |
||||||
|
out[27] = (real_t)(1.0000000000000000e+00); |
||||||
|
} |
||||||
|
|
||||||
|
/* Fixed step size:0.01 */ |
||||||
|
int acado_integrate( real_t* const rk_eta, int resetIntegrator, int rk_index ) |
||||||
|
{ |
||||||
|
int error; |
||||||
|
|
||||||
|
int run1; |
||||||
|
int numSteps[32] = {1, 3, 5, 7, 9, 11, 13, 15, 17, 19, 21, 22, 24, 26, 28, 30, 32, 34, 36, 38, 40, 42, 44, 46, 48, 50, 52, 54, 56, 58, 60, 62}; |
||||||
|
int numInts = numSteps[rk_index]; |
||||||
|
acadoWorkspace.rk_ttt = 0.0000000000000000e+00; |
||||||
|
rk_eta[4] = 1.0000000000000000e+00; |
||||||
|
rk_eta[5] = 0.0000000000000000e+00; |
||||||
|
rk_eta[6] = 0.0000000000000000e+00; |
||||||
|
rk_eta[7] = 0.0000000000000000e+00; |
||||||
|
rk_eta[8] = 0.0000000000000000e+00; |
||||||
|
rk_eta[9] = 1.0000000000000000e+00; |
||||||
|
rk_eta[10] = 0.0000000000000000e+00; |
||||||
|
rk_eta[11] = 0.0000000000000000e+00; |
||||||
|
rk_eta[12] = 0.0000000000000000e+00; |
||||||
|
rk_eta[13] = 0.0000000000000000e+00; |
||||||
|
rk_eta[14] = 1.0000000000000000e+00; |
||||||
|
rk_eta[15] = 0.0000000000000000e+00; |
||||||
|
rk_eta[16] = 0.0000000000000000e+00; |
||||||
|
rk_eta[17] = 0.0000000000000000e+00; |
||||||
|
rk_eta[18] = 0.0000000000000000e+00; |
||||||
|
rk_eta[19] = 1.0000000000000000e+00; |
||||||
|
rk_eta[20] = 0.0000000000000000e+00; |
||||||
|
rk_eta[21] = 0.0000000000000000e+00; |
||||||
|
rk_eta[22] = 0.0000000000000000e+00; |
||||||
|
rk_eta[23] = 0.0000000000000000e+00; |
||||||
|
rk_eta[24] = 0.0000000000000000e+00; |
||||||
|
rk_eta[25] = 0.0000000000000000e+00; |
||||||
|
rk_eta[26] = 0.0000000000000000e+00; |
||||||
|
rk_eta[27] = 0.0000000000000000e+00; |
||||||
|
acadoWorkspace.rk_xxx[28] = rk_eta[28]; |
||||||
|
acadoWorkspace.rk_xxx[29] = rk_eta[29]; |
||||||
|
acadoWorkspace.rk_xxx[30] = rk_eta[30]; |
||||||
|
acadoWorkspace.rk_xxx[31] = rk_eta[31]; |
||||||
|
|
||||||
|
for (run1 = 0; run1 < 1; ++run1) |
||||||
|
{ |
||||||
|
for(run1 = 0; run1 < numInts; run1++ ) { |
||||||
|
acadoWorkspace.rk_xxx[0] = + rk_eta[0]; |
||||||
|
acadoWorkspace.rk_xxx[1] = + rk_eta[1]; |
||||||
|
acadoWorkspace.rk_xxx[2] = + rk_eta[2]; |
||||||
|
acadoWorkspace.rk_xxx[3] = + rk_eta[3]; |
||||||
|
acadoWorkspace.rk_xxx[4] = + rk_eta[4]; |
||||||
|
acadoWorkspace.rk_xxx[5] = + rk_eta[5]; |
||||||
|
acadoWorkspace.rk_xxx[6] = + rk_eta[6]; |
||||||
|
acadoWorkspace.rk_xxx[7] = + rk_eta[7]; |
||||||
|
acadoWorkspace.rk_xxx[8] = + rk_eta[8]; |
||||||
|
acadoWorkspace.rk_xxx[9] = + rk_eta[9]; |
||||||
|
acadoWorkspace.rk_xxx[10] = + rk_eta[10]; |
||||||
|
acadoWorkspace.rk_xxx[11] = + rk_eta[11]; |
||||||
|
acadoWorkspace.rk_xxx[12] = + rk_eta[12]; |
||||||
|
acadoWorkspace.rk_xxx[13] = + rk_eta[13]; |
||||||
|
acadoWorkspace.rk_xxx[14] = + rk_eta[14]; |
||||||
|
acadoWorkspace.rk_xxx[15] = + rk_eta[15]; |
||||||
|
acadoWorkspace.rk_xxx[16] = + rk_eta[16]; |
||||||
|
acadoWorkspace.rk_xxx[17] = + rk_eta[17]; |
||||||
|
acadoWorkspace.rk_xxx[18] = + rk_eta[18]; |
||||||
|
acadoWorkspace.rk_xxx[19] = + rk_eta[19]; |
||||||
|
acadoWorkspace.rk_xxx[20] = + rk_eta[20]; |
||||||
|
acadoWorkspace.rk_xxx[21] = + rk_eta[21]; |
||||||
|
acadoWorkspace.rk_xxx[22] = + rk_eta[22]; |
||||||
|
acadoWorkspace.rk_xxx[23] = + rk_eta[23]; |
||||||
|
acadoWorkspace.rk_xxx[24] = + rk_eta[24]; |
||||||
|
acadoWorkspace.rk_xxx[25] = + rk_eta[25]; |
||||||
|
acadoWorkspace.rk_xxx[26] = + rk_eta[26]; |
||||||
|
acadoWorkspace.rk_xxx[27] = + rk_eta[27]; |
||||||
|
acado_rhs_forw( acadoWorkspace.rk_xxx, acadoWorkspace.rk_kkk ); |
||||||
|
acadoWorkspace.rk_xxx[0] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[0] + rk_eta[0]; |
||||||
|
acadoWorkspace.rk_xxx[1] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[1] + rk_eta[1]; |
||||||
|
acadoWorkspace.rk_xxx[2] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[2] + rk_eta[2]; |
||||||
|
acadoWorkspace.rk_xxx[3] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[3] + rk_eta[3]; |
||||||
|
acadoWorkspace.rk_xxx[4] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[4] + rk_eta[4]; |
||||||
|
acadoWorkspace.rk_xxx[5] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[5] + rk_eta[5]; |
||||||
|
acadoWorkspace.rk_xxx[6] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[6] + rk_eta[6]; |
||||||
|
acadoWorkspace.rk_xxx[7] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[7] + rk_eta[7]; |
||||||
|
acadoWorkspace.rk_xxx[8] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[8] + rk_eta[8]; |
||||||
|
acadoWorkspace.rk_xxx[9] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[9] + rk_eta[9]; |
||||||
|
acadoWorkspace.rk_xxx[10] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[10] + rk_eta[10]; |
||||||
|
acadoWorkspace.rk_xxx[11] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[11] + rk_eta[11]; |
||||||
|
acadoWorkspace.rk_xxx[12] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[12] + rk_eta[12]; |
||||||
|
acadoWorkspace.rk_xxx[13] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[13] + rk_eta[13]; |
||||||
|
acadoWorkspace.rk_xxx[14] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[14] + rk_eta[14]; |
||||||
|
acadoWorkspace.rk_xxx[15] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[15] + rk_eta[15]; |
||||||
|
acadoWorkspace.rk_xxx[16] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[16] + rk_eta[16]; |
||||||
|
acadoWorkspace.rk_xxx[17] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[17] + rk_eta[17]; |
||||||
|
acadoWorkspace.rk_xxx[18] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[18] + rk_eta[18]; |
||||||
|
acadoWorkspace.rk_xxx[19] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[19] + rk_eta[19]; |
||||||
|
acadoWorkspace.rk_xxx[20] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[20] + rk_eta[20]; |
||||||
|
acadoWorkspace.rk_xxx[21] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[21] + rk_eta[21]; |
||||||
|
acadoWorkspace.rk_xxx[22] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[22] + rk_eta[22]; |
||||||
|
acadoWorkspace.rk_xxx[23] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[23] + rk_eta[23]; |
||||||
|
acadoWorkspace.rk_xxx[24] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[24] + rk_eta[24]; |
||||||
|
acadoWorkspace.rk_xxx[25] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[25] + rk_eta[25]; |
||||||
|
acadoWorkspace.rk_xxx[26] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[26] + rk_eta[26]; |
||||||
|
acadoWorkspace.rk_xxx[27] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[27] + rk_eta[27]; |
||||||
|
acado_rhs_forw( acadoWorkspace.rk_xxx, &(acadoWorkspace.rk_kkk[ 28 ]) ); |
||||||
|
acadoWorkspace.rk_xxx[0] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[28] + rk_eta[0]; |
||||||
|
acadoWorkspace.rk_xxx[1] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[29] + rk_eta[1]; |
||||||
|
acadoWorkspace.rk_xxx[2] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[30] + rk_eta[2]; |
||||||
|
acadoWorkspace.rk_xxx[3] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[31] + rk_eta[3]; |
||||||
|
acadoWorkspace.rk_xxx[4] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[32] + rk_eta[4]; |
||||||
|
acadoWorkspace.rk_xxx[5] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[33] + rk_eta[5]; |
||||||
|
acadoWorkspace.rk_xxx[6] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[34] + rk_eta[6]; |
||||||
|
acadoWorkspace.rk_xxx[7] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[35] + rk_eta[7]; |
||||||
|
acadoWorkspace.rk_xxx[8] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[36] + rk_eta[8]; |
||||||
|
acadoWorkspace.rk_xxx[9] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[37] + rk_eta[9]; |
||||||
|
acadoWorkspace.rk_xxx[10] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[38] + rk_eta[10]; |
||||||
|
acadoWorkspace.rk_xxx[11] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[39] + rk_eta[11]; |
||||||
|
acadoWorkspace.rk_xxx[12] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[40] + rk_eta[12]; |
||||||
|
acadoWorkspace.rk_xxx[13] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[41] + rk_eta[13]; |
||||||
|
acadoWorkspace.rk_xxx[14] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[42] + rk_eta[14]; |
||||||
|
acadoWorkspace.rk_xxx[15] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[43] + rk_eta[15]; |
||||||
|
acadoWorkspace.rk_xxx[16] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[44] + rk_eta[16]; |
||||||
|
acadoWorkspace.rk_xxx[17] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[45] + rk_eta[17]; |
||||||
|
acadoWorkspace.rk_xxx[18] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[46] + rk_eta[18]; |
||||||
|
acadoWorkspace.rk_xxx[19] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[47] + rk_eta[19]; |
||||||
|
acadoWorkspace.rk_xxx[20] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[48] + rk_eta[20]; |
||||||
|
acadoWorkspace.rk_xxx[21] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[49] + rk_eta[21]; |
||||||
|
acadoWorkspace.rk_xxx[22] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[50] + rk_eta[22]; |
||||||
|
acadoWorkspace.rk_xxx[23] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[51] + rk_eta[23]; |
||||||
|
acadoWorkspace.rk_xxx[24] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[52] + rk_eta[24]; |
||||||
|
acadoWorkspace.rk_xxx[25] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[53] + rk_eta[25]; |
||||||
|
acadoWorkspace.rk_xxx[26] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[54] + rk_eta[26]; |
||||||
|
acadoWorkspace.rk_xxx[27] = + (real_t)5.0000000000000001e-03*acadoWorkspace.rk_kkk[55] + rk_eta[27]; |
||||||
|
acado_rhs_forw( acadoWorkspace.rk_xxx, &(acadoWorkspace.rk_kkk[ 56 ]) ); |
||||||
|
acadoWorkspace.rk_xxx[0] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[56] + rk_eta[0]; |
||||||
|
acadoWorkspace.rk_xxx[1] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[57] + rk_eta[1]; |
||||||
|
acadoWorkspace.rk_xxx[2] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[58] + rk_eta[2]; |
||||||
|
acadoWorkspace.rk_xxx[3] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[59] + rk_eta[3]; |
||||||
|
acadoWorkspace.rk_xxx[4] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[60] + rk_eta[4]; |
||||||
|
acadoWorkspace.rk_xxx[5] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[61] + rk_eta[5]; |
||||||
|
acadoWorkspace.rk_xxx[6] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[62] + rk_eta[6]; |
||||||
|
acadoWorkspace.rk_xxx[7] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[63] + rk_eta[7]; |
||||||
|
acadoWorkspace.rk_xxx[8] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[64] + rk_eta[8]; |
||||||
|
acadoWorkspace.rk_xxx[9] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[65] + rk_eta[9]; |
||||||
|
acadoWorkspace.rk_xxx[10] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[66] + rk_eta[10]; |
||||||
|
acadoWorkspace.rk_xxx[11] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[67] + rk_eta[11]; |
||||||
|
acadoWorkspace.rk_xxx[12] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[68] + rk_eta[12]; |
||||||
|
acadoWorkspace.rk_xxx[13] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[69] + rk_eta[13]; |
||||||
|
acadoWorkspace.rk_xxx[14] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[70] + rk_eta[14]; |
||||||
|
acadoWorkspace.rk_xxx[15] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[71] + rk_eta[15]; |
||||||
|
acadoWorkspace.rk_xxx[16] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[72] + rk_eta[16]; |
||||||
|
acadoWorkspace.rk_xxx[17] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[73] + rk_eta[17]; |
||||||
|
acadoWorkspace.rk_xxx[18] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[74] + rk_eta[18]; |
||||||
|
acadoWorkspace.rk_xxx[19] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[75] + rk_eta[19]; |
||||||
|
acadoWorkspace.rk_xxx[20] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[76] + rk_eta[20]; |
||||||
|
acadoWorkspace.rk_xxx[21] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[77] + rk_eta[21]; |
||||||
|
acadoWorkspace.rk_xxx[22] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[78] + rk_eta[22]; |
||||||
|
acadoWorkspace.rk_xxx[23] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[79] + rk_eta[23]; |
||||||
|
acadoWorkspace.rk_xxx[24] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[80] + rk_eta[24]; |
||||||
|
acadoWorkspace.rk_xxx[25] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[81] + rk_eta[25]; |
||||||
|
acadoWorkspace.rk_xxx[26] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[82] + rk_eta[26]; |
||||||
|
acadoWorkspace.rk_xxx[27] = + (real_t)1.0000000000000000e-02*acadoWorkspace.rk_kkk[83] + rk_eta[27]; |
||||||
|
acado_rhs_forw( acadoWorkspace.rk_xxx, &(acadoWorkspace.rk_kkk[ 84 ]) ); |
||||||
|
rk_eta[0] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[0] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[28] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[56] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[84]; |
||||||
|
rk_eta[1] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[1] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[29] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[57] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[85]; |
||||||
|
rk_eta[2] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[2] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[30] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[58] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[86]; |
||||||
|
rk_eta[3] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[3] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[31] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[59] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[87]; |
||||||
|
rk_eta[4] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[4] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[32] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[60] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[88]; |
||||||
|
rk_eta[5] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[5] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[33] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[61] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[89]; |
||||||
|
rk_eta[6] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[6] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[34] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[62] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[90]; |
||||||
|
rk_eta[7] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[7] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[35] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[63] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[91]; |
||||||
|
rk_eta[8] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[8] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[36] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[64] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[92]; |
||||||
|
rk_eta[9] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[9] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[37] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[65] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[93]; |
||||||
|
rk_eta[10] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[10] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[38] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[66] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[94]; |
||||||
|
rk_eta[11] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[11] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[39] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[67] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[95]; |
||||||
|
rk_eta[12] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[12] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[40] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[68] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[96]; |
||||||
|
rk_eta[13] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[13] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[41] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[69] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[97]; |
||||||
|
rk_eta[14] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[14] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[42] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[70] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[98]; |
||||||
|
rk_eta[15] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[15] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[43] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[71] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[99]; |
||||||
|
rk_eta[16] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[16] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[44] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[72] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[100]; |
||||||
|
rk_eta[17] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[17] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[45] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[73] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[101]; |
||||||
|
rk_eta[18] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[18] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[46] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[74] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[102]; |
||||||
|
rk_eta[19] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[19] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[47] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[75] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[103]; |
||||||
|
rk_eta[20] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[20] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[48] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[76] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[104]; |
||||||
|
rk_eta[21] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[21] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[49] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[77] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[105]; |
||||||
|
rk_eta[22] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[22] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[50] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[78] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[106]; |
||||||
|
rk_eta[23] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[23] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[51] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[79] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[107]; |
||||||
|
rk_eta[24] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[24] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[52] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[80] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[108]; |
||||||
|
rk_eta[25] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[25] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[53] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[81] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[109]; |
||||||
|
rk_eta[26] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[26] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[54] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[82] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[110]; |
||||||
|
rk_eta[27] += + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[27] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[55] + (real_t)3.3333333333333331e-03*acadoWorkspace.rk_kkk[83] + (real_t)1.6666666666666666e-03*acadoWorkspace.rk_kkk[111]; |
||||||
|
acadoWorkspace.rk_ttt += 1.0000000000000000e+00; |
||||||
|
} |
||||||
|
} |
||||||
|
error = 0; |
||||||
|
return error; |
||||||
|
} |
||||||
|
|
File diff suppressed because one or more lines are too long
@ -0,0 +1,34 @@ |
|||||||
|
import os |
||||||
|
|
||||||
|
from cffi import FFI |
||||||
|
from common.ffi_wrapper import suffix |
||||||
|
|
||||||
|
mpc_dir = os.path.join(os.path.dirname(os.path.abspath(__file__))) |
||||||
|
libmpc_fn = os.path.join(mpc_dir, "libmpc"+suffix()) |
||||||
|
|
||||||
|
ffi = FFI() |
||||||
|
ffi.cdef(""" |
||||||
|
const int MPC_N = 32; |
||||||
|
|
||||||
|
typedef struct { |
||||||
|
double x_ego, v_ego, a_ego; |
||||||
|
} state_t; |
||||||
|
|
||||||
|
|
||||||
|
typedef struct { |
||||||
|
double x_ego[MPC_N+1]; |
||||||
|
double v_ego[MPC_N+1]; |
||||||
|
double a_ego[MPC_N+1]; |
||||||
|
double t[MPC_N+1]; |
||||||
|
double j_ego[MPC_N]; |
||||||
|
double cost; |
||||||
|
} log_t; |
||||||
|
|
||||||
|
|
||||||
|
void init(double xCost, double vCost, double aCost, double jerkCost, double constraintCost); |
||||||
|
int run_mpc(state_t * x0, log_t * solution, |
||||||
|
double target_x[MPC_N+1], double target_v[MPC_N+1], double target_a[MPC_N+1], |
||||||
|
double min_a, double max_a); |
||||||
|
""") |
||||||
|
|
||||||
|
libmpc = ffi.dlopen(libmpc_fn) |
@ -1,31 +0,0 @@ |
|||||||
Import('env', 'arch') |
|
||||||
|
|
||||||
|
|
||||||
cpp_path = [ |
|
||||||
"#phonelibs/acado/include", |
|
||||||
"#phonelibs/acado/include/acado", |
|
||||||
"#phonelibs/qpoases/INCLUDE", |
|
||||||
"#phonelibs/qpoases/INCLUDE/EXTRAS", |
|
||||||
"#phonelibs/qpoases/SRC/", |
|
||||||
"#phonelibs/qpoases", |
|
||||||
"lib_mpc_export" |
|
||||||
|
|
||||||
] |
|
||||||
|
|
||||||
mpc_files = [ |
|
||||||
"longitudinal_mpc.c", |
|
||||||
Glob("lib_mpc_export/*.c"), |
|
||||||
Glob("lib_mpc_export/*.cpp"), |
|
||||||
] |
|
||||||
|
|
||||||
interface_dir = Dir('lib_mpc_export') |
|
||||||
|
|
||||||
SConscript(['#phonelibs/qpoases/SConscript'], variant_dir='lib_qp', exports=['interface_dir']) |
|
||||||
|
|
||||||
env.SharedLibrary('mpc', mpc_files, LIBS=['m', 'qpoases'], LIBPATH=['lib_qp'], CPPPATH=cpp_path) |
|
||||||
|
|
||||||
# if arch != "aarch64": |
|
||||||
# acado_libs = [File("#phonelibs/acado/x64/lib/libacado_toolkit.a"), |
|
||||||
# File("#phonelibs/acado/x64/lib/libacado_casadi.a"), |
|
||||||
# File("#phonelibs/acado/x64/lib/libacado_csparse.a")] |
|
||||||
# env.Program('generator', 'generator.cpp', LIBS=acado_libs, CPPPATH=cpp_path) |
|
@ -1,99 +0,0 @@ |
|||||||
#include <acado_code_generation.hpp> |
|
||||||
|
|
||||||
const int controlHorizon = 50; |
|
||||||
|
|
||||||
using namespace std; |
|
||||||
|
|
||||||
|
|
||||||
int main( ) |
|
||||||
{ |
|
||||||
USING_NAMESPACE_ACADO |
|
||||||
|
|
||||||
|
|
||||||
DifferentialEquation f; |
|
||||||
|
|
||||||
DifferentialState x_ego, v_ego, a_ego, t; |
|
||||||
|
|
||||||
OnlineData x_poly_r0, x_poly_r1, x_poly_r2, x_poly_r3; |
|
||||||
OnlineData v_poly_r0, v_poly_r1, v_poly_r2, v_poly_r3; |
|
||||||
OnlineData a_poly_r0, a_poly_r1, a_poly_r2, a_poly_r3; |
|
||||||
|
|
||||||
Control j_ego; |
|
||||||
|
|
||||||
// Equations of motion
|
|
||||||
f << dot(x_ego) == v_ego; |
|
||||||
f << dot(v_ego) == a_ego; |
|
||||||
f << dot(a_ego) == j_ego; |
|
||||||
f << dot(t) == 1; |
|
||||||
|
|
||||||
auto poly_x = x_poly_r0*(t*t*t) + x_poly_r1*(t*t) + x_poly_r2*t + x_poly_r3; |
|
||||||
auto poly_v = v_poly_r0*(t*t*t) + v_poly_r1*(t*t) + v_poly_r2*t + v_poly_r3; |
|
||||||
auto poly_a = a_poly_r0*(t*t*t) + a_poly_r1*(t*t) + a_poly_r2*t + a_poly_r3; |
|
||||||
|
|
||||||
// Running cost
|
|
||||||
Function h; |
|
||||||
h << x_ego - poly_x; |
|
||||||
h << v_ego - poly_v; |
|
||||||
h << a_ego - poly_a; |
|
||||||
h << a_ego * (0.1 * v_ego + 1.0); |
|
||||||
h << j_ego * (0.1 * v_ego + 1.0); |
|
||||||
|
|
||||||
// Weights are defined in mpc.
|
|
||||||
BMatrix Q(5,5); Q.setAll(true); |
|
||||||
|
|
||||||
// Terminal cost
|
|
||||||
Function hN; |
|
||||||
hN << x_ego - poly_x; |
|
||||||
hN << v_ego - poly_v; |
|
||||||
hN << a_ego - poly_a; |
|
||||||
hN << a_ego * (0.1 * v_ego + 1.0); |
|
||||||
|
|
||||||
// Weights are defined in mpc.
|
|
||||||
BMatrix QN(4,4); QN.setAll(true); |
|
||||||
|
|
||||||
// Non uniform time grid
|
|
||||||
// First 5 timesteps are 0.2, after that it's 0.6
|
|
||||||
DMatrix numSteps(20, 1); |
|
||||||
for (int i = 0; i < 5; i++){ |
|
||||||
numSteps(i) = 1; |
|
||||||
} |
|
||||||
for (int i = 5; i < 20; i++){ |
|
||||||
numSteps(i) = 3; |
|
||||||
} |
|
||||||
|
|
||||||
// Setup Optimal Control Problem
|
|
||||||
const double tStart = 0.0; |
|
||||||
const double tEnd = 10.0; |
|
||||||
|
|
||||||
OCP ocp( tStart, tEnd, numSteps); |
|
||||||
ocp.subjectTo(f); |
|
||||||
|
|
||||||
ocp.minimizeLSQ(Q, h); |
|
||||||
ocp.minimizeLSQEndTerm(QN, hN); |
|
||||||
|
|
||||||
//ocp.subjectTo( 0.0 <= v_ego);
|
|
||||||
ocp.setNOD(12); |
|
||||||
|
|
||||||
OCPexport mpc(ocp); |
|
||||||
mpc.set( HESSIAN_APPROXIMATION, GAUSS_NEWTON ); |
|
||||||
mpc.set( DISCRETIZATION_TYPE, MULTIPLE_SHOOTING ); |
|
||||||
mpc.set( INTEGRATOR_TYPE, INT_RK4 ); |
|
||||||
mpc.set( NUM_INTEGRATOR_STEPS, controlHorizon); |
|
||||||
mpc.set( MAX_NUM_QP_ITERATIONS, 500); |
|
||||||
mpc.set( CG_USE_VARIABLE_WEIGHTING_MATRIX, YES); |
|
||||||
|
|
||||||
mpc.set( SPARSE_QP_SOLUTION, CONDENSING ); |
|
||||||
mpc.set( QP_SOLVER, QP_QPOASES ); |
|
||||||
mpc.set( HOTSTART_QP, YES ); |
|
||||||
mpc.set( GENERATE_TEST_FILE, NO); |
|
||||||
mpc.set( GENERATE_MAKE_FILE, NO ); |
|
||||||
mpc.set( GENERATE_MATLAB_INTERFACE, NO ); |
|
||||||
mpc.set( GENERATE_SIMULINK_INTERFACE, NO ); |
|
||||||
|
|
||||||
if (mpc.exportCode( "lib_mpc_export" ) != SUCCESSFUL_RETURN) |
|
||||||
exit( EXIT_FAILURE ); |
|
||||||
|
|
||||||
mpc.printDimensionsQP( ); |
|
||||||
|
|
||||||
return EXIT_SUCCESS; |
|
||||||
} |
|
@ -1,231 +0,0 @@ |
|||||||
/*
|
|
||||||
* This file was auto-generated using the ACADO Toolkit. |
|
||||||
*
|
|
||||||
* While ACADO Toolkit is free software released under the terms of |
|
||||||
* the GNU Lesser General Public License (LGPL), the generated code |
|
||||||
* as such remains the property of the user who used ACADO Toolkit |
|
||||||
* to generate this code. In particular, user dependent data of the code |
|
||||||
* do not inherit the GNU LGPL license. On the other hand, parts of the |
|
||||||
* generated code that are a direct copy of source code from the |
|
||||||
* ACADO Toolkit or the software tools it is based on, remain, as derived |
|
||||||
* work, automatically covered by the LGPL license. |
|
||||||
*
|
|
||||||
* ACADO Toolkit is distributed in the hope that it will be useful, |
|
||||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of |
|
||||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. |
|
||||||
*
|
|
||||||
*/ |
|
||||||
|
|
||||||
|
|
||||||
#include "acado_common.h" |
|
||||||
|
|
||||||
|
|
||||||
void acado_rhs_forw(const real_t* in, real_t* out) |
|
||||||
{ |
|
||||||
const real_t* xd = in; |
|
||||||
const real_t* u = in + 24; |
|
||||||
|
|
||||||
/* Compute outputs: */ |
|
||||||
out[0] = xd[1]; |
|
||||||
out[1] = xd[2]; |
|
||||||
out[2] = u[0]; |
|
||||||
out[3] = (real_t)(1.0000000000000000e+00); |
|
||||||
out[4] = xd[8]; |
|
||||||
out[5] = xd[9]; |
|
||||||
out[6] = xd[10]; |
|
||||||
out[7] = xd[11]; |
|
||||||
out[8] = xd[12]; |
|
||||||
out[9] = xd[13]; |
|
||||||
out[10] = xd[14]; |
|
||||||
out[11] = xd[15]; |
|
||||||
out[12] = (real_t)(0.0000000000000000e+00); |
|
||||||
out[13] = (real_t)(0.0000000000000000e+00); |
|
||||||
out[14] = (real_t)(0.0000000000000000e+00); |
|
||||||
out[15] = (real_t)(0.0000000000000000e+00); |
|
||||||
out[16] = (real_t)(0.0000000000000000e+00); |
|
||||||
out[17] = (real_t)(0.0000000000000000e+00); |
|
||||||
out[18] = (real_t)(0.0000000000000000e+00); |
|
||||||
out[19] = (real_t)(0.0000000000000000e+00); |
|
||||||
out[20] = xd[21]; |
|
||||||
out[21] = xd[22]; |
|
||||||
out[22] = (real_t)(1.0000000000000000e+00); |
|
||||||
out[23] = (real_t)(0.0000000000000000e+00); |
|
||||||
} |
|
||||||
|
|
||||||
/* Fixed step size:0.2 */ |
|
||||||
int acado_integrate( real_t* const rk_eta, int resetIntegrator, int rk_index ) |
|
||||||
{ |
|
||||||
int error; |
|
||||||
|
|
||||||
int run1; |
|
||||||
int numSteps[20] = {1, 1, 1, 1, 1, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3}; |
|
||||||
int numInts = numSteps[rk_index]; |
|
||||||
acadoWorkspace.rk_ttt = 0.0000000000000000e+00; |
|
||||||
rk_eta[4] = 1.0000000000000000e+00; |
|
||||||
rk_eta[5] = 0.0000000000000000e+00; |
|
||||||
rk_eta[6] = 0.0000000000000000e+00; |
|
||||||
rk_eta[7] = 0.0000000000000000e+00; |
|
||||||
rk_eta[8] = 0.0000000000000000e+00; |
|
||||||
rk_eta[9] = 1.0000000000000000e+00; |
|
||||||
rk_eta[10] = 0.0000000000000000e+00; |
|
||||||
rk_eta[11] = 0.0000000000000000e+00; |
|
||||||
rk_eta[12] = 0.0000000000000000e+00; |
|
||||||
rk_eta[13] = 0.0000000000000000e+00; |
|
||||||
rk_eta[14] = 1.0000000000000000e+00; |
|
||||||
rk_eta[15] = 0.0000000000000000e+00; |
|
||||||
rk_eta[16] = 0.0000000000000000e+00; |
|
||||||
rk_eta[17] = 0.0000000000000000e+00; |
|
||||||
rk_eta[18] = 0.0000000000000000e+00; |
|
||||||
rk_eta[19] = 1.0000000000000000e+00; |
|
||||||
rk_eta[20] = 0.0000000000000000e+00; |
|
||||||
rk_eta[21] = 0.0000000000000000e+00; |
|
||||||
rk_eta[22] = 0.0000000000000000e+00; |
|
||||||
rk_eta[23] = 0.0000000000000000e+00; |
|
||||||
acadoWorkspace.rk_xxx[24] = rk_eta[24]; |
|
||||||
acadoWorkspace.rk_xxx[25] = rk_eta[25]; |
|
||||||
acadoWorkspace.rk_xxx[26] = rk_eta[26]; |
|
||||||
acadoWorkspace.rk_xxx[27] = rk_eta[27]; |
|
||||||
acadoWorkspace.rk_xxx[28] = rk_eta[28]; |
|
||||||
acadoWorkspace.rk_xxx[29] = rk_eta[29]; |
|
||||||
acadoWorkspace.rk_xxx[30] = rk_eta[30]; |
|
||||||
acadoWorkspace.rk_xxx[31] = rk_eta[31]; |
|
||||||
acadoWorkspace.rk_xxx[32] = rk_eta[32]; |
|
||||||
acadoWorkspace.rk_xxx[33] = rk_eta[33]; |
|
||||||
acadoWorkspace.rk_xxx[34] = rk_eta[34]; |
|
||||||
acadoWorkspace.rk_xxx[35] = rk_eta[35]; |
|
||||||
acadoWorkspace.rk_xxx[36] = rk_eta[36]; |
|
||||||
|
|
||||||
for (run1 = 0; run1 < 1; ++run1) |
|
||||||
{ |
|
||||||
for(run1 = 0; run1 < numInts; run1++ ) { |
|
||||||
acadoWorkspace.rk_xxx[0] = + rk_eta[0]; |
|
||||||
acadoWorkspace.rk_xxx[1] = + rk_eta[1]; |
|
||||||
acadoWorkspace.rk_xxx[2] = + rk_eta[2]; |
|
||||||
acadoWorkspace.rk_xxx[3] = + rk_eta[3]; |
|
||||||
acadoWorkspace.rk_xxx[4] = + rk_eta[4]; |
|
||||||
acadoWorkspace.rk_xxx[5] = + rk_eta[5]; |
|
||||||
acadoWorkspace.rk_xxx[6] = + rk_eta[6]; |
|
||||||
acadoWorkspace.rk_xxx[7] = + rk_eta[7]; |
|
||||||
acadoWorkspace.rk_xxx[8] = + rk_eta[8]; |
|
||||||
acadoWorkspace.rk_xxx[9] = + rk_eta[9]; |
|
||||||
acadoWorkspace.rk_xxx[10] = + rk_eta[10]; |
|
||||||
acadoWorkspace.rk_xxx[11] = + rk_eta[11]; |
|
||||||
acadoWorkspace.rk_xxx[12] = + rk_eta[12]; |
|
||||||
acadoWorkspace.rk_xxx[13] = + rk_eta[13]; |
|
||||||
acadoWorkspace.rk_xxx[14] = + rk_eta[14]; |
|
||||||
acadoWorkspace.rk_xxx[15] = + rk_eta[15]; |
|
||||||
acadoWorkspace.rk_xxx[16] = + rk_eta[16]; |
|
||||||
acadoWorkspace.rk_xxx[17] = + rk_eta[17]; |
|
||||||
acadoWorkspace.rk_xxx[18] = + rk_eta[18]; |
|
||||||
acadoWorkspace.rk_xxx[19] = + rk_eta[19]; |
|
||||||
acadoWorkspace.rk_xxx[20] = + rk_eta[20]; |
|
||||||
acadoWorkspace.rk_xxx[21] = + rk_eta[21]; |
|
||||||
acadoWorkspace.rk_xxx[22] = + rk_eta[22]; |
|
||||||
acadoWorkspace.rk_xxx[23] = + rk_eta[23]; |
|
||||||
acado_rhs_forw( acadoWorkspace.rk_xxx, acadoWorkspace.rk_kkk ); |
|
||||||
acadoWorkspace.rk_xxx[0] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[0] + rk_eta[0]; |
|
||||||
acadoWorkspace.rk_xxx[1] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[1] + rk_eta[1]; |
|
||||||
acadoWorkspace.rk_xxx[2] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[2] + rk_eta[2]; |
|
||||||
acadoWorkspace.rk_xxx[3] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[3] + rk_eta[3]; |
|
||||||
acadoWorkspace.rk_xxx[4] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[4] + rk_eta[4]; |
|
||||||
acadoWorkspace.rk_xxx[5] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[5] + rk_eta[5]; |
|
||||||
acadoWorkspace.rk_xxx[6] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[6] + rk_eta[6]; |
|
||||||
acadoWorkspace.rk_xxx[7] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[7] + rk_eta[7]; |
|
||||||
acadoWorkspace.rk_xxx[8] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[8] + rk_eta[8]; |
|
||||||
acadoWorkspace.rk_xxx[9] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[9] + rk_eta[9]; |
|
||||||
acadoWorkspace.rk_xxx[10] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[10] + rk_eta[10]; |
|
||||||
acadoWorkspace.rk_xxx[11] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[11] + rk_eta[11]; |
|
||||||
acadoWorkspace.rk_xxx[12] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[12] + rk_eta[12]; |
|
||||||
acadoWorkspace.rk_xxx[13] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[13] + rk_eta[13]; |
|
||||||
acadoWorkspace.rk_xxx[14] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[14] + rk_eta[14]; |
|
||||||
acadoWorkspace.rk_xxx[15] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[15] + rk_eta[15]; |
|
||||||
acadoWorkspace.rk_xxx[16] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[16] + rk_eta[16]; |
|
||||||
acadoWorkspace.rk_xxx[17] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[17] + rk_eta[17]; |
|
||||||
acadoWorkspace.rk_xxx[18] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[18] + rk_eta[18]; |
|
||||||
acadoWorkspace.rk_xxx[19] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[19] + rk_eta[19]; |
|
||||||
acadoWorkspace.rk_xxx[20] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[20] + rk_eta[20]; |
|
||||||
acadoWorkspace.rk_xxx[21] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[21] + rk_eta[21]; |
|
||||||
acadoWorkspace.rk_xxx[22] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[22] + rk_eta[22]; |
|
||||||
acadoWorkspace.rk_xxx[23] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[23] + rk_eta[23]; |
|
||||||
acado_rhs_forw( acadoWorkspace.rk_xxx, &(acadoWorkspace.rk_kkk[ 24 ]) ); |
|
||||||
acadoWorkspace.rk_xxx[0] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[24] + rk_eta[0]; |
|
||||||
acadoWorkspace.rk_xxx[1] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[25] + rk_eta[1]; |
|
||||||
acadoWorkspace.rk_xxx[2] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[26] + rk_eta[2]; |
|
||||||
acadoWorkspace.rk_xxx[3] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[27] + rk_eta[3]; |
|
||||||
acadoWorkspace.rk_xxx[4] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[28] + rk_eta[4]; |
|
||||||
acadoWorkspace.rk_xxx[5] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[29] + rk_eta[5]; |
|
||||||
acadoWorkspace.rk_xxx[6] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[30] + rk_eta[6]; |
|
||||||
acadoWorkspace.rk_xxx[7] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[31] + rk_eta[7]; |
|
||||||
acadoWorkspace.rk_xxx[8] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[32] + rk_eta[8]; |
|
||||||
acadoWorkspace.rk_xxx[9] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[33] + rk_eta[9]; |
|
||||||
acadoWorkspace.rk_xxx[10] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[34] + rk_eta[10]; |
|
||||||
acadoWorkspace.rk_xxx[11] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[35] + rk_eta[11]; |
|
||||||
acadoWorkspace.rk_xxx[12] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[36] + rk_eta[12]; |
|
||||||
acadoWorkspace.rk_xxx[13] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[37] + rk_eta[13]; |
|
||||||
acadoWorkspace.rk_xxx[14] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[38] + rk_eta[14]; |
|
||||||
acadoWorkspace.rk_xxx[15] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[39] + rk_eta[15]; |
|
||||||
acadoWorkspace.rk_xxx[16] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[40] + rk_eta[16]; |
|
||||||
acadoWorkspace.rk_xxx[17] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[41] + rk_eta[17]; |
|
||||||
acadoWorkspace.rk_xxx[18] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[42] + rk_eta[18]; |
|
||||||
acadoWorkspace.rk_xxx[19] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[43] + rk_eta[19]; |
|
||||||
acadoWorkspace.rk_xxx[20] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[44] + rk_eta[20]; |
|
||||||
acadoWorkspace.rk_xxx[21] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[45] + rk_eta[21]; |
|
||||||
acadoWorkspace.rk_xxx[22] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[46] + rk_eta[22]; |
|
||||||
acadoWorkspace.rk_xxx[23] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[47] + rk_eta[23]; |
|
||||||
acado_rhs_forw( acadoWorkspace.rk_xxx, &(acadoWorkspace.rk_kkk[ 48 ]) ); |
|
||||||
acadoWorkspace.rk_xxx[0] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[48] + rk_eta[0]; |
|
||||||
acadoWorkspace.rk_xxx[1] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[49] + rk_eta[1]; |
|
||||||
acadoWorkspace.rk_xxx[2] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[50] + rk_eta[2]; |
|
||||||
acadoWorkspace.rk_xxx[3] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[51] + rk_eta[3]; |
|
||||||
acadoWorkspace.rk_xxx[4] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[52] + rk_eta[4]; |
|
||||||
acadoWorkspace.rk_xxx[5] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[53] + rk_eta[5]; |
|
||||||
acadoWorkspace.rk_xxx[6] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[54] + rk_eta[6]; |
|
||||||
acadoWorkspace.rk_xxx[7] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[55] + rk_eta[7]; |
|
||||||
acadoWorkspace.rk_xxx[8] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[56] + rk_eta[8]; |
|
||||||
acadoWorkspace.rk_xxx[9] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[57] + rk_eta[9]; |
|
||||||
acadoWorkspace.rk_xxx[10] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[58] + rk_eta[10]; |
|
||||||
acadoWorkspace.rk_xxx[11] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[59] + rk_eta[11]; |
|
||||||
acadoWorkspace.rk_xxx[12] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[60] + rk_eta[12]; |
|
||||||
acadoWorkspace.rk_xxx[13] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[61] + rk_eta[13]; |
|
||||||
acadoWorkspace.rk_xxx[14] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[62] + rk_eta[14]; |
|
||||||
acadoWorkspace.rk_xxx[15] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[63] + rk_eta[15]; |
|
||||||
acadoWorkspace.rk_xxx[16] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[64] + rk_eta[16]; |
|
||||||
acadoWorkspace.rk_xxx[17] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[65] + rk_eta[17]; |
|
||||||
acadoWorkspace.rk_xxx[18] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[66] + rk_eta[18]; |
|
||||||
acadoWorkspace.rk_xxx[19] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[67] + rk_eta[19]; |
|
||||||
acadoWorkspace.rk_xxx[20] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[68] + rk_eta[20]; |
|
||||||
acadoWorkspace.rk_xxx[21] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[69] + rk_eta[21]; |
|
||||||
acadoWorkspace.rk_xxx[22] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[70] + rk_eta[22]; |
|
||||||
acadoWorkspace.rk_xxx[23] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[71] + rk_eta[23]; |
|
||||||
acado_rhs_forw( acadoWorkspace.rk_xxx, &(acadoWorkspace.rk_kkk[ 72 ]) ); |
|
||||||
rk_eta[0] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[0] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[24] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[48] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[72]; |
|
||||||
rk_eta[1] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[1] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[25] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[49] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[73]; |
|
||||||
rk_eta[2] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[2] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[26] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[50] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[74]; |
|
||||||
rk_eta[3] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[3] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[27] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[51] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[75]; |
|
||||||
rk_eta[4] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[4] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[28] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[52] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[76]; |
|
||||||
rk_eta[5] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[5] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[29] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[53] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[77]; |
|
||||||
rk_eta[6] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[6] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[30] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[54] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[78]; |
|
||||||
rk_eta[7] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[7] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[31] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[55] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[79]; |
|
||||||
rk_eta[8] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[8] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[32] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[56] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[80]; |
|
||||||
rk_eta[9] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[9] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[33] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[57] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[81]; |
|
||||||
rk_eta[10] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[10] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[34] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[58] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[82]; |
|
||||||
rk_eta[11] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[11] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[35] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[59] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[83]; |
|
||||||
rk_eta[12] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[12] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[36] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[60] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[84]; |
|
||||||
rk_eta[13] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[13] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[37] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[61] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[85]; |
|
||||||
rk_eta[14] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[14] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[38] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[62] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[86]; |
|
||||||
rk_eta[15] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[15] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[39] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[63] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[87]; |
|
||||||
rk_eta[16] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[16] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[40] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[64] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[88]; |
|
||||||
rk_eta[17] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[17] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[41] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[65] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[89]; |
|
||||||
rk_eta[18] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[18] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[42] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[66] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[90]; |
|
||||||
rk_eta[19] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[19] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[43] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[67] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[91]; |
|
||||||
rk_eta[20] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[20] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[44] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[68] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[92]; |
|
||||||
rk_eta[21] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[21] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[45] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[69] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[93]; |
|
||||||
rk_eta[22] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[22] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[46] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[70] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[94]; |
|
||||||
rk_eta[23] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[23] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[47] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[71] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[95]; |
|
||||||
acadoWorkspace.rk_ttt += 1.0000000000000000e+00; |
|
||||||
} |
|
||||||
} |
|
||||||
error = 0; |
|
||||||
return error; |
|
||||||
} |
|
||||||
|
|
File diff suppressed because it is too large
Load Diff
@ -1,32 +0,0 @@ |
|||||||
import os |
|
||||||
|
|
||||||
from cffi import FFI |
|
||||||
from common.ffi_wrapper import suffix |
|
||||||
|
|
||||||
mpc_dir = os.path.join(os.path.dirname(os.path.abspath(__file__))) |
|
||||||
libmpc_fn = os.path.join(mpc_dir, "libmpc"+suffix()) |
|
||||||
|
|
||||||
ffi = FFI() |
|
||||||
ffi.cdef(""" |
|
||||||
|
|
||||||
typedef struct { |
|
||||||
double x_ego, v_ego, a_ego; |
|
||||||
} state_t; |
|
||||||
|
|
||||||
|
|
||||||
typedef struct { |
|
||||||
double x_ego[21]; |
|
||||||
double v_ego[21]; |
|
||||||
double a_ego[21]; |
|
||||||
double t[21]; |
|
||||||
double j_ego[20]; |
|
||||||
double cost; |
|
||||||
} log_t; |
|
||||||
|
|
||||||
|
|
||||||
void init(double xCost, double vCost, double aCost, double accelCost, double jerkCost); |
|
||||||
void init_with_simulation(double v_ego); |
|
||||||
int run_mpc(state_t * x0, log_t * solution, double x_poly[4], double v_poly[4], double a_poly[4]); |
|
||||||
""") |
|
||||||
|
|
||||||
libmpc = ffi.dlopen(libmpc_fn) |
|
@ -1,99 +0,0 @@ |
|||||||
import numpy as np |
|
||||||
|
|
||||||
|
|
||||||
def get_delta_out_limits(aEgo, aMax, aMin, jMax, jMin): |
|
||||||
|
|
||||||
tDelta = 0. |
|
||||||
if aEgo > aMax: |
|
||||||
tDelta = (aMax - aEgo) / jMin |
|
||||||
elif aEgo < aMin: |
|
||||||
tDelta = (aMin - aEgo) / jMax |
|
||||||
|
|
||||||
return tDelta |
|
||||||
|
|
||||||
|
|
||||||
def speed_smoother(vEgo, aEgo, vT, aMax, aMin, jMax, jMin, ts): |
|
||||||
|
|
||||||
dV = vT - vEgo |
|
||||||
|
|
||||||
# recover quickly if dV is positive and aEgo is negative or viceversa |
|
||||||
if dV > 0. and aEgo < 0.: |
|
||||||
jMax *= 3. |
|
||||||
elif dV < 0. and aEgo > 0.: |
|
||||||
jMin *= 3. |
|
||||||
|
|
||||||
tDelta = get_delta_out_limits(aEgo, aMax, aMin, jMax, jMin) |
|
||||||
|
|
||||||
if (ts <= tDelta): |
|
||||||
if (aEgo < aMin): |
|
||||||
vEgo += ts * aEgo + 0.5 * ts**2 * jMax |
|
||||||
aEgo += ts * jMax |
|
||||||
return vEgo, aEgo |
|
||||||
elif (aEgo > aMax): |
|
||||||
vEgo += ts * aEgo + 0.5 * ts**2 * jMin |
|
||||||
aEgo += ts * jMin |
|
||||||
return vEgo, aEgo |
|
||||||
|
|
||||||
if aEgo > aMax: |
|
||||||
dV -= 0.5 * (aMax**2 - aEgo**2) / jMin |
|
||||||
vEgo += 0.5 * (aMax**2 - aEgo**2) / jMin |
|
||||||
aEgo += tDelta * jMin |
|
||||||
elif aEgo < aMin: |
|
||||||
dV -= 0.5 * (aMin**2 - aEgo**2) / jMax |
|
||||||
vEgo += 0.5 * (aMin**2 - aEgo**2) / jMax |
|
||||||
aEgo += tDelta * jMax |
|
||||||
|
|
||||||
ts -= tDelta |
|
||||||
|
|
||||||
jLim = jMin if aEgo >= 0 else jMax |
|
||||||
# if we reduce the accel to zero immediately, how much delta speed we generate? |
|
||||||
dv_min_shift = - 0.5 * aEgo**2 / jLim |
|
||||||
|
|
||||||
# flip signs so we can consider only one case |
|
||||||
flipped = False |
|
||||||
if dV < dv_min_shift: |
|
||||||
flipped = True |
|
||||||
dV *= -1 |
|
||||||
vEgo *= -1 |
|
||||||
aEgo *= -1 |
|
||||||
aMax = -aMin |
|
||||||
jMaxcopy = -jMin |
|
||||||
jMin = -jMax |
|
||||||
jMax = jMaxcopy |
|
||||||
|
|
||||||
# small addition needed to avoid numerical issues with sqrt of ~zero |
|
||||||
aPeak = np.sqrt((0.5 * aEgo**2 / jMax + dV + 1e-9) / (0.5 / jMax - 0.5 / jMin)) |
|
||||||
|
|
||||||
if aPeak > aMax: |
|
||||||
aPeak = aMax |
|
||||||
t1 = (aPeak - aEgo) / jMax |
|
||||||
if aPeak <= 0: # there is no solution, so stop after t1 |
|
||||||
t2 = t1 + ts + 1e-9 |
|
||||||
t3 = t2 |
|
||||||
else: |
|
||||||
vChange = dV - 0.5 * (aPeak**2 - aEgo**2) / jMax + 0.5 * aPeak**2 / jMin |
|
||||||
if vChange < aPeak * ts: |
|
||||||
t2 = t1 + vChange / aPeak |
|
||||||
else: |
|
||||||
t2 = t1 + ts |
|
||||||
t3 = t2 - aPeak / jMin |
|
||||||
else: |
|
||||||
t1 = (aPeak - aEgo) / jMax |
|
||||||
t2 = t1 |
|
||||||
t3 = t2 - aPeak / jMin |
|
||||||
|
|
||||||
dt1 = min(ts, t1) |
|
||||||
dt2 = max(min(ts, t2) - t1, 0.) |
|
||||||
dt3 = max(min(ts, t3) - t2, 0.) |
|
||||||
|
|
||||||
if ts > t3: |
|
||||||
vEgo += dV |
|
||||||
aEgo = 0. |
|
||||||
else: |
|
||||||
vEgo += aEgo * dt1 + 0.5 * dt1**2 * jMax + aPeak * dt2 + aPeak * dt3 + 0.5 * dt3**2 * jMin |
|
||||||
aEgo += jMax * dt1 + dt3 * jMin |
|
||||||
|
|
||||||
vEgo *= -1 if flipped else 1 |
|
||||||
aEgo *= -1 if flipped else 1 |
|
||||||
|
|
||||||
return float(vEgo), float(aEgo) |
|
@ -1 +1 @@ |
|||||||
abe59dfbc06ed070a3ac2f4ab587d311ef808e2e |
30a27425ede01b64382326a0d1e96ac80ebeae41 |
Loading…
Reference in new issue