longitudinal MPC: use reset() function instead of recreating the solver in (#24091)

* scons: add acados_template as dependency for lat and long mpc

* long MPC: use acados reset instead of recreating the solver

* long MPC: print timings and reset commented

* update acados x86_64

* update acados include folder

* update acados Python interface

* update acados reference commit to latest acados/master

* update x86 libs

* update comma two

* update acados again with commit 8ea8827fafb1b23b4c7da1c4cf650de1cbd73584

* update comma two

* update comma three

* update x86

Co-authored-by: Adeeb Shihadeh <adeebshihadeh@gmail.com>
Co-authored-by: Comma Device <device@comma.ai>
old-commit-hash: a9bac5acf8
taco
Jonathan Frey 3 years ago committed by GitHub
parent 1ce647b0a6
commit 059dbf57e7
  1. 4
      pyextra/acados_template/acados_layout.json
  2. 4
      pyextra/acados_template/acados_ocp.py
  3. 4
      pyextra/acados_template/acados_ocp_solver.py
  4. 4
      pyextra/acados_template/acados_ocp_solver_pyx.pyx
  5. 4
      pyextra/acados_template/acados_sim.py
  6. 4
      pyextra/acados_template/acados_sim_solver.py
  7. 3
      pyextra/acados_template/builders.py
  8. 3
      pyextra/acados_template/c_templates_tera/CMakeLists.in.txt
  9. 4
      pyextra/acados_template/c_templates_tera/acados_sim_solver.in.h
  10. 4
      pyextra/acados_template/c_templates_tera/acados_solver.in.c
  11. 4
      pyextra/acados_template/c_templates_tera/acados_solver.in.h
  12. 4
      pyextra/acados_template/c_templates_tera/acados_solver.in.pxd
  13. 4
      pyextra/acados_template/c_templates_tera/acados_solver_sfun.in.c
  14. 4
      pyextra/acados_template/c_templates_tera/make_sfun.in.m
  15. 4
      pyextra/acados_template/generate_c_code_discrete_dynamics.py
  16. 4
      pyextra/acados_template/simulink_default_opts.json
  17. 4
      pyextra/acados_template/utils.py
  18. 3
      selfdrive/controls/lib/lateral_mpc_lib/SConscript
  19. 3
      selfdrive/controls/lib/longitudinal_mpc_lib/SConscript
  20. 9
      selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py
  21. 4
      third_party/acados/aarch64/lib/libacados.so
  22. 4
      third_party/acados/aarch64/lib/libblasfeo.so
  23. 4
      third_party/acados/build.sh
  24. 2
      third_party/acados/include/acados/dense_qp/dense_qp_qpoases.h
  25. 4
      third_party/acados/include/acados/ocp_nlp/ocp_nlp_common.h
  26. 4
      third_party/acados/include/acados/ocp_nlp/ocp_nlp_sqp.h
  27. 1
      third_party/acados/include/acados/ocp_qp/ocp_qp_common.h
  28. 3
      third_party/acados/include/acados/ocp_qp/ocp_qp_hpipm.h
  29. 1
      third_party/acados/include/acados/ocp_qp/ocp_qp_hpmpc.h
  30. 1
      third_party/acados/include/acados/ocp_qp/ocp_qp_ooqp.h
  31. 1
      third_party/acados/include/acados/ocp_qp/ocp_qp_osqp.h
  32. 1
      third_party/acados/include/acados/ocp_qp/ocp_qp_qpdunes.h
  33. 1
      third_party/acados/include/acados/ocp_qp/ocp_qp_xcond_solver.h
  34. 1
      third_party/acados/include/acados/sim/sim_lifted_irk_integrator.h
  35. 15
      third_party/acados/include/acados/utils/types.h
  36. 85
      third_party/acados/include/acados_c/ocp_nlp_interface.h
  37. 48
      third_party/acados/include/acados_c/sim_interface.h
  38. 65
      third_party/acados/include/blasfeo/include/blasfeo_block_size.h
  39. 38
      third_party/acados/include/blasfeo/include/blasfeo_common.h
  40. 11
      third_party/acados/include/blasfeo/include/blasfeo_d_aux.h
  41. 142
      third_party/acados/include/blasfeo/include/blasfeo_d_blas_api.h
  42. 22
      third_party/acados/include/blasfeo/include/blasfeo_d_blasfeo_api.h
  43. 84
      third_party/acados/include/blasfeo/include/blasfeo_d_blasfeo_hp_api.h
  44. 12
      third_party/acados/include/blasfeo/include/blasfeo_d_blasfeo_ref_api.h
  45. 74
      third_party/acados/include/blasfeo/include/blasfeo_d_kernel.h
  46. 28
      third_party/acados/include/blasfeo/include/blasfeo_processor_features.h
  47. 75
      third_party/acados/include/blasfeo/include/blasfeo_s_blas_api.h
  48. 12
      third_party/acados/include/blasfeo/include/blasfeo_s_blasfeo_api.h
  49. 12
      third_party/acados/include/blasfeo/include/blasfeo_s_blasfeo_ref_api.h
  50. 12
      third_party/acados/include/blasfeo/include/blasfeo_target.h
  51. 1
      third_party/acados/include/blasfeo/include/d_blas.h
  52. 1
      third_party/acados/include/blasfeo/include/s_blas.h
  53. 4
      third_party/acados/larch64/lib/libacados.so
  54. 4
      third_party/acados/larch64/lib/libblasfeo.so
  55. 4
      third_party/acados/x86_64/lib/libacados.so
  56. 4
      third_party/acados/x86_64/lib/libblasfeo.so
  57. 2
      third_party/acados/x86_64/lib/libhpipm.so
  58. 2
      third_party/acados/x86_64/lib/libqpOASES_e.so.3.1
  59. 4
      third_party/acados/x86_64/t_renderer

@ -1,3 +1,3 @@
version https://git-lfs.github.com/spec/v1 version https://git-lfs.github.com/spec/v1
oid sha256:5c727abe27e9d89f04baca65f02c77ad8dcb918cd9f782df0575c01350dc8a5f oid sha256:c116b7b6dae6a24ed2e3f55604edce722d6b86c9c25451e3ebe96c278f700cc9
size 14205 size 14258

@ -1,3 +1,3 @@
version https://git-lfs.github.com/spec/v1 version https://git-lfs.github.com/spec/v1
oid sha256:d85c58ec2b66a50cb1008cc134e43278afc38f9ba261aee1a4c02495895e237c oid sha256:00a5921254ea36f5cb0c80838bbc18bd7544990f4366979152c9a81cd0f302b8
size 99987 size 101018

@ -1,3 +1,3 @@
version https://git-lfs.github.com/spec/v1 version https://git-lfs.github.com/spec/v1
oid sha256:c8cfc4b83e74e6841aa4572535e6e42bc82e76c62f7294b3a93ec438995d694a oid sha256:88265ec648408897af39ffe030823b009dde3cf56e588d3e717c60898432461c
size 78430 size 84016

@ -1,3 +1,3 @@
version https://git-lfs.github.com/spec/v1 version https://git-lfs.github.com/spec/v1
oid sha256:22f6a541bce66f0d2d050295c1c7dae17aeaff2daf7aeb3e5dcc7194ae869cac oid sha256:74e00646a8d51f0f4e8d0aa3d0e31160949f9a69df05b3d6b200ec3d60c560fb
size 28607 size 29596

@ -1,3 +1,3 @@
version https://git-lfs.github.com/spec/v1 version https://git-lfs.github.com/spec/v1
oid sha256:3c74e04339b39aa20917d85d4a7743f18bca6a2d0a3d9524aead6dfb5843aec9 oid sha256:ded40649250d2bb047cadb87584e5f2bbbd1c8b88276ca8d7909acd11454cfa9
size 11857 size 12029

@ -1,3 +1,3 @@
version https://git-lfs.github.com/spec/v1 version https://git-lfs.github.com/spec/v1
oid sha256:33e2008b08a828e396f79169c888934a5a42a1acbae5e504222a4de345a3128e oid sha256:5969249d08301184bdfb0f90adeb23e518a892d38005c3b34ab1d32114f7820f
size 17417 size 18884

@ -0,0 +1,3 @@
version https://git-lfs.github.com/spec/v1
oid sha256:6e365ee08adc63a7d366dd283171bcd4b7f8e25825ea1d4fff09b36ba1ab754a
size 5454

@ -0,0 +1,3 @@
version https://git-lfs.github.com/spec/v1
oid sha256:259e9620ab3810be89004b58838f7a72edd4729928a899c3938d49c05bd10359
size 14199

@ -1,3 +1,3 @@
version https://git-lfs.github.com/spec/v1 version https://git-lfs.github.com/spec/v1
oid sha256:6d12f0cbf3624a4dbf05cd50fadcbf895507d84f869c741bc1c2876ea7bdf18f oid sha256:9299ceb39f13dfc8adac44ca5965713b64c76626f216de0d95505204229daed6
size 4193 size 4445

@ -1,3 +1,3 @@
version https://git-lfs.github.com/spec/v1 version https://git-lfs.github.com/spec/v1
oid sha256:6755f5a6a891a5ac691b5c916679a266cddfd0e1ea2cf2b66700197e03668ab6 oid sha256:933ccc120f3eb064619c1b1b7c69dee3d48492d7bbcbede5480f5e146aae103c
size 98679 size 101177

@ -1,3 +1,3 @@
version https://git-lfs.github.com/spec/v1 version https://git-lfs.github.com/spec/v1
oid sha256:eb3e1902761787e0d910b826baf6c4a9fb968a525e4463949244d53ec2430c6b oid sha256:17274e2daf731a43a8e28cb8da55e767cffe907a16d9d1338271494649a77715
size 10191 size 10723

@ -1,3 +1,3 @@
version https://git-lfs.github.com/spec/v1 version https://git-lfs.github.com/spec/v1
oid sha256:51a0b126e0f9fda18acc137766af4f5c669ec8d60e847b254aeb175388776548 oid sha256:8c2eb33568b8c3a7fdc13bab1c922329b6e7c55b0e99eb93becc3853ab9c1ae8
size 3917 size 4000

@ -1,3 +1,3 @@
version https://git-lfs.github.com/spec/v1 version https://git-lfs.github.com/spec/v1
oid sha256:f5b7c14eed81ec50f8cbbba42c74c71558df8d29651b682a90519b0918d9f5ae oid sha256:6dad085983af45f46d30dd3ac45615fe0224c4821992de7b8d20b0fff625878a
size 28559 size 29202

@ -1,3 +1,3 @@
version https://git-lfs.github.com/spec/v1 version https://git-lfs.github.com/spec/v1
oid sha256:3ba6545310bbb8c2cf6864278a3129d05c11b84ff9de2caa464397740b9ed8ca oid sha256:b8d2619181da8938064c8e867ae7b511e476002f6c33e73324f60ac88bea7f22
size 15359 size 15658

@ -1,3 +1,3 @@
version https://git-lfs.github.com/spec/v1 version https://git-lfs.github.com/spec/v1
oid sha256:25cbd49d4188265253ff16f537bb13b64b2d20957416009b8bf09704952dd318 oid sha256:90b41224841a3bc26fef52eed4f88b4a2c7e6c4ab08ebc3b943f45dde83847db
size 3677 size 3702

@ -1,3 +1,3 @@
version https://git-lfs.github.com/spec/v1 version https://git-lfs.github.com/spec/v1
oid sha256:a67e0da674dcf93f148072c1ac49666d2edf29ec954642a47a7d175c130a59a0 oid sha256:947332713be607beb2599a93f0d999b4019d096322766564fa1bcaed01b0eebd
size 751 size 778

@ -1,3 +1,3 @@
version https://git-lfs.github.com/spec/v1 version https://git-lfs.github.com/spec/v1
oid sha256:4e4cd82cf613ac671f5b5dde04063c8e2e556edfebdc34a0c971f9456a33a5cd oid sha256:122176a24fd4a96f0a14201ddea9883bf4ca279ba62aaec78c97bcf1eb3a3174
size 15987 size 15953

@ -44,11 +44,14 @@ generated_files = [
] + build_files ] + build_files
acados_dir = '#third_party/acados' acados_dir = '#third_party/acados'
acados_templates_dir = '#pyextra/acados_template/c_templates_tera'
source_list = ['lat_mpc.py', source_list = ['lat_mpc.py',
f'{acados_dir}/include/acados_c/ocp_nlp_interface.h', f'{acados_dir}/include/acados_c/ocp_nlp_interface.h',
f'{acados_dir}/aarch64/lib/libacados.so', f'{acados_dir}/aarch64/lib/libacados.so',
f'{acados_dir}/x86_64/lib/libacados.so', f'{acados_dir}/x86_64/lib/libacados.so',
f'{acados_dir}/larch64/lib/libacados.so', f'{acados_dir}/larch64/lib/libacados.so',
f'{acados_templates_dir}/acados_solver.in.c',
] ]
lenv = env.Clone() lenv = env.Clone()

@ -51,11 +51,14 @@ generated_files = [
] + build_files ] + build_files
acados_dir = '#third_party/acados' acados_dir = '#third_party/acados'
acados_templates_dir = '#pyextra/acados_template/c_templates_tera'
source_list = ['long_mpc.py', source_list = ['long_mpc.py',
f'{acados_dir}/include/acados_c/ocp_nlp_interface.h', f'{acados_dir}/include/acados_c/ocp_nlp_interface.h',
f'{acados_dir}/aarch64/lib/libacados.so', f'{acados_dir}/aarch64/lib/libacados.so',
f'{acados_dir}/x86_64/lib/libacados.so', f'{acados_dir}/x86_64/lib/libacados.so',
f'{acados_dir}/larch64/lib/libacados.so', f'{acados_dir}/larch64/lib/libacados.so',
f'{acados_templates_dir}/acados_solver.in.c',
] ]
lenv = env.Clone() lenv = env.Clone()

@ -192,11 +192,14 @@ def gen_long_ocp():
class LongitudinalMpc: class LongitudinalMpc:
def __init__(self, e2e=False): def __init__(self, e2e=False):
self.e2e = e2e self.e2e = e2e
self.solver = AcadosOcpSolverCython(MODEL_NAME, ACADOS_SOLVER_TYPE, N)
self.reset() self.reset()
self.source = SOURCES[2] self.source = SOURCES[2]
def reset(self): def reset(self):
self.solver = AcadosOcpSolverCython(MODEL_NAME, ACADOS_SOLVER_TYPE, N) # self.solver = AcadosOcpSolverCython(MODEL_NAME, ACADOS_SOLVER_TYPE, N)
self.solver.reset()
# self.solver.options_set('print_level', 2)
self.v_solution = np.zeros(N+1) self.v_solution = np.zeros(N+1)
self.a_solution = np.zeros(N+1) self.a_solution = np.zeros(N+1)
self.prev_a = np.array(self.a_solution) self.prev_a = np.array(self.a_solution)
@ -352,6 +355,8 @@ class LongitudinalMpc:
self.run() self.run()
def run(self): def run(self):
# t0 = sec_since_boot()
# reset = 0
for i in range(N+1): for i in range(N+1):
self.solver.set(i, 'p', self.params[i]) self.solver.set(i, 'p', self.params[i])
self.solver.constraints_set(0, "lbx", self.x0) self.solver.constraints_set(0, "lbx", self.x0)
@ -386,6 +391,8 @@ class LongitudinalMpc:
self.last_cloudlog_t = t self.last_cloudlog_t = t
cloudlog.warning(f"Long mpc reset, solution_status: {self.solution_status}") cloudlog.warning(f"Long mpc reset, solution_status: {self.solution_status}")
self.reset() self.reset()
# reset = 1
# print(f"long_mpc timings: total internal {self.solve_time:.2e}, external: {(sec_since_boot() - t0):.2e} qp {self.time_qp_solution:.2e}, lin {self.time_linearization:.2e} qp_iter {qp_iter}, reset {reset}")
if __name__ == "__main__": if __name__ == "__main__":

@ -1,3 +1,3 @@
version https://git-lfs.github.com/spec/v1 version https://git-lfs.github.com/spec/v1
oid sha256:a4d51bdef2544ba6c3b7cf119f464b29b48f4759f96490ec3561ae5fc1200cf9 oid sha256:fa02515dd1229ea78c0354189112f1d5ca777f581803d4344f744e80e3b2aa91
size 571865 size 576129

@ -1,3 +1,3 @@
version https://git-lfs.github.com/spec/v1 version https://git-lfs.github.com/spec/v1
oid sha256:802d85593bac49cbf325a7a05b3c2dd909f09843e462e4eea526faaad7cc33a8 oid sha256:ed4929ed8af91c883a28d53e491eca6e970cebc09669a3499db4cd380c937a9a
size 694257 size 1200745

@ -17,8 +17,8 @@ if [ ! -d acados_repo/ ]; then
# git clone https://github.com/commaai/acados.git $DIR/acados_repo # git clone https://github.com/commaai/acados.git $DIR/acados_repo
fi fi
cd acados_repo cd acados_repo
git fetch git fetch --all
git checkout 105e06df87f06ea02df4af825867c946b31defdd git checkout 8ea8827fafb1b23b4c7da1c4cf650de1cbd73584
git submodule update --recursive --init git submodule update --recursive --init
# build # build

@ -118,6 +118,8 @@ int dense_qp_qpoases(void *config, dense_qp_in *qp_in, dense_qp_out *qp_out, voi
// //
void dense_qp_qpoases_eval_sens(void *config_, void *qp_in, void *qp_out, void *opts_, void *mem_, void *work_); void dense_qp_qpoases_eval_sens(void *config_, void *qp_in, void *qp_out, void *opts_, void *mem_, void *work_);
// //
void dense_qp_qpoases_memory_reset(void *config_, void *qp_in, void *qp_out, void *opts_, void *mem_, void *work_);
//
void dense_qp_qpoases_config_initialize_default(void *config_); void dense_qp_qpoases_config_initialize_default(void *config_);
#ifdef __cplusplus #ifdef __cplusplus

@ -93,6 +93,7 @@ typedef struct ocp_nlp_config
char *field, int stage, int index, void *sens_nlp_out); char *field, int stage, int index, void *sens_nlp_out);
// prepare memory // prepare memory
int (*precompute)(void *config, void *dims, void *nlp_in, void *nlp_out, void *opts_, void *mem, void *work); int (*precompute)(void *config, void *dims, void *nlp_in, void *nlp_out, void *opts_, void *mem, void *work);
void (*memory_reset_qp_solver)(void *config, void *dims, void *nlp_in, void *nlp_out, void *opts_, void *mem, void *work);
// initalize this struct with default values // initalize this struct with default values
void (*config_initialize_default)(void *config); void (*config_initialize_default)(void *config);
// general getter // general getter
@ -306,6 +307,7 @@ typedef struct ocp_nlp_res
struct blasfeo_dvec *res_eq; // dynamics struct blasfeo_dvec *res_eq; // dynamics
struct blasfeo_dvec *res_ineq; // inequality constraints struct blasfeo_dvec *res_ineq; // inequality constraints
struct blasfeo_dvec *res_comp; // complementarity struct blasfeo_dvec *res_comp; // complementarity
struct blasfeo_dvec tmp; // tmp
double inf_norm_res_stat; double inf_norm_res_stat;
double inf_norm_res_eq; double inf_norm_res_eq;
double inf_norm_res_ineq; double inf_norm_res_ineq;
@ -402,7 +404,7 @@ ocp_nlp_workspace *ocp_nlp_workspace_assign(ocp_nlp_config *config, ocp_nlp_dims
void ocp_nlp_alias_memory_to_submodules(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in, void ocp_nlp_alias_memory_to_submodules(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in,
ocp_nlp_out *out, ocp_nlp_opts *opts, ocp_nlp_memory *mem, ocp_nlp_workspace *work); ocp_nlp_out *out, ocp_nlp_opts *opts, ocp_nlp_memory *mem, ocp_nlp_workspace *work);
// //
void ocp_nlp_initialize_qp(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in, void ocp_nlp_initialize_submodules(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in,
ocp_nlp_out *out, ocp_nlp_opts *opts, ocp_nlp_memory *mem, ocp_nlp_workspace *work); ocp_nlp_out *out, ocp_nlp_opts *opts, ocp_nlp_memory *mem, ocp_nlp_workspace *work);
// //
void ocp_nlp_approximate_qp_matrices(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in, void ocp_nlp_approximate_qp_matrices(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in,

@ -122,7 +122,9 @@ typedef struct
acados_size_t ocp_nlp_sqp_memory_calculate_size(void *config, void *dims, void *opts_); acados_size_t ocp_nlp_sqp_memory_calculate_size(void *config, void *dims, void *opts_);
// //
void *ocp_nlp_sqp_memory_assign(void *config, void *dims, void *opts_, void *raw_memory); void *ocp_nlp_sqp_memory_assign(void *config, void *dims, void *opts_, void *raw_memory);
//
void ocp_nlp_sqp_memory_reset_qp_solver(void *config_, void *dims_, void *nlp_in_, void *nlp_out_,
void *opts_, void *mem_, void *work_);
/************************************************ /************************************************

@ -72,6 +72,7 @@ typedef struct
void (*memory_get)(void *config_, void *mem_, const char *field, void* value); void (*memory_get)(void *config_, void *mem_, const char *field, void* value);
acados_size_t (*workspace_calculate_size)(void *config, void *dims, void *opts); acados_size_t (*workspace_calculate_size)(void *config, void *dims, void *opts);
int (*evaluate)(void *config, void *qp_in, void *qp_out, void *opts, void *mem, void *work); int (*evaluate)(void *config, void *qp_in, void *qp_out, void *opts, void *mem, void *work);
void (*memory_reset)(void *config, void *qp_in, void *qp_out, void *opts, void *mem, void *work);
void (*eval_sens)(void *config, void *qp_in, void *qp_out, void *opts, void *mem, void *work); void (*eval_sens)(void *config, void *qp_in, void *qp_out, void *opts, void *mem, void *work);
} qp_solver_config; } qp_solver_config;
#endif #endif

@ -63,6 +63,7 @@ typedef struct ocp_qp_hpipm_memory_
struct d_ocp_qp_ipm_ws *hpipm_workspace; struct d_ocp_qp_ipm_ws *hpipm_workspace;
double time_qp_solver_call; double time_qp_solver_call;
int iter; int iter;
int status;
} ocp_qp_hpipm_memory; } ocp_qp_hpipm_memory;
@ -87,6 +88,8 @@ acados_size_t ocp_qp_hpipm_workspace_calculate_size(void *config, void *dims, vo
// //
int ocp_qp_hpipm(void *config, void *qp_in, void *qp_out, void *opts_, void *mem_, void *work_); int ocp_qp_hpipm(void *config, void *qp_in, void *qp_out, void *opts_, void *mem_, void *work_);
// //
void ocp_qp_hpipm_memory_reset(void *config_, void *qp_in_, void *qp_out_, void *opts_, void *mem_, void *work_);
//
void ocp_qp_hpipm_eval_sens(void *config, void *qp_in, void *qp_out, void *opts_, void *mem_, void *work_); void ocp_qp_hpipm_eval_sens(void *config, void *qp_in, void *qp_out, void *opts_, void *mem_, void *work_);
// //
void ocp_qp_hpipm_config_initialize_default(void *config); void ocp_qp_hpipm_config_initialize_default(void *config);

@ -99,6 +99,7 @@ typedef struct ocp_qp_hpmpc_memory_
double time_qp_solver_call; double time_qp_solver_call;
int iter; int iter;
int status;
} ocp_qp_hpmpc_memory; } ocp_qp_hpmpc_memory;

@ -112,6 +112,7 @@ typedef struct ocp_qp_ooqp_memory_
int nnz; // max(nnzQ, nnzA, nnzC) int nnz; // max(nnzQ, nnzA, nnzC)
double time_qp_solver_call; double time_qp_solver_call;
int iter; int iter;
int status;
} ocp_qp_ooqp_memory; } ocp_qp_ooqp_memory;

@ -75,6 +75,7 @@ typedef struct ocp_qp_osqp_memory_
double time_qp_solver_call; double time_qp_solver_call;
int iter; int iter;
int status;
} ocp_qp_osqp_memory; } ocp_qp_osqp_memory;

@ -71,6 +71,7 @@ typedef struct ocp_qp_qpdunes_memory_
qpData_t qpData; qpData_t qpData;
double time_qp_solver_call; double time_qp_solver_call;
int iter; int iter;
int status;
} ocp_qp_qpdunes_memory; } ocp_qp_qpdunes_memory;

@ -92,6 +92,7 @@ typedef struct
acados_size_t (*memory_calculate_size)(void *config, ocp_qp_xcond_solver_dims *dims, void *opts); acados_size_t (*memory_calculate_size)(void *config, ocp_qp_xcond_solver_dims *dims, void *opts);
void *(*memory_assign)(void *config, ocp_qp_xcond_solver_dims *dims, void *opts, void *raw_memory); void *(*memory_assign)(void *config, ocp_qp_xcond_solver_dims *dims, void *opts, void *raw_memory);
void (*memory_get)(void *config_, void *mem_, const char *field, void* value); void (*memory_get)(void *config_, void *mem_, const char *field, void* value);
void (*memory_reset)(void *config, ocp_qp_xcond_solver_dims *dims, ocp_qp_in *qp_in, ocp_qp_out *qp_out, void *opts, void *mem, void *work);
acados_size_t (*workspace_calculate_size)(void *config, ocp_qp_xcond_solver_dims *dims, void *opts); acados_size_t (*workspace_calculate_size)(void *config, ocp_qp_xcond_solver_dims *dims, void *opts);
int (*evaluate)(void *config, ocp_qp_xcond_solver_dims *dims, ocp_qp_in *qp_in, ocp_qp_out *qp_out, void *opts, void *mem, void *work); int (*evaluate)(void *config, ocp_qp_xcond_solver_dims *dims, ocp_qp_in *qp_in, ocp_qp_out *qp_out, void *opts, void *mem, void *work);
void (*eval_sens)(void *config, ocp_qp_xcond_solver_dims *dims, ocp_qp_in *param_qp_in, ocp_qp_out *sens_qp_out, void *opts, void *mem, void *work); void (*eval_sens)(void *config, ocp_qp_xcond_solver_dims *dims, ocp_qp_in *param_qp_in, ocp_qp_out *sens_qp_out, void *opts, void *mem, void *work);

@ -96,6 +96,7 @@ typedef struct
struct blasfeo_dvec *u; // controls (nu) -- for expansion step struct blasfeo_dvec *u; // controls (nu) -- for expansion step
int update_sens; int update_sens;
// int init_K;
double time_sim; double time_sim;
double time_ad; double time_ad;

@ -35,6 +35,21 @@
#ifndef ACADOS_UTILS_TYPES_H_ #ifndef ACADOS_UTILS_TYPES_H_
#define ACADOS_UTILS_TYPES_H_ #define ACADOS_UTILS_TYPES_H_
/* Symbol visibility in DLLs */
#ifndef ACADOS_SYMBOL_EXPORT
#if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__)
#if defined(STATIC_LINKED)
#define ACADOS_SYMBOL_EXPORT
#else
#define ACADOS_SYMBOL_EXPORT __declspec(dllexport)
#endif
#elif defined(__GNUC__) && ((__GNUC__ >= 4) || (__GNUC__ == 3 && __GNUC_MINOR__ >= 4))
#define ACADOS_SYMBOL_EXPORT __attribute__ ((visibility ("default")))
#else
#define ACADOS_SYMBOL_EXPORT
#endif
#endif
#ifdef __cplusplus #ifdef __cplusplus
extern "C" { extern "C" {
#endif #endif

@ -46,6 +46,7 @@ extern "C" {
#include "acados/sim/sim_irk_integrator.h" #include "acados/sim/sim_irk_integrator.h"
#include "acados/sim/sim_lifted_irk_integrator.h" #include "acados/sim/sim_lifted_irk_integrator.h"
#include "acados/sim/sim_gnsf.h" #include "acados/sim/sim_gnsf.h"
#include "acados/utils/types.h"
// acados_c // acados_c
#include "acados_c/ocp_qp_interface.h" #include "acados_c/ocp_qp_interface.h"
#include "acados_c/sim_interface.h" #include "acados_c/sim_interface.h"
@ -151,46 +152,46 @@ typedef struct ocp_nlp_solver
/// default/invalid state. /// default/invalid state.
/// ///
/// \param N Horizon length /// \param N Horizon length
ocp_nlp_plan_t *ocp_nlp_plan_create(int N); ACADOS_SYMBOL_EXPORT ocp_nlp_plan_t *ocp_nlp_plan_create(int N);
/// Destructor for plan struct, frees memory. /// Destructor for plan struct, frees memory.
/// ///
/// \param plan_ The plan struct to destroy. /// \param plan_ The plan struct to destroy.
void ocp_nlp_plan_destroy(void* plan_); ACADOS_SYMBOL_EXPORT void ocp_nlp_plan_destroy(void* plan_);
/// Constructs an nlp configuration struct from a plan. /// Constructs an nlp configuration struct from a plan.
/// ///
/// \param plan The plan (user nlp configuration). /// \param plan The plan (user nlp configuration).
ocp_nlp_config *ocp_nlp_config_create(ocp_nlp_plan_t plan); ACADOS_SYMBOL_EXPORT ocp_nlp_config *ocp_nlp_config_create(ocp_nlp_plan_t plan);
/// Desctructor of the nlp configuration. /// Desctructor of the nlp configuration.
/// ///
/// \param config_ The configuration struct. /// \param config_ The configuration struct.
void ocp_nlp_config_destroy(void *config_); ACADOS_SYMBOL_EXPORT void ocp_nlp_config_destroy(void *config_);
/// Constructs an struct that contains the dimensions of the variables. /// Constructs an struct that contains the dimensions of the variables.
/// ///
/// \param config_ The configuration struct. /// \param config_ The configuration struct.
ocp_nlp_dims *ocp_nlp_dims_create(void *config_); ACADOS_SYMBOL_EXPORT ocp_nlp_dims *ocp_nlp_dims_create(void *config_);
/// Destructor of The dimension struct. /// Destructor of The dimension struct.
/// ///
/// \param dims_ The dimension struct. /// \param dims_ The dimension struct.
void ocp_nlp_dims_destroy(void *dims_); ACADOS_SYMBOL_EXPORT void ocp_nlp_dims_destroy(void *dims_);
/// Constructs an input struct for a non-linear programs. /// Constructs an input struct for a non-linear programs.
/// ///
/// \param config The configuration struct. /// \param config The configuration struct.
/// \param dims The dimension struct. /// \param dims The dimension struct.
ocp_nlp_in *ocp_nlp_in_create(ocp_nlp_config *config, ocp_nlp_dims *dims); ACADOS_SYMBOL_EXPORT ocp_nlp_in *ocp_nlp_in_create(ocp_nlp_config *config, ocp_nlp_dims *dims);
/// Destructor of the inputs struct. /// Destructor of the inputs struct.
/// ///
/// \param in The inputs struct. /// \param in The inputs struct.
void ocp_nlp_in_destroy(void *in); ACADOS_SYMBOL_EXPORT void ocp_nlp_in_destroy(void *in);
/// Sets the sampling times for the given stage. /// Sets the sampling times for the given stage.
@ -201,9 +202,12 @@ void ocp_nlp_in_destroy(void *in);
/// \param stage Stage number. /// \param stage Stage number.
/// \param field Has to be "Ts" (TBC other options). /// \param field Has to be "Ts" (TBC other options).
/// \param value The sampling times (floating point). /// \param value The sampling times (floating point).
void ocp_nlp_in_set(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in, int stage, ACADOS_SYMBOL_EXPORT void ocp_nlp_in_set(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in, int stage,
const char *field, void *value); const char *field, void *value);
///
// void ocp_nlp_in_get(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in, int stage,
// const char *field, void *value);
/// Sets the function pointers to the dynamics functions for the given stage. /// Sets the function pointers to the dynamics functions for the given stage.
/// ///
@ -214,7 +218,7 @@ void ocp_nlp_in_set(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in,
/// \param fun_type The name of the function type, either impl_ode_fun, /// \param fun_type The name of the function type, either impl_ode_fun,
/// impl_ode_fun_jac_x_xdot, impl_ode_jac_x_xdot_u (TBC) /// impl_ode_fun_jac_x_xdot, impl_ode_jac_x_xdot_u (TBC)
/// \param fun_ptr Function pointer to the dynamics function. /// \param fun_ptr Function pointer to the dynamics function.
int ocp_nlp_dynamics_model_set(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in, ACADOS_SYMBOL_EXPORT int ocp_nlp_dynamics_model_set(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in,
int stage, const char *fun_type, void *fun_ptr); int stage, const char *fun_type, void *fun_ptr);
@ -227,7 +231,7 @@ int ocp_nlp_dynamics_model_set(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_n
/// \param field The name of the field, either nls_res_jac, /// \param field The name of the field, either nls_res_jac,
/// y_ref, W (others TBC) /// y_ref, W (others TBC)
/// \param value Cost values. /// \param value Cost values.
int ocp_nlp_cost_model_set(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in, ACADOS_SYMBOL_EXPORT int ocp_nlp_cost_model_set(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in,
int stage, const char *field, void *value); int stage, const char *field, void *value);
@ -239,7 +243,7 @@ int ocp_nlp_cost_model_set(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_i
/// \param stage Stage number. /// \param stage Stage number.
/// \param field The name of the field, either lb, ub (others TBC) /// \param field The name of the field, either lb, ub (others TBC)
/// \param value Constraints function or values. /// \param value Constraints function or values.
int ocp_nlp_constraints_model_set(ocp_nlp_config *config, ocp_nlp_dims *dims, ACADOS_SYMBOL_EXPORT int ocp_nlp_constraints_model_set(ocp_nlp_config *config, ocp_nlp_dims *dims,
ocp_nlp_in *in, int stage, const char *field, void *value); ocp_nlp_in *in, int stage, const char *field, void *value);
/* out */ /* out */
@ -248,12 +252,12 @@ int ocp_nlp_constraints_model_set(ocp_nlp_config *config, ocp_nlp_dims *dims,
/// ///
/// \param config The configuration struct. /// \param config The configuration struct.
/// \param dims The dimension struct. /// \param dims The dimension struct.
ocp_nlp_out *ocp_nlp_out_create(ocp_nlp_config *config, ocp_nlp_dims *dims); ACADOS_SYMBOL_EXPORT ocp_nlp_out *ocp_nlp_out_create(ocp_nlp_config *config, ocp_nlp_dims *dims);
/// Destructor of the output struct. /// Destructor of the output struct.
/// ///
/// \param out The output struct. /// \param out The output struct.
void ocp_nlp_out_destroy(void *out); ACADOS_SYMBOL_EXPORT void ocp_nlp_out_destroy(void *out);
/// Sets fields in the output struct of an nlp solver, used to initialize the solver. /// Sets fields in the output struct of an nlp solver, used to initialize the solver.
@ -264,7 +268,7 @@ void ocp_nlp_out_destroy(void *out);
/// \param stage Stage number. /// \param stage Stage number.
/// \param field The name of the field, either x, u, pi. /// \param field The name of the field, either x, u, pi.
/// \param value Initialization values. /// \param value Initialization values.
void ocp_nlp_out_set(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_out *out, ACADOS_SYMBOL_EXPORT void ocp_nlp_out_set(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_out *out,
int stage, const char *field, void *value); int stage, const char *field, void *value);
@ -276,21 +280,21 @@ void ocp_nlp_out_set(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_out *ou
/// \param stage Stage number. /// \param stage Stage number.
/// \param field The name of the field, either x, u, z, pi. /// \param field The name of the field, either x, u, z, pi.
/// \param value Pointer to the output memory. /// \param value Pointer to the output memory.
void ocp_nlp_out_get(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_out *out, ACADOS_SYMBOL_EXPORT void ocp_nlp_out_get(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_out *out,
int stage, const char *field, void *value); int stage, const char *field, void *value);
// //
void ocp_nlp_get_at_stage(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_solver *solver, ACADOS_SYMBOL_EXPORT void ocp_nlp_get_at_stage(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_solver *solver,
int stage, const char *field, void *value); int stage, const char *field, void *value);
// TODO(andrea): remove this once/if the MATLAB interface uses the new setters below? // TODO(andrea): remove this once/if the MATLAB interface uses the new setters below?
int ocp_nlp_dims_get_from_attr(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_out *out, ACADOS_SYMBOL_EXPORT int ocp_nlp_dims_get_from_attr(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_out *out,
int stage, const char *field); int stage, const char *field);
void ocp_nlp_constraint_dims_get_from_attr(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_out *out, ACADOS_SYMBOL_EXPORT void ocp_nlp_constraint_dims_get_from_attr(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_out *out,
int stage, const char *field, int *dims_out); int stage, const char *field, int *dims_out);
void ocp_nlp_cost_dims_get_from_attr(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_out *out, ACADOS_SYMBOL_EXPORT void ocp_nlp_cost_dims_get_from_attr(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_out *out,
int stage, const char *field, int *dims_out); int stage, const char *field, int *dims_out);
void ocp_nlp_dynamics_dims_get_from_attr(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_out *out, void ocp_nlp_dynamics_dims_get_from_attr(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_out *out,
@ -302,12 +306,12 @@ void ocp_nlp_dynamics_dims_get_from_attr(ocp_nlp_config *config, ocp_nlp_dims *d
/// ///
/// \param config The configuration struct. /// \param config The configuration struct.
/// \param dims The dimension struct. /// \param dims The dimension struct.
void *ocp_nlp_solver_opts_create(ocp_nlp_config *config, ocp_nlp_dims *dims); ACADOS_SYMBOL_EXPORT void *ocp_nlp_solver_opts_create(ocp_nlp_config *config, ocp_nlp_dims *dims);
/// Destructor of the options. /// Destructor of the options.
/// ///
/// \param opts The options struct. /// \param opts The options struct.
void ocp_nlp_solver_opts_destroy(void *opts); ACADOS_SYMBOL_EXPORT void ocp_nlp_solver_opts_destroy(void *opts);
/// Sets an option. /// Sets an option.
/// ///
@ -315,10 +319,13 @@ void ocp_nlp_solver_opts_destroy(void *opts);
/// \param opts_ The options struct. /// \param opts_ The options struct.
/// \param field Name of the option. /// \param field Name of the option.
/// \param value Value of the option. /// \param value Value of the option.
void ocp_nlp_solver_opts_set(ocp_nlp_config *config, void *opts_, const char *field, void* value); ACADOS_SYMBOL_EXPORT void ocp_nlp_solver_opts_set(ocp_nlp_config *config, void *opts_, const char *field, void* value);
// ACADOS_SYMBOL_EXPORT void ocp_nlp_solver_opts_get(ocp_nlp_config *config, void *opts_, const char *field, void* value);
void ocp_nlp_solver_opts_set_at_stage(ocp_nlp_config *config, void *opts_, int stage, const char *field, void* value); ACADOS_SYMBOL_EXPORT void ocp_nlp_solver_opts_set_at_stage(ocp_nlp_config *config, void *opts_, int stage, const char *field, void* value);
/// TBC /// TBC
@ -327,7 +334,7 @@ void ocp_nlp_solver_opts_set_at_stage(ocp_nlp_config *config, void *opts_, int s
/// \param config The configuration struct. /// \param config The configuration struct.
/// \param dims The dimension struct. /// \param dims The dimension struct.
/// \param opts_ The options struct. /// \param opts_ The options struct.
void ocp_nlp_solver_opts_update(ocp_nlp_config *config, ocp_nlp_dims *dims, void *opts_); ACADOS_SYMBOL_EXPORT void ocp_nlp_solver_opts_update(ocp_nlp_config *config, ocp_nlp_dims *dims, void *opts_);
/* solver */ /* solver */
@ -338,12 +345,12 @@ void ocp_nlp_solver_opts_update(ocp_nlp_config *config, ocp_nlp_dims *dims, void
/// \param dims The dimension struct. /// \param dims The dimension struct.
/// \param opts_ The options struct. /// \param opts_ The options struct.
/// \return The solver. /// \return The solver.
ocp_nlp_solver *ocp_nlp_solver_create(ocp_nlp_config *config, ocp_nlp_dims *dims, void *opts_); ACADOS_SYMBOL_EXPORT ocp_nlp_solver *ocp_nlp_solver_create(ocp_nlp_config *config, ocp_nlp_dims *dims, void *opts_);
/// Destructor of the solver. /// Destructor of the solver.
/// ///
/// \param solver The solver struct. /// \param solver The solver struct.
void ocp_nlp_solver_destroy(void *solver); ACADOS_SYMBOL_EXPORT void ocp_nlp_solver_destroy(void *solver);
/// Solves the optimal control problem. Call ocp_nlp_precompute before /// Solves the optimal control problem. Call ocp_nlp_precompute before
/// calling this functions (TBC). /// calling this functions (TBC).
@ -351,7 +358,17 @@ void ocp_nlp_solver_destroy(void *solver);
/// \param solver The solver struct. /// \param solver The solver struct.
/// \param nlp_in The inputs struct. /// \param nlp_in The inputs struct.
/// \param nlp_out The output struct. /// \param nlp_out The output struct.
int ocp_nlp_solve(ocp_nlp_solver *solver, ocp_nlp_in *nlp_in, ocp_nlp_out *nlp_out); ACADOS_SYMBOL_EXPORT int ocp_nlp_solve(ocp_nlp_solver *solver, ocp_nlp_in *nlp_in, ocp_nlp_out *nlp_out);
/// Resets the memory of the QP solver
///
/// \param solver The solver struct.
/// \param nlp_in The inputs struct.
/// \param nlp_out The output struct.
ACADOS_SYMBOL_EXPORT void ocp_nlp_solver_reset_qp_memory(ocp_nlp_solver *solver, ocp_nlp_in *nlp_in, ocp_nlp_out *nlp_out);
/// Performs precomputations for the solver. Needs to be called before /// Performs precomputations for the solver. Needs to be called before
/// ocl_nlp_solve (TBC). /// ocl_nlp_solve (TBC).
@ -359,7 +376,7 @@ int ocp_nlp_solve(ocp_nlp_solver *solver, ocp_nlp_in *nlp_in, ocp_nlp_out *nlp_o
/// \param solver The solver struct. /// \param solver The solver struct.
/// \param nlp_in The inputs struct. /// \param nlp_in The inputs struct.
/// \param nlp_out The output struct. /// \param nlp_out The output struct.
int ocp_nlp_precompute(ocp_nlp_solver *solver, ocp_nlp_in *nlp_in, ocp_nlp_out *nlp_out); ACADOS_SYMBOL_EXPORT int ocp_nlp_precompute(ocp_nlp_solver *solver, ocp_nlp_in *nlp_in, ocp_nlp_out *nlp_out);
/// Computes cost function value. /// Computes cost function value.
@ -367,7 +384,7 @@ int ocp_nlp_precompute(ocp_nlp_solver *solver, ocp_nlp_in *nlp_in, ocp_nlp_out *
/// \param solver The solver struct. /// \param solver The solver struct.
/// \param nlp_in The inputs struct. /// \param nlp_in The inputs struct.
/// \param nlp_out The output struct. /// \param nlp_out The output struct.
void ocp_nlp_eval_cost(ocp_nlp_solver *solver, ocp_nlp_in *nlp_in, ocp_nlp_out *nlp_out); ACADOS_SYMBOL_EXPORT void ocp_nlp_eval_cost(ocp_nlp_solver *solver, ocp_nlp_in *nlp_in, ocp_nlp_out *nlp_out);
// //
void ocp_nlp_eval_residuals(ocp_nlp_solver *solver, ocp_nlp_in *nlp_in, ocp_nlp_out *nlp_out); void ocp_nlp_eval_residuals(ocp_nlp_solver *solver, ocp_nlp_in *nlp_in, ocp_nlp_out *nlp_out);
@ -377,18 +394,18 @@ void ocp_nlp_eval_residuals(ocp_nlp_solver *solver, ocp_nlp_in *nlp_in, ocp_nlp_
/// \param solver The solver struct. /// \param solver The solver struct.
/// \param nlp_in The inputs struct. /// \param nlp_in The inputs struct.
/// \param nlp_out The output struct. /// \param nlp_out The output struct.
void ocp_nlp_eval_residuals(ocp_nlp_solver *solver, ocp_nlp_in *nlp_in, ocp_nlp_out *nlp_out); ACADOS_SYMBOL_EXPORT void ocp_nlp_eval_residuals(ocp_nlp_solver *solver, ocp_nlp_in *nlp_in, ocp_nlp_out *nlp_out);
// //
void ocp_nlp_eval_param_sens(ocp_nlp_solver *solver, char *field, int stage, int index, ocp_nlp_out *sens_nlp_out); ACADOS_SYMBOL_EXPORT void ocp_nlp_eval_param_sens(ocp_nlp_solver *solver, char *field, int stage, int index, ocp_nlp_out *sens_nlp_out);
/* get */ /* get */
/// \param config The configuration struct. /// \param config The configuration struct.
/// \param solver The solver struct. /// \param solver The solver struct.
/// \param field Supports "sqp_iter", "status", "nlp_res", "time_tot", ... /// \param field Supports "sqp_iter", "status", "nlp_res", "time_tot", ...
/// \param return_value_ Pointer to the output memory. /// \param return_value_ Pointer to the output memory.
void ocp_nlp_get(ocp_nlp_config *config, ocp_nlp_solver *solver, ACADOS_SYMBOL_EXPORT void ocp_nlp_get(ocp_nlp_config *config, ocp_nlp_solver *solver,
const char *field, void *return_value_); const char *field, void *return_value_);
/* set */ /* set */
@ -399,7 +416,7 @@ void ocp_nlp_get(ocp_nlp_config *config, ocp_nlp_solver *solver,
/// \param stage Stage number. /// \param stage Stage number.
/// \param field Supports "z_guess", "xdot_guess" (IRK), "phi_guess" (GNSF-IRK) /// \param field Supports "z_guess", "xdot_guess" (IRK), "phi_guess" (GNSF-IRK)
/// \param value The initial guess for the algebraic variables in the integrator (if continuous model is used). /// \param value The initial guess for the algebraic variables in the integrator (if continuous model is used).
void ocp_nlp_set(ocp_nlp_config *config, ocp_nlp_solver *solver, ACADOS_SYMBOL_EXPORT void ocp_nlp_set(ocp_nlp_config *config, ocp_nlp_solver *solver,
int stage, const char *field, void *value); int stage, const char *field, void *value);

@ -74,64 +74,64 @@ typedef struct
/* config */ /* config */
// //
sim_config *sim_config_create(sim_solver_plan_t plan); ACADOS_SYMBOL_EXPORT sim_config *sim_config_create(sim_solver_plan_t plan);
// //
void sim_config_destroy(void *config); ACADOS_SYMBOL_EXPORT void sim_config_destroy(void *config);
/* dims */ /* dims */
// //
void *sim_dims_create(void *config_); ACADOS_SYMBOL_EXPORT void *sim_dims_create(void *config_);
// //
void sim_dims_destroy(void *dims); ACADOS_SYMBOL_EXPORT void sim_dims_destroy(void *dims);
// //
void sim_dims_set(sim_config *config, void *dims, const char *field, const int* value); ACADOS_SYMBOL_EXPORT void sim_dims_set(sim_config *config, void *dims, const char *field, const int* value);
// //
void sim_dims_get(sim_config *config, void *dims, const char *field, int* value); ACADOS_SYMBOL_EXPORT void sim_dims_get(sim_config *config, void *dims, const char *field, int* value);
// //
void sim_dims_get_from_attr(sim_config *config, void *dims, const char *field, int *dims_out); ACADOS_SYMBOL_EXPORT void sim_dims_get_from_attr(sim_config *config, void *dims, const char *field, int *dims_out);
/* in */ /* in */
// //
sim_in *sim_in_create(sim_config *config, void *dims); ACADOS_SYMBOL_EXPORT sim_in *sim_in_create(sim_config *config, void *dims);
// //
void sim_in_destroy(void *out); ACADOS_SYMBOL_EXPORT void sim_in_destroy(void *out);
// //
int sim_in_set(void *config_, void *dims_, sim_in *in, const char *field, void *value); ACADOS_SYMBOL_EXPORT int sim_in_set(void *config_, void *dims_, sim_in *in, const char *field, void *value);
/* out */ /* out */
// //
sim_out *sim_out_create(sim_config *config, void *dims); ACADOS_SYMBOL_EXPORT sim_out *sim_out_create(sim_config *config, void *dims);
// //
void sim_out_destroy(void *out); ACADOS_SYMBOL_EXPORT void sim_out_destroy(void *out);
// //
int sim_out_get(void *config, void *dims, sim_out *out, const char *field, void *value); ACADOS_SYMBOL_EXPORT int sim_out_get(void *config, void *dims, sim_out *out, const char *field, void *value);
/* opts */ /* opts */
// //
void *sim_opts_create(sim_config *config, void *dims); ACADOS_SYMBOL_EXPORT void *sim_opts_create(sim_config *config, void *dims);
// //
void sim_opts_destroy(void *opts); ACADOS_SYMBOL_EXPORT void sim_opts_destroy(void *opts);
// //
void sim_opts_set(sim_config *config, void *opts, const char *field, void *value); ACADOS_SYMBOL_EXPORT void sim_opts_set(sim_config *config, void *opts, const char *field, void *value);
// //
void sim_opts_get(sim_config *config, void *opts, const char *field, void *value); ACADOS_SYMBOL_EXPORT void sim_opts_get(sim_config *config, void *opts, const char *field, void *value);
/* solver */ /* solver */
// //
acados_size_t sim_calculate_size(sim_config *config, void *dims, void *opts_); ACADOS_SYMBOL_EXPORT acados_size_t sim_calculate_size(sim_config *config, void *dims, void *opts_);
// //
sim_solver *sim_assign(sim_config *config, void *dims, void *opts_, void *raw_memory); ACADOS_SYMBOL_EXPORT sim_solver *sim_assign(sim_config *config, void *dims, void *opts_, void *raw_memory);
// //
sim_solver *sim_solver_create(sim_config *config, void *dims, void *opts_); ACADOS_SYMBOL_EXPORT sim_solver *sim_solver_create(sim_config *config, void *dims, void *opts_);
// //
void sim_solver_destroy(void *solver); ACADOS_SYMBOL_EXPORT void sim_solver_destroy(void *solver);
// //
int sim_solve(sim_solver *solver, sim_in *in, sim_out *out); ACADOS_SYMBOL_EXPORT int sim_solve(sim_solver *solver, sim_in *in, sim_out *out);
// //
int sim_precompute(sim_solver *solver, sim_in *in, sim_out *out); ACADOS_SYMBOL_EXPORT int sim_precompute(sim_solver *solver, sim_in *in, sim_out *out);
// //
int sim_solver_set(sim_solver *solver, const char *field, void *value); ACADOS_SYMBOL_EXPORT int sim_solver_set(sim_solver *solver, const char *field, void *value);
#ifdef __cplusplus #ifdef __cplusplus
} /* extern "C" */ } /* extern "C" */

@ -53,6 +53,7 @@
#define D_PS 8 // panel size #define D_PS 8 // panel size
#define D_PLD 8 // 4 // GCD of panel length #define D_PLD 8 // 4 // GCD of panel length
#define D_M_KERNEL 24 // max kernel size #define D_M_KERNEL 24 // max kernel size
#define D_N_KERNEL 8 // max kernel size
#define D_KC 128 //256 // 192 #define D_KC 128 //256 // 192
#define D_NC 144 //72 //96 //72 // 120 // 512 #define D_NC 144 //72 //96 //72 // 120 // 512
#define D_MC 2400 // 6000 #define D_MC 2400 // 6000
@ -60,6 +61,7 @@
#define S_PS 16 // panel size #define S_PS 16 // panel size
#define S_PLD 4 // GCD of panel length TODO probably 16 when writing assebly #define S_PLD 4 // GCD of panel length TODO probably 16 when writing assebly
#define S_M_KERNEL 32 // max kernel size #define S_M_KERNEL 32 // max kernel size
#define S_N_KERNEL 8 // max kernel size
#define S_KC 128 //256 #define S_KC 128 //256
#define S_NC 128 //144 #define S_NC 128 //144
#define S_MC 3000 #define S_MC 3000
@ -74,13 +76,15 @@
#define D_PS 4 // panel size #define D_PS 4 // panel size
#define D_PLD 4 // 2 // GCD of panel length #define D_PLD 4 // 2 // GCD of panel length
#define D_M_KERNEL 12 // max kernel size #define D_M_KERNEL 12 // max kernel size
#define D_N_KERNEL 8 // max kernel size
#define D_KC 256 // 192 #define D_KC 256 // 192
#define D_NC 72 //96 //72 // 120 // 512 #define D_NC 64 //96 //72 // 120 // 512
#define D_MC 1500 // 6000 #define D_MC 1500
// single // single
#define S_PS 8 // panel size #define S_PS 8 // panel size
#define S_PLD 4 // 2 // GCD of panel length #define S_PLD 4 // 2 // GCD of panel length
#define S_M_KERNEL 24 // max kernel size #define S_M_KERNEL 24 // max kernel size
#define S_N_KERNEL 8 // max kernel size
#define S_KC 256 #define S_KC 256
#define S_NC 144 #define S_NC 144
#define S_MC 3000 #define S_MC 3000
@ -95,6 +99,7 @@
#define D_PS 4 // panel size #define D_PS 4 // panel size
#define D_PLD 4 // 2 // GCD of panel length #define D_PLD 4 // 2 // GCD of panel length
#define D_M_KERNEL 8 // max kernel size #define D_M_KERNEL 8 // max kernel size
#define D_N_KERNEL 4 // max kernel size
#define D_KC 256 //320 //256 //320 #define D_KC 256 //320 //256 //320
#define D_NC 72 //64 //72 //60 // 120 #define D_NC 72 //64 //72 //60 // 120
#define D_MC 1000 // 800 #define D_MC 1000 // 800
@ -102,6 +107,7 @@
#define S_PS 8 // panel size #define S_PS 8 // panel size
#define S_PLD 4 // 2 // GCD of panel length #define S_PLD 4 // 2 // GCD of panel length
#define S_M_KERNEL 16 // max kernel size #define S_M_KERNEL 16 // max kernel size
#define S_N_KERNEL 8 // max kernel size
#define S_KC 256 #define S_KC 256
#define S_NC 144 #define S_NC 144
#define S_MC 2000 #define S_MC 2000
@ -114,6 +120,7 @@
#define D_PS 4 // panel size #define D_PS 4 // panel size
#define D_PLD 4 // 2 // GCD of panel length #define D_PLD 4 // 2 // GCD of panel length
#define D_M_KERNEL 4 // max kernel size #define D_M_KERNEL 4 // max kernel size
#define D_N_KERNEL 4 // max kernel size
#define D_KC 256 #define D_KC 256
#define D_NC 128 // TODO these are just dummy #define D_NC 128 // TODO these are just dummy
#define D_MC 3000 // TODO these are just dummy #define D_MC 3000 // TODO these are just dummy
@ -121,6 +128,7 @@
#define S_PS 4 #define S_PS 4
#define S_PLD 4 //2 #define S_PLD 4 //2
#define S_M_KERNEL 4 // max kernel size #define S_M_KERNEL 4 // max kernel size
#define S_N_KERNEL 4 // max kernel size
#define S_KC 256 #define S_KC 256
#define S_NC 128 // TODO these are just dummy #define S_NC 128 // TODO these are just dummy
#define S_MC 3000 // TODO these are just dummy #define S_MC 3000 // TODO these are just dummy
@ -133,6 +141,7 @@
#define D_PS 4 // panel size #define D_PS 4 // panel size
#define D_PLD 4 // 2 // GCD of panel length #define D_PLD 4 // 2 // GCD of panel length
#define D_M_KERNEL 4 // max kernel size #define D_M_KERNEL 4 // max kernel size
#define D_N_KERNEL 4 // max kernel size
#define D_KC 256 #define D_KC 256
#define D_NC 128 // TODO these are just dummy #define D_NC 128 // TODO these are just dummy
#define D_MC 3000 // TODO these are just dummy #define D_MC 3000 // TODO these are just dummy
@ -140,6 +149,7 @@
#define S_PS 4 #define S_PS 4
#define S_PLD 4 //2 #define S_PLD 4 //2
#define S_M_KERNEL 4 // max kernel size #define S_M_KERNEL 4 // max kernel size
#define S_N_KERNEL 4 // max kernel size
#define S_KC 256 #define S_KC 256
#define S_NC 128 // TODO these are just dummy #define S_NC 128 // TODO these are just dummy
#define S_MC 3000 // TODO these are just dummy #define S_MC 3000 // TODO these are just dummy
@ -153,6 +163,7 @@
#define D_PS 4 // panel size #define D_PS 4 // panel size
#define D_PLD 4 // 2 // GCD of panel length #define D_PLD 4 // 2 // GCD of panel length
#define D_M_KERNEL 4 // max kernel size #define D_M_KERNEL 4 // max kernel size
#define D_N_KERNEL 4 // max kernel size
#define D_KC 256 #define D_KC 256
#define D_NC 128 // TODO these are just dummy #define D_NC 128 // TODO these are just dummy
#define D_MC 3000 // TODO these are just dummy #define D_MC 3000 // TODO these are just dummy
@ -160,6 +171,7 @@
#define S_PS 4 #define S_PS 4
#define S_PLD 4 //2 #define S_PLD 4 //2
#define S_M_KERNEL 4 // max kernel size #define S_M_KERNEL 4 // max kernel size
#define S_N_KERNEL 4 // max kernel size
#define S_KC 256 #define S_KC 256
#define S_NC 128 // TODO these are just dummy #define S_NC 128 // TODO these are just dummy
#define S_MC 3000 // TODO these are just dummy #define S_MC 3000 // TODO these are just dummy
@ -173,6 +185,7 @@
#define D_PS 4 // panel size #define D_PS 4 // panel size
#define D_PLD 4 // 2 // GCD of panel length #define D_PLD 4 // 2 // GCD of panel length
#define D_M_KERNEL 4 // max kernel size #define D_M_KERNEL 4 // max kernel size
#define D_N_KERNEL 4 // max kernel size
#define D_KC 256 #define D_KC 256
#define D_NC 128 // TODO these are just dummy #define D_NC 128 // TODO these are just dummy
#define D_MC 3000 // TODO these are just dummy #define D_MC 3000 // TODO these are just dummy
@ -180,11 +193,35 @@
#define S_PS 4 #define S_PS 4
#define S_PLD 4 //2 #define S_PLD 4 //2
#define S_M_KERNEL 4 // max kernel size #define S_M_KERNEL 4 // max kernel size
#define S_N_KERNEL 4 // max kernel size
#define S_KC 256 #define S_KC 256
#define S_NC 128 // TODO these are just dummy #define S_NC 128 // TODO these are just dummy
#define S_MC 3000 // TODO these are just dummy #define S_MC 3000 // TODO these are just dummy
#elif defined(TARGET_ARMV8A_APPLE_M1)
// common
#define CACHE_LINE_SIZE 64
#define L1_CACHE_SIZE (128*1024) // L1 data cache size (big cores): 64 kB, ?-way ; DTLB1 ?
#define LLC_CACHE_SIZE (12*1024*1024) // LLC (L2) cache size (big cores): 12 MB
// double
#define D_PS 4 // panel size
#define D_PLD 4 // 2 // GCD of panel length
#define D_M_KERNEL 8 // max kernel size
#define D_N_KERNEL 4 // max kernel size
#define D_KC 512 //256
#define D_NC 128 //256
#define D_MC 6000
// single
#define S_PS 4
#define S_PLD 4 //2
#define S_M_KERNEL 8 // max kernel size
#define S_N_KERNEL 8 // max kernel size
#define S_KC 512
#define S_NC 256
#define S_MC 6000
#elif defined(TARGET_ARMV8A_ARM_CORTEX_A76) #elif defined(TARGET_ARMV8A_ARM_CORTEX_A76)
// common // common
#define CACHE_LINE_SIZE 64 #define CACHE_LINE_SIZE 64
@ -194,6 +231,7 @@
#define D_PS 4 // panel size #define D_PS 4 // panel size
#define D_PLD 4 // 2 // GCD of panel length #define D_PLD 4 // 2 // GCD of panel length
#define D_M_KERNEL 8 // max kernel size #define D_M_KERNEL 8 // max kernel size
#define D_N_KERNEL 4 // max kernel size
#define D_KC 512 //256 #define D_KC 512 //256
#define D_NC 128 //256 #define D_NC 128 //256
#define D_MC 6000 #define D_MC 6000
@ -201,6 +239,7 @@
#define S_PS 4 #define S_PS 4
#define S_PLD 4 //2 #define S_PLD 4 //2
#define S_M_KERNEL 8 // max kernel size #define S_M_KERNEL 8 // max kernel size
#define S_N_KERNEL 8 // max kernel size
#define S_KC 512 #define S_KC 512
#define S_NC 256 #define S_NC 256
#define S_MC 6000 #define S_MC 6000
@ -215,6 +254,7 @@
#define D_PS 4 // panel size #define D_PS 4 // panel size
#define D_PLD 4 // 2 // GCD of panel length #define D_PLD 4 // 2 // GCD of panel length
#define D_M_KERNEL 8 // max kernel size #define D_M_KERNEL 8 // max kernel size
#define D_N_KERNEL 4 // max kernel size
#define D_KC 320 #define D_KC 320
#define D_NC 256 #define D_NC 256
#define D_MC 6000 #define D_MC 6000
@ -222,6 +262,7 @@
#define S_PS 4 #define S_PS 4
#define S_PLD 4 //2 #define S_PLD 4 //2
#define S_M_KERNEL 8 // max kernel size #define S_M_KERNEL 8 // max kernel size
#define S_N_KERNEL 8 // max kernel size
#define S_KC 256 #define S_KC 256
#define S_NC 128 // TODO these are just dummy #define S_NC 128 // TODO these are just dummy
#define S_MC 3000 // TODO these are just dummy #define S_MC 3000 // TODO these are just dummy
@ -236,13 +277,15 @@
#define D_PS 4 // panel size #define D_PS 4 // panel size
#define D_PLD 4 // 2 // GCD of panel length #define D_PLD 4 // 2 // GCD of panel length
#define D_M_KERNEL 8 // max kernel size #define D_M_KERNEL 8 // max kernel size
#define D_KC 224 //256 //192 #define D_N_KERNEL 4 // max kernel size
#define D_NC 40 //36 //48 #define D_KC 128 //224 //256 //192
#define D_MC 512 //488 //600 #define D_NC 72 //40 //36 //48
#define D_MC (4*192) //512 //488 //600
// single // single
#define S_PS 4 #define S_PS 4
#define S_PLD 4 //2 #define S_PLD 4 //2
#define S_M_KERNEL 8 // max kernel size #define S_M_KERNEL 8 // max kernel size
#define S_N_KERNEL 8 // max kernel size
#define S_KC 256 #define S_KC 256
#define S_NC 128 // TODO these are just dummy #define S_NC 128 // TODO these are just dummy
#define S_MC 3000 // TODO these are just dummy #define S_MC 3000 // TODO these are just dummy
@ -257,6 +300,7 @@
#define D_PS 4 // panel size #define D_PS 4 // panel size
#define D_PLD 4 // 2 // GCD of panel length #define D_PLD 4 // 2 // GCD of panel length
#define D_M_KERNEL 12 // max kernel size #define D_M_KERNEL 12 // max kernel size
#define D_N_KERNEL 4 // max kernel size
#define D_KC 224 #define D_KC 224
#define D_NC 160 #define D_NC 160
#define D_MC 6000 #define D_MC 6000
@ -264,6 +308,7 @@
#define S_PS 4 #define S_PS 4
#define S_PLD 4 //2 #define S_PLD 4 //2
#define S_M_KERNEL 8 // max kernel size #define S_M_KERNEL 8 // max kernel size
#define S_N_KERNEL 8 // max kernel size
#define S_KC 256 #define S_KC 256
#define S_NC 128 // TODO these are just dummy #define S_NC 128 // TODO these are just dummy
#define S_MC 3000 // TODO these are just dummy #define S_MC 3000 // TODO these are just dummy
@ -278,6 +323,7 @@
#define D_PS 4 // panel size #define D_PS 4 // panel size
#define D_PLD 4 // 2 // GCD of panel length #define D_PLD 4 // 2 // GCD of panel length
#define D_M_KERNEL 12 // max kernel size #define D_M_KERNEL 12 // max kernel size
#define D_N_KERNEL 4 // max kernel size
#define D_KC 160 #define D_KC 160
#define D_NC 128 #define D_NC 128
#define D_MC 6000 #define D_MC 6000
@ -285,6 +331,7 @@
#define S_PS 4 #define S_PS 4
#define S_PLD 4 //2 #define S_PLD 4 //2
#define S_M_KERNEL 8 // max kernel size #define S_M_KERNEL 8 // max kernel size
#define S_N_KERNEL 8 // max kernel size
#define S_KC 256 #define S_KC 256
#define S_NC 128 // TODO these are just dummy #define S_NC 128 // TODO these are just dummy
#define S_MC 3000 // TODO these are just dummy #define S_MC 3000 // TODO these are just dummy
@ -298,6 +345,7 @@
#define D_PS 4 // panel size #define D_PS 4 // panel size
#define D_PLD 4 // 2 // GCD of panel length #define D_PLD 4 // 2 // GCD of panel length
#define D_M_KERNEL 4 // max kernel size #define D_M_KERNEL 4 // max kernel size
#define D_N_KERNEL 4 // max kernel size
#define D_KC 256 #define D_KC 256
#define D_NC 128 // TODO these are just dummy #define D_NC 128 // TODO these are just dummy
#define D_MC 3000 // TODO these are just dummy #define D_MC 3000 // TODO these are just dummy
@ -305,6 +353,7 @@
#define S_PS 4 #define S_PS 4
#define S_PLD 4 //2 #define S_PLD 4 //2
#define S_M_KERNEL 4 // max kernel size #define S_M_KERNEL 4 // max kernel size
#define S_N_KERNEL 4 // max kernel size
#define S_KC 256 #define S_KC 256
#define S_NC 128 // TODO these are just dummy #define S_NC 128 // TODO these are just dummy
#define S_MC 3000 // TODO these are just dummy #define S_MC 3000 // TODO these are just dummy
@ -318,6 +367,7 @@
#define D_PS 4 // panel size #define D_PS 4 // panel size
#define D_PLD 4 // 2 // GCD of panel length #define D_PLD 4 // 2 // GCD of panel length
#define D_M_KERNEL 4 // max kernel size #define D_M_KERNEL 4 // max kernel size
#define D_N_KERNEL 4 // max kernel size
#define D_KC 256 #define D_KC 256
#define D_NC 128 // TODO these are just dummy #define D_NC 128 // TODO these are just dummy
#define D_MC 3000 // TODO these are just dummy #define D_MC 3000 // TODO these are just dummy
@ -325,6 +375,7 @@
#define S_PS 4 #define S_PS 4
#define S_PLD 4 //2 #define S_PLD 4 //2
#define S_M_KERNEL 4 // max kernel size #define S_M_KERNEL 4 // max kernel size
#define S_N_KERNEL 4 // max kernel size
#define S_KC 256 #define S_KC 256
#define S_NC 128 // TODO these are just dummy #define S_NC 128 // TODO these are just dummy
#define S_MC 3000 // TODO these are just dummy #define S_MC 3000 // TODO these are just dummy
@ -338,6 +389,7 @@
#define D_PS 4 // panel size #define D_PS 4 // panel size
#define D_PLD 4 // 2 // GCD of panel length #define D_PLD 4 // 2 // GCD of panel length
#define D_M_KERNEL 4 // max kernel size #define D_M_KERNEL 4 // max kernel size
#define D_N_KERNEL 4 // max kernel size
#define D_KC 256 #define D_KC 256
#define D_NC 128 // TODO these are just dummy #define D_NC 128 // TODO these are just dummy
#define D_MC 3000 // TODO these are just dummy #define D_MC 3000 // TODO these are just dummy
@ -345,6 +397,7 @@
#define S_PS 4 #define S_PS 4
#define S_PLD 4 //2 #define S_PLD 4 //2
#define S_M_KERNEL 4 // max kernel size #define S_M_KERNEL 4 // max kernel size
#define S_N_KERNEL 4 // max kernel size
#define S_KC 256 #define S_KC 256
#define S_NC 128 // TODO these are just dummy #define S_NC 128 // TODO these are just dummy
#define S_MC 3000 // TODO these are just dummy #define S_MC 3000 // TODO these are just dummy
@ -358,6 +411,7 @@
#define D_PS 4 // panel size #define D_PS 4 // panel size
#define D_PLD 4 // 2 // GCD of panel length #define D_PLD 4 // 2 // GCD of panel length
#define D_M_KERNEL 4 // max kernel size #define D_M_KERNEL 4 // max kernel size
#define D_N_KERNEL 4 // max kernel size
#define D_KC 256 #define D_KC 256
#define D_NC 128 // TODO these are just dummy #define D_NC 128 // TODO these are just dummy
#define D_MC 3000 // TODO these are just dummy #define D_MC 3000 // TODO these are just dummy
@ -366,6 +420,7 @@
#define S_PS 4 #define S_PS 4
#define S_PLD 4 //2 #define S_PLD 4 //2
#define S_M_KERNEL 4 // max kernel size #define S_M_KERNEL 4 // max kernel size
#define S_N_KERNEL 4 // max kernel size
#define S_KC 256 #define S_KC 256
#define S_NC 128 // TODO these are just dummy #define S_NC 128 // TODO these are just dummy
#define S_MC 3000 // TODO these are just dummy #define S_MC 3000 // TODO these are just dummy

@ -198,6 +198,24 @@ struct blasfeo_pm_smat
int memsize; // size of needed memory int memsize; // size of needed memory
}; };
struct blasfeo_pm_dvec
{
double *mem; // pointer to passed chunk of memory
double *pa; // pointer to a pm array of doubles, the first is aligned to cache line size
int m; // size
int pm; // packed size
int memsize; // size of needed memory
};
struct blasfeo_pm_svec
{
float *mem; // pointer to passed chunk of memory
float *pa; // pointer to a pm array of floats, the first is aligned to cache line size
int m; // size
int pm; // packed size
int memsize; // size of needed memory
};
// Explicitly column-major matrix structure // Explicitly column-major matrix structure
struct blasfeo_cm_dmat struct blasfeo_cm_dmat
{ {
@ -221,11 +239,31 @@ struct blasfeo_cm_smat
int memsize; // size of needed memory int memsize; // size of needed memory
}; };
struct blasfeo_cm_dvec
{
double *mem; // pointer to passed chunk of memory
double *pa; // pointer to a m array of doubles, the first is aligned to cache line size
int m; // size
int memsize; // size of needed memory
};
struct blasfeo_cm_svec
{
float *mem; // pointer to passed chunk of memory
float *pa; // pointer to a m array of floats, the first is aligned to cache line size
int m; // size
int memsize; // size of needed memory
};
#define BLASFEO_PM_DMATEL(sA,ai,aj) ((sA)->pA[((ai)-((ai)&((sA)->ps-1)))*(sA)->cn+(aj)*((sA)->ps)+((ai)&((sA)->ps-1))]) #define BLASFEO_PM_DMATEL(sA,ai,aj) ((sA)->pA[((ai)-((ai)&((sA)->ps-1)))*(sA)->cn+(aj)*((sA)->ps)+((ai)&((sA)->ps-1))])
#define BLASFEO_PM_SMATEL(sA,ai,aj) ((sA)->pA[((ai)-((ai)&((sA)->ps-1)))*(sA)->cn+(aj)*((sA)->ps)+((ai)&((sA)->ps-1))]) #define BLASFEO_PM_SMATEL(sA,ai,aj) ((sA)->pA[((ai)-((ai)&((sA)->ps-1)))*(sA)->cn+(aj)*((sA)->ps)+((ai)&((sA)->ps-1))])
#define BLASFEO_PM_DVECEL(sa,ai) ((sa)->pa[ai])
#define BLASFEO_PM_SVECEL(sa,ai) ((sa)->pa[ai])
#define BLASFEO_CM_DMATEL(sA,ai,aj) ((sA)->pA[(ai)+(aj)*(sA)->m]) #define BLASFEO_CM_DMATEL(sA,ai,aj) ((sA)->pA[(ai)+(aj)*(sA)->m])
#define BLASFEO_CM_SMATEL(sA,ai,aj) ((sA)->pA[(ai)+(aj)*(sA)->m]) #define BLASFEO_CM_SMATEL(sA,ai,aj) ((sA)->pA[(ai)+(aj)*(sA)->m])
#define BLASFEO_CM_DVECEL(sa,ai) ((sa)->pa[ai])
#define BLASFEO_CM_SVECEL(sa,ai) ((sa)->pa[ai])

@ -237,6 +237,17 @@ void blasfeo_cm_create_dmat(int m, int n, struct blasfeo_pm_dmat *sA, void *memo
//
// BLAS API helper functions
//
#if ( defined(BLAS_API) & defined(MF_PANELMAJ) )
// aux
void blasfeo_cm_dgetr(int m, int n, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj);
#endif
#ifdef __cplusplus #ifdef __cplusplus
} }
#endif #endif

@ -44,6 +44,30 @@
#ifdef BLAS_API
#ifdef CBLAS_API
#ifndef BLASFEO_CBLAS_ENUM
#define BLASFEO_CBLAS_ENUM
#ifdef FORTRAN_BLAS_API
#ifndef CBLAS_H
enum CBLAS_ORDER {CblasRowMajor=101, CblasColMajor=102};
enum CBLAS_TRANSPOSE {CblasNoTrans=111, CblasTrans=112, CblasConjTrans=113};
enum CBLAS_UPLO {CblasUpper=121, CblasLower=122};
enum CBLAS_DIAG {CblasNonUnit=131, CblasUnit=132};
enum CBLAS_SIDE {CblasLeft=141, CblasRight=142};
#endif // CBLAS_H
#else // FORTRAN_BLAS_API
enum BLASFEO_CBLAS_ORDER {BlasfeoCblasRowMajor=101, BlasfeoCblasColMajor=102};
enum BLASFEO_CBLAS_TRANSPOSE {BlasfeoCblasNoTrans=111, BlasfeoCblasTrans=112, BlasfeoCblasConjTrans=113};
enum BLASFEO_CBLAS_UPLO {BlasfeoCblasUpper=121, BlasfeoCblasLower=122};
enum BLASFEO_CBLAS_DIAG {BlasfeoCblasNonUnit=131, BlasfeoCblasUnit=132};
enum BLASFEO_CBLAS_SIDE {BlasfeoCblasLeft=141, BlasfeoCblasRight=142};
#endif // FORTRAN_BLAS_API
#endif // BLASFEO_CBLAS_ENUM
#endif // CBLAS_API
#endif // BLAS_API
#ifdef __cplusplus #ifdef __cplusplus
extern "C" { extern "C" {
#endif #endif
@ -66,6 +90,14 @@ void dcopy_(int *n, double *x, int *incx, double *y, int *incy);
// //
double ddot_(int *n, double *x, int *incx, double *y, int *incy); double ddot_(int *n, double *x, int *incx, double *y, int *incy);
// BLAS 2
//
void dgemv_(char *tran, int *m, int *n, double *alpha, double *A, int *lda, double *x, int *incx, double *beta, double *y, int *incy);
//
void dsymv_(char *uplo, int *n, double *alpha, double *A, int *lda, double *x, int *incx, double *beta, double *y, int *incy);
//
void dger_(int *m, int *n, double *alpha, double *x, int *incx, double *y, int *incy, double *A, int *lda);
// BLAS 3 // BLAS 3
// //
void dgemm_(char *ta, char *tb, int *m, int *n, int *k, double *alpha, double *A, int *lda, double *B, int *ldb, double *beta, double *C, int *ldc); void dgemm_(char *ta, char *tb, int *m, int *n, int *k, double *alpha, double *A, int *lda, double *B, int *ldb, double *beta, double *C, int *ldc);
@ -75,6 +107,8 @@ void dsyrk_(char *uplo, char *ta, int *m, int *k, double *alpha, double *A, int
void dtrmm_(char *side, char *uplo, char *transa, char *diag, int *m, int *n, double *alpha, double *A, int *lda, double *B, int *ldb); void dtrmm_(char *side, char *uplo, char *transa, char *diag, int *m, int *n, double *alpha, double *A, int *lda, double *B, int *ldb);
// //
void dtrsm_(char *side, char *uplo, char *transa, char *diag, int *m, int *n, double *alpha, double *A, int *lda, double *B, int *ldb); void dtrsm_(char *side, char *uplo, char *transa, char *diag, int *m, int *n, double *alpha, double *A, int *lda, double *B, int *ldb);
//
void dsyr2k_(char *uplo, char *ta, int *m, int *k, double *alpha, double *A, int *lda, double *B, int *ldb, double *beta, double *C, int *ldc);
@ -100,49 +134,125 @@ void dtrtrs_(char *uplo, char *trans, char *diag, int *m, int *n, double *A, int
// aux
void dgetr_(int *m, int *n, double *A, int *lda, double *B, int *ldb);
#ifdef CBLAS_API
// CBLAS 1
//
void cblas_daxpy(const int N, const double alpha, const double *X, const int incX, double *Y, const int incY);
//
void cblas_dswap(const int N, double *X, const int incX, double *Y, const int incY);
//
void cblas_dcopy(const int N, const double *X, const int incX, double *Y, const int incY);
// CBLAS 3
//
void cblas_dgemm(const enum CBLAS_ORDER Order, const enum CBLAS_TRANSPOSE TransA, const enum CBLAS_TRANSPOSE TransB, const int M, const int N, const int K, const double alpha, const double *A, const int lda, const double *B, const int ldb, const double beta, double *C, const int ldc);
//
void cblas_dsyrk(const enum CBLAS_ORDER Order, const enum CBLAS_UPLO Uplo, const enum CBLAS_TRANSPOSE Trans, const int N, const int K, const double alpha, const double *A, const int lda, const double beta, double *C, const int ldc);
//
void cblas_dtrmm(const enum CBLAS_ORDER Order, const enum CBLAS_SIDE Side, const enum CBLAS_UPLO Uplo, const enum CBLAS_TRANSPOSE TransA, const enum CBLAS_DIAG Diag, const int M, const int N, const double alpha, const double *A, const int lda, double *B, const int ldb);
//
void cblas_dtrsm(const enum CBLAS_ORDER Order, const enum CBLAS_SIDE Side, const enum CBLAS_UPLO Uplo, const enum CBLAS_TRANSPOSE TransA, const enum CBLAS_DIAG Diag, const int M, const int N, const double alpha, const double *A, const int lda, double *B, const int ldb);
#endif // CBLAS_API
#else // BLASFEO_API #else // BLASFEO_API
// BLAS 1 // BLAS 1
// //
void blas_daxpy(int *n, double *alpha, double *x, int *incx, double *y, int *incy); void blasfeo_blas_daxpy(int *n, double *alpha, double *x, int *incx, double *y, int *incy);
// //
double blas_ddot(int *n, double *x, int *incx, double *y, int *incy); double blasfeo_blas_ddot(int *n, double *x, int *incx, double *y, int *incy);
// //
void blas_dcopy(int *n, double *x, int *incx, double *y, int *incy); void blasfeo_blas_dcopy(int *n, double *x, int *incx, double *y, int *incy);
// BLAS 2
//
void blasfeo_blas_dgemv(char *trans, int *m, int *n, double *alpha, double *A, int *lda, double *x, int *incx, double *beta, double *y, int *incy);
//
void blasfeo_blas_dsymv(char *uplo, int *n, double *alpha, double *A, int *lda, double *x, int *incx, double *beta, double *y, int *incy);
//
void blasfeo_blas_dger(int *m, int *n, double *alpha, double *x, int *incx, double *y, int *incy, double *A, int *lda);
// BLAS 3 // BLAS 3
// //
void blas_dgemm(char *ta, char *tb, int *m, int *n, int *k, double *alpha, double *A, int *lda, double *B, int *ldb, double *beta, double *C, int *ldc); void blasfeo_blas_dgemm(char *ta, char *tb, int *m, int *n, int *k, double *alpha, double *A, int *lda, double *B, int *ldb, double *beta, double *C, int *ldc);
//
void blasfeo_blas_dsyrk(char *uplo, char *ta, int *m, int *k, double *alpha, double *A, int *lda, double *beta, double *C, int *ldc);
// //
void blas_dsyrk(char *uplo, char *ta, int *m, int *k, double *alpha, double *A, int *lda, double *beta, double *C, int *ldc); void blasfeo_blas_dtrmm(char *side, char *uplo, char *transa, char *diag, int *m, int *n, double *alpha, double *A, int *lda, double *B, int *ldb);
// //
void blas_dtrmm(char *side, char *uplo, char *transa, char *diag, int *m, int *n, double *alpha, double *A, int *lda, double *B, int *ldb); void blasfeo_blas_dtrsm(char *side, char *uplo, char *transa, char *diag, int *m, int *n, double *alpha, double *A, int *lda, double *B, int *ldb);
// //
void blas_dtrsm(char *side, char *uplo, char *transa, char *diag, int *m, int *n, double *alpha, double *A, int *lda, double *B, int *ldb); void blasfeo_blas_dsyr2k(char *uplo, char *ta, int *m, int *k, double *alpha, double *A, int *lda, double *B, int *ldb, double *beta, double *C, int *ldc);
// LAPACK // LAPACK
// //
void blas_dgesv(int *m, int *n, double *A, int *lda, int *ipiv, double *B, int *ldb, int *info); void blasfeo_lapack_dgesv(int *m, int *n, double *A, int *lda, int *ipiv, double *B, int *ldb, int *info);
// //
void blas_dgetrf(int *m, int *n, double *A, int *lda, int *ipiv, int *info); void blasfeo_lapack_dgetrf(int *m, int *n, double *A, int *lda, int *ipiv, int *info);
// //
void blas_dgetrf_np(int *m, int *n, double *A, int *lda, int *info); void blasfeo_lapack_dgetrf_np(int *m, int *n, double *A, int *lda, int *info);
// //
void blas_dgetrs(char *trans, int *m, int *n, double *A, int *lda, int *ipiv, double *B, int *ldb, int *info); void blasfeo_lapack_dgetrs(char *trans, int *m, int *n, double *A, int *lda, int *ipiv, double *B, int *ldb, int *info);
// //
void blas_dlaswp(int *n, double *A, int *lda, int *k1, int *k2, int *ipiv, int *incx); void blasfeo_lapack_dlaswp(int *n, double *A, int *lda, int *k1, int *k2, int *ipiv, int *incx);
// //
void blas_dposv(char *uplo, int *m, int *n, double *A, int *lda, double *B, int *ldb, int *info); void blasfeo_lapack_dposv(char *uplo, int *m, int *n, double *A, int *lda, double *B, int *ldb, int *info);
// //
void blas_dpotrf(char *uplo, int *m, double *A, int *lda, int *info); void blasfeo_lapack_dpotrf(char *uplo, int *m, double *A, int *lda, int *info);
// //
void blas_dpotrs(char *uplo, int *m, int *n, double *A, int *lda, double *B, int *ldb, int *info); void blasfeo_lapack_dpotrs(char *uplo, int *m, int *n, double *A, int *lda, double *B, int *ldb, int *info);
// //
void blas_dtrtrs(char *uplo, char *trans, char *diag, int *m, int *n, double *A, int *lda, double *B, int *ldb, int *info); void blasfeo_lapack_dtrtrs(char *uplo, char *trans, char *diag, int *m, int *n, double *A, int *lda, double *B, int *ldb, int *info);
// aux
void blasfeo_blas_dgetr(int *m, int *n, double *A, int *lda, double *B, int *ldb);
#ifdef CBLAS_API
// CBLAS 1
//
void blasfeo_cblas_daxpy(const int N, const double alpha, const double *X, const int incX, double *Y, const int incY);
//
void blasfeo_cblas_dswap(const int N, double *X, const int incX, double *Y, const int incY);
//
void blasfeo_cblas_dcopy(const int N, const double *X, const int incX, double *Y, const int incY);
// CBLAS 3
//
void blasfeo_cblas_dgemm(const enum BLASFEO_CBLAS_ORDER Order, const enum BLASFEO_CBLAS_TRANSPOSE TransA, const enum BLASFEO_CBLAS_TRANSPOSE TransB, const int M, const int N, const int K, const double alpha, const double *A, const int lda, const double *B, const int ldb, const double beta, double *C, const int ldc);
//
void blasfeo_cblas_dsyrk(const enum BLASFEO_CBLAS_ORDER Order, const enum BLASFEO_CBLAS_UPLO Uplo, const enum BLASFEO_CBLAS_TRANSPOSE Trans, const int N, const int K, const double alpha, const double *A, const int lda, const double beta, double *C, const int ldc);
//
void blasfeo_cblas_dtrmm(const enum BLASFEO_CBLAS_ORDER Order, const enum BLASFEO_CBLAS_SIDE Side, const enum BLASFEO_CBLAS_UPLO Uplo, const enum BLASFEO_CBLAS_TRANSPOSE TransA, const enum BLASFEO_CBLAS_DIAG Diag, const int M, const int N, const double alpha, const double *A, const int lda, double *B, const int ldb);
//
void blasfeo_cblas_dtrsm(const enum BLASFEO_CBLAS_ORDER Order, const enum BLASFEO_CBLAS_SIDE Side, const enum BLASFEO_CBLAS_UPLO Uplo, const enum BLASFEO_CBLAS_TRANSPOSE TransA, const enum BLASFEO_CBLAS_DIAG Diag, const int M, const int N, const double alpha, const double *A, const int lda, double *B, const int ldb);
#endif // CBLAS_API

@ -119,6 +119,10 @@ void blasfeo_dgemv_nt(int m, int n, double alpha_n, double alpha_t, struct blasf
// z <= beta * y + alpha * A * x, where A is symmetric and only the lower triangular patr of A is accessed // z <= beta * y + alpha * A * x, where A is symmetric and only the lower triangular patr of A is accessed
void blasfeo_dsymv_l(int m, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, double beta, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); void blasfeo_dsymv_l(int m, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, double beta, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi);
void blasfeo_dsymv_l_mn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, double beta, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); void blasfeo_dsymv_l_mn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, double beta, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi);
// z <= beta * y + alpha * A * x, where A is symmetric and only the upper triangular patr of A is accessed
void blasfeo_dsymv_u(int m, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, double beta, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi);
// D = C + alpha * x * y^T
void blasfeo_dger(int m, int n, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sy, int yi, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj);
// diagonal // diagonal
@ -227,6 +231,14 @@ void blasfeo_dtrsm_runu(int m, int n, double alpha, struct blasfeo_dmat *sA, int
void blasfeo_dtrsm_rutn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); void blasfeo_dtrsm_rutn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj);
// D <= alpha * B * A^{-T} , with A upper triangular with unit diagonal // D <= alpha * B * A^{-T} , with A upper triangular with unit diagonal
void blasfeo_dtrsm_rutu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); void blasfeo_dtrsm_rutu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj);
// D <= beta * C + alpha * A * B^T + alpha * B * A^T; C, D lower triangular
void blasfeo_dsyr2k_ln(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj);
// D <= beta * C + alpha * A^T * B + alpha * B^T * A; C, D lower triangular
void blasfeo_dsyr2k_lt(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj);
// D <= beta * C + alpha * A * B^T + alpha * B * A^T; C, D upper triangular
void blasfeo_dsyr2k_un(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj);
// D <= beta * C + alpha * A^T * B + alpha * B^T * A; C, D upper triangular
void blasfeo_dsyr2k_ut(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj);
// diagonal // diagonal
@ -327,6 +339,16 @@ void blasfeo_cm_dtrmm_runn(int m, int n, double alpha, struct blasfeo_cm_dmat *s
void blasfeo_cm_dtrmm_runu(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); void blasfeo_cm_dtrmm_runu(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj);
void blasfeo_cm_dtrmm_rutn(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); void blasfeo_cm_dtrmm_rutn(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj);
void blasfeo_cm_dtrmm_rutu(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); void blasfeo_cm_dtrmm_rutu(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj);
void blasfeo_cm_dsyr2k_ln(int m, int k, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, double beta, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj);
void blasfeo_cm_dsyr2k_lt(int m, int k, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, double beta, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj);
void blasfeo_cm_dsyr2k_un(int m, int k, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, double beta, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj);
void blasfeo_cm_dsyr2k_ut(int m, int k, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, double beta, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj);
// BLAS 2
void blasfeo_cm_dgemv_n(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dvec *sx, int xi, double beta, struct blasfeo_cm_dvec *sy, int yi, struct blasfeo_cm_dvec *sz, int zi);
void blasfeo_cm_dgemv_t(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dvec *sx, int xi, double beta, struct blasfeo_cm_dvec *sy, int yi, struct blasfeo_cm_dvec *sz, int zi);
void blasfeo_cm_dsymv_l(int m, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dvec *sx, int xi, double beta, struct blasfeo_cm_dvec *sy, int yi, struct blasfeo_cm_dvec *sz, int zi);
void blasfeo_cm_dsymv_u(int m, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dvec *sx, int xi, double beta, struct blasfeo_cm_dvec *sy, int yi, struct blasfeo_cm_dvec *sz, int zi);
void blasfeo_cm_dger(int m, int n, double alpha, struct blasfeo_cm_dvec *sx, int xi, struct blasfeo_cm_dvec *sy, int yi, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj);
// LAPACK // LAPACK
void blasfeo_cm_dpotrf_l(int m, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj); void blasfeo_cm_dpotrf_l(int m, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj);
void blasfeo_cm_dpotrf_u(int m, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj); void blasfeo_cm_dpotrf_u(int m, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj);

@ -0,0 +1,84 @@
/**************************************************************************************************
* *
* This file is part of BLASFEO. *
* *
* BLASFEO -- BLAS For Embedded Optimization. *
* Copyright (C) 2019 by Gianluca Frison. *
* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. *
* All rights reserved. *
* *
* The 2-Clause BSD License *
* *
* Redistribution and use in source and binary forms, with or without *
* modification, are permitted provided that the following conditions are met: *
* *
* 1. Redistributions of source code must retain the above copyright notice, this *
* list of conditions and the following disclaimer. *
* 2. Redistributions in binary form must reproduce the above copyright notice, *
* this list of conditions and the following disclaimer in the documentation *
* and/or other materials provided with the distribution. *
* *
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND *
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED *
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE *
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR *
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES *
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; *
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND *
* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT *
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS *
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *
* *
* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de *
* *
**************************************************************************************************/
#ifndef BLASFEO_D_BLASFEO_HP_API_H_
#define BLASFEO_D_BLASFEO_HP_API_H_
#include "blasfeo_common.h"
#ifdef __cplusplus
extern "C" {
#endif
//
// level 3 BLAS
//
// dense
// D <= beta * C + alpha * A^T * B
void blasfeo_hp_dgemm_tn(int m, int n, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj);
// D <= beta * C + alpha * A * B^T; C, D lower triangular
void blasfeo_hp_dsyrk_ln(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj);
// D <= beta * C + alpha * A * A^T ; C, D lower triangular
void blasfeo_hp_dsyrk3_ln(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj);
// D <= alpha * B * A^{-T} , with A lower triangular
void blasfeo_hp_dtrsm_rltn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj);
//
// level 2 BLAS
//
// dense
// z <= beta * y + alpha * A * x
void blasfeo_hp_dgemv_n(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, double beta, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi);
#ifdef __cplusplus
}
#endif
#endif // BLASFEO_D_BLASFEO_HP_API_H_

@ -119,6 +119,10 @@ void blasfeo_ref_dgemv_nt(int m, int n, double alpha_n, double alpha_t, struct b
// z <= beta * y + alpha * A * x, where A is symmetric and only the lower triangular patr of A is accessed // z <= beta * y + alpha * A * x, where A is symmetric and only the lower triangular patr of A is accessed
void blasfeo_ref_dsymv_l(int m, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, double beta, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); void blasfeo_ref_dsymv_l(int m, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, double beta, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi);
void blasfeo_ref_dsymv_l_mn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, double beta, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); void blasfeo_ref_dsymv_l_mn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, double beta, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi);
// z <= beta * y + alpha * A * x, where A is symmetric and only the upper triangular patr of A is accessed
void blasfeo_ref_dsymv_u(int m, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, double beta, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi);
// D = C + alpha * x * y^T
void blasfeo_ref_dger(int m, int n, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sy, int yi, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj);
// diagonal // diagonal
@ -214,6 +218,14 @@ void blasfeo_ref_dtrsm_runu(int m, int n, double alpha, struct blasfeo_dmat *sA,
void blasfeo_ref_dtrsm_rutn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); void blasfeo_ref_dtrsm_rutn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj);
// D <= alpha * B * A^{-T} , with A upper triangular with unit diagonal // D <= alpha * B * A^{-T} , with A upper triangular with unit diagonal
void blasfeo_ref_dtrsm_rutu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); void blasfeo_ref_dtrsm_rutu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj);
// D <= beta * C + alpha * A * B^T + alpha * B * A^T ; C, D lower triangular
void blasfeo_ref_dsyr2k_ln(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj);
// D <= beta * C + alpha * A^T * B + alpha * B^T * A ; C, D lower triangular
void blasfeo_ref_dsyr2k_lt(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj);
// D <= beta * C + alpha * A * B^T + alpha * B * A^T ; C, D upper triangular
void blasfeo_ref_dsyr2k_un(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj);
// D <= beta * C + alpha * A^T * B + alpha * B^T * A ; C, D upper triangular
void blasfeo_ref_dsyr2k_ut(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj);
// diagonal // diagonal

@ -728,14 +728,22 @@ void kernel_dsyrk_nt_l_12x4_lib44cc(int kmax, double *alpha, double *A, int sda,
void kernel_dsyrk_nt_l_12x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); void kernel_dsyrk_nt_l_12x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
void kernel_dsyrk_nt_u_12x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd); void kernel_dsyrk_nt_u_12x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd);
void kernel_dsyrk_nt_u_12x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); void kernel_dsyrk_nt_u_12x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
void kernel_dger2k_nt_12x4_lib44cc(int kmax, double *alpha, double *A0, int sda0, double *B0, double *A1, int sda1, double *B1, double *beta, double *C, int ldc, double *D, int ldd);
void kernel_dger2k_nt_12x4_vs_lib44cc(int kmax, double *alpha, double *A0, int sda0, double *B0, double *A1, int sda1, double *B1, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
void kernel_dsyr2k_nt_l_12x4_lib44cc(int kmax, double *alpha, double *A0, int sda0, double *B0, double *A1, int sda1, double *B1, double *beta, double *C, int ldc, double *D, int ldd);
void kernel_dsyr2k_nt_l_12x4_vs_lib44cc(int kmax, double *alpha, double *A0, int sda0, double *B0, double *A1, int sda1, double *B1, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
void kernel_dtrmm_nt_rl_12x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd); void kernel_dtrmm_nt_rl_12x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd);
void kernel_dtrmm_nt_rl_12x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); void kernel_dtrmm_nt_rl_12x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
void kernel_dtrmm_nt_rl_one_12x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd); void kernel_dtrmm_nt_rl_one_12x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd);
void kernel_dtrmm_nt_rl_one_12x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); void kernel_dtrmm_nt_rl_one_12x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
void kernel_dtrmm_nt_ru_12x4_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd);
void kernel_dtrmm_nt_ru_12x4_vs_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1);
void kernel_dtrmm_nt_ru_12x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd); void kernel_dtrmm_nt_ru_12x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd);
void kernel_dtrmm_nt_ru_12x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); void kernel_dtrmm_nt_ru_12x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
void kernel_dtrmm_nt_ru_one_12x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd); void kernel_dtrmm_nt_ru_one_12x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd);
void kernel_dtrmm_nt_ru_one_12x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); void kernel_dtrmm_nt_ru_one_12x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
void kernel_dtrsm_nt_ll_inv_12x4_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, int sde, double *inv_diag_E);
void kernel_dtrsm_nt_ll_inv_12x4_vs_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, int sde, double *inv_diag_E, int km, int kn);
void kernel_dtrsm_nt_rl_inv_12x4_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *dE); void kernel_dtrsm_nt_rl_inv_12x4_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *dE);
void kernel_dtrsm_nt_rl_inv_12x4_vs_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *dE, int m1, int n1); void kernel_dtrsm_nt_rl_inv_12x4_vs_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *dE, int m1, int n1);
void kernel_dtrsm_nt_rl_inv_12x4_lib44ccc(int kmax, double *A, int sda, double *B, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE); void kernel_dtrsm_nt_rl_inv_12x4_lib44ccc(int kmax, double *A, int sda, double *B, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE);
@ -751,6 +759,7 @@ void kernel_dpotrf_nt_l_12x4_vs_lib44cc(int kmax, double *A, int sda, double *B,
// 4x12 // 4x12
void kernel_dgemm_nt_4x12_lib44cc(int kmax, double *alpha, double *A, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd); void kernel_dgemm_nt_4x12_lib44cc(int kmax, double *alpha, double *A, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd);
void kernel_dgemm_nt_4x12_vs_lib44cc(int kmax, double *alpha, double *A, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); void kernel_dgemm_nt_4x12_vs_lib44cc(int kmax, double *alpha, double *A, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
void kernel_dgemm_nt_4x12_p0_vs_lib44cc(int kmax, double *alpha, double *A, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1, double *A_p, double *B_p);
void kernel_dtrmm_nt_rl_4x12_tran_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd); void kernel_dtrmm_nt_rl_4x12_tran_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd);
void kernel_dtrmm_nt_rl_4x12_tran_vs_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); void kernel_dtrmm_nt_rl_4x12_tran_vs_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1);
void kernel_dtrmm_nt_rl_one_4x12_tran_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd); void kernel_dtrmm_nt_rl_one_4x12_tran_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd);
@ -764,6 +773,10 @@ void kernel_dsyrk_nt_l_8x8_lib44cc(int kmax, double *alpha, double *A, int sda,
void kernel_dsyrk_nt_l_8x8_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); void kernel_dsyrk_nt_l_8x8_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
void kernel_dsyrk_nt_u_8x8_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd); void kernel_dsyrk_nt_u_8x8_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd);
void kernel_dsyrk_nt_u_8x8_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); void kernel_dsyrk_nt_u_8x8_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
void kernel_dger2k_nt_8x8_lib44cc(int kmax, double *alpha, double *A0, int sda0, double *B0, int sdb0, double *A1, int sda1, double *B1, int sdb1, double *beta, double *C, int ldc, double *D, int ldd);
void kernel_dger2k_nt_8x8_vs_lib44cc(int kmax, double *alpha, double *A0, int sda0, double *B0, int sdb0, double *A1, int sda1, double *B1, int sdb1, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
void kernel_dsyr2k_nt_l_8x8_lib44cc(int kmax, double *alpha, double *A0, int sda0, double *B0, int sdb0, double *A1, int sda1, double *B1, int sdb1, double *beta, double *C, int ldc, double *D, int ldd);
void kernel_dsyr2k_nt_l_8x8_vs_lib44cc(int kmax, double *alpha, double *A0, int sda0, double *B0, int sdb0, double *A1, int sda1, double *B1, int sdb1, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
void kernel_dpotrf_nt_l_8x8_lib44cc(int kmax, double *A, int sda, double *B, int sdb, double *C, int ldc, double *D, int ldd, double *dD); void kernel_dpotrf_nt_l_8x8_lib44cc(int kmax, double *A, int sda, double *B, int sdb, double *C, int ldc, double *D, int ldd, double *dD);
void kernel_dpotrf_nt_l_8x8_vs_lib44cc(int kmax, double *A, int sda, double *B, int sdb, double *C, int ldc, double *D, int ldd, double *dD, int m1, int n1); void kernel_dpotrf_nt_l_8x8_vs_lib44cc(int kmax, double *A, int sda, double *B, int sdb, double *C, int ldc, double *D, int ldd, double *dD, int m1, int n1);
// 8x4 // 8x4
@ -775,14 +788,22 @@ void kernel_dsyrk_nt_l_8x4_lib44cc(int kmax, double *alpha, double *A, int sda,
void kernel_dsyrk_nt_l_8x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); void kernel_dsyrk_nt_l_8x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
void kernel_dsyrk_nt_u_8x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd); void kernel_dsyrk_nt_u_8x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd);
void kernel_dsyrk_nt_u_8x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); void kernel_dsyrk_nt_u_8x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
void kernel_dger2k_nt_8x4_lib44cc(int kmax, double *alpha, double *A0, int sda0, double *B0, double *A1, int sda1, double *B1, double *beta, double *C, int ldc, double *D, int ldd);
void kernel_dger2k_nt_8x4_vs_lib44cc(int kmax, double *alpha, double *A0, int sda0, double *B0, double *A1, int sda1, double *B1, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
void kernel_dsyr2k_nt_l_8x4_lib44cc(int kmax, double *alpha, double *A0, int sda0, double *B0, double *A1, int sda1, double *B1, double *beta, double *C, int ldc, double *D, int ldd);
void kernel_dsyr2k_nt_l_8x4_vs_lib44cc(int kmax, double *alpha, double *A0, int sda0, double *B0, double *A1, int sda1, double *B1, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
void kernel_dtrmm_nt_rl_8x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd); void kernel_dtrmm_nt_rl_8x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd);
void kernel_dtrmm_nt_rl_8x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); void kernel_dtrmm_nt_rl_8x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
void kernel_dtrmm_nt_rl_one_8x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd); void kernel_dtrmm_nt_rl_one_8x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd);
void kernel_dtrmm_nt_rl_one_8x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); void kernel_dtrmm_nt_rl_one_8x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
void kernel_dtrmm_nt_ru_8x4_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd);
void kernel_dtrmm_nt_ru_8x4_vs_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1);
void kernel_dtrmm_nt_ru_8x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd); void kernel_dtrmm_nt_ru_8x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd);
void kernel_dtrmm_nt_ru_8x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); void kernel_dtrmm_nt_ru_8x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
void kernel_dtrmm_nt_ru_one_8x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd); void kernel_dtrmm_nt_ru_one_8x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd);
void kernel_dtrmm_nt_ru_one_8x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); void kernel_dtrmm_nt_ru_one_8x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
void kernel_dtrsm_nt_ll_inv_8x4_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, int sde, double *inv_diag_E);
void kernel_dtrsm_nt_ll_inv_8x4_vs_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, int sde, double *inv_diag_E, int km, int kn);
void kernel_dtrsm_nt_rl_inv_8x4_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *dE); void kernel_dtrsm_nt_rl_inv_8x4_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *dE);
void kernel_dtrsm_nt_rl_inv_8x4_vs_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *dE, int m1, int n1); void kernel_dtrsm_nt_rl_inv_8x4_vs_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *dE, int m1, int n1);
void kernel_dtrsm_nt_rl_inv_8x4_lib44ccc(int kmax, double *A, int sda, double *B, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE); void kernel_dtrsm_nt_rl_inv_8x4_lib44ccc(int kmax, double *A, int sda, double *B, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE);
@ -813,6 +834,10 @@ void kernel_dsyrk_nt_l_4x4_lib44cc(int kmax, double *alpha, double *A, double *B
void kernel_dsyrk_nt_l_4x4_vs_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); void kernel_dsyrk_nt_l_4x4_vs_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
void kernel_dsyrk_nt_u_4x4_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd); void kernel_dsyrk_nt_u_4x4_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd);
void kernel_dsyrk_nt_u_4x4_vs_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); void kernel_dsyrk_nt_u_4x4_vs_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
void kernel_dger2k_nt_4x4_lib44cc(int kmax, double *alpha, double *A0, double *B0, double *A1, double *B1, double *beta, double *C, int ldc, double *D, int ldd);
void kernel_dger2k_nt_4x4_vs_lib44cc(int kmax, double *alpha, double *A0, double *B0, double *A1, double *B1, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
void kernel_dsyr2k_nt_l_4x4_lib44cc(int kmax, double *alpha, double *A0, double *B0, double *A1, double *B1, double *beta, double *C, int ldc, double *D, int ldd);
void kernel_dsyr2k_nt_l_4x4_vs_lib44cc(int kmax, double *alpha, double *A0, double *B0, double *A1, double *B1, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
void kernel_dtrmm_nt_rl_4x4_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd); void kernel_dtrmm_nt_rl_4x4_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd);
void kernel_dtrmm_nt_rl_4x4_vs_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); void kernel_dtrmm_nt_rl_4x4_vs_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
void kernel_dtrmm_nt_rl_4x4_tran_lib444c(int kmax, double *alpha, double *A, double *B, double *beta, double *C, double *D, int ldd); void kernel_dtrmm_nt_rl_4x4_tran_lib444c(int kmax, double *alpha, double *A, double *B, double *beta, double *C, double *D, int ldd);
@ -821,6 +846,8 @@ void kernel_dtrmm_nt_rl_one_4x4_lib44cc(int kmax, double *alpha, double *A, doub
void kernel_dtrmm_nt_rl_one_4x4_vs_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); void kernel_dtrmm_nt_rl_one_4x4_vs_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
void kernel_dtrmm_nt_rl_one_4x4_tran_lib444c(int kmax, double *alpha, double *A, double *B, double *beta, double *C, double *D, int ldd); void kernel_dtrmm_nt_rl_one_4x4_tran_lib444c(int kmax, double *alpha, double *A, double *B, double *beta, double *C, double *D, int ldd);
void kernel_dtrmm_nt_rl_one_4x4_tran_vs_lib444c(int kmax, double *alpha, double *A, double *B, double *beta, double *C, double *D, int ldd, int m1, int n1); void kernel_dtrmm_nt_rl_one_4x4_tran_vs_lib444c(int kmax, double *alpha, double *A, double *B, double *beta, double *C, double *D, int ldd, int m1, int n1);
void kernel_dtrmm_nt_ru_4x4_lib444c(int kmax, double *alpha, double *A, double *B, double *beta, double *C, double *D, int ldd);
void kernel_dtrmm_nt_ru_4x4_vs_lib444c(int kmax, double *alpha, double *A, double *B, double *beta, double *C, double *D, int ldd, int m1, int n1);
void kernel_dtrmm_nt_ru_4x4_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd); void kernel_dtrmm_nt_ru_4x4_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd);
void kernel_dtrmm_nt_ru_4x4_vs_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); void kernel_dtrmm_nt_ru_4x4_vs_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
void kernel_dtrmm_nt_ru_4x4_tran_lib444c(int kmax, double *alpha, double *A, double *B, double *beta, double *C, double *D, int ldd); void kernel_dtrmm_nt_ru_4x4_tran_lib444c(int kmax, double *alpha, double *A, double *B, double *beta, double *C, double *D, int ldd);
@ -829,6 +856,8 @@ void kernel_dtrmm_nt_ru_one_4x4_lib44cc(int kmax, double *alpha, double *A, doub
void kernel_dtrmm_nt_ru_one_4x4_vs_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); void kernel_dtrmm_nt_ru_one_4x4_vs_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
void kernel_dtrmm_nt_ru_one_4x4_tran_lib444c(int kmax, double *alpha, double *A, double *B, double *beta, double *C, double *D, int ldd); void kernel_dtrmm_nt_ru_one_4x4_tran_lib444c(int kmax, double *alpha, double *A, double *B, double *beta, double *C, double *D, int ldd);
void kernel_dtrmm_nt_ru_one_4x4_tran_vs_lib444c(int kmax, double *alpha, double *A, double *B, double *beta, double *C, double *D, int ldd, int m1, int n1); void kernel_dtrmm_nt_ru_one_4x4_tran_vs_lib444c(int kmax, double *alpha, double *A, double *B, double *beta, double *C, double *D, int ldd, int m1, int n1);
void kernel_dtrsm_nt_ll_inv_4x4_lib44cc4(int kmax, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *inv_diag_E);
void kernel_dtrsm_nt_ll_inv_4x4_vs_lib44cc4(int kmax, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *inv_diag_E, int km, int kn);
void kernel_dtrsm_nt_rl_inv_4x4_lib44cc4(int kmax, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *dE); void kernel_dtrsm_nt_rl_inv_4x4_lib44cc4(int kmax, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *dE);
void kernel_dtrsm_nt_rl_inv_4x4_vs_lib44cc4(int kmax, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *dE, int m1, int n1); void kernel_dtrsm_nt_rl_inv_4x4_vs_lib44cc4(int kmax, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *dE, int m1, int n1);
void kernel_dtrsm_nt_rl_inv_4x4_lib44ccc(int kmax, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE); void kernel_dtrsm_nt_rl_inv_4x4_lib44ccc(int kmax, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE);
@ -852,6 +881,8 @@ void kernel_dgemm_nt_12x4_lib4ccc(int kmax, double *alpha, double *A, int sda, d
void kernel_dgemm_nt_12x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); void kernel_dgemm_nt_12x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
void kernel_dsyrk_nt_l_12x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); void kernel_dsyrk_nt_l_12x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd);
void kernel_dsyrk_nt_l_12x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); void kernel_dsyrk_nt_l_12x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
void kernel_dger2k_nt_12x4_lib4ccc(int kmax, double *alpha, double *A0, int sda0, double *B0, int ldb0, double *A1, int sda1, double *B1, int ldb1, double *beta, double *C, int ldc, double *D, int ldd);
void kernel_dger2k_nt_12x4_vs_lib4ccc(int kmax, double *alpha, double *A0, int sda0, double *B0, int ldb0, double *A1, int sda1, double *B1, int ldb1, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
void kernel_dtrmm_nn_rl_12x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); void kernel_dtrmm_nn_rl_12x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd);
void kernel_dtrmm_nn_rl_12x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); void kernel_dtrmm_nn_rl_12x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
void kernel_dtrmm_nn_rl_one_12x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); void kernel_dtrmm_nn_rl_one_12x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd);
@ -868,6 +899,8 @@ void kernel_dtrmm_nt_ru_12x4_lib4ccc(int kmax, double *alpha, double *A, int sda
void kernel_dtrmm_nt_ru_12x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); void kernel_dtrmm_nt_ru_12x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
void kernel_dtrmm_nt_ru_one_12x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); void kernel_dtrmm_nt_ru_one_12x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd);
void kernel_dtrmm_nt_ru_one_12x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); void kernel_dtrmm_nt_ru_one_12x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
void kernel_dtrsm_nn_ll_inv_12x4_lib4ccc4(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int sde, double *inv_diag_E);
void kernel_dtrsm_nn_ll_inv_12x4_vs_lib4ccc4(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int sde, double *inv_diag_E, int km, int kn);
void kernel_dtrsm_nn_ll_one_12x4_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde); void kernel_dtrsm_nn_ll_one_12x4_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde);
void kernel_dtrsm_nn_ll_one_12x4_vs_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, int m1, int n1); void kernel_dtrsm_nn_ll_one_12x4_vs_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, int m1, int n1);
void kernel_dtrsm_nn_rl_inv_12x4_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE); void kernel_dtrsm_nn_rl_inv_12x4_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE);
@ -920,6 +953,8 @@ void kernel_dgemm_nt_8x4_lib4ccc(int kmax, double *alpha, double *A, int sda, do
void kernel_dgemm_nt_8x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); void kernel_dgemm_nt_8x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
void kernel_dsyrk_nt_l_8x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); void kernel_dsyrk_nt_l_8x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd);
void kernel_dsyrk_nt_l_8x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); void kernel_dsyrk_nt_l_8x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
void kernel_dger2k_nt_8x4_lib4ccc(int kmax, double *alpha, double *A0, int sda0, double *B0, int ldb0, double *A1, int sda1, double *B1, int ldb1, double *beta, double *C, int ldc, double *D, int ldd);
void kernel_dger2k_nt_8x4_vs_lib4ccc(int kmax, double *alpha, double *A0, int sda0, double *B0, int ldb0, double *A1, int sda1, double *B1, int ldb1, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
void kernel_dtrmm_nn_rl_8x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); void kernel_dtrmm_nn_rl_8x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd);
void kernel_dtrmm_nn_rl_8x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); void kernel_dtrmm_nn_rl_8x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
void kernel_dtrmm_nn_rl_one_8x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); void kernel_dtrmm_nn_rl_one_8x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd);
@ -936,6 +971,8 @@ void kernel_dtrmm_nt_ru_8x4_lib4ccc(int kmax, double *alpha, double *A, int sda,
void kernel_dtrmm_nt_ru_8x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); void kernel_dtrmm_nt_ru_8x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
void kernel_dtrmm_nt_ru_one_8x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); void kernel_dtrmm_nt_ru_one_8x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd);
void kernel_dtrmm_nt_ru_one_8x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); void kernel_dtrmm_nt_ru_one_8x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
void kernel_dtrsm_nn_ll_inv_8x4_lib4ccc4(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int sde, double *inv_diag_E);
void kernel_dtrsm_nn_ll_inv_8x4_vs_lib4ccc4(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int sde, double *inv_diag_E, int km, int kn);
void kernel_dtrsm_nn_ll_one_8x4_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde); void kernel_dtrsm_nn_ll_one_8x4_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde);
void kernel_dtrsm_nn_ll_one_8x4_vs_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, int m1, int n1); void kernel_dtrsm_nn_ll_one_8x4_vs_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, int m1, int n1);
void kernel_dtrsm_nn_rl_inv_8x4_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE); void kernel_dtrsm_nn_rl_inv_8x4_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE);
@ -986,6 +1023,8 @@ void kernel_dgemm_nt_4x4_lib4ccc(int kmax, double *alpha, double *A, double *B,
void kernel_dgemm_nt_4x4_vs_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); void kernel_dgemm_nt_4x4_vs_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
void kernel_dsyrk_nt_l_4x4_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); void kernel_dsyrk_nt_l_4x4_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd);
void kernel_dsyrk_nt_l_4x4_vs_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); void kernel_dsyrk_nt_l_4x4_vs_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
void kernel_dger2k_nt_4x4_lib4ccc(int kmax, double *alpha, double *A0, double *B0, int ldb0, double *A1, double *B1, int ldb1, double *beta, double *C, int ldc, double *D, int ldd);
void kernel_dger2k_nt_4x4_vs_lib4ccc(int kmax, double *alpha, double *A0, double *B0, int ldb0, double *A1, double *B1, int ldb1, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
void kernel_dtrmm_nn_rl_4x4_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); void kernel_dtrmm_nn_rl_4x4_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd);
void kernel_dtrmm_nn_rl_4x4_vs_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); void kernel_dtrmm_nn_rl_4x4_vs_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
void kernel_dtrmm_nn_rl_4x4_tran_lib4c4c(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, double *D, int ldd); void kernel_dtrmm_nn_rl_4x4_tran_lib4c4c(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, double *D, int ldd);
@ -1018,6 +1057,8 @@ void kernel_dtrmm_nt_ru_one_4x4_lib4ccc(int kmax, double *alpha, double *A, doub
void kernel_dtrmm_nt_ru_one_4x4_vs_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); void kernel_dtrmm_nt_ru_one_4x4_vs_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
void kernel_dtrmm_nt_ru_one_4x4_tran_lib4c4c(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, double *D, int ldd); void kernel_dtrmm_nt_ru_one_4x4_tran_lib4c4c(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, double *D, int ldd);
void kernel_dtrmm_nt_ru_one_4x4_tran_vs_lib4c4c(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, double *D, int ldd, int m1, int n1); void kernel_dtrmm_nt_ru_one_4x4_tran_vs_lib4c4c(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, double *D, int ldd, int m1, int n1);
void kernel_dtrsm_nn_ll_inv_4x4_lib4ccc4(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *inv_diag_E);
void kernel_dtrsm_nn_ll_inv_4x4_vs_lib4ccc4(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *inv_diag_E, int km, int kn);
void kernel_dtrsm_nn_ll_one_4x4_lib4cccc(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde); void kernel_dtrsm_nn_ll_one_4x4_lib4cccc(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde);
void kernel_dtrsm_nn_ll_one_4x4_vs_lib4cccc(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, int m1, int n1); void kernel_dtrsm_nn_ll_one_4x4_vs_lib4cccc(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, int m1, int n1);
void kernel_dtrsm_nn_rl_inv_4x4_lib4cccc(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE); void kernel_dtrsm_nn_rl_inv_4x4_lib4cccc(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE);
@ -1181,6 +1222,7 @@ void kernel_drowsw_lib(int kmax, double *pA, int lda, double *pC, int ldc);
// 12 // 12
void kernel_dgemm_nt_12xn_p0_lib44cc(int n, int k, double *alpha, double *A, int sda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, double *A_p, double *B_p); void kernel_dgemm_nt_12xn_p0_lib44cc(int n, int k, double *alpha, double *A, int sda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, double *A_p, double *B_p);
void kernel_dgemm_nt_12xn_pl_lib44cc(int n, int k, double *alpha, double *A, int sda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, double *A_p, double *B_p); void kernel_dgemm_nt_12xn_pl_lib44cc(int n, int k, double *alpha, double *A, int sda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, double *A_p, double *B_p);
void kernel_dgemm_nt_mx12_p0_lib44cc(int m, int k, double *alpha, double *A, int sda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, double *A_p, double *B_p);
// 8 // 8
void kernel_dgemm_nt_8xn_p0_lib44cc(int n, int k, double *alpha, double *A, int sda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, double *A_p, double *B_p); void kernel_dgemm_nt_8xn_p0_lib44cc(int n, int k, double *alpha, double *A, int sda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, double *A_p, double *B_p);
@ -1232,11 +1274,43 @@ void kernel_dgemm_tt_8x8_libc8cc(int kmax, double *alpha, double *A, int lda, do
void kernel_dgemm_tt_8x8_vs_libc8cc(int kmax, double *alpha, double *A, int lda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); void kernel_dgemm_tt_8x8_vs_libc8cc(int kmax, double *alpha, double *A, int lda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1);
// level 2 BLAS
void kernel_dgemv_n_4_libc(int kmax, double *alpha, double *A, int lda, double *x, double *z);
void kernel_dgemv_n_4_vs_libc(int kmax, double *alpha, double *A, int lda, double *x, double *z, int km);
void kernel_dgemv_t_4_libc(int kmax, double *alpha, double *A, int lda, double *x, double *beta, double *y, double *z);
void kernel_dgemv_t_4_vs_libc(int kmax, double *alpha, double *A, int lda, double *x, double *beta, double *y, double *z, int km);
void kernel_dsymv_l_4_libc(int kmax, double *alpha, double *A, int lda, double *x, double *z);
void kernel_dsymv_l_4_vs_libc(int kmax, double *alpha, double *A, int lda, double *x, double *z, int km);
void kernel_dsymv_u_4_libc(int kmax, double *alpha, double *A, int lda, double *x, double *z);
void kernel_dsymv_u_4_vs_libc(int kmax, double *alpha, double *A, int lda, double *x, double *z, int km);
void kernel_dger_4_libc(int kmax, double *alpha, double *x, double *y, double *C, int ldc, double *D, int ldd);
void kernel_dger_4_vs_libc(int kmax, double *alpha, double *x, double *y, double *C, int ldc, double *D, int ldd, int km);
// aux // aux
void kernel_dvecld_inc1(int kmax, double *x); void kernel_dvecld_inc1(int kmax, double *x);
void kernel_dveccp_inc1(int kmax, double *x, double *y); void kernel_dveccp_inc1(int kmax, double *x, double *y);
//void kernel_dgetr_nt_8_p0_lib(int kmax, double *A, int lda, double *C, int ldc, double *Ap, double *Bp);
//void kernel_dgetr_nt_8_lib(int kmax, double *A, int lda, double *C, int ldc);
//void kernel_dgetr_nt_4_lib(int kmax, double *A, int lda, double *C, int ldc);
void kernel_dgetr_tn_8_p0_lib(int kmax, double *A, int lda, double *C, int ldc, double *Ap, double *Bp);
void kernel_dgetr_tn_8_lib(int kmax, double *A, int lda, double *C, int ldc);
void kernel_dgetr_tn_4_lib(int kmax, double *A, int lda, double *C, int ldc);
void kernel_dgetr_tn_4_vs_lib(int kmax, double *A, int lda, double *C, int ldc, int m1);
// building blocks for blocked algorithms
//
void blasfeo_hp_dgemm_nt_m2(int m, int n, int k, double alpha, double *pA, int sda, double *pB, int sdb, double beta, double *C, int ldc, double *D, int ldd);
void blasfeo_hp_dgemm_nt_n2(int m, int n, int k, double alpha, double *pA, int sda, double *pB, int sdb, double beta, double *C, int ldc, double *D, int ldd);
//
void kernel_dpack_buffer_fn(int m, int n, double *A, int lda, double *pA, int sda);
void kernel_dpack_buffer_ft(int m, int n, double *A, int lda, double *pA, int sda);
void kernel_dpack_buffer_ln(int m, double *A, int lda, double *pA, int sda);
void kernel_dpack_buffer_lt(int m, double *A, int lda, double *pA, int sda);
void kernel_dpack_buffer_ut(int m, double *A, int lda, double *pA, int sda);

@ -39,20 +39,20 @@
/** /**
* Flags to indicate the different processor features * Flags to indicate the different processor features
*/ */
enum //enum
{ //{
// x86-64 CPU features // // x86-64 CPU features
BLASFEO_PROCESSOR_FEATURE_AVX = 0x0001, /// AVX instruction set // BLASFEO_PROCESSOR_FEATURE_AVX = 0x0001, /// AVX instruction set
BLASFEO_PROCESSOR_FEATURE_AVX2 = 0x0002, /// AVX2 instruction set // BLASFEO_PROCESSOR_FEATURE_AVX2 = 0x0002, /// AVX2 instruction set
BLASFEO_PROCESSOR_FEATURE_FMA = 0x0004, /// FMA instruction set // BLASFEO_PROCESSOR_FEATURE_FMA = 0x0004, /// FMA instruction set
BLASFEO_PROCESSOR_FEATURE_SSE3 = 0x0008, /// SSE3 instruction set // BLASFEO_PROCESSOR_FEATURE_SSE3 = 0x0008, /// SSE3 instruction set
//
// ARM CPU features // // ARM CPU features
BLASFEO_PROCESSOR_FEATURE_VFPv3 = 0x0100, /// VFPv3 instruction set // BLASFEO_PROCESSOR_FEATURE_VFPv3 = 0x0100, /// VFPv3 instruction set
BLASFEO_PROCESSOR_FEATURE_NEON = 0x0100, /// NEON instruction set // BLASFEO_PROCESSOR_FEATURE_NEON = 0x0100, /// NEON instruction set
BLASFEO_PROCESSOR_FEATURE_VFPv4 = 0x0100, /// VFPv4 instruction set // BLASFEO_PROCESSOR_FEATURE_VFPv4 = 0x0100, /// VFPv4 instruction set
BLASFEO_PROCESSOR_FEATURE_NEONv2 = 0x0100, /// NEONv2 instruction set // BLASFEO_PROCESSOR_FEATURE_NEONv2 = 0x0100, /// NEONv2 instruction set
} BLASFEO_PROCESSOR_FEATURES; //} BLASFEO_PROCESSOR_FEATURES;
/** /**
* Test the features that this processor provides against what the library was compiled with. * Test the features that this processor provides against what the library was compiled with.

@ -44,6 +44,31 @@
#ifdef BLAS_API
#ifdef CBLAS_API
#ifndef BLASFEO_CBLAS_ENUM
#define BLASFEO_CBLAS_ENUM
#ifdef FORTRAN_BLAS_API
#ifndef CBLAS_H
enum CBLAS_ORDER {CblasRowMajor=101, CblasColMajor=102};
enum CBLAS_TRANSPOSE {CblasNoTrans=111, CblasTrans=112, CblasConjTrans=113};
enum CBLAS_UPLO {CblasUpper=121, CblasLower=122};
enum CBLAS_DIAG {CblasNonUnit=131, CblasUnit=132};
enum CBLAS_SIDE {CblasLeft=141, CblasRight=142};
#endif // CBLAS_H
#else // FORTRAN_BLAS_API
enum BLASFEO_CBLAS_ORDER {CblasRowMajor=101, CblasColMajor=102};
enum BLASFEO_CBLAS_TRANSPOSE {CblasNoTrans=111, CblasTrans=112, CblasConjTrans=113};
enum BLASFEO_CBLAS_UPLO {CblasUpper=121, CblasLower=122};
enum BLASFEO_CBLAS_DIAG {CblasNonUnit=131, CblasUnit=132};
enum BLASFEO_CBLAS_SIDE {CblasLeft=141, CblasRight=142};
#endif // FORTRAN_BLAS_API
#endif // BLASFEO_CBLAS_ENUM
#endif // CBLAS_API
#endif // BLAS_API
#ifdef __cplusplus #ifdef __cplusplus
extern "C" { extern "C" {
#endif #endif
@ -78,27 +103,67 @@ void spotrf_(char *uplo, int *m, float *A, int *lda, int *info);
#ifdef CBLAS_API
// CBLAS 1
//
void cblas_saxpy(const int N, const float alpha, const float *X, const int incX, float *Y, const int incY);
// CBLAS 3
//
void cblas_sgemm(const enum CBLAS_ORDER Order, const enum CBLAS_TRANSPOSE TransA, const enum CBLAS_TRANSPOSE TransB, const int M, const int N, const int K, const float alpha, const float *A, const int lda, const float *B, const int ldb, const float beta, float *C, const int ldc);
//
void cblas_strsm(const enum CBLAS_ORDER Order, const enum CBLAS_SIDE Side, const enum CBLAS_UPLO Uplo, const enum CBLAS_TRANSPOSE TransA, const enum CBLAS_DIAG Diag, const int M, const int N, const float alpha, const float *A, const int lda, float *B, const int ldb);
#endif // CBLAS_API
#else // BLASFEO_API #else // BLASFEO_API
// BLAS 1 // BLAS 1
// //
void blas_saxpy(int *n, float *alpha, float *x, int *incx, float *y, int *incy); void blasfeo_blas_saxpy(int *n, float *alpha, float *x, int *incx, float *y, int *incy);
// //
float blas_sdot(int *n, float *x, int *incx, float *y, int *incy); float blasfeo_blas_sdot(int *n, float *x, int *incx, float *y, int *incy);
// BLAS 3 // BLAS 3
// //
void blas_sgemm(char *ta, char *tb, int *m, int *n, int *k, float *alpha, float *A, int *lda, float *B, int *ldb, float *beta, float *C, int *ldc); void blasfeo_blas_sgemm(char *ta, char *tb, int *m, int *n, int *k, float *alpha, float *A, int *lda, float *B, int *ldb, float *beta, float *C, int *ldc);
// //
void blas_strsm(char *side, char *uplo, char *transa, char *diag, int *m, int *n, float *alpha, float *A, int *lda, float *B, int *ldb); void blasfeo_blas_strsm(char *side, char *uplo, char *transa, char *diag, int *m, int *n, float *alpha, float *A, int *lda, float *B, int *ldb);
// LAPACK // LAPACK
// //
void blas_spotrf(char *uplo, int *m, float *A, int *lda, int *info); void blasfeo_lapack_spotrf(char *uplo, int *m, float *A, int *lda, int *info);
#ifdef CBLAS_API
// CBLAS 1
//
void blasfeo_cblas_saxpy(const int N, const float alpha, const float *X, const int incX, float *Y, const int incY);
// CBLAS 3
//
void blasfeo_cblas_sgemm(const enum BLASFEO_CBLAS_ORDER Order, const enum BLASFEO_CBLAS_TRANSPOSE TransA, const enum BLASFEO_CBLAS_TRANSPOSE TransB, const int M, const int N, const int K, const float alpha, const float *A, const int lda, const float *B, const int ldb, const float beta, float *C, const int ldc);
//
void blasfeo_cblas_strsm(const enum BLASFEO_CBLAS_ORDER Order, const enum BLASFEO_CBLAS_SIDE Side, const enum BLASFEO_CBLAS_UPLO Uplo, const enum BLASFEO_CBLAS_TRANSPOSE TransA, const enum BLASFEO_CBLAS_DIAG Diag, const int M, const int N, const float alpha, const float *A, const int lda, float *B, const int ldb);
#endif // CBLAS_API

@ -115,6 +115,10 @@ void blasfeo_sgemv_nt(int m, int n, float alpha_n, float alpha_t, struct blasfeo
// z <= beta * y + alpha * A * x, where A is symmetric and only the lower triangular patr of A is accessed // z <= beta * y + alpha * A * x, where A is symmetric and only the lower triangular patr of A is accessed
void blasfeo_ssymv_l(int m, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, float beta, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); void blasfeo_ssymv_l(int m, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, float beta, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi);
void blasfeo_ssymv_l_mn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, float beta, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); void blasfeo_ssymv_l_mn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, float beta, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi);
// z <= beta * y + alpha * A * x, where A is symmetric and only the upper triangular patr of A is accessed
void blasfeo_ssymv_u(int m, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, float beta, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi);
// D = C + alpha * x * y^T
void blasfeo_sger(int m, int n, float alpha, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sy, int yi, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj);
// diagonal // diagonal
@ -182,6 +186,14 @@ void blasfeo_strsm_runu(int m, int n, float alpha, struct blasfeo_smat *sA, int
void blasfeo_strsm_rutn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); void blasfeo_strsm_rutn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj);
// D <= alpha * B * A^{-T} , with A upper triangular with unit diagonal // D <= alpha * B * A^{-T} , with A upper triangular with unit diagonal
void blasfeo_strsm_rutu(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); void blasfeo_strsm_rutu(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj);
// D <= beta * C + alpha * A * B^T + alpha * B * A^T; C, D lower triangular
void blasfeo_ssyr2k_ln(int m, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj);
// D <= beta * C + alpha * A^T * B + alpha * B^T * A; C, D lower triangular
void blasfeo_ssyr2k_lt(int m, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj);
// D <= beta * C + alpha * A * B^T + alpha * B * A^T; C, D upper triangular
void blasfeo_ssyr2k_un(int m, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj);
// D <= beta * C + alpha * A^T * B + alpha * B^T * A; C, D upper triangular
void blasfeo_ssyr2k_ut(int m, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj);
// diagonal // diagonal

@ -115,6 +115,10 @@ void blasfeo_ref_sgemv_nt(int m, int n, float alpha_n, float alpha_t, struct bla
// z <= beta * y + alpha * A * x, where A is symmetric and only the lower triangular patr of A is accessed // z <= beta * y + alpha * A * x, where A is symmetric and only the lower triangular patr of A is accessed
void blasfeo_ref_ssymv_l(int m, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, float beta, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); void blasfeo_ref_ssymv_l(int m, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, float beta, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi);
void blasfeo_ref_ssymv_l_mn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, float beta, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); void blasfeo_ref_ssymv_l_mn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, float beta, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi);
// z <= beta * y + alpha * A * x, where A is symmetric and only the upper triangular patr of A is accessed
void blasfeo_ref_ssymv_u(int m, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, float beta, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi);
// D = C + alpha * x * y^T
void blasfeo_ref_sger(int m, int n, float alpha, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sy, int yi, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj);
// diagonal // diagonal
@ -182,6 +186,14 @@ void blasfeo_ref_strsm_runu(int m, int n, float alpha, struct blasfeo_smat *sA,
void blasfeo_ref_strsm_rutn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); void blasfeo_ref_strsm_rutn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj);
// D <= alpha * B * A^{-T} , with A upper triangular with unit diagonal // D <= alpha * B * A^{-T} , with A upper triangular with unit diagonal
void blasfeo_ref_strsm_rutu(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); void blasfeo_ref_strsm_rutu(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj);
// D <= beta * C + alpha * A * B^T + alpha * B * A^T ; C, D lower triangular
void blasfeo_ref_ssyr2k_ln(int m, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj);
// D <= beta * C + alpha * A^T * B + alpha * B^T * A ; C, D lower triangular
void blasfeo_ref_ssyr2k_lt(int m, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj);
// D <= beta * C + alpha * A * B^T + alpha * B * A^T ; C, D upper triangular
void blasfeo_ref_ssyr2k_un(int m, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj);
// D <= beta * C + alpha * A^T * B + alpha * B^T * A ; C, D upper triangular
void blasfeo_ref_ssyr2k_ut(int m, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj);
// diagonal // diagonal

@ -1,13 +1,13 @@
#ifndef TARGET_X64_INTEL_HASWELL #ifndef TARGET_ARMV8A_ARM_CORTEX_A57
#define TARGET_X64_INTEL_HASWELL #define TARGET_ARMV8A_ARM_CORTEX_A57
#endif #endif
#ifndef TARGET_NEED_FEATURE_AVX2 #ifndef TARGET_NEED_FEATURE_AVX2
#define TARGET_NEED_FEATURE_AVX2 1 /* #undef TARGET_NEED_FEATURE_AVX2 */
#endif #endif
#ifndef TARGET_NEED_FEATURE_FMA #ifndef TARGET_NEED_FEATURE_FMA
#define TARGET_NEED_FEATURE_FMA 1 /* #undef TARGET_NEED_FEATURE_FMA */
#endif #endif
#ifndef TARGET_NEED_FEATURE_SSE3 #ifndef TARGET_NEED_FEATURE_SSE3
@ -27,11 +27,11 @@
#endif #endif
#ifndef TARGET_NEED_FEATURE_VFPv4 #ifndef TARGET_NEED_FEATURE_VFPv4
/* #undef TARGET_NEED_FEATURE_VFPv4 */ #define TARGET_NEED_FEATURE_VFPv4 1
#endif #endif
#ifndef TARGET_NEED_FEATURE_NEONv2 #ifndef TARGET_NEED_FEATURE_NEONv2
/* #undef TARGET_NEED_FEATURE_NEONv2 */ #define TARGET_NEED_FEATURE_NEONv2 1
#endif #endif
#ifndef LA_HIGH_PERFORMANCE #ifndef LA_HIGH_PERFORMANCE

@ -61,6 +61,7 @@ void dgemm_(char *ta, char *tb, int *m, int *n, int *k, double *alpha, double *A
void dsyrk_(char *uplo, char *trans, int *n, int *k, double *alpha, double *A, int *lda, double *beta, double *C, int *ldc); void dsyrk_(char *uplo, char *trans, int *n, int *k, double *alpha, double *A, int *lda, double *beta, double *C, int *ldc);
void dtrmm_(char *side, char *uplo, char *trans, char *diag, int *m, int *n, double *alpha, double *A, int *lda, double *B, int *ldb); void dtrmm_(char *side, char *uplo, char *trans, char *diag, int *m, int *n, double *alpha, double *A, int *lda, double *B, int *ldb);
void dtrsm_(char *side, char *uplo, char *trans, char *diag, int *m, int *n, double *alpha, double *A, int *lda, double *B, int *ldb); void dtrsm_(char *side, char *uplo, char *trans, char *diag, int *m, int *n, double *alpha, double *A, int *lda, double *B, int *ldb);
void dsyr2k_(char *uplo, char *trans, int *n, int *k, double *alpha, double *A, int *lda, double *B, int *ldb, double *beta, double *C, int *ldc);
// lapack // lapack
void dpotrf_(char *uplo, int *m, double *A, int *lda, int *info); void dpotrf_(char *uplo, int *m, double *A, int *lda, int *info);

@ -61,6 +61,7 @@ void sgemm_(char *ta, char *tb, int *m, int *n, int *k, float *alpha, float *A,
void ssyrk_(char *uplo, char *trans, int *n, int *k, float *alpha, float *A, int *lda, float *beta, float *C, int *ldc); void ssyrk_(char *uplo, char *trans, int *n, int *k, float *alpha, float *A, int *lda, float *beta, float *C, int *ldc);
void strmm_(char *side, char *uplo, char *transa, char *diag, int *m, int *n, float *alpha, float *A, int *lda, float *B, int *ldb); void strmm_(char *side, char *uplo, char *transa, char *diag, int *m, int *n, float *alpha, float *A, int *lda, float *B, int *ldb);
void strsm_(char *side, char *uplo, char *transa, char *diag, int *m, int *n, float *alpha, float *A, int *lda, float *B, int *ldb); void strsm_(char *side, char *uplo, char *transa, char *diag, int *m, int *n, float *alpha, float *A, int *lda, float *B, int *ldb);
void ssyr2k_(char *uplo, char *trans, int *n, int *k, float *alpha, float *A, int *lda, float *B, int *ldb, float *beta, float *C, int *ldc);
// lapack // lapack
void spotrf_(char *uplo, int *m, float *A, int *lda, int *info); void spotrf_(char *uplo, int *m, float *A, int *lda, int *info);

@ -1,3 +1,3 @@
version https://git-lfs.github.com/spec/v1 version https://git-lfs.github.com/spec/v1
oid sha256:08d73672735c9bf05babda079627e3b93c593954a8b164f529c422cf9867d791 oid sha256:d320459a896c765a75456bc7cfb89bacfd692709ccbf5e261051d37eb0cb11e2
size 489256 size 493656

@ -1,3 +1,3 @@
version https://git-lfs.github.com/spec/v1 version https://git-lfs.github.com/spec/v1
oid sha256:1e0cbc45c14340834991e617cd28045b8cac34bd094c73f3c4a0b3506ce3cdbe oid sha256:3ddffc8ed63d42b4301ce0f7f599c39177298cc598a2cb5e1d26990460ea59be
size 726592 size 1150320

@ -1,3 +1,3 @@
version https://git-lfs.github.com/spec/v1 version https://git-lfs.github.com/spec/v1
oid sha256:5b84ad639a00b9ad35e502588a96145b9914ef0fc24262b3e9bfcdbcd655d9ae oid sha256:ab9cb6079675937ddb09fcc77133a14ebdc29dd9338e4d79a3e61af1efa271aa
size 534128 size 534416

@ -1,3 +1,3 @@
version https://git-lfs.github.com/spec/v1 version https://git-lfs.github.com/spec/v1
oid sha256:2361e3efae8404b728e631bcaaa1f686158e0b62e19b6237d01c2efa17147c21 oid sha256:e64a78c320f1ed03c086506ba400149edaa33b3c9a71f3547d2593ee169751b9
size 1265168 size 2155088

@ -1,3 +1,3 @@
version https://git-lfs.github.com/spec/v1 version https://git-lfs.github.com/spec/v1
oid sha256:559bb84f78448803ef2b455cfb53aff95e283eb452c5e132afc5e663510802a0 oid sha256:0cabd3d3b9ceffbe1f7b783089b54c68e4cf635053a0f1cec96ffaf5f68589c1
size 1572648 size 1572648

@ -1,3 +1,3 @@
version https://git-lfs.github.com/spec/v1 version https://git-lfs.github.com/spec/v1
oid sha256:6452b56b86528616695f44752d975d26c93a0692246a8ca313fc969effec75ca oid sha256:67661c8be478b34680e093df1d7221679bdbf20c5abd39cfaadd74cac11e44f5
size 262824 size 262824

@ -1,3 +1,3 @@
version https://git-lfs.github.com/spec/v1 version https://git-lfs.github.com/spec/v1
oid sha256:703e96a35b87eeace4b4558266a4d715742e28f17be0c02a6fcc3ea975d050f6 oid sha256:f39cc2f561109c4d311a6503cd03883a132ae7a49dbb2e5ef457aaf176df390b
size 15186136 size 7286616

Loading…
Cancel
Save