diff --git a/.gitignore b/.gitignore index 3d0a6b7bf..5b73c561b 100644 --- a/.gitignore +++ b/.gitignore @@ -56,7 +56,6 @@ selfdrive/modeld/_dmonitoringmodeld /src/ one -openpilot notebooks xx yy @@ -85,4 +84,6 @@ build/ !**/.gitkeep poetry.toml -third_party/mapd/ \ No newline at end of file +Pipfile + +third_party/mapd/ diff --git a/CHANGELOGS.md b/CHANGELOGS.md index 55cb21379..f40270656 100644 --- a/CHANGELOGS.md +++ b/CHANGELOGS.md @@ -1,4 +1,4 @@ -dragonpilot beta3 2023.08.15 +dragonpilot beta3 2023.08.22 ======================= * openpilot master branch on 2023.07.21. diff --git a/body/board/obj/body.bin b/body/board/obj/body.bin index a8bea545e..f23a2edd8 100755 Binary files a/body/board/obj/body.bin and b/body/board/obj/body.bin differ diff --git a/body/board/obj/body.bin.signed b/body/board/obj/body.bin.signed index fd41ac7d0..1913b5d2f 100644 Binary files a/body/board/obj/body.bin.signed and b/body/board/obj/body.bin.signed differ diff --git a/body/board/obj/body.elf b/body/board/obj/body.elf index 2548b6870..d355901bb 100755 Binary files a/body/board/obj/body.elf and b/body/board/obj/body.elf differ diff --git a/body/board/obj/bootstub.body.bin b/body/board/obj/bootstub.body.bin index 9ca0ed50c..4d212e48f 100755 Binary files a/body/board/obj/bootstub.body.bin and b/body/board/obj/bootstub.body.bin differ diff --git a/body/board/obj/bootstub.body.elf b/body/board/obj/bootstub.body.elf index d9d3814b5..a4d54ddeb 100755 Binary files a/body/board/obj/bootstub.body.elf and b/body/board/obj/bootstub.body.elf differ diff --git a/body/board/obj/gitversion.h b/body/board/obj/gitversion.h index 2e5febb07..420852029 100644 --- a/body/board/obj/gitversion.h +++ b/body/board/obj/gitversion.h @@ -1 +1 @@ -const uint8_t gitversion[8] = "929c52ce"; +const uint8_t gitversion[8] = "501626f0"; diff --git a/cereal/car.capnp b/cereal/car.capnp index 25f396ec9..1039e5cbe 100644 --- a/cereal/car.capnp +++ b/cereal/car.capnp @@ -450,6 +450,7 @@ struct CarParams { # things we can derive rotationalInertia @22 :Float32; # [kg*m2] body rotational inertia + tireStiffnessFactor @72 :Float32; # scaling factor used in calculating tireStiffness[Front,Rear] tireStiffnessFront @23 :Float32; # [N/rad] front tire coeff of stiff tireStiffnessRear @24 :Float32; # [N/rad] rear tire coeff of stiff @@ -591,6 +592,7 @@ struct CarParams { hongqi @26; body @27; hyundaiCanfd @28; + volkswagenMqbEvo @29; } enum SteerControlType { diff --git a/cereal/gen/cpp/car.capnp.c++ b/cereal/gen/cpp/car.capnp.c++ index 8167ce58a..f260e7801 100644 --- a/cereal/gen/cpp/car.capnp.c++ +++ b/cereal/gen/cpp/car.capnp.c++ @@ -3490,7 +3490,7 @@ const ::capnp::_::RawSchema s_f5a5e26c954e339e = { }; #endif // !CAPNP_LITE CAPNP_DEFINE_ENUM(AudibleAlert_f5a5e26c954e339e, f5a5e26c954e339e); -static const ::capnp::_::AlignedData<1252> b_8c69372490aaa9da = { +static const ::capnp::_::AlignedData<1269> b_8c69372490aaa9da = { { 0, 0, 0, 0, 5, 0, 6, 0, 218, 169, 170, 144, 36, 55, 105, 140, 10, 0, 0, 0, 1, 0, 17, 0, @@ -3500,7 +3500,7 @@ static const ::capnp::_::AlignedData<1252> b_8c69372490aaa9da = { 21, 0, 0, 0, 162, 0, 0, 0, 29, 0, 0, 0, 231, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 17, 1, 0, 0, 31, 15, 0, 0, + 17, 1, 0, 0, 87, 15, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 99, 97, 114, 46, 99, 97, 112, 110, @@ -3569,490 +3569,497 @@ static const ::capnp::_::AlignedData<1252> b_8c69372490aaa9da = { 101, 0, 0, 0, 0, 0, 0, 0, 78, 101, 116, 119, 111, 114, 107, 76, 111, 99, 97, 116, 105, 111, 110, 0, - 20, 1, 0, 0, 3, 0, 4, 0, + 24, 1, 0, 0, 3, 0, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 125, 7, 0, 0, 66, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 120, 7, 0, 0, 3, 0, 1, 0, - 132, 7, 0, 0, 2, 0, 1, 0, - 1, 0, 0, 0, 1, 0, 0, 0, - 0, 0, 1, 0, 1, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 129, 7, 0, 0, 122, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 128, 7, 0, 0, 3, 0, 1, 0, - 140, 7, 0, 0, 2, 0, 1, 0, - 4, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 1, 0, 2, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 137, 7, 0, 0, 170, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 140, 7, 0, 0, 3, 0, 1, 0, - 152, 7, 0, 0, 2, 0, 1, 0, - 5, 0, 0, 0, 1, 0, 0, 0, - 0, 0, 1, 0, 3, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 149, 7, 0, 0, 82, 0, 0, 0, + 153, 7, 0, 0, 66, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 148, 7, 0, 0, 3, 0, 1, 0, 160, 7, 0, 0, 2, 0, 1, 0, - 50, 0, 0, 0, 2, 0, 0, 0, - 0, 0, 1, 0, 4, 0, 0, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 157, 7, 0, 0, 186, 0, 0, 0, + 157, 7, 0, 0, 122, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 160, 7, 0, 0, 3, 0, 1, 0, - 172, 7, 0, 0, 2, 0, 1, 0, - 6, 0, 0, 0, 3, 0, 0, 0, - 0, 0, 1, 0, 5, 0, 0, 0, + 156, 7, 0, 0, 3, 0, 1, 0, + 168, 7, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 169, 7, 0, 0, 82, 0, 0, 0, + 165, 7, 0, 0, 170, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 168, 7, 0, 0, 3, 0, 1, 0, 180, 7, 0, 0, 2, 0, 1, 0, - 51, 0, 0, 0, 4, 0, 0, 0, - 0, 0, 1, 0, 6, 0, 0, 0, + 5, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 177, 7, 0, 0, 170, 0, 0, 0, + 177, 7, 0, 0, 82, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 180, 7, 0, 0, 3, 0, 1, 0, - 192, 7, 0, 0, 2, 0, 1, 0, - 10, 0, 0, 0, 1, 0, 0, 0, - 0, 0, 1, 0, 7, 0, 0, 0, + 176, 7, 0, 0, 3, 0, 1, 0, + 188, 7, 0, 0, 2, 0, 1, 0, + 51, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 189, 7, 0, 0, 122, 0, 0, 0, + 185, 7, 0, 0, 186, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 188, 7, 0, 0, 3, 0, 1, 0, 200, 7, 0, 0, 2, 0, 1, 0, - 11, 0, 0, 0, 2, 0, 0, 0, - 0, 0, 1, 0, 8, 0, 0, 0, + 6, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 197, 7, 0, 0, 114, 0, 0, 0, + 197, 7, 0, 0, 82, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 196, 7, 0, 0, 3, 0, 1, 0, 208, 7, 0, 0, 2, 0, 1, 0, - 56, 0, 0, 0, 1, 0, 0, 0, - 0, 0, 1, 0, 9, 0, 0, 0, + 52, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 205, 7, 0, 0, 178, 0, 0, 0, + 205, 7, 0, 0, 170, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 208, 7, 0, 0, 3, 0, 1, 0, 220, 7, 0, 0, 2, 0, 1, 0, - 55, 0, 0, 0, 6, 0, 0, 0, + 10, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 217, 7, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 7, 0, 0, 3, 0, 1, 0, + 228, 7, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 225, 7, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 224, 7, 0, 0, 3, 0, 1, 0, + 236, 7, 0, 0, 2, 0, 1, 0, + 57, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 233, 7, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 236, 7, 0, 0, 3, 0, 1, 0, + 248, 7, 0, 0, 2, 0, 1, 0, + 56, 0, 0, 0, 6, 0, 0, 0, 0, 0, 1, 0, 10, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 217, 7, 0, 0, 178, 0, 0, 0, + 245, 7, 0, 0, 178, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 220, 7, 0, 0, 3, 0, 1, 0, - 232, 7, 0, 0, 2, 0, 1, 0, - 61, 0, 0, 0, 2, 0, 0, 0, + 248, 7, 0, 0, 3, 0, 1, 0, + 4, 8, 0, 0, 2, 0, 1, 0, + 62, 0, 0, 0, 2, 0, 0, 0, 0, 0, 1, 0, 11, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 229, 7, 0, 0, 170, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 232, 7, 0, 0, 3, 0, 1, 0, - 4, 8, 0, 0, 2, 0, 1, 0, - 62, 0, 0, 0, 3, 0, 0, 0, - 0, 0, 1, 0, 12, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 8, 0, 0, 162, 0, 0, 0, + 1, 8, 0, 0, 170, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 4, 8, 0, 0, 3, 0, 1, 0, 32, 8, 0, 0, 2, 0, 1, 0, - 63, 0, 0, 0, 4, 0, 0, 0, - 0, 0, 1, 0, 13, 0, 0, 0, + 63, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 29, 8, 0, 0, 154, 0, 0, 0, + 29, 8, 0, 0, 162, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 32, 8, 0, 0, 3, 0, 1, 0, 60, 8, 0, 0, 2, 0, 1, 0, - 64, 0, 0, 0, 5, 0, 0, 0, - 0, 0, 1, 0, 14, 0, 0, 0, + 64, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 57, 8, 0, 0, 146, 0, 0, 0, + 57, 8, 0, 0, 154, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 60, 8, 0, 0, 3, 0, 1, 0, 88, 8, 0, 0, 2, 0, 1, 0, - 65, 0, 0, 0, 6, 0, 0, 0, - 0, 0, 1, 0, 15, 0, 0, 0, + 65, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 85, 8, 0, 0, 170, 0, 0, 0, + 85, 8, 0, 0, 146, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 88, 8, 0, 0, 3, 0, 1, 0, 116, 8, 0, 0, 2, 0, 1, 0, - 66, 0, 0, 0, 7, 0, 0, 0, - 0, 0, 1, 0, 16, 0, 0, 0, + 66, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 15, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 113, 8, 0, 0, 162, 0, 0, 0, + 113, 8, 0, 0, 170, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 116, 8, 0, 0, 3, 0, 1, 0, 144, 8, 0, 0, 2, 0, 1, 0, + 67, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 16, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 141, 8, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 144, 8, 0, 0, 3, 0, 1, 0, + 172, 8, 0, 0, 2, 0, 1, 0, 16, 0, 0, 0, 4, 0, 0, 0, 0, 0, 1, 0, 17, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 141, 8, 0, 0, 42, 0, 0, 0, + 169, 8, 0, 0, 42, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 136, 8, 0, 0, 3, 0, 1, 0, - 148, 8, 0, 0, 2, 0, 1, 0, + 164, 8, 0, 0, 3, 0, 1, 0, + 176, 8, 0, 0, 2, 0, 1, 0, 17, 0, 0, 0, 5, 0, 0, 0, 0, 0, 1, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 145, 8, 0, 0, 82, 0, 0, 0, + 173, 8, 0, 0, 82, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 144, 8, 0, 0, 3, 0, 1, 0, - 156, 8, 0, 0, 2, 0, 1, 0, + 172, 8, 0, 0, 3, 0, 1, 0, + 184, 8, 0, 0, 2, 0, 1, 0, 18, 0, 0, 0, 6, 0, 0, 0, 0, 0, 1, 0, 19, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 153, 8, 0, 0, 114, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 152, 8, 0, 0, 3, 0, 1, 0, - 164, 8, 0, 0, 2, 0, 1, 0, - 19, 0, 0, 0, 7, 0, 0, 0, - 0, 0, 1, 0, 20, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 161, 8, 0, 0, 90, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 160, 8, 0, 0, 3, 0, 1, 0, - 172, 8, 0, 0, 2, 0, 1, 0, - 20, 0, 0, 0, 8, 0, 0, 0, - 0, 0, 1, 0, 21, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 169, 8, 0, 0, 122, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 168, 8, 0, 0, 3, 0, 1, 0, - 180, 8, 0, 0, 2, 0, 1, 0, - 21, 0, 0, 0, 9, 0, 0, 0, - 0, 0, 1, 0, 22, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 177, 8, 0, 0, 146, 0, 0, 0, + 181, 8, 0, 0, 114, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 180, 8, 0, 0, 3, 0, 1, 0, 192, 8, 0, 0, 2, 0, 1, 0, - 22, 0, 0, 0, 10, 0, 0, 0, + 19, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 20, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 8, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 188, 8, 0, 0, 3, 0, 1, 0, + 200, 8, 0, 0, 2, 0, 1, 0, + 20, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 21, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 8, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 8, 0, 0, 3, 0, 1, 0, + 208, 8, 0, 0, 2, 0, 1, 0, + 21, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 22, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 8, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 8, 0, 0, 3, 0, 1, 0, + 220, 8, 0, 0, 2, 0, 1, 0, + 23, 0, 0, 0, 10, 0, 0, 0, 0, 0, 1, 0, 23, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 189, 8, 0, 0, 154, 0, 0, 0, + 217, 8, 0, 0, 154, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 192, 8, 0, 0, 3, 0, 1, 0, - 204, 8, 0, 0, 2, 0, 1, 0, - 23, 0, 0, 0, 11, 0, 0, 0, + 220, 8, 0, 0, 3, 0, 1, 0, + 232, 8, 0, 0, 2, 0, 1, 0, + 24, 0, 0, 0, 11, 0, 0, 0, 0, 0, 1, 0, 24, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 201, 8, 0, 0, 146, 0, 0, 0, + 229, 8, 0, 0, 146, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 204, 8, 0, 0, 3, 0, 1, 0, - 216, 8, 0, 0, 2, 0, 1, 0, - 24, 0, 0, 0, 8, 0, 0, 0, + 232, 8, 0, 0, 3, 0, 1, 0, + 244, 8, 0, 0, 2, 0, 1, 0, + 25, 0, 0, 0, 8, 0, 0, 0, 0, 0, 1, 0, 25, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 213, 8, 0, 0, 154, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 216, 8, 0, 0, 3, 0, 1, 0, - 228, 8, 0, 0, 2, 0, 1, 0, - 26, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 104, 149, 51, 53, 10, 88, 252, 147, - 225, 8, 0, 0, 114, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 27, 0, 0, 0, 5, 0, 0, 0, - 0, 0, 1, 0, 28, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 205, 8, 0, 0, 130, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 204, 8, 0, 0, 3, 0, 1, 0, - 216, 8, 0, 0, 2, 0, 1, 0, - 29, 0, 0, 0, 12, 0, 0, 0, - 0, 0, 1, 0, 29, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 213, 8, 0, 0, 106, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 212, 8, 0, 0, 3, 0, 1, 0, - 224, 8, 0, 0, 2, 0, 1, 0, - 67, 0, 0, 0, 6, 0, 0, 0, - 0, 0, 1, 0, 30, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 221, 8, 0, 0, 234, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 228, 8, 0, 0, 3, 0, 1, 0, - 240, 8, 0, 0, 2, 0, 1, 0, - 31, 0, 0, 0, 7, 0, 0, 0, - 0, 0, 1, 0, 31, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 237, 8, 0, 0, 130, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 236, 8, 0, 0, 3, 0, 1, 0, - 248, 8, 0, 0, 2, 0, 1, 0, - 36, 0, 0, 0, 13, 0, 0, 0, - 0, 0, 1, 0, 32, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 245, 8, 0, 0, 90, 0, 0, 0, + 241, 8, 0, 0, 154, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 244, 8, 0, 0, 3, 0, 1, 0, 0, 9, 0, 0, 2, 0, 1, 0, - 52, 0, 0, 0, 14, 0, 0, 0, - 0, 0, 1, 0, 33, 0, 0, 0, + 27, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 104, 149, 51, 53, 10, 88, 252, 147, + 253, 8, 0, 0, 114, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 253, 8, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 28, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 28, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 233, 8, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 8, 0, 0, 3, 0, 1, 0, + 244, 8, 0, 0, 2, 0, 1, 0, + 30, 0, 0, 0, 12, 0, 0, 0, + 0, 0, 1, 0, 29, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 8, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 240, 8, 0, 0, 3, 0, 1, 0, + 252, 8, 0, 0, 2, 0, 1, 0, + 68, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 30, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 249, 8, 0, 0, 234, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 9, 0, 0, 3, 0, 1, 0, 12, 9, 0, 0, 2, 0, 1, 0, - 32, 0, 0, 0, 30, 0, 0, 0, + 32, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 31, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 9, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 9, 0, 0, 3, 0, 1, 0, + 20, 9, 0, 0, 2, 0, 1, 0, + 37, 0, 0, 0, 13, 0, 0, 0, + 0, 0, 1, 0, 32, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 17, 9, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 9, 0, 0, 3, 0, 1, 0, + 28, 9, 0, 0, 2, 0, 1, 0, + 53, 0, 0, 0, 14, 0, 0, 0, + 0, 0, 1, 0, 33, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 9, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 28, 9, 0, 0, 3, 0, 1, 0, + 40, 9, 0, 0, 2, 0, 1, 0, + 33, 0, 0, 0, 30, 0, 0, 0, 0, 0, 1, 0, 34, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 9, 9, 0, 0, 138, 0, 0, 0, + 37, 9, 0, 0, 138, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 12, 9, 0, 0, 3, 0, 1, 0, - 24, 9, 0, 0, 2, 0, 1, 0, - 33, 0, 0, 0, 8, 0, 0, 0, + 40, 9, 0, 0, 3, 0, 1, 0, + 52, 9, 0, 0, 2, 0, 1, 0, + 34, 0, 0, 0, 8, 0, 0, 0, 0, 0, 1, 0, 35, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 21, 9, 0, 0, 138, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 24, 9, 0, 0, 3, 0, 1, 0, - 36, 9, 0, 0, 2, 0, 1, 0, - 38, 0, 0, 0, 16, 0, 0, 0, - 0, 0, 1, 0, 36, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 33, 9, 0, 0, 154, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 36, 9, 0, 0, 3, 0, 1, 0, - 48, 9, 0, 0, 2, 0, 1, 0, - 41, 0, 0, 0, 9, 0, 0, 0, - 0, 0, 1, 0, 37, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 45, 9, 0, 0, 234, 0, 0, 0, + 49, 9, 0, 0, 138, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 52, 9, 0, 0, 3, 0, 1, 0, 64, 9, 0, 0, 2, 0, 1, 0, - 42, 0, 0, 0, 10, 0, 0, 0, + 39, 0, 0, 0, 16, 0, 0, 0, + 0, 0, 1, 0, 36, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 9, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 9, 0, 0, 3, 0, 1, 0, + 76, 9, 0, 0, 2, 0, 1, 0, + 42, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 37, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 9, 0, 0, 234, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 80, 9, 0, 0, 3, 0, 1, 0, + 92, 9, 0, 0, 2, 0, 1, 0, + 43, 0, 0, 0, 10, 0, 0, 0, 0, 0, 1, 0, 38, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 61, 9, 0, 0, 58, 0, 0, 0, + 89, 9, 0, 0, 58, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 56, 9, 0, 0, 3, 0, 1, 0, - 68, 9, 0, 0, 2, 0, 1, 0, - 53, 0, 0, 0, 10, 0, 0, 0, + 84, 9, 0, 0, 3, 0, 1, 0, + 96, 9, 0, 0, 2, 0, 1, 0, + 54, 0, 0, 0, 10, 0, 0, 0, 0, 0, 1, 0, 39, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 65, 9, 0, 0, 186, 0, 0, 0, + 93, 9, 0, 0, 186, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 68, 9, 0, 0, 3, 0, 1, 0, - 80, 9, 0, 0, 2, 0, 1, 0, - 43, 0, 0, 0, 11, 0, 0, 0, + 96, 9, 0, 0, 3, 0, 1, 0, + 108, 9, 0, 0, 2, 0, 1, 0, + 44, 0, 0, 0, 11, 0, 0, 0, 0, 0, 1, 0, 41, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 77, 9, 0, 0, 98, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 76, 9, 0, 0, 3, 0, 1, 0, - 88, 9, 0, 0, 2, 0, 1, 0, - 57, 0, 0, 0, 31, 0, 0, 0, - 0, 0, 1, 0, 42, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 85, 9, 0, 0, 234, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 92, 9, 0, 0, 3, 0, 1, 0, - 104, 9, 0, 0, 2, 0, 1, 0, - 44, 0, 0, 0, 34, 0, 0, 0, - 0, 0, 1, 0, 43, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 101, 9, 0, 0, 138, 0, 0, 0, + 105, 9, 0, 0, 98, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 104, 9, 0, 0, 3, 0, 1, 0, 116, 9, 0, 0, 2, 0, 1, 0, - 45, 0, 0, 0, 11, 0, 0, 0, - 0, 0, 1, 0, 44, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 113, 9, 0, 0, 50, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 108, 9, 0, 0, 3, 0, 1, 0, - 136, 9, 0, 0, 2, 0, 1, 0, - 46, 0, 0, 0, 18, 0, 0, 0, - 0, 0, 1, 0, 45, 0, 0, 0, + 58, 0, 0, 0, 31, 0, 0, 0, + 0, 0, 1, 0, 42, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, - 133, 9, 0, 0, 114, 0, 0, 0, + 113, 9, 0, 0, 234, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 9, 0, 0, 3, 0, 1, 0, + 132, 9, 0, 0, 2, 0, 1, 0, + 45, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 1, 0, 43, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 129, 9, 0, 0, 138, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 132, 9, 0, 0, 3, 0, 1, 0, 144, 9, 0, 0, 2, 0, 1, 0, - 59, 0, 0, 0, 12, 0, 0, 0, + 46, 0, 0, 0, 11, 0, 0, 0, + 0, 0, 1, 0, 44, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 141, 9, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 136, 9, 0, 0, 3, 0, 1, 0, + 164, 9, 0, 0, 2, 0, 1, 0, + 47, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 1, 0, 45, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 161, 9, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 160, 9, 0, 0, 3, 0, 1, 0, + 172, 9, 0, 0, 2, 0, 1, 0, + 60, 0, 0, 0, 12, 0, 0, 0, 0, 0, 1, 0, 46, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 141, 9, 0, 0, 218, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 148, 9, 0, 0, 3, 0, 1, 0, - 160, 9, 0, 0, 2, 0, 1, 0, - 28, 0, 0, 0, 19, 0, 0, 0, - 0, 0, 1, 0, 47, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 157, 9, 0, 0, 130, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 156, 9, 0, 0, 3, 0, 1, 0, - 168, 9, 0, 0, 2, 0, 1, 0, - 25, 0, 0, 0, 12, 0, 0, 0, - 0, 0, 1, 0, 48, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 165, 9, 0, 0, 114, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 164, 9, 0, 0, 3, 0, 1, 0, - 176, 9, 0, 0, 2, 0, 1, 0, - 47, 0, 0, 0, 35, 0, 0, 0, - 0, 0, 1, 0, 49, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 173, 9, 0, 0, 146, 0, 0, 0, + 169, 9, 0, 0, 218, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 176, 9, 0, 0, 3, 0, 1, 0, 188, 9, 0, 0, 2, 0, 1, 0, - 48, 0, 0, 0, 40, 0, 0, 0, - 0, 0, 1, 0, 50, 0, 0, 0, + 29, 0, 0, 0, 19, 0, 0, 0, + 0, 0, 1, 0, 47, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 185, 9, 0, 0, 130, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 184, 9, 0, 0, 3, 0, 1, 0, 196, 9, 0, 0, 2, 0, 1, 0, - 58, 0, 0, 0, 21, 0, 0, 0, + 26, 0, 0, 0, 12, 0, 0, 0, + 0, 0, 1, 0, 48, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 9, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 192, 9, 0, 0, 3, 0, 1, 0, + 204, 9, 0, 0, 2, 0, 1, 0, + 48, 0, 0, 0, 35, 0, 0, 0, + 0, 0, 1, 0, 49, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 9, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 9, 0, 0, 3, 0, 1, 0, + 216, 9, 0, 0, 2, 0, 1, 0, + 49, 0, 0, 0, 40, 0, 0, 0, + 0, 0, 1, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 9, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 212, 9, 0, 0, 3, 0, 1, 0, + 224, 9, 0, 0, 2, 0, 1, 0, + 59, 0, 0, 0, 21, 0, 0, 0, 0, 0, 1, 0, 51, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 193, 9, 0, 0, 178, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 196, 9, 0, 0, 3, 0, 1, 0, - 208, 9, 0, 0, 2, 0, 1, 0, - 35, 0, 0, 0, 22, 0, 0, 0, - 0, 0, 1, 0, 52, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 205, 9, 0, 0, 146, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 208, 9, 0, 0, 3, 0, 1, 0, - 220, 9, 0, 0, 2, 0, 1, 0, - 60, 0, 0, 0, 23, 0, 0, 0, - 0, 0, 1, 0, 53, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 217, 9, 0, 0, 226, 0, 0, 0, + 221, 9, 0, 0, 178, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 224, 9, 0, 0, 3, 0, 1, 0, 236, 9, 0, 0, 2, 0, 1, 0, - 68, 0, 0, 0, 24, 0, 0, 0, - 0, 0, 1, 0, 54, 0, 0, 0, + 36, 0, 0, 0, 22, 0, 0, 0, + 0, 0, 1, 0, 52, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 233, 9, 0, 0, 242, 0, 0, 0, + 233, 9, 0, 0, 146, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 240, 9, 0, 0, 3, 0, 1, 0, - 252, 9, 0, 0, 2, 0, 1, 0, - 2, 0, 0, 0, 13, 0, 0, 0, - 0, 0, 1, 0, 55, 0, 0, 0, + 236, 9, 0, 0, 3, 0, 1, 0, + 248, 9, 0, 0, 2, 0, 1, 0, + 61, 0, 0, 0, 23, 0, 0, 0, + 0, 0, 1, 0, 53, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 249, 9, 0, 0, 138, 0, 0, 0, + 245, 9, 0, 0, 226, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 252, 9, 0, 0, 3, 0, 1, 0, 8, 10, 0, 0, 2, 0, 1, 0, + 69, 0, 0, 0, 24, 0, 0, 0, + 0, 0, 1, 0, 54, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 10, 0, 0, 242, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 10, 0, 0, 3, 0, 1, 0, + 24, 10, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 13, 0, 0, 0, + 0, 0, 1, 0, 55, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 10, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 24, 10, 0, 0, 3, 0, 1, 0, + 36, 10, 0, 0, 2, 0, 1, 0, 7, 0, 0, 0, 14, 0, 0, 0, 0, 0, 1, 0, 56, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 5, 10, 0, 0, 82, 0, 0, 0, + 33, 10, 0, 0, 82, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 4, 10, 0, 0, 3, 0, 1, 0, - 16, 10, 0, 0, 2, 0, 1, 0, - 54, 0, 0, 0, 15, 0, 0, 0, + 32, 10, 0, 0, 3, 0, 1, 0, + 44, 10, 0, 0, 2, 0, 1, 0, + 55, 0, 0, 0, 15, 0, 0, 0, 0, 0, 1, 0, 57, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 13, 10, 0, 0, 202, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 20, 10, 0, 0, 3, 0, 1, 0, - 32, 10, 0, 0, 2, 0, 1, 0, - 40, 0, 0, 0, 25, 0, 0, 0, - 0, 0, 1, 0, 58, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 29, 10, 0, 0, 34, 1, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 40, 10, 0, 0, 3, 0, 1, 0, - 52, 10, 0, 0, 2, 0, 1, 0, - 30, 0, 0, 0, 26, 0, 0, 0, - 0, 0, 1, 0, 59, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 49, 10, 0, 0, 106, 0, 0, 0, + 41, 10, 0, 0, 202, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 48, 10, 0, 0, 3, 0, 1, 0, 60, 10, 0, 0, 2, 0, 1, 0, - 34, 0, 0, 0, 27, 0, 0, 0, - 0, 0, 1, 0, 60, 0, 0, 0, + 41, 0, 0, 0, 25, 0, 0, 0, + 0, 0, 1, 0, 58, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 57, 10, 0, 0, 82, 0, 0, 0, + 57, 10, 0, 0, 34, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 56, 10, 0, 0, 3, 0, 1, 0, - 68, 10, 0, 0, 2, 0, 1, 0, - 39, 0, 0, 0, 28, 0, 0, 0, - 0, 0, 1, 0, 61, 0, 0, 0, + 68, 10, 0, 0, 3, 0, 1, 0, + 80, 10, 0, 0, 2, 0, 1, 0, + 31, 0, 0, 0, 26, 0, 0, 0, + 0, 0, 1, 0, 59, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 65, 10, 0, 0, 34, 1, 0, 0, + 77, 10, 0, 0, 106, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 76, 10, 0, 0, 3, 0, 1, 0, 88, 10, 0, 0, 2, 0, 1, 0, + 35, 0, 0, 0, 27, 0, 0, 0, + 0, 0, 1, 0, 60, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 85, 10, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 84, 10, 0, 0, 3, 0, 1, 0, + 96, 10, 0, 0, 2, 0, 1, 0, + 40, 0, 0, 0, 28, 0, 0, 0, + 0, 0, 1, 0, 61, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 93, 10, 0, 0, 34, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 10, 0, 0, 3, 0, 1, 0, + 116, 10, 0, 0, 2, 0, 1, 0, 12, 0, 0, 0, 13, 0, 0, 0, 0, 0, 1, 0, 62, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 85, 10, 0, 0, 114, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 84, 10, 0, 0, 3, 0, 1, 0, - 112, 10, 0, 0, 2, 0, 1, 0, - 49, 0, 0, 0, 29, 0, 0, 0, - 0, 0, 1, 0, 63, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 109, 10, 0, 0, 138, 0, 0, 0, + 113, 10, 0, 0, 114, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 112, 10, 0, 0, 3, 0, 1, 0, - 124, 10, 0, 0, 2, 0, 1, 0, - 8, 0, 0, 0, 30, 0, 0, 0, - 0, 0, 1, 0, 64, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 121, 10, 0, 0, 50, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 116, 10, 0, 0, 3, 0, 1, 0, - 128, 10, 0, 0, 2, 0, 1, 0, - 13, 0, 0, 0, 41, 0, 0, 0, - 0, 0, 1, 0, 65, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 125, 10, 0, 0, 178, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 128, 10, 0, 0, 3, 0, 1, 0, 140, 10, 0, 0, 2, 0, 1, 0, - 3, 0, 0, 0, 224, 3, 0, 0, - 0, 0, 1, 0, 66, 0, 0, 0, + 50, 0, 0, 0, 29, 0, 0, 0, + 0, 0, 1, 0, 63, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 137, 10, 0, 0, 58, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 132, 10, 0, 0, 3, 0, 1, 0, - 144, 10, 0, 0, 2, 0, 1, 0, - 14, 0, 0, 0, 32, 0, 0, 0, - 0, 0, 1, 0, 68, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 141, 10, 0, 0, 130, 0, 0, 0, + 137, 10, 0, 0, 138, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 140, 10, 0, 0, 3, 0, 1, 0, 152, 10, 0, 0, 2, 0, 1, 0, - 15, 0, 0, 0, 225, 3, 0, 0, - 0, 0, 1, 0, 69, 0, 0, 0, + 8, 0, 0, 0, 30, 0, 0, 0, + 0, 0, 1, 0, 64, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 149, 10, 0, 0, 114, 0, 0, 0, + 149, 10, 0, 0, 50, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 148, 10, 0, 0, 3, 0, 1, 0, - 160, 10, 0, 0, 2, 0, 1, 0, - 37, 0, 0, 0, 226, 3, 0, 0, - 0, 0, 1, 0, 70, 0, 0, 0, + 144, 10, 0, 0, 3, 0, 1, 0, + 156, 10, 0, 0, 2, 0, 1, 0, + 13, 0, 0, 0, 41, 0, 0, 0, + 0, 0, 1, 0, 65, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 157, 10, 0, 0, 114, 0, 0, 0, + 153, 10, 0, 0, 178, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 156, 10, 0, 0, 3, 0, 1, 0, 168, 10, 0, 0, 2, 0, 1, 0, - 9, 0, 0, 0, 227, 3, 0, 0, - 0, 0, 1, 0, 71, 0, 0, 0, + 3, 0, 0, 0, 224, 3, 0, 0, + 0, 0, 1, 0, 66, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 165, 10, 0, 0, 18, 1, 0, 0, + 165, 10, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 160, 10, 0, 0, 3, 0, 1, 0, + 172, 10, 0, 0, 2, 0, 1, 0, + 14, 0, 0, 0, 32, 0, 0, 0, + 0, 0, 1, 0, 68, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 169, 10, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 10, 0, 0, 3, 0, 1, 0, + 180, 10, 0, 0, 2, 0, 1, 0, + 15, 0, 0, 0, 225, 3, 0, 0, + 0, 0, 1, 0, 69, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 10, 0, 0, 114, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 176, 10, 0, 0, 3, 0, 1, 0, 188, 10, 0, 0, 2, 0, 1, 0, + 38, 0, 0, 0, 226, 3, 0, 0, + 0, 0, 1, 0, 70, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 10, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 10, 0, 0, 3, 0, 1, 0, + 196, 10, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 227, 3, 0, 0, + 0, 0, 1, 0, 71, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 10, 0, 0, 18, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 10, 0, 0, 3, 0, 1, 0, + 216, 10, 0, 0, 2, 0, 1, 0, + 22, 0, 0, 0, 33, 0, 0, 0, + 0, 0, 1, 0, 72, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 10, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 10, 0, 0, 3, 0, 1, 0, + 228, 10, 0, 0, 2, 0, 1, 0, 99, 97, 114, 78, 97, 109, 101, 0, 12, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, @@ -4741,6 +4748,16 @@ static const ::capnp::_::AlignedData<1252> b_8c69372490aaa9da = { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 105, 114, 101, 83, 116, 105, 102, + 102, 110, 101, 115, 115, 70, 97, 99, + 116, 111, 114, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, } }; @@ -4758,11 +4775,11 @@ static const ::capnp::_::RawSchema* const d_8c69372490aaa9da[] = { &s_e836349c6056b0c9, &s_ff99e3682a833c51, }; -static const uint16_t m_8c69372490aaa9da[] = {63, 66, 15, 16, 1, 42, 0, 37, 19, 44, 39, 29, 6, 54, 4, 5, 2, 68, 47, 62, 53, 13, 14, 55, 38, 46, 26, 59, 56, 25, 17, 65, 52, 7, 49, 8, 48, 64, 36, 3, 43, 34, 22, 60, 9, 40, 10, 31, 51, 67, 35, 33, 27, 45, 11, 12, 32, 20, 21, 58, 30, 50, 23, 24, 41, 57, 28, 61, 18}; -static const uint16_t i_8c69372490aaa9da[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 67, 68}; +static const uint16_t m_8c69372490aaa9da[] = {63, 66, 15, 16, 1, 42, 0, 37, 19, 44, 39, 29, 6, 54, 4, 5, 2, 68, 47, 62, 53, 13, 14, 55, 38, 46, 26, 59, 56, 25, 17, 65, 52, 7, 49, 8, 48, 64, 36, 3, 43, 34, 22, 60, 9, 40, 10, 31, 51, 67, 35, 33, 27, 45, 11, 12, 32, 20, 21, 58, 30, 50, 69, 23, 24, 41, 57, 28, 61, 18}; +static const uint16_t i_8c69372490aaa9da[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 67, 68, 69}; const ::capnp::_::RawSchema s_8c69372490aaa9da = { - 0x8c69372490aaa9da, b_8c69372490aaa9da.words, 1252, d_8c69372490aaa9da, m_8c69372490aaa9da, - 10, 69, i_8c69372490aaa9da, nullptr, nullptr, { &s_8c69372490aaa9da, nullptr, nullptr, 0, 0, nullptr } + 0x8c69372490aaa9da, b_8c69372490aaa9da.words, 1269, d_8c69372490aaa9da, m_8c69372490aaa9da, + 10, 70, i_8c69372490aaa9da, nullptr, nullptr, { &s_8c69372490aaa9da, nullptr, nullptr, 0, 0, nullptr } }; #endif // !CAPNP_LITE static const ::capnp::_::AlignedData<85> b_e836349c6056b0c9 = { @@ -5805,7 +5822,7 @@ const ::capnp::_::RawSchema s_9d151e3f28616a12 = { 0, 8, i_9d151e3f28616a12, nullptr, nullptr, { &s_9d151e3f28616a12, nullptr, nullptr, 0, 0, nullptr } }; #endif // !CAPNP_LITE -static const ::capnp::_::AlignedData<152> b_95551e5b1edaf451 = { +static const ::capnp::_::AlignedData<158> b_95551e5b1edaf451 = { { 0, 0, 0, 0, 5, 0, 6, 0, 81, 244, 218, 30, 91, 30, 85, 149, 20, 0, 0, 0, 2, 0, 0, 0, @@ -5815,7 +5832,7 @@ static const ::capnp::_::AlignedData<152> b_95551e5b1edaf451 = { 21, 0, 0, 0, 2, 1, 0, 0, 33, 0, 0, 0, 7, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 29, 0, 0, 0, 191, 2, 0, 0, + 29, 0, 0, 0, 215, 2, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 99, 97, 114, 46, 99, 97, 112, 110, @@ -5823,93 +5840,96 @@ static const ::capnp::_::AlignedData<152> b_95551e5b1edaf451 = { 97, 109, 115, 46, 83, 97, 102, 101, 116, 121, 77, 111, 100, 101, 108, 0, 0, 0, 0, 0, 1, 0, 1, 0, - 116, 0, 0, 0, 1, 0, 2, 0, + 120, 0, 0, 0, 1, 0, 2, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 85, 1, 0, 0, 58, 0, 0, 0, + 97, 1, 0, 0, 58, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, - 77, 1, 0, 0, 90, 0, 0, 0, + 89, 1, 0, 0, 90, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2, 0, 0, 0, 0, 0, 0, 0, - 73, 1, 0, 0, 58, 0, 0, 0, + 85, 1, 0, 0, 58, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 3, 0, 0, 0, 0, 0, 0, 0, - 65, 1, 0, 0, 58, 0, 0, 0, + 77, 1, 0, 0, 58, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 4, 0, 0, 0, 0, 0, 0, 0, - 57, 1, 0, 0, 26, 0, 0, 0, + 69, 1, 0, 0, 26, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 5, 0, 0, 0, 0, 0, 0, 0, - 49, 1, 0, 0, 146, 0, 0, 0, + 61, 1, 0, 0, 146, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, - 49, 1, 0, 0, 42, 0, 0, 0, + 61, 1, 0, 0, 42, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 0, 0, 0, 0, 0, 0, 0, - 41, 1, 0, 0, 74, 0, 0, 0, + 53, 1, 0, 0, 74, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 8, 0, 0, 0, 0, 0, 0, 0, - 37, 1, 0, 0, 66, 0, 0, 0, + 49, 1, 0, 0, 66, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 9, 0, 0, 0, 0, 0, 0, 0, - 29, 1, 0, 0, 74, 0, 0, 0, + 41, 1, 0, 0, 74, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 10, 0, 0, 0, 0, 0, 0, 0, - 25, 1, 0, 0, 50, 0, 0, 0, + 37, 1, 0, 0, 50, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 11, 0, 0, 0, 0, 0, 0, 0, - 17, 1, 0, 0, 58, 0, 0, 0, + 29, 1, 0, 0, 58, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 12, 0, 0, 0, 0, 0, 0, 0, - 9, 1, 0, 0, 82, 0, 0, 0, + 21, 1, 0, 0, 82, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 13, 0, 0, 0, 0, 0, 0, 0, - 5, 1, 0, 0, 50, 0, 0, 0, + 17, 1, 0, 0, 50, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 14, 0, 0, 0, 0, 0, 0, 0, - 253, 0, 0, 0, 58, 0, 0, 0, + 9, 1, 0, 0, 58, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 15, 0, 0, 0, 0, 0, 0, 0, - 245, 0, 0, 0, 90, 0, 0, 0, + 1, 1, 0, 0, 90, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 16, 0, 0, 0, 0, 0, 0, 0, - 241, 0, 0, 0, 90, 0, 0, 0, + 253, 0, 0, 0, 90, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 17, 0, 0, 0, 0, 0, 0, 0, - 237, 0, 0, 0, 82, 0, 0, 0, + 249, 0, 0, 0, 82, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 0, 0, 0, 0, 0, 0, 0, - 233, 0, 0, 0, 58, 0, 0, 0, + 245, 0, 0, 0, 58, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 19, 0, 0, 0, 0, 0, 0, 0, - 225, 0, 0, 0, 74, 0, 0, 0, + 237, 0, 0, 0, 74, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 20, 0, 0, 0, 0, 0, 0, 0, - 221, 0, 0, 0, 90, 0, 0, 0, + 233, 0, 0, 0, 90, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 21, 0, 0, 0, 0, 0, 0, 0, - 217, 0, 0, 0, 106, 0, 0, 0, + 229, 0, 0, 0, 106, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 22, 0, 0, 0, 0, 0, 0, 0, - 213, 0, 0, 0, 130, 0, 0, 0, + 225, 0, 0, 0, 130, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 23, 0, 0, 0, 0, 0, 0, 0, - 209, 0, 0, 0, 114, 0, 0, 0, + 221, 0, 0, 0, 114, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 24, 0, 0, 0, 0, 0, 0, 0, - 205, 0, 0, 0, 138, 0, 0, 0, + 217, 0, 0, 0, 138, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 25, 0, 0, 0, 0, 0, 0, 0, - 205, 0, 0, 0, 114, 0, 0, 0, + 217, 0, 0, 0, 114, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 26, 0, 0, 0, 0, 0, 0, 0, - 201, 0, 0, 0, 58, 0, 0, 0, + 213, 0, 0, 0, 58, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 27, 0, 0, 0, 0, 0, 0, 0, - 193, 0, 0, 0, 42, 0, 0, 0, + 205, 0, 0, 0, 42, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 28, 0, 0, 0, 0, 0, 0, 0, - 185, 0, 0, 0, 106, 0, 0, 0, + 197, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 0, 0, 0, 0, + 193, 0, 0, 0, 138, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 115, 105, 108, 101, 110, 116, 0, 0, 104, 111, 110, 100, 97, 78, 105, 100, @@ -5957,14 +5977,17 @@ static const ::capnp::_::AlignedData<152> b_95551e5b1edaf451 = { 104, 111, 110, 103, 113, 105, 0, 0, 98, 111, 100, 121, 0, 0, 0, 0, 104, 121, 117, 110, 100, 97, 105, 67, - 97, 110, 102, 100, 0, 0, 0, 0, } + 97, 110, 102, 100, 0, 0, 0, 0, + 118, 111, 108, 107, 115, 119, 97, 103, + 101, 110, 77, 113, 98, 69, 118, 111, + 0, 0, 0, 0, 0, 0, 0, 0, } }; ::capnp::word const* const bp_95551e5b1edaf451 = b_95551e5b1edaf451.words; #if !CAPNP_LITE -static const uint16_t m_95551e5b1edaf451[] = {17, 27, 7, 9, 3, 6, 4, 18, 12, 20, 5, 1, 26, 8, 28, 24, 23, 13, 14, 19, 0, 11, 22, 10, 2, 16, 15, 25, 21}; +static const uint16_t m_95551e5b1edaf451[] = {17, 27, 7, 9, 3, 6, 4, 18, 12, 20, 5, 1, 26, 8, 28, 24, 23, 13, 14, 19, 0, 11, 22, 10, 2, 16, 15, 25, 29, 21}; const ::capnp::_::RawSchema s_95551e5b1edaf451 = { - 0x95551e5b1edaf451, b_95551e5b1edaf451.words, 152, nullptr, m_95551e5b1edaf451, - 0, 29, nullptr, nullptr, nullptr, { &s_95551e5b1edaf451, nullptr, nullptr, 0, 0, nullptr } + 0x95551e5b1edaf451, b_95551e5b1edaf451.words, 158, nullptr, m_95551e5b1edaf451, + 0, 30, nullptr, nullptr, nullptr, { &s_95551e5b1edaf451, nullptr, nullptr, 0, 0, nullptr } }; #endif // !CAPNP_LITE CAPNP_DEFINE_ENUM(SafetyModel_95551e5b1edaf451, 95551e5b1edaf451); diff --git a/cereal/gen/cpp/car.capnp.h b/cereal/gen/cpp/car.capnp.h index f198bd245..23accb52f 100644 --- a/cereal/gen/cpp/car.capnp.h +++ b/cereal/gen/cpp/car.capnp.h @@ -256,6 +256,7 @@ enum class SafetyModel_95551e5b1edaf451: uint16_t { HONGQI, BODY, HYUNDAI_CANFD, + VOLKSWAGEN_MQB_EVO, }; CAPNP_DECLARE_ENUM(SafetyModel, 95551e5b1edaf451); CAPNP_DECLARE_SCHEMA(d661512be2def77f); @@ -2340,6 +2341,8 @@ public: inline bool getExperimentalLongitudinalAvailable() const; + inline float getTireStiffnessFactor() const; + private: ::capnp::_::StructReader _reader; template @@ -2633,6 +2636,9 @@ public: inline bool getExperimentalLongitudinalAvailable(); inline void setExperimentalLongitudinalAvailable(bool value); + inline float getTireStiffnessFactor(); + inline void setTireStiffnessFactor(float value); + private: ::capnp::_::StructBuilder _builder; template @@ -7137,6 +7143,20 @@ inline void CarParams::Builder::setExperimentalLongitudinalAvailable(bool value) ::capnp::bounded<995>() * ::capnp::ELEMENTS, value); } +inline float CarParams::Reader::getTireStiffnessFactor() const { + return _reader.getDataField( + ::capnp::bounded<33>() * ::capnp::ELEMENTS); +} + +inline float CarParams::Builder::getTireStiffnessFactor() { + return _builder.getDataField( + ::capnp::bounded<33>() * ::capnp::ELEMENTS); +} +inline void CarParams::Builder::setTireStiffnessFactor(float value) { + _builder.setDataField( + ::capnp::bounded<33>() * ::capnp::ELEMENTS, value); +} + inline ::cereal::CarParams::SafetyModel CarParams::SafetyConfig::Reader::getSafetyModel() const { return _reader.getDataField< ::cereal::CarParams::SafetyModel>( ::capnp::bounded<0>() * ::capnp::ELEMENTS); diff --git a/cereal/libcereal_shared.so b/cereal/libcereal_shared.so index aa3015932..bdeb9a898 100755 Binary files a/cereal/libcereal_shared.so and b/cereal/libcereal_shared.so differ diff --git a/cereal/visionipc/visionipc_pyx.so b/cereal/visionipc/visionipc_pyx.so index d5aa370ef..18934d172 100755 Binary files a/cereal/visionipc/visionipc_pyx.so and b/cereal/visionipc/visionipc_pyx.so differ diff --git a/common/file_helpers.py b/common/file_helpers.py index 8a45fa313..227d614d7 100644 --- a/common/file_helpers.py +++ b/common/file_helpers.py @@ -5,7 +5,7 @@ from atomicwrites import AtomicWriter def mkdirs_exists_ok(path): - if path.startswith('http://') or path.startswith('https://'): + if path.startswith(('http://', 'https://')): raise ValueError('URL path') try: os.makedirs(path) diff --git a/common/logging_extra.py b/common/logging_extra.py index 899ad7a39..e2637d2e0 100644 --- a/common/logging_extra.py +++ b/common/logging_extra.py @@ -65,7 +65,7 @@ class SwagFormatter(logging.Formatter): return record_dict - def format(self, record): + def format(self, record): # noqa: A003 if self.swaglogger is None: raise Exception("must set swaglogger before calling format()") return json_robust_dumps(self.format_dict(record)) @@ -95,7 +95,7 @@ class SwagLogFileFormatter(SwagFormatter): k += "$a" return k, v - def format(self, record): + def format(self, record): # noqa: A003 if isinstance(record, str): v = json.loads(record) else: diff --git a/common/params_pyx.so b/common/params_pyx.so index eec86ee0b..35e6777b3 100755 Binary files a/common/params_pyx.so and b/common/params_pyx.so differ diff --git a/common/spinner.py b/common/spinner.py index 57242d644..34fd720ee 100644 --- a/common/spinner.py +++ b/common/spinner.py @@ -29,11 +29,11 @@ class Spinner(): def close(self): if self.spinner_proc is not None: + self.spinner_proc.kill() try: - self.spinner_proc.stdin.close() - except BrokenPipeError: - pass - self.spinner_proc.terminate() + self.spinner_proc.communicate(timeout=2.) + except subprocess.TimeoutExpired: + print("WARNING: failed to kill spinner") self.spinner_proc = None def __del__(self): diff --git a/common/transformations/camera.py b/common/transformations/camera.py index b20ed5c64..eaed0e7af 100644 --- a/common/transformations/camera.py +++ b/common/transformations/camera.py @@ -61,14 +61,6 @@ device_frame_from_view_frame = np.array([ view_frame_from_device_frame = device_frame_from_view_frame.T -def get_calib_from_vp(vp): - vp_norm = normalize(vp) - yaw_calib = np.arctan(vp_norm[0]) - pitch_calib = -np.arctan(vp_norm[1]*np.cos(yaw_calib)) - roll_calib = 0 - return roll_calib, pitch_calib, yaw_calib - - # aka 'extrinsic_matrix' # road : x->forward, y -> left, z->up def get_view_frame_from_road_frame(roll, pitch, yaw, height): @@ -131,6 +123,14 @@ def denormalize(img_pts, intrinsics=fcam_intrinsics, width=np.inf, height=np.inf return img_pts_denormalized[:, :2].reshape(input_shape) +def get_calib_from_vp(vp, intrinsics=fcam_intrinsics): + vp_norm = normalize(vp, intrinsics) + yaw_calib = np.arctan(vp_norm[0]) + pitch_calib = -np.arctan(vp_norm[1]*np.cos(yaw_calib)) + roll_calib = 0 + return roll_calib, pitch_calib, yaw_calib + + def device_from_ecef(pos_ecef, orientation_ecef, pt_ecef): # device from ecef frame # device frame is x -> forward, y-> right, z -> down diff --git a/common/util.h b/common/util.h index 34721700e..aaa54d52a 100644 --- a/common/util.h +++ b/common/util.h @@ -44,6 +44,7 @@ namespace util { void set_thread_name(const char* name); int set_realtime_priority(int level); int set_core_affinity(std::vector cores); +int set_file_descriptor_limit(uint64_t limit); // ***** Time helpers ***** struct tm get_time(); @@ -75,10 +76,13 @@ int getenv(const char* key, int default_val); float getenv(const char* key, float default_val); std::string hexdump(const uint8_t* in, const size_t size); -std::string random_string(std::string::size_type length); std::string dir_name(std::string const& path); -// **** file fhelpers ***** +// ***** random helpers ***** +int random_int(int min, int max); +std::string random_string(std::string::size_type length); + +// **** file helpers ***** std::string read_file(const std::string& fn); std::map read_files_in_dir(const std::string& path); int write_file(const char* path, const void* data, size_t size, int flags = O_WRONLY, mode_t mode = 0664); diff --git a/common/version.h b/common/version.h index 7be778ea8..47c2a167a 100644 --- a/common/version.h +++ b/common/version.h @@ -1 +1 @@ -#define COMMA_VERSION "2023.08.15" +#define COMMA_VERSION "2023.08.22" diff --git a/opendbc/can/common.h b/opendbc/can/common.h index 0031d787f..03b99e559 100644 --- a/opendbc/can/common.h +++ b/opendbc/can/common.h @@ -76,8 +76,7 @@ public: uint64_t can_invalid_cnt = CAN_INVALID_CNT; CANParser(int abus, const std::string& dbc_name, - const std::vector &options, - const std::vector &sigoptions); + const std::vector> &messages); CANParser(int abus, const std::string& dbc_name, bool ignore_checksum, bool ignore_counter); #ifndef DYNAMIC_CAPNP void update_string(const std::string &data, bool sendcan); diff --git a/opendbc/can/common.pxd b/opendbc/can/common.pxd index aeb1f0a92..4f62ba2a1 100644 --- a/opendbc/can/common.pxd +++ b/opendbc/can/common.pxd @@ -3,6 +3,7 @@ from libc.stdint cimport uint8_t, uint16_t, uint32_t, uint64_t from libcpp cimport bool +from libcpp.pair cimport pair from libcpp.string cimport string from libcpp.vector cimport vector @@ -48,14 +49,6 @@ cdef extern from "common_dbc.h": vector[Msg] msgs vector[Val] vals - cdef struct SignalParseOptions: - uint32_t address - string name - - cdef struct MessageParseOptions: - uint32_t address - int check_frequency - cdef struct SignalValue: uint32_t address uint64_t ts_nanos @@ -74,8 +67,8 @@ cdef extern from "common.h": cdef cppclass CANParser: bool can_valid bool bus_timeout - CANParser(int, string, vector[MessageParseOptions], vector[SignalParseOptions]) - void update_strings(vector[string]&, vector[SignalValue]&, bool) + CANParser(int, string, vector[pair[uint32_t, int]]) + void update_strings(vector[string]&, vector[SignalValue]&, bool) except + cdef cppclass CANPacker: CANPacker(string) diff --git a/opendbc/can/common_dbc.h b/opendbc/can/common_dbc.h index 1e0f03452..e8c27278c 100644 --- a/opendbc/can/common_dbc.h +++ b/opendbc/can/common_dbc.h @@ -12,16 +12,6 @@ struct SignalPackValue { double value; }; -struct SignalParseOptions { - uint32_t address; - std::string name; -}; - -struct MessageParseOptions { - uint32_t address; - int check_frequency; -}; - struct SignalValue { uint32_t address; uint64_t ts_nanos; diff --git a/opendbc/can/libdbc.so b/opendbc/can/libdbc.so index 954033706..5c9cfa058 100755 Binary files a/opendbc/can/libdbc.so and b/opendbc/can/libdbc.so differ diff --git a/opendbc/can/packer_pyx.cpp b/opendbc/can/packer_pyx.cpp index be4b130ce..050b4b130 100644 --- a/opendbc/can/packer_pyx.cpp +++ b/opendbc/can/packer_pyx.cpp @@ -1405,7 +1405,7 @@ static const char *__pyx_f[] = { /*--- Type declarations ---*/ struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker; -/* "common.pxd":10 +/* "common.pxd":11 * * * ctypedef unsigned int (*calc_checksum_type)(uint32_t, const Signal&, const vector[uint8_t] &) # <<<<<<<<<<<<<< @@ -2112,6 +2112,8 @@ static PyObject *__pyx_f_7opendbc_3can_10packer_pyx_9CANPacker_make_can_msg(stru /* Module declarations from "libcpp" */ +/* Module declarations from "libcpp.pair" */ + /* Module declarations from "opendbc.can.common" */ /* Module declarations from "opendbc.can.packer_pyx" */ @@ -2218,6 +2220,8 @@ typedef struct { #if CYTHON_USE_MODULE_STATE #endif #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE PyObject *__pyx_type_7opendbc_3can_10packer_pyx_CANPacker; #endif PyTypeObject *__pyx_ptype_7opendbc_3can_10packer_pyx_CANPacker; @@ -2473,6 +2477,8 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #if CYTHON_USE_MODULE_STATE #endif #if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE #define __pyx_type_7opendbc_3can_10packer_pyx_CANPacker __pyx_mstate_global->__pyx_type_7opendbc_3can_10packer_pyx_CANPacker #endif #define __pyx_ptype_7opendbc_3can_10packer_pyx_CANPacker __pyx_mstate_global->__pyx_ptype_7opendbc_3can_10packer_pyx_CANPacker diff --git a/opendbc/can/packer_pyx.so b/opendbc/can/packer_pyx.so index f94bcbd86..a81fb0dc0 100755 Binary files a/opendbc/can/packer_pyx.so and b/opendbc/can/packer_pyx.so differ diff --git a/opendbc/can/parser_pyx.cpp b/opendbc/can/parser_pyx.cpp index e76b3b4a3..8f2e4627f 100644 --- a/opendbc/can/parser_pyx.cpp +++ b/opendbc/can/parser_pyx.cpp @@ -1108,13 +1108,10 @@ static CYTHON_INLINE float __PYX_NAN() { #define __PYX_HAVE__opendbc__can__parser_pyx #define __PYX_HAVE_API__opendbc__can__parser_pyx /* Early includes */ -#include -#include #include "ios" #include "new" #include "stdexcept" #include "typeinfo" -#include #include #if __cplusplus >= 201103L || (defined(_MSC_VER) && _MSC_VER >= 1600) @@ -1128,9 +1125,11 @@ static CYTHON_INLINE float __PYX_NAN() { #endif +#include +#include +#include #include #include -#include #include "common_dbc.h" #include "common.h" #ifdef _OPENMP @@ -1406,11 +1405,8 @@ static const char *__pyx_f[] = { /*--- Type declarations ---*/ struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser; struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine; -struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__; -struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr; -struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr; -/* "common.pxd":10 +/* "common.pxd":11 * * * ctypedef unsigned int (*calc_checksum_type)(uint32_t, const Signal&, const vector[uint8_t] &) # <<<<<<<<<<<<<< @@ -1430,7 +1426,6 @@ struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser { PyObject_HEAD CANParser *can; struct DBC const *dbc; - std::map address_to_msg_name; std::vector can_values; PyObject *vl; PyObject *vl_all; @@ -1439,7 +1434,7 @@ struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser { }; -/* "opendbc/can/parser_pyx.pyx":147 +/* "opendbc/can/parser_pyx.pyx":104 * * * cdef class CANDefine(): # <<<<<<<<<<<<<< @@ -1453,49 +1448,6 @@ struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine { std::string dbc_name; }; - -/* "opendbc/can/parser_pyx.pyx":31 - * string dbc_name - * - * def __init__(self, dbc_name, signals, checks=None, bus=0, enforce_checks=True): # <<<<<<<<<<<<<< - * if checks is None: - * checks = [] - */ -struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ { - PyObject_HEAD - struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self; -}; - - -/* "opendbc/can/parser_pyx.pyx":92 - * unchecked = signal_addrs - checked_addrs - * if len(unchecked): - * err_msg = ", ".join(f"{self.address_to_msg_name[addr].decode()} ({hex(addr)})" for addr in unchecked) # <<<<<<<<<<<<<< - * raise RuntimeError(f"Unchecked addrs: {err_msg}") - * - */ -struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr { - PyObject_HEAD - struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ *__pyx_outer_scope; - PyObject *__pyx_genexpr_arg_0; - PyObject *__pyx_v_addr; -}; - - -/* "opendbc/can/parser_pyx.pyx":102 - * signal_options_v.push_back(spo) - * - * message_options = dict((address, 0) for _, address in signals) # <<<<<<<<<<<<<< - * message_options.update(dict(checks)) - * - */ -struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr { - PyObject_HEAD - PyObject *__pyx_genexpr_arg_0; - PyObject *__pyx_v__; - PyObject *__pyx_v_address; -}; - /* #### Code section: utility_code_proto ### */ /* --- Runtime support code (head) --- */ @@ -1642,6 +1594,18 @@ static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, P /* GetBuiltinName.proto */ static PyObject *__Pyx_GetBuiltinName(PyObject *name); +/* RaiseTooManyValuesToUnpack.proto */ +static CYTHON_INLINE void __Pyx_RaiseTooManyValuesError(Py_ssize_t expected); + +/* RaiseNeedMoreValuesToUnpack.proto */ +static CYTHON_INLINE void __Pyx_RaiseNeedMoreValuesError(Py_ssize_t index); + +/* IterFinish.proto */ +static CYTHON_INLINE int __Pyx_IterFinish(void); + +/* UnpackItemEndCheck.proto */ +static int __Pyx_IternextUnpackEndCheck(PyObject *retval, Py_ssize_t expected); + /* TupleAndListFromArray.proto */ #if CYTHON_COMPILING_IN_CPYTHON static CYTHON_INLINE PyObject* __Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n); @@ -1697,60 +1661,35 @@ static int __Pyx_ParseOptionalKeywords(PyObject *kwds, PyObject *const *kwvalues PyObject *kwds2, PyObject *values[], Py_ssize_t num_pos_args, const char* function_name); -/* RaiseUnboundLocalError.proto */ -static CYTHON_INLINE void __Pyx_RaiseUnboundLocalError(const char *varname); - -/* ListCompAppend.proto */ -#if CYTHON_USE_PYLIST_INTERNALS && CYTHON_ASSUME_SAFE_MACROS -static CYTHON_INLINE int __Pyx_ListComp_Append(PyObject* list, PyObject* x) { - PyListObject* L = (PyListObject*) list; - Py_ssize_t len = Py_SIZE(list); - if (likely(L->allocated > len)) { - Py_INCREF(x); - PyList_SET_ITEM(list, len, x); - __Pyx_SET_SIZE(list, len + 1); - return 0; - } - return PyList_Append(list, x); -} +/* MoveIfSupported.proto */ +#if __cplusplus >= 201103L || (defined(_MSC_VER) && _MSC_VER >= 1600) + #include + #define __PYX_STD_MOVE_IF_SUPPORTED(x) std::move(x) #else -#define __Pyx_ListComp_Append(L,x) PyList_Append(L,x) + #define __PYX_STD_MOVE_IF_SUPPORTED(x) x #endif -/* IncludeCppStringH.proto */ -#include - -/* decode_c_string_utf16.proto */ -static CYTHON_INLINE PyObject *__Pyx_PyUnicode_DecodeUTF16(const char *s, Py_ssize_t size, const char *errors) { - int byteorder = 0; - return PyUnicode_DecodeUTF16(s, size, errors, &byteorder); -} -static CYTHON_INLINE PyObject *__Pyx_PyUnicode_DecodeUTF16LE(const char *s, Py_ssize_t size, const char *errors) { - int byteorder = -1; - return PyUnicode_DecodeUTF16(s, size, errors, &byteorder); -} -static CYTHON_INLINE PyObject *__Pyx_PyUnicode_DecodeUTF16BE(const char *s, Py_ssize_t size, const char *errors) { - int byteorder = 1; - return PyUnicode_DecodeUTF16(s, size, errors, &byteorder); -} - -/* decode_c_bytes.proto */ -static CYTHON_INLINE PyObject* __Pyx_decode_c_bytes( - const char* cstring, Py_ssize_t length, Py_ssize_t start, Py_ssize_t stop, - const char* encoding, const char* errors, - PyObject* (*decode_func)(const char *s, Py_ssize_t size, const char *errors)); - -/* decode_cpp_string.proto */ -static CYTHON_INLINE PyObject* __Pyx_decode_cpp_string( - std::string cppstring, Py_ssize_t start, Py_ssize_t stop, - const char* encoding, const char* errors, - PyObject* (*decode_func)(const char *s, Py_ssize_t size, const char *errors)) { - return __Pyx_decode_c_bytes( - cppstring.data(), cppstring.size(), start, stop, encoding, errors, decode_func); -} - -/* RaiseClosureNameError.proto */ -static CYTHON_INLINE void __Pyx_RaiseClosureNameError(const char *varname); +/* PyObjectFormatSimple.proto */ +#if CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + PyObject_Format(s, f)) +#elif PY_MAJOR_VERSION < 3 + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + likely(PyString_CheckExact(s)) ? PyUnicode_FromEncodedObject(s, NULL, "strict") :\ + PyObject_Format(s, f)) +#elif CYTHON_USE_TYPE_SLOTS + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + likely(PyLong_CheckExact(s)) ? PyLong_Type.tp_repr(s) :\ + likely(PyFloat_CheckExact(s)) ? PyFloat_Type.tp_repr(s) :\ + PyObject_Format(s, f)) +#else + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + PyObject_Format(s, f)) +#endif /* PyFunctionFastCall.proto */ #if CYTHON_FAST_PYCALL @@ -1806,66 +1745,41 @@ static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObj /* PyObjectCallOneArg.proto */ static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg); -/* PyObjectFormatSimple.proto */ -#if CYTHON_COMPILING_IN_PYPY - #define __Pyx_PyObject_FormatSimple(s, f) (\ - likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ - PyObject_Format(s, f)) -#elif PY_MAJOR_VERSION < 3 - #define __Pyx_PyObject_FormatSimple(s, f) (\ - likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ - likely(PyString_CheckExact(s)) ? PyUnicode_FromEncodedObject(s, NULL, "strict") :\ - PyObject_Format(s, f)) -#elif CYTHON_USE_TYPE_SLOTS - #define __Pyx_PyObject_FormatSimple(s, f) (\ - likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ - likely(PyLong_CheckExact(s)) ? PyLong_Type.tp_repr(s) :\ - likely(PyFloat_CheckExact(s)) ? PyFloat_Type.tp_repr(s) :\ - PyObject_Format(s, f)) -#else - #define __Pyx_PyObject_FormatSimple(s, f) (\ - likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ - PyObject_Format(s, f)) -#endif - -/* JoinPyUnicode.proto */ -static PyObject* __Pyx_PyUnicode_Join(PyObject* value_tuple, Py_ssize_t value_count, Py_ssize_t result_ulength, - Py_UCS4 max_char); - -/* GetException.proto */ -#if CYTHON_FAST_THREAD_STATE -#define __Pyx_GetException(type, value, tb) __Pyx__GetException(__pyx_tstate, type, value, tb) -static int __Pyx__GetException(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); -#else -static int __Pyx_GetException(PyObject **type, PyObject **value, PyObject **tb); -#endif - -/* pep479.proto */ -static void __Pyx_Generator_Replace_StopIteration(int in_async_gen); - -/* RaiseTooManyValuesToUnpack.proto */ -static CYTHON_INLINE void __Pyx_RaiseTooManyValuesError(Py_ssize_t expected); - -/* RaiseNeedMoreValuesToUnpack.proto */ -static CYTHON_INLINE void __Pyx_RaiseNeedMoreValuesError(Py_ssize_t index); - -/* IterFinish.proto */ -static CYTHON_INLINE int __Pyx_IterFinish(void); - -/* UnpackItemEndCheck.proto */ -static int __Pyx_IternextUnpackEndCheck(PyObject *retval, Py_ssize_t expected); - -/* MoveIfSupported.proto */ -#if __cplusplus >= 201103L || (defined(_MSC_VER) && _MSC_VER >= 1600) - #include - #define __PYX_STD_MOVE_IF_SUPPORTED(x) std::move(x) -#else - #define __PYX_STD_MOVE_IF_SUPPORTED(x) x -#endif - /* RaiseException.proto */ static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause); +/* IncludeCppStringH.proto */ +#include + +/* decode_c_string_utf16.proto */ +static CYTHON_INLINE PyObject *__Pyx_PyUnicode_DecodeUTF16(const char *s, Py_ssize_t size, const char *errors) { + int byteorder = 0; + return PyUnicode_DecodeUTF16(s, size, errors, &byteorder); +} +static CYTHON_INLINE PyObject *__Pyx_PyUnicode_DecodeUTF16LE(const char *s, Py_ssize_t size, const char *errors) { + int byteorder = -1; + return PyUnicode_DecodeUTF16(s, size, errors, &byteorder); +} +static CYTHON_INLINE PyObject *__Pyx_PyUnicode_DecodeUTF16BE(const char *s, Py_ssize_t size, const char *errors) { + int byteorder = 1; + return PyUnicode_DecodeUTF16(s, size, errors, &byteorder); +} + +/* decode_c_bytes.proto */ +static CYTHON_INLINE PyObject* __Pyx_decode_c_bytes( + const char* cstring, Py_ssize_t length, Py_ssize_t start, Py_ssize_t stop, + const char* encoding, const char* errors, + PyObject* (*decode_func)(const char *s, Py_ssize_t size, const char *errors)); + +/* decode_cpp_string.proto */ +static CYTHON_INLINE PyObject* __Pyx_decode_cpp_string( + std::string cppstring, Py_ssize_t start, Py_ssize_t stop, + const char* encoding, const char* errors, + PyObject* (*decode_func)(const char *s, Py_ssize_t size, const char *errors)) { + return __Pyx_decode_c_bytes( + cppstring.data(), cppstring.size(), start, stop, encoding, errors, decode_func); +} + /* DictGetItem.proto */ #if PY_MAJOR_VERSION >= 3 && !CYTHON_COMPILING_IN_PYPY static PyObject *__Pyx_PyDict_GetItem(PyObject *d, PyObject* key); @@ -1980,24 +1894,9 @@ static CYTHON_INLINE int __Pyx_PyDict_ContainsTF(PyObject* item, PyObject* dict, return unlikely(result < 0) ? result : (result == (eq == Py_EQ)); } -/* PySequenceContains.proto */ -static CYTHON_INLINE int __Pyx_PySequence_ContainsTF(PyObject* item, PyObject* seq, int eq) { - int result = PySequence_Contains(seq, item); - return unlikely(result < 0) ? result : (result == (eq == Py_EQ)); -} - -/* SetItemInt.proto */ -#define __Pyx_SetItemInt(o, i, v, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ - (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ - __Pyx_SetItemInt_Fast(o, (Py_ssize_t)i, v, is_list, wraparound, boundscheck) :\ - (is_list ? (PyErr_SetString(PyExc_IndexError, "list assignment index out of range"), -1) :\ - __Pyx_SetItemInt_Generic(o, to_py_func(i), v))) -static int __Pyx_SetItemInt_Generic(PyObject *o, PyObject *j, PyObject *v); -static CYTHON_INLINE int __Pyx_SetItemInt_Fast(PyObject *o, Py_ssize_t i, PyObject *v, - int is_list, int wraparound, int boundscheck); - -/* PyUnicode_Unicode.proto */ -static CYTHON_INLINE PyObject* __Pyx_PyUnicode_Unicode(PyObject *obj); +/* JoinPyUnicode.proto */ +static PyObject* __Pyx_PyUnicode_Join(PyObject* value_tuple, Py_ssize_t value_count, Py_ssize_t result_ulength, + Py_UCS4 max_char); /* PyObjectCallNoArg.proto */ static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func); @@ -2042,6 +1941,23 @@ static CYTHON_INLINE PyObject *__Pyx_PyObject_GetItem(PyObject *obj, PyObject *k #define __Pyx_PyObject_GetItem(obj, key) PyObject_GetItem(obj, key) #endif +/* ListCompAppend.proto */ +#if CYTHON_USE_PYLIST_INTERNALS && CYTHON_ASSUME_SAFE_MACROS +static CYTHON_INLINE int __Pyx_ListComp_Append(PyObject* list, PyObject* x) { + PyListObject* L = (PyListObject*) list; + Py_ssize_t len = Py_SIZE(list); + if (likely(L->allocated > len)) { + Py_INCREF(x); + PyList_SET_ITEM(list, len, x); + __Pyx_SET_SIZE(list, len + 1); + return 0; + } + return PyList_Append(list, x); +} +#else +#define __Pyx_ListComp_Append(L,x) PyList_Append(L,x) +#endif + /* RaiseUnexpectedTypeError.proto */ static int __Pyx_RaiseUnexpectedTypeError(const char *expected, PyObject *obj); @@ -2339,112 +2255,6 @@ static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches2(PyObject *err, PyObj #define __Pyx_PyErr_ExceptionMatches2(err1, err2) __Pyx_PyErr_GivenExceptionMatches2(__Pyx_PyErr_CurrentExceptionType(), err1, err2) #define __Pyx_PyException_Check(obj) __Pyx_TypeCheck(obj, PyExc_Exception) -/* GetTopmostException.proto */ -#if CYTHON_USE_EXC_INFO_STACK && CYTHON_FAST_THREAD_STATE -static _PyErr_StackItem * __Pyx_PyErr_GetTopmostException(PyThreadState *tstate); -#endif - -/* SaveResetException.proto */ -#if CYTHON_FAST_THREAD_STATE -#define __Pyx_ExceptionSave(type, value, tb) __Pyx__ExceptionSave(__pyx_tstate, type, value, tb) -static CYTHON_INLINE void __Pyx__ExceptionSave(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); -#define __Pyx_ExceptionReset(type, value, tb) __Pyx__ExceptionReset(__pyx_tstate, type, value, tb) -static CYTHON_INLINE void __Pyx__ExceptionReset(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb); -#else -#define __Pyx_ExceptionSave(type, value, tb) PyErr_GetExcInfo(type, value, tb) -#define __Pyx_ExceptionReset(type, value, tb) PyErr_SetExcInfo(type, value, tb) -#endif - -/* SwapException.proto */ -#if CYTHON_FAST_THREAD_STATE -#define __Pyx_ExceptionSwap(type, value, tb) __Pyx__ExceptionSwap(__pyx_tstate, type, value, tb) -static CYTHON_INLINE void __Pyx__ExceptionSwap(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); -#else -static CYTHON_INLINE void __Pyx_ExceptionSwap(PyObject **type, PyObject **value, PyObject **tb); -#endif - -/* PyObjectCall2Args.proto */ -static CYTHON_INLINE PyObject* __Pyx_PyObject_Call2Args(PyObject* function, PyObject* arg1, PyObject* arg2); - -/* PyObjectCallMethod1.proto */ -static PyObject* __Pyx_PyObject_CallMethod1(PyObject* obj, PyObject* method_name, PyObject* arg); - -/* CoroutineBase.proto */ -struct __pyx_CoroutineObject; -typedef PyObject *(*__pyx_coroutine_body_t)(struct __pyx_CoroutineObject *, PyThreadState *, PyObject *); -#if CYTHON_USE_EXC_INFO_STACK -#define __Pyx_ExcInfoStruct _PyErr_StackItem -#else -typedef struct { - PyObject *exc_type; - PyObject *exc_value; - PyObject *exc_traceback; -} __Pyx_ExcInfoStruct; -#endif -typedef struct __pyx_CoroutineObject { - PyObject_HEAD - __pyx_coroutine_body_t body; - PyObject *closure; - __Pyx_ExcInfoStruct gi_exc_state; - PyObject *gi_weakreflist; - PyObject *classobj; - PyObject *yieldfrom; - PyObject *gi_name; - PyObject *gi_qualname; - PyObject *gi_modulename; - PyObject *gi_code; - PyObject *gi_frame; - int resume_label; - char is_running; -} __pyx_CoroutineObject; -static __pyx_CoroutineObject *__Pyx__Coroutine_New( - PyTypeObject *type, __pyx_coroutine_body_t body, PyObject *code, PyObject *closure, - PyObject *name, PyObject *qualname, PyObject *module_name); -static __pyx_CoroutineObject *__Pyx__Coroutine_NewInit( - __pyx_CoroutineObject *gen, __pyx_coroutine_body_t body, PyObject *code, PyObject *closure, - PyObject *name, PyObject *qualname, PyObject *module_name); -static CYTHON_INLINE void __Pyx_Coroutine_ExceptionClear(__Pyx_ExcInfoStruct *self); -static int __Pyx_Coroutine_clear(PyObject *self); -static PyObject *__Pyx_Coroutine_Send(PyObject *self, PyObject *value); -static PyObject *__Pyx_Coroutine_Close(PyObject *self); -static PyObject *__Pyx_Coroutine_Throw(PyObject *gen, PyObject *args); -#if CYTHON_USE_EXC_INFO_STACK -#define __Pyx_Coroutine_SwapException(self) -#define __Pyx_Coroutine_ResetAndClearException(self) __Pyx_Coroutine_ExceptionClear(&(self)->gi_exc_state) -#else -#define __Pyx_Coroutine_SwapException(self) {\ - __Pyx_ExceptionSwap(&(self)->gi_exc_state.exc_type, &(self)->gi_exc_state.exc_value, &(self)->gi_exc_state.exc_traceback);\ - __Pyx_Coroutine_ResetFrameBackpointer(&(self)->gi_exc_state);\ - } -#define __Pyx_Coroutine_ResetAndClearException(self) {\ - __Pyx_ExceptionReset((self)->gi_exc_state.exc_type, (self)->gi_exc_state.exc_value, (self)->gi_exc_state.exc_traceback);\ - (self)->gi_exc_state.exc_type = (self)->gi_exc_state.exc_value = (self)->gi_exc_state.exc_traceback = NULL;\ - } -#endif -#if CYTHON_FAST_THREAD_STATE -#define __Pyx_PyGen_FetchStopIterationValue(pvalue)\ - __Pyx_PyGen__FetchStopIterationValue(__pyx_tstate, pvalue) -#else -#define __Pyx_PyGen_FetchStopIterationValue(pvalue)\ - __Pyx_PyGen__FetchStopIterationValue(__Pyx_PyThreadState_Current, pvalue) -#endif -static int __Pyx_PyGen__FetchStopIterationValue(PyThreadState *tstate, PyObject **pvalue); -static CYTHON_INLINE void __Pyx_Coroutine_ResetFrameBackpointer(__Pyx_ExcInfoStruct *exc_state); - -/* PatchModuleWithCoroutine.proto */ -static PyObject* __Pyx_Coroutine_patch_module(PyObject* module, const char* py_code); - -/* PatchGeneratorABC.proto */ -static int __Pyx_patch_abc(void); - -/* Generator.proto */ -#define __Pyx_Generator_USED -#define __Pyx_Generator_CheckExact(obj) __Pyx_IS_TYPE(obj, __pyx_GeneratorType) -#define __Pyx_Generator_New(body, code, closure, name, qualname, module_name)\ - __Pyx__Coroutine_New(__pyx_GeneratorType, body, code, closure, name, qualname, module_name) -static PyObject *__Pyx_Generator_Next(PyObject *self); -static int __pyx_Generator_init(PyObject *module); - /* CheckBinaryVersion.proto */ static int __Pyx_check_binary_version(void); @@ -2453,20 +2263,20 @@ static int __Pyx_InitStrings(__Pyx_StringTabEntry *t); /* #### Code section: module_declarations ### */ +/* Module declarations from "libcpp.utility" */ + +/* Module declarations from "libcpp.pair" */ + /* Module declarations from "libc.string" */ /* Module declarations from "libcpp.string" */ /* Module declarations from "libcpp.vector" */ -/* Module declarations from "libcpp.utility" */ - /* Module declarations from "libcpp.unordered_set" */ /* Module declarations from "libc.stdint" */ -/* Module declarations from "libcpp.map" */ - /* Module declarations from "libcpp" */ /* Module declarations from "opendbc.can.common" */ @@ -2478,6 +2288,7 @@ static CYTHON_INLINE PyObject *__pyx_convert_PyUnicode_string_to_py_std__in_stri static CYTHON_INLINE PyObject *__pyx_convert_PyStr_string_to_py_std__in_string(std::string const &); /*proto*/ static CYTHON_INLINE PyObject *__pyx_convert_PyBytes_string_to_py_std__in_string(std::string const &); /*proto*/ static CYTHON_INLINE PyObject *__pyx_convert_PyByteArray_string_to_py_std__in_string(std::string const &); /*proto*/ +static std::pair __pyx_convert_pair_from_py_uint32_t__and_int(PyObject *); /*proto*/ static std::vector __pyx_convert_vector_from_py_std_3a__3a_string(PyObject *); /*proto*/ static PyObject *__pyx_convert_vector_to_py_double(std::vector const &); /*proto*/ static PyObject *__pyx_convert_unordered_set_to_py_uint32_t(std::unordered_set const &); /*proto*/ @@ -2491,63 +2302,44 @@ int __pyx_module_is_main_opendbc__can__parser_pyx = 0; /* #### Code section: global_var ### */ static PyObject *__pyx_builtin_RuntimeError; static PyObject *__pyx_builtin_range; -static PyObject *__pyx_builtin_print; -static PyObject *__pyx_builtin_hex; static PyObject *__pyx_builtin_TypeError; static PyObject *__pyx_builtin_zip; static PyObject *__pyx_builtin_MemoryError; /* #### Code section: string_decls ### */ -static const char __pyx_k_[] = " ("; +static const char __pyx_k_[] = "'"; static const char __pyx_k_l[] = "l"; static const char __pyx_k_v[] = "v"; -static const char __pyx_k__2[] = ")"; -static const char __pyx_k__3[] = ", "; -static const char __pyx_k__4[] = "'"; -static const char __pyx_k__7[] = "*"; -static const char __pyx_k__8[] = "."; +static const char __pyx_k__4[] = "*"; +static const char __pyx_k__5[] = "."; static const char __pyx_k_cv[] = "cv"; static const char __pyx_k_gc[] = "gc"; -static const char __pyx_k_in[] = " in "; static const char __pyx_k_it[] = "it"; -static const char __pyx_k_DBC[] = ", DBC "; -static const char __pyx_k__18[] = "?"; -static const char __pyx_k_add[] = "add"; +static const char __pyx_k__15[] = "?"; static const char __pyx_k_bus[] = "bus"; static const char __pyx_k_get[] = "get"; -static const char __pyx_k_hex[] = "hex"; static const char __pyx_k_zip[] = "zip"; -static const char __pyx_k_None[] = "None"; -static const char __pyx_k_args[] = "args"; static const char __pyx_k_main[] = "__main__"; static const char __pyx_k_name[] = "__name__"; static const char __pyx_k_self[] = "self"; -static const char __pyx_k_send[] = "send"; static const char __pyx_k_spec[] = "__spec__"; static const char __pyx_k_test[] = "__test__"; static const char __pyx_k_clear[] = "clear"; -static const char __pyx_k_close[] = "close"; -static const char __pyx_k_items[] = "items"; -static const char __pyx_k_print[] = "print"; static const char __pyx_k_range[] = "range"; static const char __pyx_k_split[] = "split"; -static const char __pyx_k_throw[] = "throw"; static const char __pyx_k_Number[] = "Number"; -static const char __pyx_k_checks[] = "checks"; static const char __pyx_k_enable[] = "enable"; static const char __pyx_k_import[] = "__import__"; static const char __pyx_k_in_DBC[] = " in DBC "; static const char __pyx_k_reduce[] = "__reduce__"; -static const char __pyx_k_update[] = "update"; static const char __pyx_k_values[] = "values"; static const char __pyx_k_cv_name[] = "cv_name"; static const char __pyx_k_disable[] = "disable"; -static const char __pyx_k_genexpr[] = "genexpr"; static const char __pyx_k_numbers[] = "numbers"; static const char __pyx_k_sendcan[] = "sendcan"; -static const char __pyx_k_signals[] = "signals"; static const char __pyx_k_strings[] = "strings"; static const char __pyx_k_dbc_name[] = "dbc_name"; static const char __pyx_k_getstate[] = "__getstate__"; +static const char __pyx_k_messages[] = "messages"; static const char __pyx_k_new_vals[] = "new_vals"; static const char __pyx_k_setstate[] = "__setstate__"; static const char __pyx_k_CANDefine[] = "CANDefine"; @@ -2567,15 +2359,11 @@ static const char __pyx_k_class_getitem[] = "__class_getitem__"; static const char __pyx_k_reduce_cython[] = "__reduce_cython__"; static const char __pyx_k_updated_addrs[] = "updated_addrs"; static const char __pyx_k_Can_t_find_DBC[] = "Can't find DBC: "; -static const char __pyx_k_enforce_checks[] = "enforce_checks"; static const char __pyx_k_update_strings[] = "update_strings"; -static const char __pyx_k_Unchecked_addrs[] = "Unchecked addrs: "; static const char __pyx_k_setstate_cython[] = "__setstate_cython__"; static const char __pyx_k_Can_t_find_DBC_2[] = "Can't find DBC: '"; static const char __pyx_k_asyncio_coroutines[] = "asyncio.coroutines"; static const char __pyx_k_cline_in_traceback[] = "cline_in_traceback"; -static const char __pyx_k_could_not_find_signal[] = "could not find signal "; -static const char __pyx_k_init___locals_genexpr[] = "__init__..genexpr"; static const char __pyx_k_could_not_find_message[] = "could not find message "; static const char __pyx_k_opendbc_can_parser_pyx[] = "opendbc.can.parser_pyx"; static const char __pyx_k_CANParser_update_strings[] = "CANParser.update_strings"; @@ -2587,9 +2375,7 @@ static const char __pyx_k_CANParser___setstate_cython[] = "CANParser.__setstate_ static const char __pyx_k_self_dbc_cannot_be_converted_to[] = "self.dbc cannot be converted to a Python object for pickling"; static const char __pyx_k_self_can_self_dbc_cannot_be_conv[] = "self.can,self.dbc cannot be converted to a Python object for pickling"; /* #### Code section: decls ### */ -static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_8__init___genexpr(PyObject *__pyx_self, PyObject *__pyx_genexpr_arg_0); /* proto */ -static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_8__init___3genexpr(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_genexpr_arg_0); /* proto */ -static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANParser___init__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self, PyObject *__pyx_v_dbc_name, PyObject *__pyx_v_signals, PyObject *__pyx_v_checks, PyObject *__pyx_v_bus, PyObject *__pyx_v_enforce_checks); /* proto */ +static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANParser___init__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self, PyObject *__pyx_v_dbc_name, PyObject *__pyx_v_messages, PyObject *__pyx_v_bus); /* proto */ static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_2update_strings(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self, PyObject *__pyx_v_strings, PyObject *__pyx_v_sendcan); /* proto */ static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_9can_valid___get__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self); /* proto */ static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_11bus_timeout___get__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self); /* proto */ @@ -2609,11 +2395,7 @@ static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_2__reduce_cython static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_4__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ static PyObject *__pyx_tp_new_7opendbc_3can_10parser_pyx_CANParser(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ static PyObject *__pyx_tp_new_7opendbc_3can_10parser_pyx_CANDefine(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ -static PyObject *__pyx_tp_new_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ -static PyObject *__pyx_tp_new_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ -static PyObject *__pyx_tp_new_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ static __Pyx_CachedCFunction __pyx_umethod_PyDict_Type_get = {0, 0, 0, 0, 0}; -static __Pyx_CachedCFunction __pyx_umethod_PyDict_Type_update = {0, 0, 0, 0, 0}; /* #### Code section: late_includes ### */ /* #### Code section: module_state ### */ typedef struct { @@ -2662,15 +2444,9 @@ typedef struct { #if CYTHON_USE_MODULE_STATE PyObject *__pyx_type_7opendbc_3can_10parser_pyx_CANParser; PyObject *__pyx_type_7opendbc_3can_10parser_pyx_CANDefine; - PyObject *__pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__; - PyObject *__pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr; - PyObject *__pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr; #endif PyTypeObject *__pyx_ptype_7opendbc_3can_10parser_pyx_CANParser; PyTypeObject *__pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine; - PyTypeObject *__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__; - PyTypeObject *__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr; - PyTypeObject *__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr; PyObject *__pyx_kp_u_; PyObject *__pyx_n_s_CANDefine; PyObject *__pyx_n_s_CANDefine___reduce_cython; @@ -2681,60 +2457,43 @@ typedef struct { PyObject *__pyx_n_s_CANParser_update_strings; PyObject *__pyx_kp_u_Can_t_find_DBC; PyObject *__pyx_kp_u_Can_t_find_DBC_2; - PyObject *__pyx_kp_u_DBC; PyObject *__pyx_n_s_MemoryError; - PyObject *__pyx_kp_u_None; PyObject *__pyx_n_s_Number; PyObject *__pyx_n_s_RuntimeError; PyObject *__pyx_n_s_TypeError; - PyObject *__pyx_kp_u_Unchecked_addrs; - PyObject *__pyx_n_s__18; - PyObject *__pyx_kp_u__2; - PyObject *__pyx_kp_u__3; - PyObject *__pyx_kp_u__4; - PyObject *__pyx_n_s__7; - PyObject *__pyx_kp_u__8; - PyObject *__pyx_n_s_add; - PyObject *__pyx_n_s_args; + PyObject *__pyx_n_s__15; + PyObject *__pyx_n_s__4; + PyObject *__pyx_kp_u__5; PyObject *__pyx_n_s_asyncio_coroutines; PyObject *__pyx_n_s_bus; - PyObject *__pyx_n_s_checks; PyObject *__pyx_n_s_class_getitem; PyObject *__pyx_n_s_clear; PyObject *__pyx_n_s_cline_in_traceback; - PyObject *__pyx_n_s_close; PyObject *__pyx_n_s_collections; PyObject *__pyx_kp_u_could_not_find_message; - PyObject *__pyx_kp_u_could_not_find_signal; PyObject *__pyx_n_s_cv; PyObject *__pyx_n_s_cv_name; PyObject *__pyx_n_s_dbc_name; PyObject *__pyx_n_s_defaultdict; PyObject *__pyx_kp_u_disable; PyObject *__pyx_kp_u_enable; - PyObject *__pyx_n_s_enforce_checks; PyObject *__pyx_kp_u_gc; - PyObject *__pyx_n_s_genexpr; PyObject *__pyx_n_s_get; PyObject *__pyx_n_s_getstate; - PyObject *__pyx_n_s_hex; PyObject *__pyx_n_s_import; - PyObject *__pyx_kp_u_in; PyObject *__pyx_kp_u_in_DBC; - PyObject *__pyx_n_s_init___locals_genexpr; PyObject *__pyx_n_s_initializing; PyObject *__pyx_n_s_is_coroutine; PyObject *__pyx_kp_u_isenabled; PyObject *__pyx_n_s_it; - PyObject *__pyx_n_s_items; PyObject *__pyx_n_s_l; PyObject *__pyx_n_s_main; + PyObject *__pyx_n_s_messages; PyObject *__pyx_n_s_name; PyObject *__pyx_n_s_new_vals; PyObject *__pyx_n_s_numbers; PyObject *__pyx_n_s_opendbc_can_parser_pyx; PyObject *__pyx_kp_s_opendbc_can_parser_pyx_pyx; - PyObject *__pyx_n_s_print; PyObject *__pyx_n_s_pyx_state; PyObject *__pyx_n_s_range; PyObject *__pyx_n_s_reduce; @@ -2743,18 +2502,14 @@ typedef struct { PyObject *__pyx_n_s_self; PyObject *__pyx_kp_s_self_can_self_dbc_cannot_be_conv; PyObject *__pyx_kp_s_self_dbc_cannot_be_converted_to; - PyObject *__pyx_n_s_send; PyObject *__pyx_n_s_sendcan; PyObject *__pyx_n_s_setstate; PyObject *__pyx_n_s_setstate_cython; - PyObject *__pyx_n_s_signals; PyObject *__pyx_n_s_spec; PyObject *__pyx_n_s_split; PyObject *__pyx_n_s_strings; PyObject *__pyx_kp_s_stringsource; PyObject *__pyx_n_s_test; - PyObject *__pyx_n_s_throw; - PyObject *__pyx_n_s_update; PyObject *__pyx_n_s_update_strings; PyObject *__pyx_n_s_updated_addrs; PyObject *__pyx_n_s_v; @@ -2763,17 +2518,17 @@ typedef struct { PyObject *__pyx_int_0; PyObject *__pyx_int_1; PyObject *__pyx_int_2; - PyObject *__pyx_slice__5; - PyObject *__pyx_slice__6; + PyObject *__pyx_slice__2; + PyObject *__pyx_slice__3; + PyObject *__pyx_tuple__6; + PyObject *__pyx_tuple__8; PyObject *__pyx_tuple__9; PyObject *__pyx_tuple__11; - PyObject *__pyx_tuple__12; - PyObject *__pyx_tuple__14; + PyObject *__pyx_codeobj__7; PyObject *__pyx_codeobj__10; + PyObject *__pyx_codeobj__12; PyObject *__pyx_codeobj__13; - PyObject *__pyx_codeobj__15; - PyObject *__pyx_codeobj__16; - PyObject *__pyx_codeobj__17; + PyObject *__pyx_codeobj__14; } __pyx_mstate; #if CYTHON_USE_MODULE_STATE @@ -2820,12 +2575,6 @@ static int __pyx_m_clear(PyObject *m) { Py_CLEAR(clear_module_state->__pyx_type_7opendbc_3can_10parser_pyx_CANParser); Py_CLEAR(clear_module_state->__pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine); Py_CLEAR(clear_module_state->__pyx_type_7opendbc_3can_10parser_pyx_CANDefine); - Py_CLEAR(clear_module_state->__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__); - Py_CLEAR(clear_module_state->__pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__); - Py_CLEAR(clear_module_state->__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr); - Py_CLEAR(clear_module_state->__pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr); - Py_CLEAR(clear_module_state->__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr); - Py_CLEAR(clear_module_state->__pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr); Py_CLEAR(clear_module_state->__pyx_kp_u_); Py_CLEAR(clear_module_state->__pyx_n_s_CANDefine); Py_CLEAR(clear_module_state->__pyx_n_s_CANDefine___reduce_cython); @@ -2836,60 +2585,43 @@ static int __pyx_m_clear(PyObject *m) { Py_CLEAR(clear_module_state->__pyx_n_s_CANParser_update_strings); Py_CLEAR(clear_module_state->__pyx_kp_u_Can_t_find_DBC); Py_CLEAR(clear_module_state->__pyx_kp_u_Can_t_find_DBC_2); - Py_CLEAR(clear_module_state->__pyx_kp_u_DBC); Py_CLEAR(clear_module_state->__pyx_n_s_MemoryError); - Py_CLEAR(clear_module_state->__pyx_kp_u_None); Py_CLEAR(clear_module_state->__pyx_n_s_Number); Py_CLEAR(clear_module_state->__pyx_n_s_RuntimeError); Py_CLEAR(clear_module_state->__pyx_n_s_TypeError); - Py_CLEAR(clear_module_state->__pyx_kp_u_Unchecked_addrs); - Py_CLEAR(clear_module_state->__pyx_n_s__18); - Py_CLEAR(clear_module_state->__pyx_kp_u__2); - Py_CLEAR(clear_module_state->__pyx_kp_u__3); - Py_CLEAR(clear_module_state->__pyx_kp_u__4); - Py_CLEAR(clear_module_state->__pyx_n_s__7); - Py_CLEAR(clear_module_state->__pyx_kp_u__8); - Py_CLEAR(clear_module_state->__pyx_n_s_add); - Py_CLEAR(clear_module_state->__pyx_n_s_args); + Py_CLEAR(clear_module_state->__pyx_n_s__15); + Py_CLEAR(clear_module_state->__pyx_n_s__4); + Py_CLEAR(clear_module_state->__pyx_kp_u__5); Py_CLEAR(clear_module_state->__pyx_n_s_asyncio_coroutines); Py_CLEAR(clear_module_state->__pyx_n_s_bus); - Py_CLEAR(clear_module_state->__pyx_n_s_checks); Py_CLEAR(clear_module_state->__pyx_n_s_class_getitem); Py_CLEAR(clear_module_state->__pyx_n_s_clear); Py_CLEAR(clear_module_state->__pyx_n_s_cline_in_traceback); - Py_CLEAR(clear_module_state->__pyx_n_s_close); Py_CLEAR(clear_module_state->__pyx_n_s_collections); Py_CLEAR(clear_module_state->__pyx_kp_u_could_not_find_message); - Py_CLEAR(clear_module_state->__pyx_kp_u_could_not_find_signal); Py_CLEAR(clear_module_state->__pyx_n_s_cv); Py_CLEAR(clear_module_state->__pyx_n_s_cv_name); Py_CLEAR(clear_module_state->__pyx_n_s_dbc_name); Py_CLEAR(clear_module_state->__pyx_n_s_defaultdict); Py_CLEAR(clear_module_state->__pyx_kp_u_disable); Py_CLEAR(clear_module_state->__pyx_kp_u_enable); - Py_CLEAR(clear_module_state->__pyx_n_s_enforce_checks); Py_CLEAR(clear_module_state->__pyx_kp_u_gc); - Py_CLEAR(clear_module_state->__pyx_n_s_genexpr); Py_CLEAR(clear_module_state->__pyx_n_s_get); Py_CLEAR(clear_module_state->__pyx_n_s_getstate); - Py_CLEAR(clear_module_state->__pyx_n_s_hex); Py_CLEAR(clear_module_state->__pyx_n_s_import); - Py_CLEAR(clear_module_state->__pyx_kp_u_in); Py_CLEAR(clear_module_state->__pyx_kp_u_in_DBC); - Py_CLEAR(clear_module_state->__pyx_n_s_init___locals_genexpr); Py_CLEAR(clear_module_state->__pyx_n_s_initializing); Py_CLEAR(clear_module_state->__pyx_n_s_is_coroutine); Py_CLEAR(clear_module_state->__pyx_kp_u_isenabled); Py_CLEAR(clear_module_state->__pyx_n_s_it); - Py_CLEAR(clear_module_state->__pyx_n_s_items); Py_CLEAR(clear_module_state->__pyx_n_s_l); Py_CLEAR(clear_module_state->__pyx_n_s_main); + Py_CLEAR(clear_module_state->__pyx_n_s_messages); Py_CLEAR(clear_module_state->__pyx_n_s_name); Py_CLEAR(clear_module_state->__pyx_n_s_new_vals); Py_CLEAR(clear_module_state->__pyx_n_s_numbers); Py_CLEAR(clear_module_state->__pyx_n_s_opendbc_can_parser_pyx); Py_CLEAR(clear_module_state->__pyx_kp_s_opendbc_can_parser_pyx_pyx); - Py_CLEAR(clear_module_state->__pyx_n_s_print); Py_CLEAR(clear_module_state->__pyx_n_s_pyx_state); Py_CLEAR(clear_module_state->__pyx_n_s_range); Py_CLEAR(clear_module_state->__pyx_n_s_reduce); @@ -2898,18 +2630,14 @@ static int __pyx_m_clear(PyObject *m) { Py_CLEAR(clear_module_state->__pyx_n_s_self); Py_CLEAR(clear_module_state->__pyx_kp_s_self_can_self_dbc_cannot_be_conv); Py_CLEAR(clear_module_state->__pyx_kp_s_self_dbc_cannot_be_converted_to); - Py_CLEAR(clear_module_state->__pyx_n_s_send); Py_CLEAR(clear_module_state->__pyx_n_s_sendcan); Py_CLEAR(clear_module_state->__pyx_n_s_setstate); Py_CLEAR(clear_module_state->__pyx_n_s_setstate_cython); - Py_CLEAR(clear_module_state->__pyx_n_s_signals); Py_CLEAR(clear_module_state->__pyx_n_s_spec); Py_CLEAR(clear_module_state->__pyx_n_s_split); Py_CLEAR(clear_module_state->__pyx_n_s_strings); Py_CLEAR(clear_module_state->__pyx_kp_s_stringsource); Py_CLEAR(clear_module_state->__pyx_n_s_test); - Py_CLEAR(clear_module_state->__pyx_n_s_throw); - Py_CLEAR(clear_module_state->__pyx_n_s_update); Py_CLEAR(clear_module_state->__pyx_n_s_update_strings); Py_CLEAR(clear_module_state->__pyx_n_s_updated_addrs); Py_CLEAR(clear_module_state->__pyx_n_s_v); @@ -2918,17 +2646,17 @@ static int __pyx_m_clear(PyObject *m) { Py_CLEAR(clear_module_state->__pyx_int_0); Py_CLEAR(clear_module_state->__pyx_int_1); Py_CLEAR(clear_module_state->__pyx_int_2); - Py_CLEAR(clear_module_state->__pyx_slice__5); - Py_CLEAR(clear_module_state->__pyx_slice__6); + Py_CLEAR(clear_module_state->__pyx_slice__2); + Py_CLEAR(clear_module_state->__pyx_slice__3); + Py_CLEAR(clear_module_state->__pyx_tuple__6); + Py_CLEAR(clear_module_state->__pyx_tuple__8); Py_CLEAR(clear_module_state->__pyx_tuple__9); Py_CLEAR(clear_module_state->__pyx_tuple__11); - Py_CLEAR(clear_module_state->__pyx_tuple__12); - Py_CLEAR(clear_module_state->__pyx_tuple__14); + Py_CLEAR(clear_module_state->__pyx_codeobj__7); Py_CLEAR(clear_module_state->__pyx_codeobj__10); + Py_CLEAR(clear_module_state->__pyx_codeobj__12); Py_CLEAR(clear_module_state->__pyx_codeobj__13); - Py_CLEAR(clear_module_state->__pyx_codeobj__15); - Py_CLEAR(clear_module_state->__pyx_codeobj__16); - Py_CLEAR(clear_module_state->__pyx_codeobj__17); + Py_CLEAR(clear_module_state->__pyx_codeobj__14); return 0; } #endif @@ -2953,12 +2681,6 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { Py_VISIT(traverse_module_state->__pyx_type_7opendbc_3can_10parser_pyx_CANParser); Py_VISIT(traverse_module_state->__pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine); Py_VISIT(traverse_module_state->__pyx_type_7opendbc_3can_10parser_pyx_CANDefine); - Py_VISIT(traverse_module_state->__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__); - Py_VISIT(traverse_module_state->__pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__); - Py_VISIT(traverse_module_state->__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr); - Py_VISIT(traverse_module_state->__pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr); - Py_VISIT(traverse_module_state->__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr); - Py_VISIT(traverse_module_state->__pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr); Py_VISIT(traverse_module_state->__pyx_kp_u_); Py_VISIT(traverse_module_state->__pyx_n_s_CANDefine); Py_VISIT(traverse_module_state->__pyx_n_s_CANDefine___reduce_cython); @@ -2969,60 +2691,43 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { Py_VISIT(traverse_module_state->__pyx_n_s_CANParser_update_strings); Py_VISIT(traverse_module_state->__pyx_kp_u_Can_t_find_DBC); Py_VISIT(traverse_module_state->__pyx_kp_u_Can_t_find_DBC_2); - Py_VISIT(traverse_module_state->__pyx_kp_u_DBC); Py_VISIT(traverse_module_state->__pyx_n_s_MemoryError); - Py_VISIT(traverse_module_state->__pyx_kp_u_None); Py_VISIT(traverse_module_state->__pyx_n_s_Number); Py_VISIT(traverse_module_state->__pyx_n_s_RuntimeError); Py_VISIT(traverse_module_state->__pyx_n_s_TypeError); - Py_VISIT(traverse_module_state->__pyx_kp_u_Unchecked_addrs); - Py_VISIT(traverse_module_state->__pyx_n_s__18); - Py_VISIT(traverse_module_state->__pyx_kp_u__2); - Py_VISIT(traverse_module_state->__pyx_kp_u__3); - Py_VISIT(traverse_module_state->__pyx_kp_u__4); - Py_VISIT(traverse_module_state->__pyx_n_s__7); - Py_VISIT(traverse_module_state->__pyx_kp_u__8); - Py_VISIT(traverse_module_state->__pyx_n_s_add); - Py_VISIT(traverse_module_state->__pyx_n_s_args); + Py_VISIT(traverse_module_state->__pyx_n_s__15); + Py_VISIT(traverse_module_state->__pyx_n_s__4); + Py_VISIT(traverse_module_state->__pyx_kp_u__5); Py_VISIT(traverse_module_state->__pyx_n_s_asyncio_coroutines); Py_VISIT(traverse_module_state->__pyx_n_s_bus); - Py_VISIT(traverse_module_state->__pyx_n_s_checks); Py_VISIT(traverse_module_state->__pyx_n_s_class_getitem); Py_VISIT(traverse_module_state->__pyx_n_s_clear); Py_VISIT(traverse_module_state->__pyx_n_s_cline_in_traceback); - Py_VISIT(traverse_module_state->__pyx_n_s_close); Py_VISIT(traverse_module_state->__pyx_n_s_collections); Py_VISIT(traverse_module_state->__pyx_kp_u_could_not_find_message); - Py_VISIT(traverse_module_state->__pyx_kp_u_could_not_find_signal); Py_VISIT(traverse_module_state->__pyx_n_s_cv); Py_VISIT(traverse_module_state->__pyx_n_s_cv_name); Py_VISIT(traverse_module_state->__pyx_n_s_dbc_name); Py_VISIT(traverse_module_state->__pyx_n_s_defaultdict); Py_VISIT(traverse_module_state->__pyx_kp_u_disable); Py_VISIT(traverse_module_state->__pyx_kp_u_enable); - Py_VISIT(traverse_module_state->__pyx_n_s_enforce_checks); Py_VISIT(traverse_module_state->__pyx_kp_u_gc); - Py_VISIT(traverse_module_state->__pyx_n_s_genexpr); Py_VISIT(traverse_module_state->__pyx_n_s_get); Py_VISIT(traverse_module_state->__pyx_n_s_getstate); - Py_VISIT(traverse_module_state->__pyx_n_s_hex); Py_VISIT(traverse_module_state->__pyx_n_s_import); - Py_VISIT(traverse_module_state->__pyx_kp_u_in); Py_VISIT(traverse_module_state->__pyx_kp_u_in_DBC); - Py_VISIT(traverse_module_state->__pyx_n_s_init___locals_genexpr); Py_VISIT(traverse_module_state->__pyx_n_s_initializing); Py_VISIT(traverse_module_state->__pyx_n_s_is_coroutine); Py_VISIT(traverse_module_state->__pyx_kp_u_isenabled); Py_VISIT(traverse_module_state->__pyx_n_s_it); - Py_VISIT(traverse_module_state->__pyx_n_s_items); Py_VISIT(traverse_module_state->__pyx_n_s_l); Py_VISIT(traverse_module_state->__pyx_n_s_main); + Py_VISIT(traverse_module_state->__pyx_n_s_messages); Py_VISIT(traverse_module_state->__pyx_n_s_name); Py_VISIT(traverse_module_state->__pyx_n_s_new_vals); Py_VISIT(traverse_module_state->__pyx_n_s_numbers); Py_VISIT(traverse_module_state->__pyx_n_s_opendbc_can_parser_pyx); Py_VISIT(traverse_module_state->__pyx_kp_s_opendbc_can_parser_pyx_pyx); - Py_VISIT(traverse_module_state->__pyx_n_s_print); Py_VISIT(traverse_module_state->__pyx_n_s_pyx_state); Py_VISIT(traverse_module_state->__pyx_n_s_range); Py_VISIT(traverse_module_state->__pyx_n_s_reduce); @@ -3031,18 +2736,14 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { Py_VISIT(traverse_module_state->__pyx_n_s_self); Py_VISIT(traverse_module_state->__pyx_kp_s_self_can_self_dbc_cannot_be_conv); Py_VISIT(traverse_module_state->__pyx_kp_s_self_dbc_cannot_be_converted_to); - Py_VISIT(traverse_module_state->__pyx_n_s_send); Py_VISIT(traverse_module_state->__pyx_n_s_sendcan); Py_VISIT(traverse_module_state->__pyx_n_s_setstate); Py_VISIT(traverse_module_state->__pyx_n_s_setstate_cython); - Py_VISIT(traverse_module_state->__pyx_n_s_signals); Py_VISIT(traverse_module_state->__pyx_n_s_spec); Py_VISIT(traverse_module_state->__pyx_n_s_split); Py_VISIT(traverse_module_state->__pyx_n_s_strings); Py_VISIT(traverse_module_state->__pyx_kp_s_stringsource); Py_VISIT(traverse_module_state->__pyx_n_s_test); - Py_VISIT(traverse_module_state->__pyx_n_s_throw); - Py_VISIT(traverse_module_state->__pyx_n_s_update); Py_VISIT(traverse_module_state->__pyx_n_s_update_strings); Py_VISIT(traverse_module_state->__pyx_n_s_updated_addrs); Py_VISIT(traverse_module_state->__pyx_n_s_v); @@ -3051,17 +2752,17 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { Py_VISIT(traverse_module_state->__pyx_int_0); Py_VISIT(traverse_module_state->__pyx_int_1); Py_VISIT(traverse_module_state->__pyx_int_2); - Py_VISIT(traverse_module_state->__pyx_slice__5); - Py_VISIT(traverse_module_state->__pyx_slice__6); + Py_VISIT(traverse_module_state->__pyx_slice__2); + Py_VISIT(traverse_module_state->__pyx_slice__3); + Py_VISIT(traverse_module_state->__pyx_tuple__6); + Py_VISIT(traverse_module_state->__pyx_tuple__8); Py_VISIT(traverse_module_state->__pyx_tuple__9); Py_VISIT(traverse_module_state->__pyx_tuple__11); - Py_VISIT(traverse_module_state->__pyx_tuple__12); - Py_VISIT(traverse_module_state->__pyx_tuple__14); + Py_VISIT(traverse_module_state->__pyx_codeobj__7); Py_VISIT(traverse_module_state->__pyx_codeobj__10); + Py_VISIT(traverse_module_state->__pyx_codeobj__12); Py_VISIT(traverse_module_state->__pyx_codeobj__13); - Py_VISIT(traverse_module_state->__pyx_codeobj__15); - Py_VISIT(traverse_module_state->__pyx_codeobj__16); - Py_VISIT(traverse_module_state->__pyx_codeobj__17); + Py_VISIT(traverse_module_state->__pyx_codeobj__14); return 0; } #endif @@ -3111,15 +2812,9 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #if CYTHON_USE_MODULE_STATE #define __pyx_type_7opendbc_3can_10parser_pyx_CANParser __pyx_mstate_global->__pyx_type_7opendbc_3can_10parser_pyx_CANParser #define __pyx_type_7opendbc_3can_10parser_pyx_CANDefine __pyx_mstate_global->__pyx_type_7opendbc_3can_10parser_pyx_CANDefine -#define __pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ __pyx_mstate_global->__pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ -#define __pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr __pyx_mstate_global->__pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr -#define __pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr __pyx_mstate_global->__pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr #endif #define __pyx_ptype_7opendbc_3can_10parser_pyx_CANParser __pyx_mstate_global->__pyx_ptype_7opendbc_3can_10parser_pyx_CANParser #define __pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine __pyx_mstate_global->__pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine -#define __pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ __pyx_mstate_global->__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ -#define __pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr __pyx_mstate_global->__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr -#define __pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr __pyx_mstate_global->__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr #define __pyx_kp_u_ __pyx_mstate_global->__pyx_kp_u_ #define __pyx_n_s_CANDefine __pyx_mstate_global->__pyx_n_s_CANDefine #define __pyx_n_s_CANDefine___reduce_cython __pyx_mstate_global->__pyx_n_s_CANDefine___reduce_cython @@ -3130,60 +2825,43 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #define __pyx_n_s_CANParser_update_strings __pyx_mstate_global->__pyx_n_s_CANParser_update_strings #define __pyx_kp_u_Can_t_find_DBC __pyx_mstate_global->__pyx_kp_u_Can_t_find_DBC #define __pyx_kp_u_Can_t_find_DBC_2 __pyx_mstate_global->__pyx_kp_u_Can_t_find_DBC_2 -#define __pyx_kp_u_DBC __pyx_mstate_global->__pyx_kp_u_DBC #define __pyx_n_s_MemoryError __pyx_mstate_global->__pyx_n_s_MemoryError -#define __pyx_kp_u_None __pyx_mstate_global->__pyx_kp_u_None #define __pyx_n_s_Number __pyx_mstate_global->__pyx_n_s_Number #define __pyx_n_s_RuntimeError __pyx_mstate_global->__pyx_n_s_RuntimeError #define __pyx_n_s_TypeError __pyx_mstate_global->__pyx_n_s_TypeError -#define __pyx_kp_u_Unchecked_addrs __pyx_mstate_global->__pyx_kp_u_Unchecked_addrs -#define __pyx_n_s__18 __pyx_mstate_global->__pyx_n_s__18 -#define __pyx_kp_u__2 __pyx_mstate_global->__pyx_kp_u__2 -#define __pyx_kp_u__3 __pyx_mstate_global->__pyx_kp_u__3 -#define __pyx_kp_u__4 __pyx_mstate_global->__pyx_kp_u__4 -#define __pyx_n_s__7 __pyx_mstate_global->__pyx_n_s__7 -#define __pyx_kp_u__8 __pyx_mstate_global->__pyx_kp_u__8 -#define __pyx_n_s_add __pyx_mstate_global->__pyx_n_s_add -#define __pyx_n_s_args __pyx_mstate_global->__pyx_n_s_args +#define __pyx_n_s__15 __pyx_mstate_global->__pyx_n_s__15 +#define __pyx_n_s__4 __pyx_mstate_global->__pyx_n_s__4 +#define __pyx_kp_u__5 __pyx_mstate_global->__pyx_kp_u__5 #define __pyx_n_s_asyncio_coroutines __pyx_mstate_global->__pyx_n_s_asyncio_coroutines #define __pyx_n_s_bus __pyx_mstate_global->__pyx_n_s_bus -#define __pyx_n_s_checks __pyx_mstate_global->__pyx_n_s_checks #define __pyx_n_s_class_getitem __pyx_mstate_global->__pyx_n_s_class_getitem #define __pyx_n_s_clear __pyx_mstate_global->__pyx_n_s_clear #define __pyx_n_s_cline_in_traceback __pyx_mstate_global->__pyx_n_s_cline_in_traceback -#define __pyx_n_s_close __pyx_mstate_global->__pyx_n_s_close #define __pyx_n_s_collections __pyx_mstate_global->__pyx_n_s_collections #define __pyx_kp_u_could_not_find_message __pyx_mstate_global->__pyx_kp_u_could_not_find_message -#define __pyx_kp_u_could_not_find_signal __pyx_mstate_global->__pyx_kp_u_could_not_find_signal #define __pyx_n_s_cv __pyx_mstate_global->__pyx_n_s_cv #define __pyx_n_s_cv_name __pyx_mstate_global->__pyx_n_s_cv_name #define __pyx_n_s_dbc_name __pyx_mstate_global->__pyx_n_s_dbc_name #define __pyx_n_s_defaultdict __pyx_mstate_global->__pyx_n_s_defaultdict #define __pyx_kp_u_disable __pyx_mstate_global->__pyx_kp_u_disable #define __pyx_kp_u_enable __pyx_mstate_global->__pyx_kp_u_enable -#define __pyx_n_s_enforce_checks __pyx_mstate_global->__pyx_n_s_enforce_checks #define __pyx_kp_u_gc __pyx_mstate_global->__pyx_kp_u_gc -#define __pyx_n_s_genexpr __pyx_mstate_global->__pyx_n_s_genexpr #define __pyx_n_s_get __pyx_mstate_global->__pyx_n_s_get #define __pyx_n_s_getstate __pyx_mstate_global->__pyx_n_s_getstate -#define __pyx_n_s_hex __pyx_mstate_global->__pyx_n_s_hex #define __pyx_n_s_import __pyx_mstate_global->__pyx_n_s_import -#define __pyx_kp_u_in __pyx_mstate_global->__pyx_kp_u_in #define __pyx_kp_u_in_DBC __pyx_mstate_global->__pyx_kp_u_in_DBC -#define __pyx_n_s_init___locals_genexpr __pyx_mstate_global->__pyx_n_s_init___locals_genexpr #define __pyx_n_s_initializing __pyx_mstate_global->__pyx_n_s_initializing #define __pyx_n_s_is_coroutine __pyx_mstate_global->__pyx_n_s_is_coroutine #define __pyx_kp_u_isenabled __pyx_mstate_global->__pyx_kp_u_isenabled #define __pyx_n_s_it __pyx_mstate_global->__pyx_n_s_it -#define __pyx_n_s_items __pyx_mstate_global->__pyx_n_s_items #define __pyx_n_s_l __pyx_mstate_global->__pyx_n_s_l #define __pyx_n_s_main __pyx_mstate_global->__pyx_n_s_main +#define __pyx_n_s_messages __pyx_mstate_global->__pyx_n_s_messages #define __pyx_n_s_name __pyx_mstate_global->__pyx_n_s_name #define __pyx_n_s_new_vals __pyx_mstate_global->__pyx_n_s_new_vals #define __pyx_n_s_numbers __pyx_mstate_global->__pyx_n_s_numbers #define __pyx_n_s_opendbc_can_parser_pyx __pyx_mstate_global->__pyx_n_s_opendbc_can_parser_pyx #define __pyx_kp_s_opendbc_can_parser_pyx_pyx __pyx_mstate_global->__pyx_kp_s_opendbc_can_parser_pyx_pyx -#define __pyx_n_s_print __pyx_mstate_global->__pyx_n_s_print #define __pyx_n_s_pyx_state __pyx_mstate_global->__pyx_n_s_pyx_state #define __pyx_n_s_range __pyx_mstate_global->__pyx_n_s_range #define __pyx_n_s_reduce __pyx_mstate_global->__pyx_n_s_reduce @@ -3192,18 +2870,14 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #define __pyx_n_s_self __pyx_mstate_global->__pyx_n_s_self #define __pyx_kp_s_self_can_self_dbc_cannot_be_conv __pyx_mstate_global->__pyx_kp_s_self_can_self_dbc_cannot_be_conv #define __pyx_kp_s_self_dbc_cannot_be_converted_to __pyx_mstate_global->__pyx_kp_s_self_dbc_cannot_be_converted_to -#define __pyx_n_s_send __pyx_mstate_global->__pyx_n_s_send #define __pyx_n_s_sendcan __pyx_mstate_global->__pyx_n_s_sendcan #define __pyx_n_s_setstate __pyx_mstate_global->__pyx_n_s_setstate #define __pyx_n_s_setstate_cython __pyx_mstate_global->__pyx_n_s_setstate_cython -#define __pyx_n_s_signals __pyx_mstate_global->__pyx_n_s_signals #define __pyx_n_s_spec __pyx_mstate_global->__pyx_n_s_spec #define __pyx_n_s_split __pyx_mstate_global->__pyx_n_s_split #define __pyx_n_s_strings __pyx_mstate_global->__pyx_n_s_strings #define __pyx_kp_s_stringsource __pyx_mstate_global->__pyx_kp_s_stringsource #define __pyx_n_s_test __pyx_mstate_global->__pyx_n_s_test -#define __pyx_n_s_throw __pyx_mstate_global->__pyx_n_s_throw -#define __pyx_n_s_update __pyx_mstate_global->__pyx_n_s_update #define __pyx_n_s_update_strings __pyx_mstate_global->__pyx_n_s_update_strings #define __pyx_n_s_updated_addrs __pyx_mstate_global->__pyx_n_s_updated_addrs #define __pyx_n_s_v __pyx_mstate_global->__pyx_n_s_v @@ -3212,17 +2886,17 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #define __pyx_int_0 __pyx_mstate_global->__pyx_int_0 #define __pyx_int_1 __pyx_mstate_global->__pyx_int_1 #define __pyx_int_2 __pyx_mstate_global->__pyx_int_2 -#define __pyx_slice__5 __pyx_mstate_global->__pyx_slice__5 -#define __pyx_slice__6 __pyx_mstate_global->__pyx_slice__6 +#define __pyx_slice__2 __pyx_mstate_global->__pyx_slice__2 +#define __pyx_slice__3 __pyx_mstate_global->__pyx_slice__3 +#define __pyx_tuple__6 __pyx_mstate_global->__pyx_tuple__6 +#define __pyx_tuple__8 __pyx_mstate_global->__pyx_tuple__8 #define __pyx_tuple__9 __pyx_mstate_global->__pyx_tuple__9 #define __pyx_tuple__11 __pyx_mstate_global->__pyx_tuple__11 -#define __pyx_tuple__12 __pyx_mstate_global->__pyx_tuple__12 -#define __pyx_tuple__14 __pyx_mstate_global->__pyx_tuple__14 +#define __pyx_codeobj__7 __pyx_mstate_global->__pyx_codeobj__7 #define __pyx_codeobj__10 __pyx_mstate_global->__pyx_codeobj__10 +#define __pyx_codeobj__12 __pyx_mstate_global->__pyx_codeobj__12 #define __pyx_codeobj__13 __pyx_mstate_global->__pyx_codeobj__13 -#define __pyx_codeobj__15 __pyx_mstate_global->__pyx_codeobj__15 -#define __pyx_codeobj__16 __pyx_mstate_global->__pyx_codeobj__16 -#define __pyx_codeobj__17 __pyx_mstate_global->__pyx_codeobj__17 +#define __pyx_codeobj__14 __pyx_mstate_global->__pyx_codeobj__14 /* #### Code section: module_code ### */ /* "string.from_py":13 @@ -3546,6 +3220,127 @@ static CYTHON_INLINE PyObject *__pyx_convert_PyByteArray_string_to_py_std__in_st return __pyx_r; } +/* "pair.from_py":177 + * + * @cname("__pyx_convert_pair_from_py_uint32_t__and_int") + * cdef pair[X,Y] __pyx_convert_pair_from_py_uint32_t__and_int(object o) except *: # <<<<<<<<<<<<<< + * x, y = o + * return pair[X,Y](x, y) + */ + +static std::pair __pyx_convert_pair_from_py_uint32_t__and_int(PyObject *__pyx_v_o) { + PyObject *__pyx_v_x = NULL; + PyObject *__pyx_v_y = NULL; + std::pair __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *(*__pyx_t_4)(PyObject *); + uint32_t __pyx_t_5; + int __pyx_t_6; + std::pair __pyx_t_7; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_pair_from_py_uint32_t__and_int", 0); + + /* "pair.from_py":178 + * @cname("__pyx_convert_pair_from_py_uint32_t__and_int") + * cdef pair[X,Y] __pyx_convert_pair_from_py_uint32_t__and_int(object o) except *: + * x, y = o # <<<<<<<<<<<<<< + * return pair[X,Y](x, y) + * + */ + if ((likely(PyTuple_CheckExact(__pyx_v_o))) || (PyList_CheckExact(__pyx_v_o))) { + PyObject* sequence = __pyx_v_o; + Py_ssize_t size = __Pyx_PySequence_SIZE(sequence); + if (unlikely(size != 2)) { + if (size > 2) __Pyx_RaiseTooManyValuesError(2); + else if (size >= 0) __Pyx_RaiseNeedMoreValuesError(size); + __PYX_ERR(1, 178, __pyx_L1_error) + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + if (likely(PyTuple_CheckExact(sequence))) { + __pyx_t_1 = PyTuple_GET_ITEM(sequence, 0); + __pyx_t_2 = PyTuple_GET_ITEM(sequence, 1); + } else { + __pyx_t_1 = PyList_GET_ITEM(sequence, 0); + __pyx_t_2 = PyList_GET_ITEM(sequence, 1); + } + __Pyx_INCREF(__pyx_t_1); + __Pyx_INCREF(__pyx_t_2); + #else + __pyx_t_1 = PySequence_ITEM(sequence, 0); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 178, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = PySequence_ITEM(sequence, 1); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 178, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + #endif + } else { + Py_ssize_t index = -1; + __pyx_t_3 = PyObject_GetIter(__pyx_v_o); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 178, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_3); + index = 0; __pyx_t_1 = __pyx_t_4(__pyx_t_3); if (unlikely(!__pyx_t_1)) goto __pyx_L3_unpacking_failed; + __Pyx_GOTREF(__pyx_t_1); + index = 1; __pyx_t_2 = __pyx_t_4(__pyx_t_3); if (unlikely(!__pyx_t_2)) goto __pyx_L3_unpacking_failed; + __Pyx_GOTREF(__pyx_t_2); + if (__Pyx_IternextUnpackEndCheck(__pyx_t_4(__pyx_t_3), 2) < 0) __PYX_ERR(1, 178, __pyx_L1_error) + __pyx_t_4 = NULL; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L4_unpacking_done; + __pyx_L3_unpacking_failed:; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_4 = NULL; + if (__Pyx_IterFinish() == 0) __Pyx_RaiseNeedMoreValuesError(index); + __PYX_ERR(1, 178, __pyx_L1_error) + __pyx_L4_unpacking_done:; + } + __pyx_v_x = __pyx_t_1; + __pyx_t_1 = 0; + __pyx_v_y = __pyx_t_2; + __pyx_t_2 = 0; + + /* "pair.from_py":179 + * cdef pair[X,Y] __pyx_convert_pair_from_py_uint32_t__and_int(object o) except *: + * x, y = o + * return pair[X,Y](x, y) # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_5 = __Pyx_PyInt_As_uint32_t(__pyx_v_x); if (unlikely((__pyx_t_5 == ((uint32_t)-1)) && PyErr_Occurred())) __PYX_ERR(1, 179, __pyx_L1_error) + __pyx_t_6 = __Pyx_PyInt_As_int(__pyx_v_y); if (unlikely((__pyx_t_6 == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 179, __pyx_L1_error) + try { + __pyx_t_7 = std::pair (((uint32_t)__pyx_t_5), ((int)__pyx_t_6)); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(1, 179, __pyx_L1_error) + } + __pyx_r = __pyx_t_7; + goto __pyx_L0; + + /* "pair.from_py":177 + * + * @cname("__pyx_convert_pair_from_py_uint32_t__and_int") + * cdef pair[X,Y] __pyx_convert_pair_from_py_uint32_t__and_int(object o) except *: # <<<<<<<<<<<<<< + * x, y = o + * return pair[X,Y](x, y) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("pair.from_py.__pyx_convert_pair_from_py_uint32_t__and_int", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_pretend_to_initialize(&__pyx_r); + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_x); + __Pyx_XDECREF(__pyx_v_y); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + /* "vector.from_py":45 * * @cname("__pyx_convert_vector_from_py_std_3a__3a_string") @@ -3889,22 +3684,20 @@ static PyObject *__pyx_convert_unordered_set_to_py_uint32_t(std::unordered_set 0) { - PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_checks); - if (value) { values[2] = value; kw_args--; } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 31, __pyx_L3_error) - } - CYTHON_FALLTHROUGH; - case 3: if (kw_args > 0) { PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_bus); - if (value) { values[3] = value; kw_args--; } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 31, __pyx_L3_error) - } - CYTHON_FALLTHROUGH; - case 4: - if (kw_args > 0) { - PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_enforce_checks); - if (value) { values[4] = value; kw_args--; } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 31, __pyx_L3_error) + if (value) { values[2] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 30, __pyx_L3_error) } } if (unlikely(kw_args > 0)) { const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__init__") < 0)) __PYX_ERR(0, 31, __pyx_L3_error) + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__init__") < 0)) __PYX_ERR(0, 30, __pyx_L3_error) } } else { switch (__pyx_nargs) { - case 5: values[4] = __Pyx_Arg_VARARGS(__pyx_args, 4); - CYTHON_FALLTHROUGH; - case 4: values[3] = __Pyx_Arg_VARARGS(__pyx_args, 3); - CYTHON_FALLTHROUGH; case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); CYTHON_FALLTHROUGH; case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); @@ -3989,559 +3758,107 @@ static int __pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_1__init__(PyObject *__ } } __pyx_v_dbc_name = values[0]; - __pyx_v_signals = values[1]; - __pyx_v_checks = values[2]; - __pyx_v_bus = values[3]; - __pyx_v_enforce_checks = values[4]; + __pyx_v_messages = values[1]; + __pyx_v_bus = values[2]; } goto __pyx_L4_argument_unpacking_done; __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("__init__", 0, 2, 5, __pyx_nargs); __PYX_ERR(0, 31, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("__init__", 0, 2, 3, __pyx_nargs); __PYX_ERR(0, 30, __pyx_L3_error) __pyx_L3_error:; __Pyx_AddTraceback("opendbc.can.parser_pyx.CANParser.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); __Pyx_RefNannyFinishContext(); return -1; __pyx_L4_argument_unpacking_done:; - __pyx_r = __pyx_pf_7opendbc_3can_10parser_pyx_9CANParser___init__(((struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *)__pyx_v_self), __pyx_v_dbc_name, __pyx_v_signals, __pyx_v_checks, __pyx_v_bus, __pyx_v_enforce_checks); + __pyx_r = __pyx_pf_7opendbc_3can_10parser_pyx_9CANParser___init__(((struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *)__pyx_v_self), __pyx_v_dbc_name, __pyx_v_messages, __pyx_v_bus); /* function exit code */ __Pyx_RefNannyFinishContext(); return __pyx_r; } -static PyObject *__pyx_gb_7opendbc_3can_10parser_pyx_9CANParser_8__init___2generator(__pyx_CoroutineObject *__pyx_generator, CYTHON_UNUSED PyThreadState *__pyx_tstate, PyObject *__pyx_sent_value); /* proto */ -/* "opendbc/can/parser_pyx.pyx":92 - * unchecked = signal_addrs - checked_addrs - * if len(unchecked): - * err_msg = ", ".join(f"{self.address_to_msg_name[addr].decode()} ({hex(addr)})" for addr in unchecked) # <<<<<<<<<<<<<< - * raise RuntimeError(f"Unchecked addrs: {err_msg}") - * - */ - -static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_8__init___genexpr(PyObject *__pyx_self, PyObject *__pyx_genexpr_arg_0) { - struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr *__pyx_cur_scope; - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("genexpr", 0); - __pyx_cur_scope = (struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr *)__pyx_tp_new_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr(__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr, __pyx_empty_tuple, NULL); - if (unlikely(!__pyx_cur_scope)) { - __pyx_cur_scope = ((struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr *)Py_None); - __Pyx_INCREF(Py_None); - __PYX_ERR(0, 92, __pyx_L1_error) - } else { - __Pyx_GOTREF((PyObject *)__pyx_cur_scope); - } - __pyx_cur_scope->__pyx_outer_scope = (struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ *) __pyx_self; - __Pyx_INCREF((PyObject *)__pyx_cur_scope->__pyx_outer_scope); - __Pyx_GIVEREF((PyObject *)__pyx_cur_scope->__pyx_outer_scope); - __pyx_cur_scope->__pyx_genexpr_arg_0 = __pyx_genexpr_arg_0; - __Pyx_INCREF(__pyx_cur_scope->__pyx_genexpr_arg_0); - __Pyx_GIVEREF(__pyx_cur_scope->__pyx_genexpr_arg_0); - { - __pyx_CoroutineObject *gen = __Pyx_Generator_New((__pyx_coroutine_body_t) __pyx_gb_7opendbc_3can_10parser_pyx_9CANParser_8__init___2generator, NULL, (PyObject *) __pyx_cur_scope, __pyx_n_s_genexpr, __pyx_n_s_init___locals_genexpr, __pyx_n_s_opendbc_can_parser_pyx); if (unlikely(!gen)) __PYX_ERR(0, 92, __pyx_L1_error) - __Pyx_DECREF(__pyx_cur_scope); - __Pyx_RefNannyFinishContext(); - return (PyObject *) gen; - } - - /* function exit code */ - __pyx_L1_error:; - __Pyx_AddTraceback("opendbc.can.parser_pyx.CANParser.__init__.genexpr", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - __Pyx_DECREF((PyObject *)__pyx_cur_scope); - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_gb_7opendbc_3can_10parser_pyx_9CANParser_8__init___2generator(__pyx_CoroutineObject *__pyx_generator, CYTHON_UNUSED PyThreadState *__pyx_tstate, PyObject *__pyx_sent_value) /* generator body */ -{ - struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr *__pyx_cur_scope = ((struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr *)__pyx_generator->closure); - PyObject *__pyx_r = NULL; - PyObject *__pyx_t_1 = NULL; - Py_ssize_t __pyx_t_2; - PyObject *(*__pyx_t_3)(PyObject *); - PyObject *__pyx_t_4 = NULL; - Py_ssize_t __pyx_t_5; - Py_UCS4 __pyx_t_6; - uint32_t __pyx_t_7; - PyObject *__pyx_t_8 = NULL; - PyObject *__pyx_t_9 = NULL; - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("genexpr", 0); - switch (__pyx_generator->resume_label) { - case 0: goto __pyx_L3_first_run; - default: /* CPython raises the right error here */ - __Pyx_RefNannyFinishContext(); - return NULL; - } - __pyx_L3_first_run:; - if (unlikely(!__pyx_sent_value)) __PYX_ERR(0, 92, __pyx_L1_error) - __pyx_r = PyList_New(0); if (unlikely(!__pyx_r)) __PYX_ERR(0, 92, __pyx_L1_error) - __Pyx_GOTREF(__pyx_r); - if (unlikely(!__pyx_cur_scope->__pyx_genexpr_arg_0)) { __Pyx_RaiseUnboundLocalError(".0"); __PYX_ERR(0, 92, __pyx_L1_error) } - if (likely(PyList_CheckExact(__pyx_cur_scope->__pyx_genexpr_arg_0)) || PyTuple_CheckExact(__pyx_cur_scope->__pyx_genexpr_arg_0)) { - __pyx_t_1 = __pyx_cur_scope->__pyx_genexpr_arg_0; __Pyx_INCREF(__pyx_t_1); __pyx_t_2 = 0; - __pyx_t_3 = NULL; - } else { - __pyx_t_2 = -1; __pyx_t_1 = PyObject_GetIter(__pyx_cur_scope->__pyx_genexpr_arg_0); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 92, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_3 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 92, __pyx_L1_error) - } - for (;;) { - if (likely(!__pyx_t_3)) { - if (likely(PyList_CheckExact(__pyx_t_1))) { - if (__pyx_t_2 >= PyList_GET_SIZE(__pyx_t_1)) break; - #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - __pyx_t_4 = PyList_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_4); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(0, 92, __pyx_L1_error) - #else - __pyx_t_4 = PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 92, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - #endif - } else { - if (__pyx_t_2 >= PyTuple_GET_SIZE(__pyx_t_1)) break; - #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - __pyx_t_4 = PyTuple_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_4); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(0, 92, __pyx_L1_error) - #else - __pyx_t_4 = PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 92, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - #endif - } - } else { - __pyx_t_4 = __pyx_t_3(__pyx_t_1); - if (unlikely(!__pyx_t_4)) { - PyObject* exc_type = PyErr_Occurred(); - if (exc_type) { - if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); - else __PYX_ERR(0, 92, __pyx_L1_error) - } - break; - } - __Pyx_GOTREF(__pyx_t_4); - } - __Pyx_XGOTREF(__pyx_cur_scope->__pyx_v_addr); - __Pyx_XDECREF_SET(__pyx_cur_scope->__pyx_v_addr, __pyx_t_4); - __Pyx_GIVEREF(__pyx_t_4); - __pyx_t_4 = 0; - __pyx_t_4 = PyTuple_New(4); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 92, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __pyx_t_5 = 0; - __pyx_t_6 = 127; - if (unlikely(!__pyx_cur_scope->__pyx_outer_scope->__pyx_v_self)) { __Pyx_RaiseClosureNameError("self"); __PYX_ERR(0, 92, __pyx_L1_error) } - __pyx_t_7 = __Pyx_PyInt_As_uint32_t(__pyx_cur_scope->__pyx_v_addr); if (unlikely((__pyx_t_7 == ((uint32_t)-1)) && PyErr_Occurred())) __PYX_ERR(0, 92, __pyx_L1_error) - __pyx_t_8 = __Pyx_decode_cpp_string((__pyx_cur_scope->__pyx_outer_scope->__pyx_v_self->address_to_msg_name[__pyx_t_7]), 0, PY_SSIZE_T_MAX, NULL, NULL, NULL); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 92, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_8); - __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_8) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_8) : __pyx_t_6; - __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_8); - __Pyx_GIVEREF(__pyx_t_8); - PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_8); - __pyx_t_8 = 0; - __Pyx_INCREF(__pyx_kp_u_); - __pyx_t_5 += 2; - __Pyx_GIVEREF(__pyx_kp_u_); - PyTuple_SET_ITEM(__pyx_t_4, 1, __pyx_kp_u_); - __pyx_t_8 = __Pyx_PyObject_CallOneArg(__pyx_builtin_hex, __pyx_cur_scope->__pyx_v_addr); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 92, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_8); - __pyx_t_9 = __Pyx_PyObject_FormatSimple(__pyx_t_8, __pyx_empty_unicode); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 92, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_9); - __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; - __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_9) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_9) : __pyx_t_6; - __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_9); - __Pyx_GIVEREF(__pyx_t_9); - PyTuple_SET_ITEM(__pyx_t_4, 2, __pyx_t_9); - __pyx_t_9 = 0; - __Pyx_INCREF(__pyx_kp_u__2); - __pyx_t_5 += 1; - __Pyx_GIVEREF(__pyx_kp_u__2); - PyTuple_SET_ITEM(__pyx_t_4, 3, __pyx_kp_u__2); - __pyx_t_9 = __Pyx_PyUnicode_Join(__pyx_t_4, 4, __pyx_t_5, __pyx_t_6); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 92, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_9); - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - if (unlikely(__Pyx_ListComp_Append(__pyx_r, (PyObject*)__pyx_t_9))) __PYX_ERR(0, 92, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; - } - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - CYTHON_MAYBE_UNUSED_VAR(__pyx_cur_scope); - - /* function exit code */ - goto __pyx_L0; - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_r); __pyx_r = 0; - __Pyx_Generator_Replace_StopIteration(0); - __Pyx_XDECREF(__pyx_t_1); - __Pyx_XDECREF(__pyx_t_4); - __Pyx_XDECREF(__pyx_t_8); - __Pyx_XDECREF(__pyx_t_9); - __Pyx_AddTraceback("genexpr", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_L0:; - __Pyx_XGIVEREF(__pyx_r); - #if !CYTHON_USE_EXC_INFO_STACK - __Pyx_Coroutine_ResetAndClearException(__pyx_generator); - #endif - __pyx_generator->resume_label = -1; - __Pyx_Coroutine_clear((PyObject*)__pyx_generator); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} -static PyObject *__pyx_gb_7opendbc_3can_10parser_pyx_9CANParser_8__init___5generator1(__pyx_CoroutineObject *__pyx_generator, CYTHON_UNUSED PyThreadState *__pyx_tstate, PyObject *__pyx_sent_value); /* proto */ - -/* "opendbc/can/parser_pyx.pyx":102 - * signal_options_v.push_back(spo) - * - * message_options = dict((address, 0) for _, address in signals) # <<<<<<<<<<<<<< - * message_options.update(dict(checks)) - * - */ - -static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_8__init___3genexpr(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_genexpr_arg_0) { - struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr *__pyx_cur_scope; - PyObject *__pyx_r = NULL; - __Pyx_RefNannyDeclarations - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("genexpr", 0); - __pyx_cur_scope = (struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr *)__pyx_tp_new_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr(__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr, __pyx_empty_tuple, NULL); - if (unlikely(!__pyx_cur_scope)) { - __pyx_cur_scope = ((struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr *)Py_None); - __Pyx_INCREF(Py_None); - __PYX_ERR(0, 102, __pyx_L1_error) - } else { - __Pyx_GOTREF((PyObject *)__pyx_cur_scope); - } - __pyx_cur_scope->__pyx_genexpr_arg_0 = __pyx_genexpr_arg_0; - __Pyx_INCREF(__pyx_cur_scope->__pyx_genexpr_arg_0); - __Pyx_GIVEREF(__pyx_cur_scope->__pyx_genexpr_arg_0); - { - __pyx_CoroutineObject *gen = __Pyx_Generator_New((__pyx_coroutine_body_t) __pyx_gb_7opendbc_3can_10parser_pyx_9CANParser_8__init___5generator1, NULL, (PyObject *) __pyx_cur_scope, __pyx_n_s_genexpr, __pyx_n_s_init___locals_genexpr, __pyx_n_s_opendbc_can_parser_pyx); if (unlikely(!gen)) __PYX_ERR(0, 102, __pyx_L1_error) - __Pyx_DECREF(__pyx_cur_scope); - __Pyx_RefNannyFinishContext(); - return (PyObject *) gen; - } - - /* function exit code */ - __pyx_L1_error:; - __Pyx_AddTraceback("opendbc.can.parser_pyx.CANParser.__init__.genexpr", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_r = NULL; - __Pyx_DECREF((PyObject *)__pyx_cur_scope); - __Pyx_XGIVEREF(__pyx_r); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -static PyObject *__pyx_gb_7opendbc_3can_10parser_pyx_9CANParser_8__init___5generator1(__pyx_CoroutineObject *__pyx_generator, CYTHON_UNUSED PyThreadState *__pyx_tstate, PyObject *__pyx_sent_value) /* generator body */ -{ - struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr *__pyx_cur_scope = ((struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr *)__pyx_generator->closure); - PyObject *__pyx_r = NULL; - PyObject *__pyx_t_1 = NULL; - Py_ssize_t __pyx_t_2; - PyObject *(*__pyx_t_3)(PyObject *); - PyObject *__pyx_t_4 = NULL; - PyObject *__pyx_t_5 = NULL; - PyObject *__pyx_t_6 = NULL; - PyObject *__pyx_t_7 = NULL; - PyObject *(*__pyx_t_8)(PyObject *); - int __pyx_lineno = 0; - const char *__pyx_filename = NULL; - int __pyx_clineno = 0; - __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("genexpr", 0); - switch (__pyx_generator->resume_label) { - case 0: goto __pyx_L3_first_run; - default: /* CPython raises the right error here */ - __Pyx_RefNannyFinishContext(); - return NULL; - } - __pyx_L3_first_run:; - if (unlikely(!__pyx_sent_value)) __PYX_ERR(0, 102, __pyx_L1_error) - __pyx_r = PyDict_New(); if (unlikely(!__pyx_r)) __PYX_ERR(0, 102, __pyx_L1_error) - __Pyx_GOTREF(__pyx_r); - if (unlikely(!__pyx_cur_scope->__pyx_genexpr_arg_0)) { __Pyx_RaiseUnboundLocalError(".0"); __PYX_ERR(0, 102, __pyx_L1_error) } - if (likely(PyList_CheckExact(__pyx_cur_scope->__pyx_genexpr_arg_0)) || PyTuple_CheckExact(__pyx_cur_scope->__pyx_genexpr_arg_0)) { - __pyx_t_1 = __pyx_cur_scope->__pyx_genexpr_arg_0; __Pyx_INCREF(__pyx_t_1); __pyx_t_2 = 0; - __pyx_t_3 = NULL; - } else { - __pyx_t_2 = -1; __pyx_t_1 = PyObject_GetIter(__pyx_cur_scope->__pyx_genexpr_arg_0); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 102, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_3 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 102, __pyx_L1_error) - } - for (;;) { - if (likely(!__pyx_t_3)) { - if (likely(PyList_CheckExact(__pyx_t_1))) { - if (__pyx_t_2 >= PyList_GET_SIZE(__pyx_t_1)) break; - #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - __pyx_t_4 = PyList_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_4); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(0, 102, __pyx_L1_error) - #else - __pyx_t_4 = PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 102, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - #endif - } else { - if (__pyx_t_2 >= PyTuple_GET_SIZE(__pyx_t_1)) break; - #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - __pyx_t_4 = PyTuple_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_4); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(0, 102, __pyx_L1_error) - #else - __pyx_t_4 = PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 102, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - #endif - } - } else { - __pyx_t_4 = __pyx_t_3(__pyx_t_1); - if (unlikely(!__pyx_t_4)) { - PyObject* exc_type = PyErr_Occurred(); - if (exc_type) { - if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); - else __PYX_ERR(0, 102, __pyx_L1_error) - } - break; - } - __Pyx_GOTREF(__pyx_t_4); - } - if ((likely(PyTuple_CheckExact(__pyx_t_4))) || (PyList_CheckExact(__pyx_t_4))) { - PyObject* sequence = __pyx_t_4; - Py_ssize_t size = __Pyx_PySequence_SIZE(sequence); - if (unlikely(size != 2)) { - if (size > 2) __Pyx_RaiseTooManyValuesError(2); - else if (size >= 0) __Pyx_RaiseNeedMoreValuesError(size); - __PYX_ERR(0, 102, __pyx_L1_error) - } - #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - if (likely(PyTuple_CheckExact(sequence))) { - __pyx_t_5 = PyTuple_GET_ITEM(sequence, 0); - __pyx_t_6 = PyTuple_GET_ITEM(sequence, 1); - } else { - __pyx_t_5 = PyList_GET_ITEM(sequence, 0); - __pyx_t_6 = PyList_GET_ITEM(sequence, 1); - } - __Pyx_INCREF(__pyx_t_5); - __Pyx_INCREF(__pyx_t_6); - #else - __pyx_t_5 = PySequence_ITEM(sequence, 0); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 102, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __pyx_t_6 = PySequence_ITEM(sequence, 1); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 102, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_6); - #endif - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - } else { - Py_ssize_t index = -1; - __pyx_t_7 = PyObject_GetIter(__pyx_t_4); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 102, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __pyx_t_8 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_7); - index = 0; __pyx_t_5 = __pyx_t_8(__pyx_t_7); if (unlikely(!__pyx_t_5)) goto __pyx_L6_unpacking_failed; - __Pyx_GOTREF(__pyx_t_5); - index = 1; __pyx_t_6 = __pyx_t_8(__pyx_t_7); if (unlikely(!__pyx_t_6)) goto __pyx_L6_unpacking_failed; - __Pyx_GOTREF(__pyx_t_6); - if (__Pyx_IternextUnpackEndCheck(__pyx_t_8(__pyx_t_7), 2) < 0) __PYX_ERR(0, 102, __pyx_L1_error) - __pyx_t_8 = NULL; - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - goto __pyx_L7_unpacking_done; - __pyx_L6_unpacking_failed:; - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - __pyx_t_8 = NULL; - if (__Pyx_IterFinish() == 0) __Pyx_RaiseNeedMoreValuesError(index); - __PYX_ERR(0, 102, __pyx_L1_error) - __pyx_L7_unpacking_done:; - } - __Pyx_XGOTREF(__pyx_cur_scope->__pyx_v__); - __Pyx_XDECREF_SET(__pyx_cur_scope->__pyx_v__, __pyx_t_5); - __Pyx_GIVEREF(__pyx_t_5); - __pyx_t_5 = 0; - __Pyx_XGOTREF(__pyx_cur_scope->__pyx_v_address); - __Pyx_XDECREF_SET(__pyx_cur_scope->__pyx_v_address, __pyx_t_6); - __Pyx_GIVEREF(__pyx_t_6); - __pyx_t_6 = 0; - if (unlikely(PyDict_SetItem(__pyx_r, (PyObject*)__pyx_cur_scope->__pyx_v_address, (PyObject*)__pyx_int_0))) __PYX_ERR(0, 102, __pyx_L1_error) - } - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - CYTHON_MAYBE_UNUSED_VAR(__pyx_cur_scope); - - /* function exit code */ - goto __pyx_L0; - __pyx_L1_error:; - __Pyx_XDECREF(__pyx_r); __pyx_r = 0; - __Pyx_Generator_Replace_StopIteration(0); - __Pyx_XDECREF(__pyx_t_1); - __Pyx_XDECREF(__pyx_t_4); - __Pyx_XDECREF(__pyx_t_5); - __Pyx_XDECREF(__pyx_t_6); - __Pyx_XDECREF(__pyx_t_7); - __Pyx_AddTraceback("genexpr", __pyx_clineno, __pyx_lineno, __pyx_filename); - __pyx_L0:; - __Pyx_XGIVEREF(__pyx_r); - #if !CYTHON_USE_EXC_INFO_STACK - __Pyx_Coroutine_ResetAndClearException(__pyx_generator); - #endif - __pyx_generator->resume_label = -1; - __Pyx_Coroutine_clear((PyObject*)__pyx_generator); - __Pyx_RefNannyFinishContext(); - return __pyx_r; -} - -/* "opendbc/can/parser_pyx.pyx":31 - * string dbc_name - * - * def __init__(self, dbc_name, signals, checks=None, bus=0, enforce_checks=True): # <<<<<<<<<<<<<< - * if checks is None: - * checks = [] - */ - -static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANParser___init__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self, PyObject *__pyx_v_dbc_name, PyObject *__pyx_v_signals, PyObject *__pyx_v_checks, PyObject *__pyx_v_bus, PyObject *__pyx_v_enforce_checks) { - struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ *__pyx_cur_scope; +static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANParser___init__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self, PyObject *__pyx_v_dbc_name, PyObject *__pyx_v_messages, PyObject *__pyx_v_bus) { + CYTHON_UNUSED PyObject *__pyx_v_checks = NULL; + CYTHON_UNUSED int __pyx_v_enforce_checks; PyObject *__pyx_v_msg_name_to_address = NULL; - PyObject *__pyx_v_msg_address_to_signals = NULL; + PyObject *__pyx_v_address_to_msg_name = NULL; std::vector ::size_type __pyx_v_i; struct Msg __pyx_v_msg; PyObject *__pyx_v_name = NULL; - struct Signal __pyx_v_sig; - PyObject *__pyx_v_s = NULL; - PyObject *__pyx_v_address = NULL; + std::vector > __pyx_v_message_v; PyObject *__pyx_v_c = NULL; - PyObject *__pyx_v_checked_addrs = NULL; - PyObject *__pyx_v_signal_addrs = NULL; - PyObject *__pyx_v_unchecked = NULL; - PyObject *__pyx_v_err_msg = NULL; - std::vector __pyx_v_signal_options_v; - struct SignalParseOptions __pyx_v_spo; - PyObject *__pyx_v_sig_name = NULL; - PyObject *__pyx_v_sig_address = NULL; - PyObject *__pyx_v_message_options = NULL; - std::vector __pyx_v_message_options_v; - struct MessageParseOptions __pyx_v_mpo; - PyObject *__pyx_v_msg_address = NULL; - PyObject *__pyx_v_freq = NULL; - PyObject *__pyx_7genexpr__pyx_v_c = NULL; - PyObject *__pyx_8genexpr1__pyx_v_s = NULL; - PyObject *__pyx_gb_7opendbc_3can_10parser_pyx_9CANParser_8__init___2generator = 0; - PyObject *__pyx_gb_7opendbc_3can_10parser_pyx_9CANParser_8__init___5generator1 = 0; + PyObject *__pyx_v_address = NULL; int __pyx_r; __Pyx_RefNannyDeclarations - int __pyx_t_1; - PyObject *__pyx_t_2 = NULL; - std::string __pyx_t_3; + std::string __pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; PyObject *__pyx_t_4 = NULL; std::vector ::size_type __pyx_t_5; std::vector ::size_type __pyx_t_6; std::vector ::size_type __pyx_t_7; - std::vector ::iterator __pyx_t_8; - struct Signal __pyx_t_9; + Py_ssize_t __pyx_t_8; + Py_ssize_t __pyx_t_9; PyObject *__pyx_t_10 = NULL; PyObject *__pyx_t_11 = NULL; - int __pyx_t_12; - Py_ssize_t __pyx_t_13; - Py_ssize_t __pyx_t_14; - Py_ssize_t __pyx_t_15; - Py_UCS4 __pyx_t_16; - int __pyx_t_17; - PyObject *(*__pyx_t_18)(PyObject *); - PyObject *__pyx_t_19 = NULL; - PyObject *(*__pyx_t_20)(PyObject *); - uint32_t __pyx_t_21; - int __pyx_t_22; + Py_ssize_t __pyx_t_12; + Py_UCS4 __pyx_t_13; + std::pair __pyx_t_14; + int __pyx_t_15; int __pyx_lineno = 0; const char *__pyx_filename = NULL; int __pyx_clineno = 0; __Pyx_RefNannySetupContext("__init__", 0); - __pyx_cur_scope = (struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ *)__pyx_tp_new_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__(__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__, __pyx_empty_tuple, NULL); - if (unlikely(!__pyx_cur_scope)) { - __pyx_cur_scope = ((struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ *)Py_None); - __Pyx_INCREF(Py_None); - __PYX_ERR(0, 31, __pyx_L1_error) - } else { - __Pyx_GOTREF((PyObject *)__pyx_cur_scope); - } - __pyx_cur_scope->__pyx_v_self = __pyx_v_self; - __Pyx_INCREF((PyObject *)__pyx_cur_scope->__pyx_v_self); - __Pyx_GIVEREF((PyObject *)__pyx_cur_scope->__pyx_v_self); - __Pyx_INCREF(__pyx_v_checks); - __Pyx_INCREF(__pyx_v_enforce_checks); - /* "opendbc/can/parser_pyx.pyx":32 - * - * def __init__(self, dbc_name, signals, checks=None, bus=0, enforce_checks=True): - * if checks is None: # <<<<<<<<<<<<<< - * checks = [] - * - */ - __pyx_t_1 = (__pyx_v_checks == Py_None); - if (__pyx_t_1) { - - /* "opendbc/can/parser_pyx.pyx":33 - * def __init__(self, dbc_name, signals, checks=None, bus=0, enforce_checks=True): - * if checks is None: - * checks = [] # <<<<<<<<<<<<<< - * - * self.dbc_name = dbc_name - */ - __pyx_t_2 = PyList_New(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 33, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __Pyx_DECREF_SET(__pyx_v_checks, __pyx_t_2); - __pyx_t_2 = 0; - - /* "opendbc/can/parser_pyx.pyx":32 - * - * def __init__(self, dbc_name, signals, checks=None, bus=0, enforce_checks=True): - * if checks is None: # <<<<<<<<<<<<<< - * checks = [] - * - */ - } - - /* "opendbc/can/parser_pyx.pyx":35 - * checks = [] + /* "opendbc/can/parser_pyx.pyx":31 * + * def __init__(self, dbc_name, messages, bus=0): * self.dbc_name = dbc_name # <<<<<<<<<<<<<< * self.dbc = dbc_lookup(dbc_name) * if not self.dbc: */ - __pyx_t_3 = __pyx_convert_string_from_py_std__in_string(__pyx_v_dbc_name); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 35, __pyx_L1_error) - __pyx_cur_scope->__pyx_v_self->dbc_name = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_3); + __pyx_t_1 = __pyx_convert_string_from_py_std__in_string(__pyx_v_dbc_name); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 31, __pyx_L1_error) + __pyx_v_self->dbc_name = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_1); - /* "opendbc/can/parser_pyx.pyx":36 - * + /* "opendbc/can/parser_pyx.pyx":32 + * def __init__(self, dbc_name, messages, bus=0): * self.dbc_name = dbc_name * self.dbc = dbc_lookup(dbc_name) # <<<<<<<<<<<<<< * if not self.dbc: * raise RuntimeError(f"Can't find DBC: {dbc_name}") */ - __pyx_t_3 = __pyx_convert_string_from_py_std__in_string(__pyx_v_dbc_name); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 36, __pyx_L1_error) - __pyx_cur_scope->__pyx_v_self->dbc = dbc_lookup(__PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_3)); + __pyx_t_1 = __pyx_convert_string_from_py_std__in_string(__pyx_v_dbc_name); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 32, __pyx_L1_error) + __pyx_v_self->dbc = dbc_lookup(__PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_1)); - /* "opendbc/can/parser_pyx.pyx":37 + /* "opendbc/can/parser_pyx.pyx":33 * self.dbc_name = dbc_name * self.dbc = dbc_lookup(dbc_name) * if not self.dbc: # <<<<<<<<<<<<<< * raise RuntimeError(f"Can't find DBC: {dbc_name}") * */ - __pyx_t_1 = (!(__pyx_cur_scope->__pyx_v_self->dbc != 0)); - if (unlikely(__pyx_t_1)) { + __pyx_t_2 = (!(__pyx_v_self->dbc != 0)); + if (unlikely(__pyx_t_2)) { - /* "opendbc/can/parser_pyx.pyx":38 + /* "opendbc/can/parser_pyx.pyx":34 * self.dbc = dbc_lookup(dbc_name) * if not self.dbc: * raise RuntimeError(f"Can't find DBC: {dbc_name}") # <<<<<<<<<<<<<< * * # rick - disable checks */ - __pyx_t_2 = __Pyx_PyObject_FormatSimple(__pyx_v_dbc_name, __pyx_empty_unicode); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 38, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __pyx_t_4 = __Pyx_PyUnicode_Concat(__pyx_kp_u_Can_t_find_DBC, __pyx_t_2); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 38, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyObject_FormatSimple(__pyx_v_dbc_name, __pyx_empty_unicode); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 34, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = __Pyx_PyUnicode_Concat(__pyx_kp_u_Can_t_find_DBC, __pyx_t_3); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 34, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - __pyx_t_2 = __Pyx_PyObject_CallOneArg(__pyx_builtin_RuntimeError, __pyx_t_4); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 38, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PyObject_CallOneArg(__pyx_builtin_RuntimeError, __pyx_t_4); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 34, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __Pyx_Raise(__pyx_t_2, 0, 0, 0); - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - __PYX_ERR(0, 38, __pyx_L1_error) + __Pyx_Raise(__pyx_t_3, 0, 0, 0); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __PYX_ERR(0, 34, __pyx_L1_error) - /* "opendbc/can/parser_pyx.pyx":37 + /* "opendbc/can/parser_pyx.pyx":33 * self.dbc_name = dbc_name * self.dbc = dbc_lookup(dbc_name) * if not self.dbc: # <<<<<<<<<<<<<< @@ -4550,1322 +3867,511 @@ static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANParser___init__(struct __pyx_ */ } - /* "opendbc/can/parser_pyx.pyx":41 + /* "opendbc/can/parser_pyx.pyx":37 * * # rick - disable checks * checks = [] # <<<<<<<<<<<<<< * enforce_checks = False * */ - __pyx_t_2 = PyList_New(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 41, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __Pyx_DECREF_SET(__pyx_v_checks, __pyx_t_2); - __pyx_t_2 = 0; + __pyx_t_3 = PyList_New(0); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 37, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_v_checks = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; - /* "opendbc/can/parser_pyx.pyx":42 + /* "opendbc/can/parser_pyx.pyx":38 * # rick - disable checks * checks = [] * enforce_checks = False # <<<<<<<<<<<<<< * * self.vl = {} */ - __Pyx_INCREF(Py_False); - __Pyx_DECREF_SET(__pyx_v_enforce_checks, Py_False); + __pyx_v_enforce_checks = 0; - /* "opendbc/can/parser_pyx.pyx":44 + /* "opendbc/can/parser_pyx.pyx":40 * enforce_checks = False * * self.vl = {} # <<<<<<<<<<<<<< * self.vl_all = {} * self.ts_nanos = {} */ - __pyx_t_2 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 44, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __Pyx_GIVEREF(__pyx_t_2); - __Pyx_GOTREF(__pyx_cur_scope->__pyx_v_self->vl); - __Pyx_DECREF(__pyx_cur_scope->__pyx_v_self->vl); - __pyx_cur_scope->__pyx_v_self->vl = ((PyObject*)__pyx_t_2); - __pyx_t_2 = 0; + __pyx_t_3 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 40, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_3); + __Pyx_GOTREF(__pyx_v_self->vl); + __Pyx_DECREF(__pyx_v_self->vl); + __pyx_v_self->vl = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; - /* "opendbc/can/parser_pyx.pyx":45 + /* "opendbc/can/parser_pyx.pyx":41 * * self.vl = {} * self.vl_all = {} # <<<<<<<<<<<<<< * self.ts_nanos = {} * msg_name_to_address = {} */ - __pyx_t_2 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 45, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __Pyx_GIVEREF(__pyx_t_2); - __Pyx_GOTREF(__pyx_cur_scope->__pyx_v_self->vl_all); - __Pyx_DECREF(__pyx_cur_scope->__pyx_v_self->vl_all); - __pyx_cur_scope->__pyx_v_self->vl_all = ((PyObject*)__pyx_t_2); - __pyx_t_2 = 0; + __pyx_t_3 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 41, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_3); + __Pyx_GOTREF(__pyx_v_self->vl_all); + __Pyx_DECREF(__pyx_v_self->vl_all); + __pyx_v_self->vl_all = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; - /* "opendbc/can/parser_pyx.pyx":46 + /* "opendbc/can/parser_pyx.pyx":42 * self.vl = {} * self.vl_all = {} * self.ts_nanos = {} # <<<<<<<<<<<<<< * msg_name_to_address = {} - * msg_address_to_signals = {} + * address_to_msg_name = {} */ - __pyx_t_2 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 46, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __Pyx_GIVEREF(__pyx_t_2); - __Pyx_GOTREF(__pyx_cur_scope->__pyx_v_self->ts_nanos); - __Pyx_DECREF(__pyx_cur_scope->__pyx_v_self->ts_nanos); - __pyx_cur_scope->__pyx_v_self->ts_nanos = ((PyObject*)__pyx_t_2); - __pyx_t_2 = 0; + __pyx_t_3 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 42, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_3); + __Pyx_GOTREF(__pyx_v_self->ts_nanos); + __Pyx_DECREF(__pyx_v_self->ts_nanos); + __pyx_v_self->ts_nanos = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; - /* "opendbc/can/parser_pyx.pyx":47 + /* "opendbc/can/parser_pyx.pyx":43 * self.vl_all = {} * self.ts_nanos = {} * msg_name_to_address = {} # <<<<<<<<<<<<<< - * msg_address_to_signals = {} + * address_to_msg_name = {} * */ - __pyx_t_2 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 47, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __pyx_v_msg_name_to_address = ((PyObject*)__pyx_t_2); - __pyx_t_2 = 0; + __pyx_t_3 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 43, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_v_msg_name_to_address = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; - /* "opendbc/can/parser_pyx.pyx":48 + /* "opendbc/can/parser_pyx.pyx":44 * self.ts_nanos = {} * msg_name_to_address = {} - * msg_address_to_signals = {} # <<<<<<<<<<<<<< + * address_to_msg_name = {} # <<<<<<<<<<<<<< * * for i in range(self.dbc[0].msgs.size()): */ - __pyx_t_2 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 48, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __pyx_v_msg_address_to_signals = ((PyObject*)__pyx_t_2); - __pyx_t_2 = 0; + __pyx_t_3 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 44, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_v_address_to_msg_name = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; - /* "opendbc/can/parser_pyx.pyx":50 - * msg_address_to_signals = {} + /* "opendbc/can/parser_pyx.pyx":46 + * address_to_msg_name = {} * * for i in range(self.dbc[0].msgs.size()): # <<<<<<<<<<<<<< * msg = self.dbc[0].msgs[i] * name = msg.name.decode("utf8") */ - __pyx_t_5 = (__pyx_cur_scope->__pyx_v_self->dbc[0]).msgs.size(); + __pyx_t_5 = (__pyx_v_self->dbc[0]).msgs.size(); __pyx_t_6 = __pyx_t_5; for (__pyx_t_7 = 0; __pyx_t_7 < __pyx_t_6; __pyx_t_7+=1) { __pyx_v_i = __pyx_t_7; - /* "opendbc/can/parser_pyx.pyx":51 + /* "opendbc/can/parser_pyx.pyx":47 * * for i in range(self.dbc[0].msgs.size()): * msg = self.dbc[0].msgs[i] # <<<<<<<<<<<<<< * name = msg.name.decode("utf8") * */ - __pyx_v_msg = ((__pyx_cur_scope->__pyx_v_self->dbc[0]).msgs[__pyx_v_i]); + __pyx_v_msg = ((__pyx_v_self->dbc[0]).msgs[__pyx_v_i]); - /* "opendbc/can/parser_pyx.pyx":52 + /* "opendbc/can/parser_pyx.pyx":48 * for i in range(self.dbc[0].msgs.size()): * msg = self.dbc[0].msgs[i] * name = msg.name.decode("utf8") # <<<<<<<<<<<<<< * * msg_name_to_address[name] = msg.address */ - __pyx_t_2 = __Pyx_decode_cpp_string(__pyx_v_msg.name, 0, PY_SSIZE_T_MAX, NULL, NULL, PyUnicode_DecodeUTF8); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 52, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __Pyx_XDECREF_SET(__pyx_v_name, __pyx_t_2); - __pyx_t_2 = 0; + __pyx_t_3 = __Pyx_decode_cpp_string(__pyx_v_msg.name, 0, PY_SSIZE_T_MAX, NULL, NULL, PyUnicode_DecodeUTF8); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 48, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_XDECREF_SET(__pyx_v_name, __pyx_t_3); + __pyx_t_3 = 0; - /* "opendbc/can/parser_pyx.pyx":54 + /* "opendbc/can/parser_pyx.pyx":50 * name = msg.name.decode("utf8") * * msg_name_to_address[name] = msg.address # <<<<<<<<<<<<<< - * msg_address_to_signals[msg.address] = set() - * for sig in msg.sigs: + * address_to_msg_name[msg.address] = name + * */ - __pyx_t_2 = __Pyx_PyInt_From_uint32_t(__pyx_v_msg.address); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 54, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - if (unlikely((PyDict_SetItem(__pyx_v_msg_name_to_address, __pyx_v_name, __pyx_t_2) < 0))) __PYX_ERR(0, 54, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_3 = __Pyx_PyInt_From_uint32_t(__pyx_v_msg.address); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 50, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (unlikely((PyDict_SetItem(__pyx_v_msg_name_to_address, __pyx_v_name, __pyx_t_3) < 0))) __PYX_ERR(0, 50, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - /* "opendbc/can/parser_pyx.pyx":55 + /* "opendbc/can/parser_pyx.pyx":51 * * msg_name_to_address[name] = msg.address - * msg_address_to_signals[msg.address] = set() # <<<<<<<<<<<<<< - * for sig in msg.sigs: - * msg_address_to_signals[msg.address].add(sig.name.decode("utf8")) - */ - __pyx_t_2 = PySet_New(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 55, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __pyx_t_4 = __Pyx_PyInt_From_uint32_t(__pyx_v_msg.address); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 55, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - if (unlikely((PyDict_SetItem(__pyx_v_msg_address_to_signals, __pyx_t_4, __pyx_t_2) < 0))) __PYX_ERR(0, 55, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - - /* "opendbc/can/parser_pyx.pyx":56 - * msg_name_to_address[name] = msg.address - * msg_address_to_signals[msg.address] = set() - * for sig in msg.sigs: # <<<<<<<<<<<<<< - * msg_address_to_signals[msg.address].add(sig.name.decode("utf8")) + * address_to_msg_name[msg.address] = name # <<<<<<<<<<<<<< * - */ - __pyx_t_8 = __pyx_v_msg.sigs.begin(); - for (;;) { - if (!(__pyx_t_8 != __pyx_v_msg.sigs.end())) break; - __pyx_t_9 = *__pyx_t_8; - ++__pyx_t_8; - __pyx_v_sig = __pyx_t_9; - - /* "opendbc/can/parser_pyx.pyx":57 - * msg_address_to_signals[msg.address] = set() - * for sig in msg.sigs: - * msg_address_to_signals[msg.address].add(sig.name.decode("utf8")) # <<<<<<<<<<<<<< - * - * self.address_to_msg_name[msg.address] = name - */ - __pyx_t_4 = __Pyx_PyInt_From_uint32_t(__pyx_v_msg.address); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 57, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __pyx_t_10 = __Pyx_PyDict_GetItem(__pyx_v_msg_address_to_signals, __pyx_t_4); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 57, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_10); - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_10, __pyx_n_s_add); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 57, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; - __pyx_t_10 = __Pyx_decode_cpp_string(__pyx_v_sig.name, 0, PY_SSIZE_T_MAX, NULL, NULL, PyUnicode_DecodeUTF8); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 57, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_10); - __pyx_t_11 = NULL; - __pyx_t_12 = 0; - if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_4))) { - __pyx_t_11 = PyMethod_GET_SELF(__pyx_t_4); - if (likely(__pyx_t_11)) { - PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_4); - __Pyx_INCREF(__pyx_t_11); - __Pyx_INCREF(function); - __Pyx_DECREF_SET(__pyx_t_4, function); - __pyx_t_12 = 1; - } - } - { - PyObject *__pyx_callargs[2] = {__pyx_t_11, __pyx_t_10}; - __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_12, 1+__pyx_t_12); - __Pyx_XDECREF(__pyx_t_11); __pyx_t_11 = 0; - __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; - if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 57, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - } - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - - /* "opendbc/can/parser_pyx.pyx":56 - * msg_name_to_address[name] = msg.address - * msg_address_to_signals[msg.address] = set() - * for sig in msg.sigs: # <<<<<<<<<<<<<< - * msg_address_to_signals[msg.address].add(sig.name.decode("utf8")) - * - */ - } - - /* "opendbc/can/parser_pyx.pyx":59 - * msg_address_to_signals[msg.address].add(sig.name.decode("utf8")) - * - * self.address_to_msg_name[msg.address] = name # <<<<<<<<<<<<<< * self.vl[msg.address] = {} - * self.vl[name] = self.vl[msg.address] */ - __pyx_t_3 = __pyx_convert_string_from_py_std__in_string(__pyx_v_name); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 59, __pyx_L1_error) - (__pyx_cur_scope->__pyx_v_self->address_to_msg_name[__pyx_v_msg.address]) = __pyx_t_3; + __pyx_t_3 = __Pyx_PyInt_From_uint32_t(__pyx_v_msg.address); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 51, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (unlikely((PyDict_SetItem(__pyx_v_address_to_msg_name, __pyx_t_3, __pyx_v_name) < 0))) __PYX_ERR(0, 51, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - /* "opendbc/can/parser_pyx.pyx":60 + /* "opendbc/can/parser_pyx.pyx":53 + * address_to_msg_name[msg.address] = name * - * self.address_to_msg_name[msg.address] = name * self.vl[msg.address] = {} # <<<<<<<<<<<<<< * self.vl[name] = self.vl[msg.address] * self.vl_all[msg.address] = {} */ - __pyx_t_2 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 60, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - if (unlikely(__pyx_cur_scope->__pyx_v_self->vl == Py_None)) { + __pyx_t_3 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 53, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (unlikely(__pyx_v_self->vl == Py_None)) { PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); - __PYX_ERR(0, 60, __pyx_L1_error) + __PYX_ERR(0, 53, __pyx_L1_error) } - __pyx_t_4 = __Pyx_PyInt_From_uint32_t(__pyx_v_msg.address); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 60, __pyx_L1_error) + __pyx_t_4 = __Pyx_PyInt_From_uint32_t(__pyx_v_msg.address); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 53, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); - if (unlikely((PyDict_SetItem(__pyx_cur_scope->__pyx_v_self->vl, __pyx_t_4, __pyx_t_2) < 0))) __PYX_ERR(0, 60, __pyx_L1_error) + if (unlikely((PyDict_SetItem(__pyx_v_self->vl, __pyx_t_4, __pyx_t_3) < 0))) __PYX_ERR(0, 53, __pyx_L1_error) __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - /* "opendbc/can/parser_pyx.pyx":61 - * self.address_to_msg_name[msg.address] = name + /* "opendbc/can/parser_pyx.pyx":54 + * * self.vl[msg.address] = {} * self.vl[name] = self.vl[msg.address] # <<<<<<<<<<<<<< * self.vl_all[msg.address] = {} * self.vl_all[name] = self.vl_all[msg.address] */ - if (unlikely(__pyx_cur_scope->__pyx_v_self->vl == Py_None)) { + if (unlikely(__pyx_v_self->vl == Py_None)) { PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); - __PYX_ERR(0, 61, __pyx_L1_error) + __PYX_ERR(0, 54, __pyx_L1_error) } - __pyx_t_2 = __Pyx_PyInt_From_uint32_t(__pyx_v_msg.address); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 61, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __pyx_t_4 = __Pyx_PyDict_GetItem(__pyx_cur_scope->__pyx_v_self->vl, __pyx_t_2); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 61, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyInt_From_uint32_t(__pyx_v_msg.address); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 54, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = __Pyx_PyDict_GetItem(__pyx_v_self->vl, __pyx_t_3); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 54, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - if (unlikely(__pyx_cur_scope->__pyx_v_self->vl == Py_None)) { + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(__pyx_v_self->vl == Py_None)) { PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); - __PYX_ERR(0, 61, __pyx_L1_error) + __PYX_ERR(0, 54, __pyx_L1_error) } - if (unlikely((PyDict_SetItem(__pyx_cur_scope->__pyx_v_self->vl, __pyx_v_name, __pyx_t_4) < 0))) __PYX_ERR(0, 61, __pyx_L1_error) + if (unlikely((PyDict_SetItem(__pyx_v_self->vl, __pyx_v_name, __pyx_t_4) < 0))) __PYX_ERR(0, 54, __pyx_L1_error) __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - /* "opendbc/can/parser_pyx.pyx":62 + /* "opendbc/can/parser_pyx.pyx":55 * self.vl[msg.address] = {} * self.vl[name] = self.vl[msg.address] * self.vl_all[msg.address] = {} # <<<<<<<<<<<<<< * self.vl_all[name] = self.vl_all[msg.address] * self.ts_nanos[msg.address] = {} */ - __pyx_t_4 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 62, __pyx_L1_error) + __pyx_t_4 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 55, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); - if (unlikely(__pyx_cur_scope->__pyx_v_self->vl_all == Py_None)) { + if (unlikely(__pyx_v_self->vl_all == Py_None)) { PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); - __PYX_ERR(0, 62, __pyx_L1_error) + __PYX_ERR(0, 55, __pyx_L1_error) } - __pyx_t_2 = __Pyx_PyInt_From_uint32_t(__pyx_v_msg.address); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 62, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - if (unlikely((PyDict_SetItem(__pyx_cur_scope->__pyx_v_self->vl_all, __pyx_t_2, __pyx_t_4) < 0))) __PYX_ERR(0, 62, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_3 = __Pyx_PyInt_From_uint32_t(__pyx_v_msg.address); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 55, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (unlikely((PyDict_SetItem(__pyx_v_self->vl_all, __pyx_t_3, __pyx_t_4) < 0))) __PYX_ERR(0, 55, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - /* "opendbc/can/parser_pyx.pyx":63 + /* "opendbc/can/parser_pyx.pyx":56 * self.vl[name] = self.vl[msg.address] * self.vl_all[msg.address] = {} * self.vl_all[name] = self.vl_all[msg.address] # <<<<<<<<<<<<<< * self.ts_nanos[msg.address] = {} * self.ts_nanos[name] = self.ts_nanos[msg.address] */ - if (unlikely(__pyx_cur_scope->__pyx_v_self->vl_all == Py_None)) { + if (unlikely(__pyx_v_self->vl_all == Py_None)) { PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); - __PYX_ERR(0, 63, __pyx_L1_error) + __PYX_ERR(0, 56, __pyx_L1_error) } - __pyx_t_4 = __Pyx_PyInt_From_uint32_t(__pyx_v_msg.address); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 63, __pyx_L1_error) + __pyx_t_4 = __Pyx_PyInt_From_uint32_t(__pyx_v_msg.address); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 56, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); - __pyx_t_2 = __Pyx_PyDict_GetItem(__pyx_cur_scope->__pyx_v_self->vl_all, __pyx_t_4); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 63, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __Pyx_PyDict_GetItem(__pyx_v_self->vl_all, __pyx_t_4); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 56, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - if (unlikely(__pyx_cur_scope->__pyx_v_self->vl_all == Py_None)) { + if (unlikely(__pyx_v_self->vl_all == Py_None)) { PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); - __PYX_ERR(0, 63, __pyx_L1_error) + __PYX_ERR(0, 56, __pyx_L1_error) } - if (unlikely((PyDict_SetItem(__pyx_cur_scope->__pyx_v_self->vl_all, __pyx_v_name, __pyx_t_2) < 0))) __PYX_ERR(0, 63, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + if (unlikely((PyDict_SetItem(__pyx_v_self->vl_all, __pyx_v_name, __pyx_t_3) < 0))) __PYX_ERR(0, 56, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - /* "opendbc/can/parser_pyx.pyx":64 + /* "opendbc/can/parser_pyx.pyx":57 * self.vl_all[msg.address] = {} * self.vl_all[name] = self.vl_all[msg.address] * self.ts_nanos[msg.address] = {} # <<<<<<<<<<<<<< * self.ts_nanos[name] = self.ts_nanos[msg.address] * */ - __pyx_t_2 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 64, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - if (unlikely(__pyx_cur_scope->__pyx_v_self->ts_nanos == Py_None)) { + __pyx_t_3 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 57, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (unlikely(__pyx_v_self->ts_nanos == Py_None)) { PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); - __PYX_ERR(0, 64, __pyx_L1_error) + __PYX_ERR(0, 57, __pyx_L1_error) } - __pyx_t_4 = __Pyx_PyInt_From_uint32_t(__pyx_v_msg.address); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 64, __pyx_L1_error) + __pyx_t_4 = __Pyx_PyInt_From_uint32_t(__pyx_v_msg.address); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 57, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); - if (unlikely((PyDict_SetItem(__pyx_cur_scope->__pyx_v_self->ts_nanos, __pyx_t_4, __pyx_t_2) < 0))) __PYX_ERR(0, 64, __pyx_L1_error) + if (unlikely((PyDict_SetItem(__pyx_v_self->ts_nanos, __pyx_t_4, __pyx_t_3) < 0))) __PYX_ERR(0, 57, __pyx_L1_error) __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - /* "opendbc/can/parser_pyx.pyx":65 + /* "opendbc/can/parser_pyx.pyx":58 * self.vl_all[name] = self.vl_all[msg.address] * self.ts_nanos[msg.address] = {} * self.ts_nanos[name] = self.ts_nanos[msg.address] # <<<<<<<<<<<<<< * - * # Convert message names into addresses + * # Convert message names into addresses and check existence in DBC */ - if (unlikely(__pyx_cur_scope->__pyx_v_self->ts_nanos == Py_None)) { + if (unlikely(__pyx_v_self->ts_nanos == Py_None)) { PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); - __PYX_ERR(0, 65, __pyx_L1_error) + __PYX_ERR(0, 58, __pyx_L1_error) } - __pyx_t_2 = __Pyx_PyInt_From_uint32_t(__pyx_v_msg.address); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 65, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __pyx_t_4 = __Pyx_PyDict_GetItem(__pyx_cur_scope->__pyx_v_self->ts_nanos, __pyx_t_2); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 65, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyInt_From_uint32_t(__pyx_v_msg.address); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 58, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = __Pyx_PyDict_GetItem(__pyx_v_self->ts_nanos, __pyx_t_3); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 58, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - if (unlikely(__pyx_cur_scope->__pyx_v_self->ts_nanos == Py_None)) { + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(__pyx_v_self->ts_nanos == Py_None)) { PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); - __PYX_ERR(0, 65, __pyx_L1_error) + __PYX_ERR(0, 58, __pyx_L1_error) } - if (unlikely((PyDict_SetItem(__pyx_cur_scope->__pyx_v_self->ts_nanos, __pyx_v_name, __pyx_t_4) < 0))) __PYX_ERR(0, 65, __pyx_L1_error) + if (unlikely((PyDict_SetItem(__pyx_v_self->ts_nanos, __pyx_v_name, __pyx_t_4) < 0))) __PYX_ERR(0, 58, __pyx_L1_error) __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; } - /* "opendbc/can/parser_pyx.pyx":68 - * - * # Convert message names into addresses - * for i in range(len(signals)): # <<<<<<<<<<<<<< - * s = signals[i] - * address = s[1] if isinstance(s[1], numbers.Number) else msg_name_to_address.get(s[1]) + /* "opendbc/can/parser_pyx.pyx":62 + * # Convert message names into addresses and check existence in DBC + * cdef vector[pair[uint32_t, int]] message_v + * for i in range(len(messages)): # <<<<<<<<<<<<<< + * c = messages[i] + * address = c[0] if isinstance(c[0], numbers.Number) else msg_name_to_address.get(c[0]) */ - __pyx_t_13 = PyObject_Length(__pyx_v_signals); if (unlikely(__pyx_t_13 == ((Py_ssize_t)-1))) __PYX_ERR(0, 68, __pyx_L1_error) - __pyx_t_14 = __pyx_t_13; - for (__pyx_t_5 = 0; __pyx_t_5 < __pyx_t_14; __pyx_t_5+=1) { + __pyx_t_8 = PyObject_Length(__pyx_v_messages); if (unlikely(__pyx_t_8 == ((Py_ssize_t)-1))) __PYX_ERR(0, 62, __pyx_L1_error) + __pyx_t_9 = __pyx_t_8; + for (__pyx_t_5 = 0; __pyx_t_5 < __pyx_t_9; __pyx_t_5+=1) { __pyx_v_i = __pyx_t_5; - /* "opendbc/can/parser_pyx.pyx":69 - * # Convert message names into addresses - * for i in range(len(signals)): - * s = signals[i] # <<<<<<<<<<<<<< - * address = s[1] if isinstance(s[1], numbers.Number) else msg_name_to_address.get(s[1]) - * if address not in msg_address_to_signals: + /* "opendbc/can/parser_pyx.pyx":63 + * cdef vector[pair[uint32_t, int]] message_v + * for i in range(len(messages)): + * c = messages[i] # <<<<<<<<<<<<<< + * address = c[0] if isinstance(c[0], numbers.Number) else msg_name_to_address.get(c[0]) + * if address not in address_to_msg_name: */ - __pyx_t_4 = __Pyx_GetItemInt(__pyx_v_signals, __pyx_v_i, std::vector ::size_type, 0, __Pyx_PyInt_FromSize_t, 0, 0, 1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 69, __pyx_L1_error) + __pyx_t_4 = __Pyx_GetItemInt(__pyx_v_messages, __pyx_v_i, std::vector ::size_type, 0, __Pyx_PyInt_FromSize_t, 0, 0, 1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 63, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); - __Pyx_XDECREF_SET(__pyx_v_s, __pyx_t_4); + __Pyx_XDECREF_SET(__pyx_v_c, __pyx_t_4); __pyx_t_4 = 0; - /* "opendbc/can/parser_pyx.pyx":70 - * for i in range(len(signals)): - * s = signals[i] - * address = s[1] if isinstance(s[1], numbers.Number) else msg_name_to_address.get(s[1]) # <<<<<<<<<<<<<< - * if address not in msg_address_to_signals: - * raise RuntimeError(f"could not find message {repr(s[1])} in DBC {self.dbc_name}") + /* "opendbc/can/parser_pyx.pyx":64 + * for i in range(len(messages)): + * c = messages[i] + * address = c[0] if isinstance(c[0], numbers.Number) else msg_name_to_address.get(c[0]) # <<<<<<<<<<<<<< + * if address not in address_to_msg_name: + * raise RuntimeError(f"could not find message {repr(c[0])} in DBC {self.dbc_name}") */ - __pyx_t_2 = __Pyx_GetItemInt(__pyx_v_s, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 70, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __Pyx_GetModuleGlobalName(__pyx_t_10, __pyx_n_s_numbers); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 70, __pyx_L1_error) + __pyx_t_3 = __Pyx_GetItemInt(__pyx_v_c, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 64, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GetModuleGlobalName(__pyx_t_10, __pyx_n_s_numbers); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 64, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_10); - __pyx_t_11 = __Pyx_PyObject_GetAttrStr(__pyx_t_10, __pyx_n_s_Number); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 70, __pyx_L1_error) + __pyx_t_11 = __Pyx_PyObject_GetAttrStr(__pyx_t_10, __pyx_n_s_Number); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 64, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_11); __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; - __pyx_t_1 = PyObject_IsInstance(__pyx_t_2, __pyx_t_11); if (unlikely(__pyx_t_1 == ((int)-1))) __PYX_ERR(0, 70, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = PyObject_IsInstance(__pyx_t_3, __pyx_t_11); if (unlikely(__pyx_t_2 == ((int)-1))) __PYX_ERR(0, 64, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; __Pyx_DECREF(__pyx_t_11); __pyx_t_11 = 0; - if (__pyx_t_1) { - __pyx_t_11 = __Pyx_GetItemInt(__pyx_v_s, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 70, __pyx_L1_error) + if (__pyx_t_2) { + __pyx_t_11 = __Pyx_GetItemInt(__pyx_v_c, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 64, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_11); __pyx_t_4 = __pyx_t_11; __pyx_t_11 = 0; } else { - __pyx_t_11 = __Pyx_GetItemInt(__pyx_v_s, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 70, __pyx_L1_error) + __pyx_t_11 = __Pyx_GetItemInt(__pyx_v_c, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 64, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_11); - __pyx_t_2 = __Pyx_PyDict_GetItemDefault(__pyx_v_msg_name_to_address, __pyx_t_11, Py_None); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 70, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __Pyx_PyDict_GetItemDefault(__pyx_v_msg_name_to_address, __pyx_t_11, Py_None); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 64, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); __Pyx_DECREF(__pyx_t_11); __pyx_t_11 = 0; - __pyx_t_4 = __pyx_t_2; - __pyx_t_2 = 0; + __pyx_t_4 = __pyx_t_3; + __pyx_t_3 = 0; } __Pyx_XDECREF_SET(__pyx_v_address, __pyx_t_4); __pyx_t_4 = 0; - /* "opendbc/can/parser_pyx.pyx":71 - * s = signals[i] - * address = s[1] if isinstance(s[1], numbers.Number) else msg_name_to_address.get(s[1]) - * if address not in msg_address_to_signals: # <<<<<<<<<<<<<< - * raise RuntimeError(f"could not find message {repr(s[1])} in DBC {self.dbc_name}") - * if s[0] not in msg_address_to_signals[address]: + /* "opendbc/can/parser_pyx.pyx":65 + * c = messages[i] + * address = c[0] if isinstance(c[0], numbers.Number) else msg_name_to_address.get(c[0]) + * if address not in address_to_msg_name: # <<<<<<<<<<<<<< + * raise RuntimeError(f"could not find message {repr(c[0])} in DBC {self.dbc_name}") + * message_v.push_back((address, c[1])) */ - __pyx_t_1 = (__Pyx_PyDict_ContainsTF(__pyx_v_address, __pyx_v_msg_address_to_signals, Py_NE)); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(0, 71, __pyx_L1_error) - if (unlikely(__pyx_t_1)) { + __pyx_t_2 = (__Pyx_PyDict_ContainsTF(__pyx_v_address, __pyx_v_address_to_msg_name, Py_NE)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 65, __pyx_L1_error) + if (unlikely(__pyx_t_2)) { - /* "opendbc/can/parser_pyx.pyx":72 - * address = s[1] if isinstance(s[1], numbers.Number) else msg_name_to_address.get(s[1]) - * if address not in msg_address_to_signals: - * raise RuntimeError(f"could not find message {repr(s[1])} in DBC {self.dbc_name}") # <<<<<<<<<<<<<< - * if s[0] not in msg_address_to_signals[address]: - * raise RuntimeError(f"could not find signal {repr(s[0])} in {repr(s[1])}, DBC {self.dbc_name}") + /* "opendbc/can/parser_pyx.pyx":66 + * address = c[0] if isinstance(c[0], numbers.Number) else msg_name_to_address.get(c[0]) + * if address not in address_to_msg_name: + * raise RuntimeError(f"could not find message {repr(c[0])} in DBC {self.dbc_name}") # <<<<<<<<<<<<<< + * message_v.push_back((address, c[1])) + * */ - __pyx_t_4 = PyTuple_New(4); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 72, __pyx_L1_error) + __pyx_t_4 = PyTuple_New(4); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 66, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); - __pyx_t_15 = 0; - __pyx_t_16 = 127; + __pyx_t_12 = 0; + __pyx_t_13 = 127; __Pyx_INCREF(__pyx_kp_u_could_not_find_message); - __pyx_t_15 += 23; + __pyx_t_12 += 23; __Pyx_GIVEREF(__pyx_kp_u_could_not_find_message); PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_kp_u_could_not_find_message); - __pyx_t_2 = __Pyx_GetItemInt(__pyx_v_s, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 72, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __pyx_t_11 = PyObject_Repr(__pyx_t_2); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 72, __pyx_L1_error) + __pyx_t_3 = __Pyx_GetItemInt(__pyx_v_c, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 66, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_11 = PyObject_Repr(__pyx_t_3); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 66, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_11); - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - __pyx_t_2 = __Pyx_PyObject_FormatSimple(__pyx_t_11, __pyx_empty_unicode); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 72, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PyObject_FormatSimple(__pyx_t_11, __pyx_empty_unicode); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 66, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); __Pyx_DECREF(__pyx_t_11); __pyx_t_11 = 0; - __pyx_t_16 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) > __pyx_t_16) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) : __pyx_t_16; - __pyx_t_15 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_2); - __Pyx_GIVEREF(__pyx_t_2); - PyTuple_SET_ITEM(__pyx_t_4, 1, __pyx_t_2); - __pyx_t_2 = 0; + __pyx_t_13 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_3) > __pyx_t_13) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_3) : __pyx_t_13; + __pyx_t_12 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_3); + PyTuple_SET_ITEM(__pyx_t_4, 1, __pyx_t_3); + __pyx_t_3 = 0; __Pyx_INCREF(__pyx_kp_u_in_DBC); - __pyx_t_15 += 8; + __pyx_t_12 += 8; __Pyx_GIVEREF(__pyx_kp_u_in_DBC); PyTuple_SET_ITEM(__pyx_t_4, 2, __pyx_kp_u_in_DBC); - __pyx_t_2 = __pyx_convert_PyBytes_string_to_py_std__in_string(__pyx_cur_scope->__pyx_v_self->dbc_name); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 72, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __pyx_t_11 = __Pyx_PyObject_FormatSimple(__pyx_t_2, __pyx_empty_unicode); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 72, __pyx_L1_error) + __pyx_t_3 = __pyx_convert_PyBytes_string_to_py_std__in_string(__pyx_v_self->dbc_name); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 66, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_11 = __Pyx_PyObject_FormatSimple(__pyx_t_3, __pyx_empty_unicode); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 66, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_11); - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - __pyx_t_16 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_11) > __pyx_t_16) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_11) : __pyx_t_16; - __pyx_t_15 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_11); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_13 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_11) > __pyx_t_13) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_11) : __pyx_t_13; + __pyx_t_12 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_11); __Pyx_GIVEREF(__pyx_t_11); PyTuple_SET_ITEM(__pyx_t_4, 3, __pyx_t_11); __pyx_t_11 = 0; - __pyx_t_11 = __Pyx_PyUnicode_Join(__pyx_t_4, 4, __pyx_t_15, __pyx_t_16); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 72, __pyx_L1_error) + __pyx_t_11 = __Pyx_PyUnicode_Join(__pyx_t_4, 4, __pyx_t_12, __pyx_t_13); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 66, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_11); __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __pyx_t_4 = __Pyx_PyObject_CallOneArg(__pyx_builtin_RuntimeError, __pyx_t_11); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 72, __pyx_L1_error) + __pyx_t_4 = __Pyx_PyObject_CallOneArg(__pyx_builtin_RuntimeError, __pyx_t_11); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 66, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); __Pyx_DECREF(__pyx_t_11); __pyx_t_11 = 0; __Pyx_Raise(__pyx_t_4, 0, 0, 0); __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __PYX_ERR(0, 72, __pyx_L1_error) + __PYX_ERR(0, 66, __pyx_L1_error) - /* "opendbc/can/parser_pyx.pyx":71 - * s = signals[i] - * address = s[1] if isinstance(s[1], numbers.Number) else msg_name_to_address.get(s[1]) - * if address not in msg_address_to_signals: # <<<<<<<<<<<<<< - * raise RuntimeError(f"could not find message {repr(s[1])} in DBC {self.dbc_name}") - * if s[0] not in msg_address_to_signals[address]: + /* "opendbc/can/parser_pyx.pyx":65 + * c = messages[i] + * address = c[0] if isinstance(c[0], numbers.Number) else msg_name_to_address.get(c[0]) + * if address not in address_to_msg_name: # <<<<<<<<<<<<<< + * raise RuntimeError(f"could not find message {repr(c[0])} in DBC {self.dbc_name}") + * message_v.push_back((address, c[1])) */ } - /* "opendbc/can/parser_pyx.pyx":73 - * if address not in msg_address_to_signals: - * raise RuntimeError(f"could not find message {repr(s[1])} in DBC {self.dbc_name}") - * if s[0] not in msg_address_to_signals[address]: # <<<<<<<<<<<<<< - * raise RuntimeError(f"could not find signal {repr(s[0])} in {repr(s[1])}, DBC {self.dbc_name}") + /* "opendbc/can/parser_pyx.pyx":67 + * if address not in address_to_msg_name: + * raise RuntimeError(f"could not find message {repr(c[0])} in DBC {self.dbc_name}") + * message_v.push_back((address, c[1])) # <<<<<<<<<<<<<< * + * self.can = new cpp_CANParser(bus, dbc_name, message_v) */ - __pyx_t_4 = __Pyx_GetItemInt(__pyx_v_s, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 73, __pyx_L1_error) + __pyx_t_4 = __Pyx_GetItemInt(__pyx_v_c, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 67, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); - __pyx_t_11 = __Pyx_PyDict_GetItem(__pyx_v_msg_address_to_signals, __pyx_v_address); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 73, __pyx_L1_error) + __pyx_t_11 = PyTuple_New(2); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 67, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_11); - __pyx_t_1 = (__Pyx_PySequence_ContainsTF(__pyx_t_4, __pyx_t_11, Py_NE)); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(0, 73, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __Pyx_DECREF(__pyx_t_11); __pyx_t_11 = 0; - if (unlikely(__pyx_t_1)) { - - /* "opendbc/can/parser_pyx.pyx":74 - * raise RuntimeError(f"could not find message {repr(s[1])} in DBC {self.dbc_name}") - * if s[0] not in msg_address_to_signals[address]: - * raise RuntimeError(f"could not find signal {repr(s[0])} in {repr(s[1])}, DBC {self.dbc_name}") # <<<<<<<<<<<<<< - * - * signals[i] = (s[0], address) - */ - __pyx_t_11 = PyTuple_New(6); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 74, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_11); - __pyx_t_15 = 0; - __pyx_t_16 = 127; - __Pyx_INCREF(__pyx_kp_u_could_not_find_signal); - __pyx_t_15 += 22; - __Pyx_GIVEREF(__pyx_kp_u_could_not_find_signal); - PyTuple_SET_ITEM(__pyx_t_11, 0, __pyx_kp_u_could_not_find_signal); - __pyx_t_4 = __Pyx_GetItemInt(__pyx_v_s, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 74, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __pyx_t_2 = PyObject_Repr(__pyx_t_4); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 74, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __pyx_t_4 = __Pyx_PyObject_FormatSimple(__pyx_t_2, __pyx_empty_unicode); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 74, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - __pyx_t_16 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_4) > __pyx_t_16) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_4) : __pyx_t_16; - __pyx_t_15 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); - __Pyx_GIVEREF(__pyx_t_4); - PyTuple_SET_ITEM(__pyx_t_11, 1, __pyx_t_4); - __pyx_t_4 = 0; - __Pyx_INCREF(__pyx_kp_u_in); - __pyx_t_15 += 4; - __Pyx_GIVEREF(__pyx_kp_u_in); - PyTuple_SET_ITEM(__pyx_t_11, 2, __pyx_kp_u_in); - __pyx_t_4 = __Pyx_GetItemInt(__pyx_v_s, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 74, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __pyx_t_2 = PyObject_Repr(__pyx_t_4); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 74, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __pyx_t_4 = __Pyx_PyObject_FormatSimple(__pyx_t_2, __pyx_empty_unicode); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 74, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - __pyx_t_16 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_4) > __pyx_t_16) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_4) : __pyx_t_16; - __pyx_t_15 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); - __Pyx_GIVEREF(__pyx_t_4); - PyTuple_SET_ITEM(__pyx_t_11, 3, __pyx_t_4); - __pyx_t_4 = 0; - __Pyx_INCREF(__pyx_kp_u_DBC); - __pyx_t_15 += 6; - __Pyx_GIVEREF(__pyx_kp_u_DBC); - PyTuple_SET_ITEM(__pyx_t_11, 4, __pyx_kp_u_DBC); - __pyx_t_4 = __pyx_convert_PyBytes_string_to_py_std__in_string(__pyx_cur_scope->__pyx_v_self->dbc_name); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 74, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __pyx_t_2 = __Pyx_PyObject_FormatSimple(__pyx_t_4, __pyx_empty_unicode); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 74, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __pyx_t_16 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) > __pyx_t_16) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) : __pyx_t_16; - __pyx_t_15 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_2); - __Pyx_GIVEREF(__pyx_t_2); - PyTuple_SET_ITEM(__pyx_t_11, 5, __pyx_t_2); - __pyx_t_2 = 0; - __pyx_t_2 = __Pyx_PyUnicode_Join(__pyx_t_11, 6, __pyx_t_15, __pyx_t_16); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 74, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __Pyx_DECREF(__pyx_t_11); __pyx_t_11 = 0; - __pyx_t_11 = __Pyx_PyObject_CallOneArg(__pyx_builtin_RuntimeError, __pyx_t_2); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 74, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_11); - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - __Pyx_Raise(__pyx_t_11, 0, 0, 0); - __Pyx_DECREF(__pyx_t_11); __pyx_t_11 = 0; - __PYX_ERR(0, 74, __pyx_L1_error) - - /* "opendbc/can/parser_pyx.pyx":73 - * if address not in msg_address_to_signals: - * raise RuntimeError(f"could not find message {repr(s[1])} in DBC {self.dbc_name}") - * if s[0] not in msg_address_to_signals[address]: # <<<<<<<<<<<<<< - * raise RuntimeError(f"could not find signal {repr(s[0])} in {repr(s[1])}, DBC {self.dbc_name}") - * - */ - } - - /* "opendbc/can/parser_pyx.pyx":76 - * raise RuntimeError(f"could not find signal {repr(s[0])} in {repr(s[1])}, DBC {self.dbc_name}") - * - * signals[i] = (s[0], address) # <<<<<<<<<<<<<< - * - * for i in range(len(checks)): - */ - __pyx_t_11 = __Pyx_GetItemInt(__pyx_v_s, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 76, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_11); - __pyx_t_2 = PyTuple_New(2); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 76, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __Pyx_GIVEREF(__pyx_t_11); - PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_t_11); __Pyx_INCREF(__pyx_v_address); __Pyx_GIVEREF(__pyx_v_address); - PyTuple_SET_ITEM(__pyx_t_2, 1, __pyx_v_address); - __pyx_t_11 = 0; - if (unlikely((__Pyx_SetItemInt(__pyx_v_signals, __pyx_v_i, __pyx_t_2, std::vector ::size_type, 0, __Pyx_PyInt_FromSize_t, 0, 0, 1) < 0))) __PYX_ERR(0, 76, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - } - - /* "opendbc/can/parser_pyx.pyx":78 - * signals[i] = (s[0], address) - * - * for i in range(len(checks)): # <<<<<<<<<<<<<< - * c = checks[i] - * if not isinstance(c[0], numbers.Number): - */ - __pyx_t_13 = PyObject_Length(__pyx_v_checks); if (unlikely(__pyx_t_13 == ((Py_ssize_t)-1))) __PYX_ERR(0, 78, __pyx_L1_error) - __pyx_t_14 = __pyx_t_13; - for (__pyx_t_5 = 0; __pyx_t_5 < __pyx_t_14; __pyx_t_5+=1) { - __pyx_v_i = __pyx_t_5; - - /* "opendbc/can/parser_pyx.pyx":79 - * - * for i in range(len(checks)): - * c = checks[i] # <<<<<<<<<<<<<< - * if not isinstance(c[0], numbers.Number): - * if c[0] not in msg_name_to_address: - */ - __pyx_t_2 = __Pyx_GetItemInt(__pyx_v_checks, __pyx_v_i, std::vector ::size_type, 0, __Pyx_PyInt_FromSize_t, 0, 0, 1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 79, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __Pyx_XDECREF_SET(__pyx_v_c, __pyx_t_2); - __pyx_t_2 = 0; - - /* "opendbc/can/parser_pyx.pyx":80 - * for i in range(len(checks)): - * c = checks[i] - * if not isinstance(c[0], numbers.Number): # <<<<<<<<<<<<<< - * if c[0] not in msg_name_to_address: - * print(msg_name_to_address) - */ - __pyx_t_2 = __Pyx_GetItemInt(__pyx_v_c, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 80, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __Pyx_GetModuleGlobalName(__pyx_t_11, __pyx_n_s_numbers); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 80, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_11); - __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_11, __pyx_n_s_Number); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 80, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __Pyx_DECREF(__pyx_t_11); __pyx_t_11 = 0; - __pyx_t_1 = PyObject_IsInstance(__pyx_t_2, __pyx_t_4); if (unlikely(__pyx_t_1 == ((int)-1))) __PYX_ERR(0, 80, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __pyx_t_17 = (!__pyx_t_1); - if (__pyx_t_17) { - - /* "opendbc/can/parser_pyx.pyx":81 - * c = checks[i] - * if not isinstance(c[0], numbers.Number): - * if c[0] not in msg_name_to_address: # <<<<<<<<<<<<<< - * print(msg_name_to_address) - * raise RuntimeError(f"could not find message {repr(c[0])} in DBC {self.dbc_name}") - */ - __pyx_t_4 = __Pyx_GetItemInt(__pyx_v_c, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 81, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __pyx_t_17 = (__Pyx_PyDict_ContainsTF(__pyx_t_4, __pyx_v_msg_name_to_address, Py_NE)); if (unlikely((__pyx_t_17 < 0))) __PYX_ERR(0, 81, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - if (unlikely(__pyx_t_17)) { - - /* "opendbc/can/parser_pyx.pyx":82 - * if not isinstance(c[0], numbers.Number): - * if c[0] not in msg_name_to_address: - * print(msg_name_to_address) # <<<<<<<<<<<<<< - * raise RuntimeError(f"could not find message {repr(c[0])} in DBC {self.dbc_name}") - * c = (msg_name_to_address[c[0]], c[1]) - */ - __pyx_t_4 = __Pyx_PyObject_CallOneArg(__pyx_builtin_print, __pyx_v_msg_name_to_address); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 82, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - - /* "opendbc/can/parser_pyx.pyx":83 - * if c[0] not in msg_name_to_address: - * print(msg_name_to_address) - * raise RuntimeError(f"could not find message {repr(c[0])} in DBC {self.dbc_name}") # <<<<<<<<<<<<<< - * c = (msg_name_to_address[c[0]], c[1]) - * checks[i] = c - */ - __pyx_t_4 = PyTuple_New(4); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 83, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __pyx_t_15 = 0; - __pyx_t_16 = 127; - __Pyx_INCREF(__pyx_kp_u_could_not_find_message); - __pyx_t_15 += 23; - __Pyx_GIVEREF(__pyx_kp_u_could_not_find_message); - PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_kp_u_could_not_find_message); - __pyx_t_2 = __Pyx_GetItemInt(__pyx_v_c, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 83, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __pyx_t_11 = PyObject_Repr(__pyx_t_2); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 83, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_11); - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - __pyx_t_2 = __Pyx_PyObject_FormatSimple(__pyx_t_11, __pyx_empty_unicode); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 83, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __Pyx_DECREF(__pyx_t_11); __pyx_t_11 = 0; - __pyx_t_16 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) > __pyx_t_16) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) : __pyx_t_16; - __pyx_t_15 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_2); - __Pyx_GIVEREF(__pyx_t_2); - PyTuple_SET_ITEM(__pyx_t_4, 1, __pyx_t_2); - __pyx_t_2 = 0; - __Pyx_INCREF(__pyx_kp_u_in_DBC); - __pyx_t_15 += 8; - __Pyx_GIVEREF(__pyx_kp_u_in_DBC); - PyTuple_SET_ITEM(__pyx_t_4, 2, __pyx_kp_u_in_DBC); - __pyx_t_2 = __pyx_convert_PyBytes_string_to_py_std__in_string(__pyx_cur_scope->__pyx_v_self->dbc_name); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 83, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __pyx_t_11 = __Pyx_PyObject_FormatSimple(__pyx_t_2, __pyx_empty_unicode); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 83, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_11); - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - __pyx_t_16 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_11) > __pyx_t_16) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_11) : __pyx_t_16; - __pyx_t_15 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_11); - __Pyx_GIVEREF(__pyx_t_11); - PyTuple_SET_ITEM(__pyx_t_4, 3, __pyx_t_11); - __pyx_t_11 = 0; - __pyx_t_11 = __Pyx_PyUnicode_Join(__pyx_t_4, 4, __pyx_t_15, __pyx_t_16); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 83, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_11); - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __pyx_t_4 = __Pyx_PyObject_CallOneArg(__pyx_builtin_RuntimeError, __pyx_t_11); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 83, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __Pyx_DECREF(__pyx_t_11); __pyx_t_11 = 0; - __Pyx_Raise(__pyx_t_4, 0, 0, 0); - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __PYX_ERR(0, 83, __pyx_L1_error) - - /* "opendbc/can/parser_pyx.pyx":81 - * c = checks[i] - * if not isinstance(c[0], numbers.Number): - * if c[0] not in msg_name_to_address: # <<<<<<<<<<<<<< - * print(msg_name_to_address) - * raise RuntimeError(f"could not find message {repr(c[0])} in DBC {self.dbc_name}") - */ - } - - /* "opendbc/can/parser_pyx.pyx":84 - * print(msg_name_to_address) - * raise RuntimeError(f"could not find message {repr(c[0])} in DBC {self.dbc_name}") - * c = (msg_name_to_address[c[0]], c[1]) # <<<<<<<<<<<<<< - * checks[i] = c - * - */ - __pyx_t_4 = __Pyx_GetItemInt(__pyx_v_c, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 84, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __pyx_t_11 = __Pyx_PyDict_GetItem(__pyx_v_msg_name_to_address, __pyx_t_4); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 84, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_11); - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __pyx_t_4 = __Pyx_GetItemInt(__pyx_v_c, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 84, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __pyx_t_2 = PyTuple_New(2); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 84, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __Pyx_GIVEREF(__pyx_t_11); - PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_t_11); - __Pyx_GIVEREF(__pyx_t_4); - PyTuple_SET_ITEM(__pyx_t_2, 1, __pyx_t_4); - __pyx_t_11 = 0; - __pyx_t_4 = 0; - __Pyx_DECREF_SET(__pyx_v_c, __pyx_t_2); - __pyx_t_2 = 0; - - /* "opendbc/can/parser_pyx.pyx":85 - * raise RuntimeError(f"could not find message {repr(c[0])} in DBC {self.dbc_name}") - * c = (msg_name_to_address[c[0]], c[1]) - * checks[i] = c # <<<<<<<<<<<<<< - * - * if enforce_checks: - */ - if (unlikely((__Pyx_SetItemInt(__pyx_v_checks, __pyx_v_i, __pyx_v_c, std::vector ::size_type, 0, __Pyx_PyInt_FromSize_t, 0, 0, 1) < 0))) __PYX_ERR(0, 85, __pyx_L1_error) - - /* "opendbc/can/parser_pyx.pyx":80 - * for i in range(len(checks)): - * c = checks[i] - * if not isinstance(c[0], numbers.Number): # <<<<<<<<<<<<<< - * if c[0] not in msg_name_to_address: - * print(msg_name_to_address) - */ - } - } - - /* "opendbc/can/parser_pyx.pyx":87 - * checks[i] = c - * - * if enforce_checks: # <<<<<<<<<<<<<< - * checked_addrs = {c[0] for c in checks} - * signal_addrs = {s[1] for s in signals} - */ - __pyx_t_17 = __Pyx_PyObject_IsTrue(__pyx_v_enforce_checks); if (unlikely((__pyx_t_17 < 0))) __PYX_ERR(0, 87, __pyx_L1_error) - if (__pyx_t_17) { - - /* "opendbc/can/parser_pyx.pyx":88 - * - * if enforce_checks: - * checked_addrs = {c[0] for c in checks} # <<<<<<<<<<<<<< - * signal_addrs = {s[1] for s in signals} - * unchecked = signal_addrs - checked_addrs - */ - { /* enter inner scope */ - __pyx_t_2 = PySet_New(NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 88, __pyx_L21_error) - __Pyx_GOTREF(__pyx_t_2); - if (likely(PyList_CheckExact(__pyx_v_checks)) || PyTuple_CheckExact(__pyx_v_checks)) { - __pyx_t_4 = __pyx_v_checks; __Pyx_INCREF(__pyx_t_4); __pyx_t_13 = 0; - __pyx_t_18 = NULL; - } else { - __pyx_t_13 = -1; __pyx_t_4 = PyObject_GetIter(__pyx_v_checks); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 88, __pyx_L21_error) - __Pyx_GOTREF(__pyx_t_4); - __pyx_t_18 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_4); if (unlikely(!__pyx_t_18)) __PYX_ERR(0, 88, __pyx_L21_error) - } - for (;;) { - if (likely(!__pyx_t_18)) { - if (likely(PyList_CheckExact(__pyx_t_4))) { - if (__pyx_t_13 >= PyList_GET_SIZE(__pyx_t_4)) break; - #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - __pyx_t_11 = PyList_GET_ITEM(__pyx_t_4, __pyx_t_13); __Pyx_INCREF(__pyx_t_11); __pyx_t_13++; if (unlikely((0 < 0))) __PYX_ERR(0, 88, __pyx_L21_error) - #else - __pyx_t_11 = PySequence_ITEM(__pyx_t_4, __pyx_t_13); __pyx_t_13++; if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 88, __pyx_L21_error) - __Pyx_GOTREF(__pyx_t_11); - #endif - } else { - if (__pyx_t_13 >= PyTuple_GET_SIZE(__pyx_t_4)) break; - #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - __pyx_t_11 = PyTuple_GET_ITEM(__pyx_t_4, __pyx_t_13); __Pyx_INCREF(__pyx_t_11); __pyx_t_13++; if (unlikely((0 < 0))) __PYX_ERR(0, 88, __pyx_L21_error) - #else - __pyx_t_11 = PySequence_ITEM(__pyx_t_4, __pyx_t_13); __pyx_t_13++; if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 88, __pyx_L21_error) - __Pyx_GOTREF(__pyx_t_11); - #endif - } - } else { - __pyx_t_11 = __pyx_t_18(__pyx_t_4); - if (unlikely(!__pyx_t_11)) { - PyObject* exc_type = PyErr_Occurred(); - if (exc_type) { - if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); - else __PYX_ERR(0, 88, __pyx_L21_error) - } - break; - } - __Pyx_GOTREF(__pyx_t_11); - } - __Pyx_XDECREF_SET(__pyx_7genexpr__pyx_v_c, __pyx_t_11); - __pyx_t_11 = 0; - __pyx_t_11 = __Pyx_GetItemInt(__pyx_7genexpr__pyx_v_c, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 88, __pyx_L21_error) - __Pyx_GOTREF(__pyx_t_11); - if (unlikely(PySet_Add(__pyx_t_2, (PyObject*)__pyx_t_11))) __PYX_ERR(0, 88, __pyx_L21_error) - __Pyx_DECREF(__pyx_t_11); __pyx_t_11 = 0; - } - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __Pyx_XDECREF(__pyx_7genexpr__pyx_v_c); __pyx_7genexpr__pyx_v_c = 0; - goto __pyx_L25_exit_scope; - __pyx_L21_error:; - __Pyx_XDECREF(__pyx_7genexpr__pyx_v_c); __pyx_7genexpr__pyx_v_c = 0; - goto __pyx_L1_error; - __pyx_L25_exit_scope:; - } /* exit inner scope */ - __pyx_v_checked_addrs = ((PyObject*)__pyx_t_2); - __pyx_t_2 = 0; - - /* "opendbc/can/parser_pyx.pyx":89 - * if enforce_checks: - * checked_addrs = {c[0] for c in checks} - * signal_addrs = {s[1] for s in signals} # <<<<<<<<<<<<<< - * unchecked = signal_addrs - checked_addrs - * if len(unchecked): - */ - { /* enter inner scope */ - __pyx_t_2 = PySet_New(NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 89, __pyx_L28_error) - __Pyx_GOTREF(__pyx_t_2); - if (likely(PyList_CheckExact(__pyx_v_signals)) || PyTuple_CheckExact(__pyx_v_signals)) { - __pyx_t_4 = __pyx_v_signals; __Pyx_INCREF(__pyx_t_4); __pyx_t_13 = 0; - __pyx_t_18 = NULL; - } else { - __pyx_t_13 = -1; __pyx_t_4 = PyObject_GetIter(__pyx_v_signals); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 89, __pyx_L28_error) - __Pyx_GOTREF(__pyx_t_4); - __pyx_t_18 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_4); if (unlikely(!__pyx_t_18)) __PYX_ERR(0, 89, __pyx_L28_error) - } - for (;;) { - if (likely(!__pyx_t_18)) { - if (likely(PyList_CheckExact(__pyx_t_4))) { - if (__pyx_t_13 >= PyList_GET_SIZE(__pyx_t_4)) break; - #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - __pyx_t_11 = PyList_GET_ITEM(__pyx_t_4, __pyx_t_13); __Pyx_INCREF(__pyx_t_11); __pyx_t_13++; if (unlikely((0 < 0))) __PYX_ERR(0, 89, __pyx_L28_error) - #else - __pyx_t_11 = PySequence_ITEM(__pyx_t_4, __pyx_t_13); __pyx_t_13++; if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 89, __pyx_L28_error) - __Pyx_GOTREF(__pyx_t_11); - #endif - } else { - if (__pyx_t_13 >= PyTuple_GET_SIZE(__pyx_t_4)) break; - #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - __pyx_t_11 = PyTuple_GET_ITEM(__pyx_t_4, __pyx_t_13); __Pyx_INCREF(__pyx_t_11); __pyx_t_13++; if (unlikely((0 < 0))) __PYX_ERR(0, 89, __pyx_L28_error) - #else - __pyx_t_11 = PySequence_ITEM(__pyx_t_4, __pyx_t_13); __pyx_t_13++; if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 89, __pyx_L28_error) - __Pyx_GOTREF(__pyx_t_11); - #endif - } - } else { - __pyx_t_11 = __pyx_t_18(__pyx_t_4); - if (unlikely(!__pyx_t_11)) { - PyObject* exc_type = PyErr_Occurred(); - if (exc_type) { - if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); - else __PYX_ERR(0, 89, __pyx_L28_error) - } - break; - } - __Pyx_GOTREF(__pyx_t_11); - } - __Pyx_XDECREF_SET(__pyx_8genexpr1__pyx_v_s, __pyx_t_11); - __pyx_t_11 = 0; - __pyx_t_11 = __Pyx_GetItemInt(__pyx_8genexpr1__pyx_v_s, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 89, __pyx_L28_error) - __Pyx_GOTREF(__pyx_t_11); - if (unlikely(PySet_Add(__pyx_t_2, (PyObject*)__pyx_t_11))) __PYX_ERR(0, 89, __pyx_L28_error) - __Pyx_DECREF(__pyx_t_11); __pyx_t_11 = 0; - } - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __Pyx_XDECREF(__pyx_8genexpr1__pyx_v_s); __pyx_8genexpr1__pyx_v_s = 0; - goto __pyx_L32_exit_scope; - __pyx_L28_error:; - __Pyx_XDECREF(__pyx_8genexpr1__pyx_v_s); __pyx_8genexpr1__pyx_v_s = 0; - goto __pyx_L1_error; - __pyx_L32_exit_scope:; - } /* exit inner scope */ - __pyx_v_signal_addrs = ((PyObject*)__pyx_t_2); - __pyx_t_2 = 0; - - /* "opendbc/can/parser_pyx.pyx":90 - * checked_addrs = {c[0] for c in checks} - * signal_addrs = {s[1] for s in signals} - * unchecked = signal_addrs - checked_addrs # <<<<<<<<<<<<<< - * if len(unchecked): - * err_msg = ", ".join(f"{self.address_to_msg_name[addr].decode()} ({hex(addr)})" for addr in unchecked) - */ - __pyx_t_2 = PyNumber_Subtract(__pyx_v_signal_addrs, __pyx_v_checked_addrs); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 90, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __pyx_v_unchecked = __pyx_t_2; - __pyx_t_2 = 0; - - /* "opendbc/can/parser_pyx.pyx":91 - * signal_addrs = {s[1] for s in signals} - * unchecked = signal_addrs - checked_addrs - * if len(unchecked): # <<<<<<<<<<<<<< - * err_msg = ", ".join(f"{self.address_to_msg_name[addr].decode()} ({hex(addr)})" for addr in unchecked) - * raise RuntimeError(f"Unchecked addrs: {err_msg}") - */ - __pyx_t_13 = PyObject_Length(__pyx_v_unchecked); if (unlikely(__pyx_t_13 == ((Py_ssize_t)-1))) __PYX_ERR(0, 91, __pyx_L1_error) - __pyx_t_17 = (__pyx_t_13 != 0); - if (unlikely(__pyx_t_17)) { - - /* "opendbc/can/parser_pyx.pyx":92 - * unchecked = signal_addrs - checked_addrs - * if len(unchecked): - * err_msg = ", ".join(f"{self.address_to_msg_name[addr].decode()} ({hex(addr)})" for addr in unchecked) # <<<<<<<<<<<<<< - * raise RuntimeError(f"Unchecked addrs: {err_msg}") - * - */ - __pyx_t_2 = __pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_8__init___genexpr(((PyObject*)__pyx_cur_scope), __pyx_v_unchecked); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 92, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __pyx_t_4 = __Pyx_Generator_Next(__pyx_t_2); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 92, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - __pyx_t_2 = PyUnicode_Join(__pyx_kp_u__3, __pyx_t_4); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 92, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __pyx_v_err_msg = ((PyObject*)__pyx_t_2); - __pyx_t_2 = 0; - - /* "opendbc/can/parser_pyx.pyx":93 - * if len(unchecked): - * err_msg = ", ".join(f"{self.address_to_msg_name[addr].decode()} ({hex(addr)})" for addr in unchecked) - * raise RuntimeError(f"Unchecked addrs: {err_msg}") # <<<<<<<<<<<<<< - * - * cdef vector[SignalParseOptions] signal_options_v - */ - __pyx_t_2 = __Pyx_PyUnicode_Unicode(__pyx_v_err_msg); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 93, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __pyx_t_4 = __Pyx_PyUnicode_Concat(__pyx_kp_u_Unchecked_addrs, __pyx_t_2); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 93, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - __pyx_t_2 = __Pyx_PyObject_CallOneArg(__pyx_builtin_RuntimeError, __pyx_t_4); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 93, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __Pyx_Raise(__pyx_t_2, 0, 0, 0); - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - __PYX_ERR(0, 93, __pyx_L1_error) - - /* "opendbc/can/parser_pyx.pyx":91 - * signal_addrs = {s[1] for s in signals} - * unchecked = signal_addrs - checked_addrs - * if len(unchecked): # <<<<<<<<<<<<<< - * err_msg = ", ".join(f"{self.address_to_msg_name[addr].decode()} ({hex(addr)})" for addr in unchecked) - * raise RuntimeError(f"Unchecked addrs: {err_msg}") - */ - } - - /* "opendbc/can/parser_pyx.pyx":87 - * checks[i] = c - * - * if enforce_checks: # <<<<<<<<<<<<<< - * checked_addrs = {c[0] for c in checks} - * signal_addrs = {s[1] for s in signals} - */ - } - - /* "opendbc/can/parser_pyx.pyx":97 - * cdef vector[SignalParseOptions] signal_options_v - * cdef SignalParseOptions spo - * for sig_name, sig_address in signals: # <<<<<<<<<<<<<< - * spo.address = sig_address - * spo.name = sig_name - */ - if (likely(PyList_CheckExact(__pyx_v_signals)) || PyTuple_CheckExact(__pyx_v_signals)) { - __pyx_t_2 = __pyx_v_signals; __Pyx_INCREF(__pyx_t_2); __pyx_t_13 = 0; - __pyx_t_18 = NULL; - } else { - __pyx_t_13 = -1; __pyx_t_2 = PyObject_GetIter(__pyx_v_signals); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 97, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __pyx_t_18 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_2); if (unlikely(!__pyx_t_18)) __PYX_ERR(0, 97, __pyx_L1_error) - } - for (;;) { - if (likely(!__pyx_t_18)) { - if (likely(PyList_CheckExact(__pyx_t_2))) { - if (__pyx_t_13 >= PyList_GET_SIZE(__pyx_t_2)) break; - #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - __pyx_t_4 = PyList_GET_ITEM(__pyx_t_2, __pyx_t_13); __Pyx_INCREF(__pyx_t_4); __pyx_t_13++; if (unlikely((0 < 0))) __PYX_ERR(0, 97, __pyx_L1_error) - #else - __pyx_t_4 = PySequence_ITEM(__pyx_t_2, __pyx_t_13); __pyx_t_13++; if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 97, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - #endif - } else { - if (__pyx_t_13 >= PyTuple_GET_SIZE(__pyx_t_2)) break; - #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - __pyx_t_4 = PyTuple_GET_ITEM(__pyx_t_2, __pyx_t_13); __Pyx_INCREF(__pyx_t_4); __pyx_t_13++; if (unlikely((0 < 0))) __PYX_ERR(0, 97, __pyx_L1_error) - #else - __pyx_t_4 = PySequence_ITEM(__pyx_t_2, __pyx_t_13); __pyx_t_13++; if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 97, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - #endif - } - } else { - __pyx_t_4 = __pyx_t_18(__pyx_t_2); - if (unlikely(!__pyx_t_4)) { - PyObject* exc_type = PyErr_Occurred(); - if (exc_type) { - if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); - else __PYX_ERR(0, 97, __pyx_L1_error) - } - break; - } - __Pyx_GOTREF(__pyx_t_4); - } - if ((likely(PyTuple_CheckExact(__pyx_t_4))) || (PyList_CheckExact(__pyx_t_4))) { - PyObject* sequence = __pyx_t_4; - Py_ssize_t size = __Pyx_PySequence_SIZE(sequence); - if (unlikely(size != 2)) { - if (size > 2) __Pyx_RaiseTooManyValuesError(2); - else if (size >= 0) __Pyx_RaiseNeedMoreValuesError(size); - __PYX_ERR(0, 97, __pyx_L1_error) - } - #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - if (likely(PyTuple_CheckExact(sequence))) { - __pyx_t_11 = PyTuple_GET_ITEM(sequence, 0); - __pyx_t_10 = PyTuple_GET_ITEM(sequence, 1); - } else { - __pyx_t_11 = PyList_GET_ITEM(sequence, 0); - __pyx_t_10 = PyList_GET_ITEM(sequence, 1); - } - __Pyx_INCREF(__pyx_t_11); - __Pyx_INCREF(__pyx_t_10); - #else - __pyx_t_11 = PySequence_ITEM(sequence, 0); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 97, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_11); - __pyx_t_10 = PySequence_ITEM(sequence, 1); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 97, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_10); - #endif - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - } else { - Py_ssize_t index = -1; - __pyx_t_19 = PyObject_GetIter(__pyx_t_4); if (unlikely(!__pyx_t_19)) __PYX_ERR(0, 97, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_19); - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __pyx_t_20 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_19); - index = 0; __pyx_t_11 = __pyx_t_20(__pyx_t_19); if (unlikely(!__pyx_t_11)) goto __pyx_L36_unpacking_failed; - __Pyx_GOTREF(__pyx_t_11); - index = 1; __pyx_t_10 = __pyx_t_20(__pyx_t_19); if (unlikely(!__pyx_t_10)) goto __pyx_L36_unpacking_failed; - __Pyx_GOTREF(__pyx_t_10); - if (__Pyx_IternextUnpackEndCheck(__pyx_t_20(__pyx_t_19), 2) < 0) __PYX_ERR(0, 97, __pyx_L1_error) - __pyx_t_20 = NULL; - __Pyx_DECREF(__pyx_t_19); __pyx_t_19 = 0; - goto __pyx_L37_unpacking_done; - __pyx_L36_unpacking_failed:; - __Pyx_DECREF(__pyx_t_19); __pyx_t_19 = 0; - __pyx_t_20 = NULL; - if (__Pyx_IterFinish() == 0) __Pyx_RaiseNeedMoreValuesError(index); - __PYX_ERR(0, 97, __pyx_L1_error) - __pyx_L37_unpacking_done:; - } - __Pyx_XDECREF_SET(__pyx_v_sig_name, __pyx_t_11); - __pyx_t_11 = 0; - __Pyx_XDECREF_SET(__pyx_v_sig_address, __pyx_t_10); - __pyx_t_10 = 0; - - /* "opendbc/can/parser_pyx.pyx":98 - * cdef SignalParseOptions spo - * for sig_name, sig_address in signals: - * spo.address = sig_address # <<<<<<<<<<<<<< - * spo.name = sig_name - * signal_options_v.push_back(spo) - */ - __pyx_t_21 = __Pyx_PyInt_As_uint32_t(__pyx_v_sig_address); if (unlikely((__pyx_t_21 == ((uint32_t)-1)) && PyErr_Occurred())) __PYX_ERR(0, 98, __pyx_L1_error) - __pyx_v_spo.address = __pyx_t_21; - - /* "opendbc/can/parser_pyx.pyx":99 - * for sig_name, sig_address in signals: - * spo.address = sig_address - * spo.name = sig_name # <<<<<<<<<<<<<< - * signal_options_v.push_back(spo) - * - */ - __pyx_t_3 = __pyx_convert_string_from_py_std__in_string(__pyx_v_sig_name); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 99, __pyx_L1_error) - __pyx_v_spo.name = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_3); - - /* "opendbc/can/parser_pyx.pyx":100 - * spo.address = sig_address - * spo.name = sig_name - * signal_options_v.push_back(spo) # <<<<<<<<<<<<<< - * - * message_options = dict((address, 0) for _, address in signals) - */ - try { - __pyx_v_signal_options_v.push_back(__pyx_v_spo); - } catch(...) { - __Pyx_CppExn2PyErr(); - __PYX_ERR(0, 100, __pyx_L1_error) - } - - /* "opendbc/can/parser_pyx.pyx":97 - * cdef vector[SignalParseOptions] signal_options_v - * cdef SignalParseOptions spo - * for sig_name, sig_address in signals: # <<<<<<<<<<<<<< - * spo.address = sig_address - * spo.name = sig_name - */ - } - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - - /* "opendbc/can/parser_pyx.pyx":102 - * signal_options_v.push_back(spo) - * - * message_options = dict((address, 0) for _, address in signals) # <<<<<<<<<<<<<< - * message_options.update(dict(checks)) - * - */ - __pyx_t_2 = __pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_8__init___3genexpr(NULL, __pyx_v_signals); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 102, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __pyx_t_4 = __Pyx_Generator_Next(__pyx_t_2); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 102, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - __pyx_v_message_options = ((PyObject*)__pyx_t_4); - __pyx_t_4 = 0; - - /* "opendbc/can/parser_pyx.pyx":103 - * - * message_options = dict((address, 0) for _, address in signals) - * message_options.update(dict(checks)) # <<<<<<<<<<<<<< - * - * cdef vector[MessageParseOptions] message_options_v - */ - __pyx_t_4 = __Pyx_PyObject_CallOneArg(((PyObject *)(&PyDict_Type)), __pyx_v_checks); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 103, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __pyx_t_2 = __Pyx_CallUnboundCMethod1(&__pyx_umethod_PyDict_Type_update, __pyx_v_message_options, __pyx_t_4); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 103, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - - /* "opendbc/can/parser_pyx.pyx":107 - * cdef vector[MessageParseOptions] message_options_v - * cdef MessageParseOptions mpo - * for msg_address, freq in message_options.items(): # <<<<<<<<<<<<<< - * mpo.address = msg_address - * mpo.check_frequency = freq - */ - __pyx_t_13 = 0; - if (unlikely(__pyx_v_message_options == Py_None)) { - PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "items"); - __PYX_ERR(0, 107, __pyx_L1_error) - } - __pyx_t_4 = __Pyx_dict_iterator(__pyx_v_message_options, 1, __pyx_n_s_items, (&__pyx_t_14), (&__pyx_t_12)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 107, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __Pyx_XDECREF(__pyx_t_2); - __pyx_t_2 = __pyx_t_4; - __pyx_t_4 = 0; - while (1) { - __pyx_t_22 = __Pyx_dict_iter_next(__pyx_t_2, __pyx_t_14, &__pyx_t_13, &__pyx_t_4, &__pyx_t_10, NULL, __pyx_t_12); - if (unlikely(__pyx_t_22 == 0)) break; - if (unlikely(__pyx_t_22 == -1)) __PYX_ERR(0, 107, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __Pyx_GOTREF(__pyx_t_10); - __Pyx_XDECREF_SET(__pyx_v_msg_address, __pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_11, 0, __pyx_v_address); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_11, 1, __pyx_t_4); __pyx_t_4 = 0; - __Pyx_XDECREF_SET(__pyx_v_freq, __pyx_t_10); - __pyx_t_10 = 0; - - /* "opendbc/can/parser_pyx.pyx":108 - * cdef MessageParseOptions mpo - * for msg_address, freq in message_options.items(): - * mpo.address = msg_address # <<<<<<<<<<<<<< - * mpo.check_frequency = freq - * message_options_v.push_back(mpo) - */ - __pyx_t_21 = __Pyx_PyInt_As_uint32_t(__pyx_v_msg_address); if (unlikely((__pyx_t_21 == ((uint32_t)-1)) && PyErr_Occurred())) __PYX_ERR(0, 108, __pyx_L1_error) - __pyx_v_mpo.address = __pyx_t_21; - - /* "opendbc/can/parser_pyx.pyx":109 - * for msg_address, freq in message_options.items(): - * mpo.address = msg_address - * mpo.check_frequency = freq # <<<<<<<<<<<<<< - * message_options_v.push_back(mpo) - * - */ - __pyx_t_22 = __Pyx_PyInt_As_int(__pyx_v_freq); if (unlikely((__pyx_t_22 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 109, __pyx_L1_error) - __pyx_v_mpo.check_frequency = __pyx_t_22; - - /* "opendbc/can/parser_pyx.pyx":110 - * mpo.address = msg_address - * mpo.check_frequency = freq - * message_options_v.push_back(mpo) # <<<<<<<<<<<<<< - * - * self.can = new cpp_CANParser(bus, dbc_name, message_options_v, signal_options_v) - */ + __pyx_t_14 = __pyx_convert_pair_from_py_uint32_t__and_int(__pyx_t_11); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 67, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_11); __pyx_t_11 = 0; try { - __pyx_v_message_options_v.push_back(__pyx_v_mpo); + __pyx_v_message_v.push_back(__pyx_t_14); } catch(...) { __Pyx_CppExn2PyErr(); - __PYX_ERR(0, 110, __pyx_L1_error) + __PYX_ERR(0, 67, __pyx_L1_error) } } - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - /* "opendbc/can/parser_pyx.pyx":112 - * message_options_v.push_back(mpo) + /* "opendbc/can/parser_pyx.pyx":69 + * message_v.push_back((address, c[1])) * - * self.can = new cpp_CANParser(bus, dbc_name, message_options_v, signal_options_v) # <<<<<<<<<<<<<< + * self.can = new cpp_CANParser(bus, dbc_name, message_v) # <<<<<<<<<<<<<< * self.update_strings([]) * */ - __pyx_t_12 = __Pyx_PyInt_As_int(__pyx_v_bus); if (unlikely((__pyx_t_12 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 112, __pyx_L1_error) - __pyx_t_3 = __pyx_convert_string_from_py_std__in_string(__pyx_v_dbc_name); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 112, __pyx_L1_error) - __pyx_cur_scope->__pyx_v_self->can = new CANParser(__pyx_t_12, __pyx_t_3, __pyx_v_message_options_v, __pyx_v_signal_options_v); + __pyx_t_15 = __Pyx_PyInt_As_int(__pyx_v_bus); if (unlikely((__pyx_t_15 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 69, __pyx_L1_error) + __pyx_t_1 = __pyx_convert_string_from_py_std__in_string(__pyx_v_dbc_name); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 69, __pyx_L1_error) + __pyx_v_self->can = new CANParser(__pyx_t_15, __pyx_t_1, __pyx_v_message_v); - /* "opendbc/can/parser_pyx.pyx":113 + /* "opendbc/can/parser_pyx.pyx":70 * - * self.can = new cpp_CANParser(bus, dbc_name, message_options_v, signal_options_v) + * self.can = new cpp_CANParser(bus, dbc_name, message_v) * self.update_strings([]) # <<<<<<<<<<<<<< * * def update_strings(self, strings, sendcan=False): */ - __pyx_t_10 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_cur_scope->__pyx_v_self), __pyx_n_s_update_strings); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 113, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_10); - __pyx_t_4 = PyList_New(0); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 113, __pyx_L1_error) + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_update_strings); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 70, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); - __pyx_t_11 = NULL; - __pyx_t_12 = 0; - if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_10))) { - __pyx_t_11 = PyMethod_GET_SELF(__pyx_t_10); - if (likely(__pyx_t_11)) { - PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_10); - __Pyx_INCREF(__pyx_t_11); + __pyx_t_3 = PyList_New(0); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 70, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_10 = NULL; + __pyx_t_15 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_4))) { + __pyx_t_10 = PyMethod_GET_SELF(__pyx_t_4); + if (likely(__pyx_t_10)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_4); + __Pyx_INCREF(__pyx_t_10); __Pyx_INCREF(function); - __Pyx_DECREF_SET(__pyx_t_10, function); - __pyx_t_12 = 1; + __Pyx_DECREF_SET(__pyx_t_4, function); + __pyx_t_15 = 1; } } { - PyObject *__pyx_callargs[2] = {__pyx_t_11, __pyx_t_4}; - __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_10, __pyx_callargs+1-__pyx_t_12, 1+__pyx_t_12); - __Pyx_XDECREF(__pyx_t_11); __pyx_t_11 = 0; + PyObject *__pyx_callargs[2] = {__pyx_t_10, __pyx_t_3}; + __pyx_t_11 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_15, 1+__pyx_t_15); + __Pyx_XDECREF(__pyx_t_10); __pyx_t_10 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 70, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_11); __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 113, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_2); - __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; } - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_11); __pyx_t_11 = 0; - /* "opendbc/can/parser_pyx.pyx":31 + /* "opendbc/can/parser_pyx.pyx":30 * string dbc_name * - * def __init__(self, dbc_name, signals, checks=None, bus=0, enforce_checks=True): # <<<<<<<<<<<<<< - * if checks is None: - * checks = [] + * def __init__(self, dbc_name, messages, bus=0): # <<<<<<<<<<<<<< + * self.dbc_name = dbc_name + * self.dbc = dbc_lookup(dbc_name) */ /* function exit code */ __pyx_r = 0; goto __pyx_L0; __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); __Pyx_XDECREF(__pyx_t_4); __Pyx_XDECREF(__pyx_t_10); __Pyx_XDECREF(__pyx_t_11); - __Pyx_XDECREF(__pyx_t_19); __Pyx_AddTraceback("opendbc.can.parser_pyx.CANParser.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); __pyx_r = -1; __pyx_L0:; - __Pyx_XDECREF(__pyx_v_msg_name_to_address); - __Pyx_XDECREF(__pyx_v_msg_address_to_signals); - __Pyx_XDECREF(__pyx_v_name); - __Pyx_XDECREF(__pyx_v_s); - __Pyx_XDECREF(__pyx_v_address); - __Pyx_XDECREF(__pyx_v_c); - __Pyx_XDECREF(__pyx_v_checked_addrs); - __Pyx_XDECREF(__pyx_v_signal_addrs); - __Pyx_XDECREF(__pyx_v_unchecked); - __Pyx_XDECREF(__pyx_v_err_msg); - __Pyx_XDECREF(__pyx_v_sig_name); - __Pyx_XDECREF(__pyx_v_sig_address); - __Pyx_XDECREF(__pyx_v_message_options); - __Pyx_XDECREF(__pyx_v_msg_address); - __Pyx_XDECREF(__pyx_v_freq); - __Pyx_XDECREF(__pyx_7genexpr__pyx_v_c); - __Pyx_XDECREF(__pyx_8genexpr1__pyx_v_s); - __Pyx_XDECREF(__pyx_gb_7opendbc_3can_10parser_pyx_9CANParser_8__init___2generator); - __Pyx_XDECREF(__pyx_gb_7opendbc_3can_10parser_pyx_9CANParser_8__init___5generator1); __Pyx_XDECREF(__pyx_v_checks); - __Pyx_XDECREF(__pyx_v_enforce_checks); - __Pyx_DECREF((PyObject *)__pyx_cur_scope); + __Pyx_XDECREF(__pyx_v_msg_name_to_address); + __Pyx_XDECREF(__pyx_v_address_to_msg_name); + __Pyx_XDECREF(__pyx_v_name); + __Pyx_XDECREF(__pyx_v_c); + __Pyx_XDECREF(__pyx_v_address); __Pyx_RefNannyFinishContext(); return __pyx_r; } -/* "opendbc/can/parser_pyx.pyx":115 +/* "opendbc/can/parser_pyx.pyx":72 * self.update_strings([]) * * def update_strings(self, strings, sendcan=False): # <<<<<<<<<<<<<< @@ -5919,19 +4425,19 @@ PyObject *__pyx_args, PyObject *__pyx_kwds switch (__pyx_nargs) { case 0: if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_strings)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 115, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 72, __pyx_L3_error) else goto __pyx_L5_argtuple_error; CYTHON_FALLTHROUGH; case 1: if (kw_args > 0) { PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_sendcan); if (value) { values[1] = value; kw_args--; } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 115, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 72, __pyx_L3_error) } } if (unlikely(kw_args > 0)) { const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "update_strings") < 0)) __PYX_ERR(0, 115, __pyx_L3_error) + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "update_strings") < 0)) __PYX_ERR(0, 72, __pyx_L3_error) } } else { switch (__pyx_nargs) { @@ -5947,7 +4453,7 @@ PyObject *__pyx_args, PyObject *__pyx_kwds } goto __pyx_L4_argument_unpacking_done; __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("update_strings", 0, 1, 2, __pyx_nargs); __PYX_ERR(0, 115, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("update_strings", 0, 1, 2, __pyx_nargs); __PYX_ERR(0, 72, __pyx_L3_error) __pyx_L3_error:; __Pyx_AddTraceback("opendbc.can.parser_pyx.CANParser.update_strings", __pyx_clineno, __pyx_lineno, __pyx_filename); __Pyx_RefNannyFinishContext(); @@ -5990,7 +4496,7 @@ static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_2update_strings( int __pyx_clineno = 0; __Pyx_RefNannySetupContext("update_strings", 0); - /* "opendbc/can/parser_pyx.pyx":116 + /* "opendbc/can/parser_pyx.pyx":73 * * def update_strings(self, strings, sendcan=False): * for v in self.vl_all.values(): # <<<<<<<<<<<<<< @@ -6000,9 +4506,9 @@ static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_2update_strings( __pyx_t_2 = 0; if (unlikely(__pyx_v_self->vl_all == Py_None)) { PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "values"); - __PYX_ERR(0, 116, __pyx_L1_error) + __PYX_ERR(0, 73, __pyx_L1_error) } - __pyx_t_5 = __Pyx_dict_iterator(__pyx_v_self->vl_all, 1, __pyx_n_s_values, (&__pyx_t_3), (&__pyx_t_4)); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 116, __pyx_L1_error) + __pyx_t_5 = __Pyx_dict_iterator(__pyx_v_self->vl_all, 1, __pyx_n_s_values, (&__pyx_t_3), (&__pyx_t_4)); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 73, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_5); __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = __pyx_t_5; @@ -6010,12 +4516,12 @@ static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_2update_strings( while (1) { __pyx_t_6 = __Pyx_dict_iter_next(__pyx_t_1, __pyx_t_3, &__pyx_t_2, NULL, &__pyx_t_5, NULL, __pyx_t_4); if (unlikely(__pyx_t_6 == 0)) break; - if (unlikely(__pyx_t_6 == -1)) __PYX_ERR(0, 116, __pyx_L1_error) + if (unlikely(__pyx_t_6 == -1)) __PYX_ERR(0, 73, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_5); __Pyx_XDECREF_SET(__pyx_v_v, __pyx_t_5); __pyx_t_5 = 0; - /* "opendbc/can/parser_pyx.pyx":117 + /* "opendbc/can/parser_pyx.pyx":74 * def update_strings(self, strings, sendcan=False): * for v in self.vl_all.values(): * for l in v.values(): # no-cython-lint # <<<<<<<<<<<<<< @@ -6025,9 +4531,9 @@ static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_2update_strings( __pyx_t_7 = 0; if (unlikely(__pyx_v_v == Py_None)) { PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "values"); - __PYX_ERR(0, 117, __pyx_L1_error) + __PYX_ERR(0, 74, __pyx_L1_error) } - __pyx_t_9 = __Pyx_dict_iterator(__pyx_v_v, 0, __pyx_n_s_values, (&__pyx_t_8), (&__pyx_t_6)); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 117, __pyx_L1_error) + __pyx_t_9 = __Pyx_dict_iterator(__pyx_v_v, 0, __pyx_n_s_values, (&__pyx_t_8), (&__pyx_t_6)); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 74, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_9); __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = __pyx_t_9; @@ -6035,19 +4541,19 @@ static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_2update_strings( while (1) { __pyx_t_10 = __Pyx_dict_iter_next(__pyx_t_5, __pyx_t_8, &__pyx_t_7, NULL, &__pyx_t_9, NULL, __pyx_t_6); if (unlikely(__pyx_t_10 == 0)) break; - if (unlikely(__pyx_t_10 == -1)) __PYX_ERR(0, 117, __pyx_L1_error) + if (unlikely(__pyx_t_10 == -1)) __PYX_ERR(0, 74, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_9); __Pyx_XDECREF_SET(__pyx_v_l, __pyx_t_9); __pyx_t_9 = 0; - /* "opendbc/can/parser_pyx.pyx":118 + /* "opendbc/can/parser_pyx.pyx":75 * for v in self.vl_all.values(): * for l in v.values(): # no-cython-lint * l.clear() # <<<<<<<<<<<<<< * * cdef vector[SignalValue] new_vals */ - __pyx_t_11 = __Pyx_PyObject_GetAttrStr(__pyx_v_l, __pyx_n_s_clear); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 118, __pyx_L1_error) + __pyx_t_11 = __Pyx_PyObject_GetAttrStr(__pyx_v_l, __pyx_n_s_clear); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 75, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_11); __pyx_t_12 = NULL; __pyx_t_10 = 0; @@ -6065,7 +4571,7 @@ static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_2update_strings( PyObject *__pyx_callargs[1] = {__pyx_t_12, }; __pyx_t_9 = __Pyx_PyObject_FastCall(__pyx_t_11, __pyx_callargs+1-__pyx_t_10, 0+__pyx_t_10); __Pyx_XDECREF(__pyx_t_12); __pyx_t_12 = 0; - if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 118, __pyx_L1_error) + if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 75, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_9); __Pyx_DECREF(__pyx_t_11); __pyx_t_11 = 0; } @@ -6075,18 +4581,23 @@ static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_2update_strings( } __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - /* "opendbc/can/parser_pyx.pyx":123 + /* "opendbc/can/parser_pyx.pyx":80 * cdef unordered_set[uint32_t] updated_addrs * * self.can.update_strings(strings, new_vals, sendcan) # <<<<<<<<<<<<<< * cdef vector[SignalValue].iterator it = new_vals.begin() * cdef SignalValue* cv */ - __pyx_t_13 = __pyx_convert_vector_from_py_std_3a__3a_string(__pyx_v_strings); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 123, __pyx_L1_error) - __pyx_t_14 = __Pyx_PyObject_IsTrue(__pyx_v_sendcan); if (unlikely((__pyx_t_14 == ((bool)-1)) && PyErr_Occurred())) __PYX_ERR(0, 123, __pyx_L1_error) - __pyx_v_self->can->update_strings(__pyx_t_13, __pyx_v_new_vals, __pyx_t_14); + __pyx_t_13 = __pyx_convert_vector_from_py_std_3a__3a_string(__pyx_v_strings); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 80, __pyx_L1_error) + __pyx_t_14 = __Pyx_PyObject_IsTrue(__pyx_v_sendcan); if (unlikely((__pyx_t_14 == ((bool)-1)) && PyErr_Occurred())) __PYX_ERR(0, 80, __pyx_L1_error) + try { + __pyx_v_self->can->update_strings(__pyx_t_13, __pyx_v_new_vals, __pyx_t_14); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(0, 80, __pyx_L1_error) + } - /* "opendbc/can/parser_pyx.pyx":124 + /* "opendbc/can/parser_pyx.pyx":81 * * self.can.update_strings(strings, new_vals, sendcan) * cdef vector[SignalValue].iterator it = new_vals.begin() # <<<<<<<<<<<<<< @@ -6095,7 +4606,7 @@ static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_2update_strings( */ __pyx_v_it = __pyx_v_new_vals.begin(); - /* "opendbc/can/parser_pyx.pyx":126 + /* "opendbc/can/parser_pyx.pyx":83 * cdef vector[SignalValue].iterator it = new_vals.begin() * cdef SignalValue* cv * while it != new_vals.end(): # <<<<<<<<<<<<<< @@ -6106,7 +4617,7 @@ static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_2update_strings( __pyx_t_15 = (__pyx_v_it != __pyx_v_new_vals.end()); if (!__pyx_t_15) break; - /* "opendbc/can/parser_pyx.pyx":127 + /* "opendbc/can/parser_pyx.pyx":84 * cdef SignalValue* cv * while it != new_vals.end(): * cv = &deref(it) # <<<<<<<<<<<<<< @@ -6115,14 +4626,14 @@ static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_2update_strings( */ __pyx_v_cv = (&(*__pyx_v_it)); - /* "opendbc/can/parser_pyx.pyx":129 + /* "opendbc/can/parser_pyx.pyx":86 * cv = &deref(it) * # Cast char * directly to unicode * cv_name = cv.name # <<<<<<<<<<<<<< * self.vl[cv.address][cv_name] = cv.value * self.vl_all[cv.address][cv_name] = cv.all_values */ - __pyx_t_1 = __pyx_convert_PyUnicode_string_to_py_std__in_string(__pyx_v_cv->name); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 129, __pyx_L1_error) + __pyx_t_1 = __pyx_convert_PyUnicode_string_to_py_std__in_string(__pyx_v_cv->name); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 86, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __pyx_t_5 = __pyx_t_1; __Pyx_INCREF(__pyx_t_5); @@ -6130,73 +4641,73 @@ static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_2update_strings( __Pyx_XDECREF_SET(__pyx_v_cv_name, ((PyObject*)__pyx_t_5)); __pyx_t_5 = 0; - /* "opendbc/can/parser_pyx.pyx":130 + /* "opendbc/can/parser_pyx.pyx":87 * # Cast char * directly to unicode * cv_name = cv.name * self.vl[cv.address][cv_name] = cv.value # <<<<<<<<<<<<<< * self.vl_all[cv.address][cv_name] = cv.all_values * self.ts_nanos[cv.address][cv_name] = cv.ts_nanos */ - __pyx_t_5 = PyFloat_FromDouble(__pyx_v_cv->value); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 130, __pyx_L1_error) + __pyx_t_5 = PyFloat_FromDouble(__pyx_v_cv->value); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 87, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_5); if (unlikely(__pyx_v_self->vl == Py_None)) { PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); - __PYX_ERR(0, 130, __pyx_L1_error) + __PYX_ERR(0, 87, __pyx_L1_error) } - __pyx_t_1 = __Pyx_PyInt_From_uint32_t(__pyx_v_cv->address); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 130, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyInt_From_uint32_t(__pyx_v_cv->address); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 87, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); - __pyx_t_9 = __Pyx_PyDict_GetItem(__pyx_v_self->vl, __pyx_t_1); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 130, __pyx_L1_error) + __pyx_t_9 = __Pyx_PyDict_GetItem(__pyx_v_self->vl, __pyx_t_1); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 87, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_9); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - if (unlikely((PyObject_SetItem(__pyx_t_9, __pyx_v_cv_name, __pyx_t_5) < 0))) __PYX_ERR(0, 130, __pyx_L1_error) + if (unlikely((PyObject_SetItem(__pyx_t_9, __pyx_v_cv_name, __pyx_t_5) < 0))) __PYX_ERR(0, 87, __pyx_L1_error) __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - /* "opendbc/can/parser_pyx.pyx":131 + /* "opendbc/can/parser_pyx.pyx":88 * cv_name = cv.name * self.vl[cv.address][cv_name] = cv.value * self.vl_all[cv.address][cv_name] = cv.all_values # <<<<<<<<<<<<<< * self.ts_nanos[cv.address][cv_name] = cv.ts_nanos * updated_addrs.insert(cv.address) */ - __pyx_t_5 = __pyx_convert_vector_to_py_double(__pyx_v_cv->all_values); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 131, __pyx_L1_error) + __pyx_t_5 = __pyx_convert_vector_to_py_double(__pyx_v_cv->all_values); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 88, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_5); if (unlikely(__pyx_v_self->vl_all == Py_None)) { PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); - __PYX_ERR(0, 131, __pyx_L1_error) + __PYX_ERR(0, 88, __pyx_L1_error) } - __pyx_t_9 = __Pyx_PyInt_From_uint32_t(__pyx_v_cv->address); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 131, __pyx_L1_error) + __pyx_t_9 = __Pyx_PyInt_From_uint32_t(__pyx_v_cv->address); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 88, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_9); - __pyx_t_1 = __Pyx_PyDict_GetItem(__pyx_v_self->vl_all, __pyx_t_9); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 131, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyDict_GetItem(__pyx_v_self->vl_all, __pyx_t_9); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 88, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; - if (unlikely((PyObject_SetItem(__pyx_t_1, __pyx_v_cv_name, __pyx_t_5) < 0))) __PYX_ERR(0, 131, __pyx_L1_error) + if (unlikely((PyObject_SetItem(__pyx_t_1, __pyx_v_cv_name, __pyx_t_5) < 0))) __PYX_ERR(0, 88, __pyx_L1_error) __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - /* "opendbc/can/parser_pyx.pyx":132 + /* "opendbc/can/parser_pyx.pyx":89 * self.vl[cv.address][cv_name] = cv.value * self.vl_all[cv.address][cv_name] = cv.all_values * self.ts_nanos[cv.address][cv_name] = cv.ts_nanos # <<<<<<<<<<<<<< * updated_addrs.insert(cv.address) * preinc(it) */ - __pyx_t_5 = __Pyx_PyInt_From_uint64_t(__pyx_v_cv->ts_nanos); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 132, __pyx_L1_error) + __pyx_t_5 = __Pyx_PyInt_From_uint64_t(__pyx_v_cv->ts_nanos); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 89, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_5); if (unlikely(__pyx_v_self->ts_nanos == Py_None)) { PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); - __PYX_ERR(0, 132, __pyx_L1_error) + __PYX_ERR(0, 89, __pyx_L1_error) } - __pyx_t_1 = __Pyx_PyInt_From_uint32_t(__pyx_v_cv->address); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 132, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyInt_From_uint32_t(__pyx_v_cv->address); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 89, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); - __pyx_t_9 = __Pyx_PyDict_GetItem(__pyx_v_self->ts_nanos, __pyx_t_1); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 132, __pyx_L1_error) + __pyx_t_9 = __Pyx_PyDict_GetItem(__pyx_v_self->ts_nanos, __pyx_t_1); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 89, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_9); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - if (unlikely((PyObject_SetItem(__pyx_t_9, __pyx_v_cv_name, __pyx_t_5) < 0))) __PYX_ERR(0, 132, __pyx_L1_error) + if (unlikely((PyObject_SetItem(__pyx_t_9, __pyx_v_cv_name, __pyx_t_5) < 0))) __PYX_ERR(0, 89, __pyx_L1_error) __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - /* "opendbc/can/parser_pyx.pyx":133 + /* "opendbc/can/parser_pyx.pyx":90 * self.vl_all[cv.address][cv_name] = cv.all_values * self.ts_nanos[cv.address][cv_name] = cv.ts_nanos * updated_addrs.insert(cv.address) # <<<<<<<<<<<<<< @@ -6207,10 +4718,10 @@ static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_2update_strings( __pyx_v_updated_addrs.insert(__pyx_v_cv->address); } catch(...) { __Pyx_CppExn2PyErr(); - __PYX_ERR(0, 133, __pyx_L1_error) + __PYX_ERR(0, 90, __pyx_L1_error) } - /* "opendbc/can/parser_pyx.pyx":134 + /* "opendbc/can/parser_pyx.pyx":91 * self.ts_nanos[cv.address][cv_name] = cv.ts_nanos * updated_addrs.insert(cv.address) * preinc(it) # <<<<<<<<<<<<<< @@ -6220,7 +4731,7 @@ static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_2update_strings( (void)((++__pyx_v_it)); } - /* "opendbc/can/parser_pyx.pyx":136 + /* "opendbc/can/parser_pyx.pyx":93 * preinc(it) * * return updated_addrs # <<<<<<<<<<<<<< @@ -6228,13 +4739,13 @@ static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_2update_strings( * @property */ __Pyx_XDECREF(__pyx_r); - __pyx_t_5 = __pyx_convert_unordered_set_to_py_uint32_t(__pyx_v_updated_addrs); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 136, __pyx_L1_error) + __pyx_t_5 = __pyx_convert_unordered_set_to_py_uint32_t(__pyx_v_updated_addrs); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 93, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_5); __pyx_r = __pyx_t_5; __pyx_t_5 = 0; goto __pyx_L0; - /* "opendbc/can/parser_pyx.pyx":115 + /* "opendbc/can/parser_pyx.pyx":72 * self.update_strings([]) * * def update_strings(self, strings, sendcan=False): # <<<<<<<<<<<<<< @@ -6260,7 +4771,7 @@ static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_2update_strings( return __pyx_r; } -/* "opendbc/can/parser_pyx.pyx":138 +/* "opendbc/can/parser_pyx.pyx":95 * return updated_addrs * * @property # <<<<<<<<<<<<<< @@ -6291,7 +4802,7 @@ static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_9can_valid___get int __pyx_clineno = 0; __Pyx_RefNannySetupContext("__get__", 0); - /* "opendbc/can/parser_pyx.pyx":140 + /* "opendbc/can/parser_pyx.pyx":97 * @property * def can_valid(self): * return self.can.can_valid # <<<<<<<<<<<<<< @@ -6299,13 +4810,13 @@ static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_9can_valid___get * @property */ __Pyx_XDECREF(__pyx_r); - __pyx_t_1 = __Pyx_PyBool_FromLong(__pyx_v_self->can->can_valid); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 140, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyBool_FromLong(__pyx_v_self->can->can_valid); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 97, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __pyx_r = __pyx_t_1; __pyx_t_1 = 0; goto __pyx_L0; - /* "opendbc/can/parser_pyx.pyx":138 + /* "opendbc/can/parser_pyx.pyx":95 * return updated_addrs * * @property # <<<<<<<<<<<<<< @@ -6324,7 +4835,7 @@ static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_9can_valid___get return __pyx_r; } -/* "opendbc/can/parser_pyx.pyx":142 +/* "opendbc/can/parser_pyx.pyx":99 * return self.can.can_valid * * @property # <<<<<<<<<<<<<< @@ -6355,7 +4866,7 @@ static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_11bus_timeout___ int __pyx_clineno = 0; __Pyx_RefNannySetupContext("__get__", 0); - /* "opendbc/can/parser_pyx.pyx":144 + /* "opendbc/can/parser_pyx.pyx":101 * @property * def bus_timeout(self): * return self.can.bus_timeout # <<<<<<<<<<<<<< @@ -6363,13 +4874,13 @@ static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_11bus_timeout___ * */ __Pyx_XDECREF(__pyx_r); - __pyx_t_1 = __Pyx_PyBool_FromLong(__pyx_v_self->can->bus_timeout); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 144, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyBool_FromLong(__pyx_v_self->can->bus_timeout); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 101, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __pyx_r = __pyx_t_1; __pyx_t_1 = 0; goto __pyx_L0; - /* "opendbc/can/parser_pyx.pyx":142 + /* "opendbc/can/parser_pyx.pyx":99 * return self.can.can_valid * * @property # <<<<<<<<<<<<<< @@ -6388,7 +4899,7 @@ static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_11bus_timeout___ return __pyx_r; } -/* "opendbc/can/parser_pyx.pyx":26 +/* "opendbc/can/parser_pyx.pyx":25 * * cdef readonly: * dict vl # <<<<<<<<<<<<<< @@ -6426,7 +4937,7 @@ static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_2vl___get__(stru return __pyx_r; } -/* "opendbc/can/parser_pyx.pyx":27 +/* "opendbc/can/parser_pyx.pyx":26 * cdef readonly: * dict vl * dict vl_all # <<<<<<<<<<<<<< @@ -6464,7 +4975,7 @@ static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_6vl_all___get__( return __pyx_r; } -/* "opendbc/can/parser_pyx.pyx":28 +/* "opendbc/can/parser_pyx.pyx":27 * dict vl * dict vl_all * dict ts_nanos # <<<<<<<<<<<<<< @@ -6502,12 +5013,12 @@ static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_8ts_nanos___get_ return __pyx_r; } -/* "opendbc/can/parser_pyx.pyx":29 +/* "opendbc/can/parser_pyx.pyx":28 * dict vl_all * dict ts_nanos * string dbc_name # <<<<<<<<<<<<<< * - * def __init__(self, dbc_name, signals, checks=None, bus=0, enforce_checks=True): + * def __init__(self, dbc_name, messages, bus=0): */ /* Python wrapper */ @@ -6533,7 +5044,7 @@ static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_8dbc_name___get_ int __pyx_clineno = 0; __Pyx_RefNannySetupContext("__get__", 0); __Pyx_XDECREF(__pyx_r); - __pyx_t_1 = __pyx_convert_PyBytes_string_to_py_std__in_string(__pyx_v_self->dbc_name); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 29, __pyx_L1_error) + __pyx_t_1 = __pyx_convert_PyBytes_string_to_py_std__in_string(__pyx_v_self->dbc_name); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 28, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __pyx_r = __pyx_t_1; __pyx_t_1 = 0; @@ -6731,7 +5242,7 @@ static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_6__setstate_cyth return __pyx_r; } -/* "opendbc/can/parser_pyx.pyx":155 +/* "opendbc/can/parser_pyx.pyx":112 * string dbc_name * * def __init__(self, dbc_name): # <<<<<<<<<<<<<< @@ -6766,12 +5277,12 @@ static int __pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_1__init__(PyObject *__ switch (__pyx_nargs) { case 0: if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_dbc_name)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 155, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 112, __pyx_L3_error) else goto __pyx_L5_argtuple_error; } if (unlikely(kw_args > 0)) { const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__init__") < 0)) __PYX_ERR(0, 155, __pyx_L3_error) + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__init__") < 0)) __PYX_ERR(0, 112, __pyx_L3_error) } } else if (unlikely(__pyx_nargs != 1)) { goto __pyx_L5_argtuple_error; @@ -6782,7 +5293,7 @@ static int __pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_1__init__(PyObject *__ } goto __pyx_L4_argument_unpacking_done; __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("__init__", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 155, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("__init__", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 112, __pyx_L3_error) __pyx_L3_error:; __Pyx_AddTraceback("opendbc.can.parser_pyx.CANDefine.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); __Pyx_RefNannyFinishContext(); @@ -6808,7 +5319,7 @@ static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine___init__(struct __pyx_ PyObject *__pyx_v_msgname = NULL; PyObject *__pyx_v_values = NULL; PyObject *__pyx_v_defs = NULL; - PyObject *__pyx_8genexpr4__pyx_v_v = NULL; + PyObject *__pyx_7genexpr__pyx_v_v = NULL; int __pyx_r; __Pyx_RefNannyDeclarations std::string __pyx_t_1; @@ -6831,27 +5342,27 @@ static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine___init__(struct __pyx_ int __pyx_clineno = 0; __Pyx_RefNannySetupContext("__init__", 0); - /* "opendbc/can/parser_pyx.pyx":156 + /* "opendbc/can/parser_pyx.pyx":113 * * def __init__(self, dbc_name): * self.dbc_name = dbc_name # <<<<<<<<<<<<<< * self.dbc = dbc_lookup(dbc_name) * if not self.dbc: */ - __pyx_t_1 = __pyx_convert_string_from_py_std__in_string(__pyx_v_dbc_name); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 156, __pyx_L1_error) + __pyx_t_1 = __pyx_convert_string_from_py_std__in_string(__pyx_v_dbc_name); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 113, __pyx_L1_error) __pyx_v_self->dbc_name = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_1); - /* "opendbc/can/parser_pyx.pyx":157 + /* "opendbc/can/parser_pyx.pyx":114 * def __init__(self, dbc_name): * self.dbc_name = dbc_name * self.dbc = dbc_lookup(dbc_name) # <<<<<<<<<<<<<< * if not self.dbc: * raise RuntimeError(f"Can't find DBC: '{dbc_name}'") */ - __pyx_t_1 = __pyx_convert_string_from_py_std__in_string(__pyx_v_dbc_name); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 157, __pyx_L1_error) + __pyx_t_1 = __pyx_convert_string_from_py_std__in_string(__pyx_v_dbc_name); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 114, __pyx_L1_error) __pyx_v_self->dbc = dbc_lookup(__PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_1)); - /* "opendbc/can/parser_pyx.pyx":158 + /* "opendbc/can/parser_pyx.pyx":115 * self.dbc_name = dbc_name * self.dbc = dbc_lookup(dbc_name) * if not self.dbc: # <<<<<<<<<<<<<< @@ -6861,14 +5372,14 @@ static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine___init__(struct __pyx_ __pyx_t_2 = (!(__pyx_v_self->dbc != 0)); if (unlikely(__pyx_t_2)) { - /* "opendbc/can/parser_pyx.pyx":159 + /* "opendbc/can/parser_pyx.pyx":116 * self.dbc = dbc_lookup(dbc_name) * if not self.dbc: * raise RuntimeError(f"Can't find DBC: '{dbc_name}'") # <<<<<<<<<<<<<< * * address_to_msg_name = {} */ - __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 159, __pyx_L1_error) + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 116, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __pyx_t_4 = 0; __pyx_t_5 = 127; @@ -6876,28 +5387,28 @@ static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine___init__(struct __pyx_ __pyx_t_4 += 17; __Pyx_GIVEREF(__pyx_kp_u_Can_t_find_DBC_2); PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_kp_u_Can_t_find_DBC_2); - __pyx_t_6 = __Pyx_PyObject_FormatSimple(__pyx_v_dbc_name, __pyx_empty_unicode); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 159, __pyx_L1_error) + __pyx_t_6 = __Pyx_PyObject_FormatSimple(__pyx_v_dbc_name, __pyx_empty_unicode); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 116, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_6); __pyx_t_5 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_6) > __pyx_t_5) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_6) : __pyx_t_5; __pyx_t_4 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_6); __Pyx_GIVEREF(__pyx_t_6); PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_6); __pyx_t_6 = 0; - __Pyx_INCREF(__pyx_kp_u__4); + __Pyx_INCREF(__pyx_kp_u_); __pyx_t_4 += 1; - __Pyx_GIVEREF(__pyx_kp_u__4); - PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_kp_u__4); - __pyx_t_6 = __Pyx_PyUnicode_Join(__pyx_t_3, 3, __pyx_t_4, __pyx_t_5); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 159, __pyx_L1_error) + __Pyx_GIVEREF(__pyx_kp_u_); + PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_kp_u_); + __pyx_t_6 = __Pyx_PyUnicode_Join(__pyx_t_3, 3, __pyx_t_4, __pyx_t_5); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 116, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_6); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - __pyx_t_3 = __Pyx_PyObject_CallOneArg(__pyx_builtin_RuntimeError, __pyx_t_6); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 159, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyObject_CallOneArg(__pyx_builtin_RuntimeError, __pyx_t_6); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 116, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; __Pyx_Raise(__pyx_t_3, 0, 0, 0); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - __PYX_ERR(0, 159, __pyx_L1_error) + __PYX_ERR(0, 116, __pyx_L1_error) - /* "opendbc/can/parser_pyx.pyx":158 + /* "opendbc/can/parser_pyx.pyx":115 * self.dbc_name = dbc_name * self.dbc = dbc_lookup(dbc_name) * if not self.dbc: # <<<<<<<<<<<<<< @@ -6906,19 +5417,19 @@ static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine___init__(struct __pyx_ */ } - /* "opendbc/can/parser_pyx.pyx":161 + /* "opendbc/can/parser_pyx.pyx":118 * raise RuntimeError(f"Can't find DBC: '{dbc_name}'") * * address_to_msg_name = {} # <<<<<<<<<<<<<< * * for i in range(self.dbc[0].msgs.size()): */ - __pyx_t_3 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 161, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 118, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __pyx_v_address_to_msg_name = ((PyObject*)__pyx_t_3); __pyx_t_3 = 0; - /* "opendbc/can/parser_pyx.pyx":163 + /* "opendbc/can/parser_pyx.pyx":120 * address_to_msg_name = {} * * for i in range(self.dbc[0].msgs.size()): # <<<<<<<<<<<<<< @@ -6930,7 +5441,7 @@ static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine___init__(struct __pyx_ for (__pyx_t_9 = 0; __pyx_t_9 < __pyx_t_8; __pyx_t_9+=1) { __pyx_v_i = __pyx_t_9; - /* "opendbc/can/parser_pyx.pyx":164 + /* "opendbc/can/parser_pyx.pyx":121 * * for i in range(self.dbc[0].msgs.size()): * msg = self.dbc[0].msgs[i] # <<<<<<<<<<<<<< @@ -6939,19 +5450,19 @@ static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine___init__(struct __pyx_ */ __pyx_v_msg = ((__pyx_v_self->dbc[0]).msgs[__pyx_v_i]); - /* "opendbc/can/parser_pyx.pyx":165 + /* "opendbc/can/parser_pyx.pyx":122 * for i in range(self.dbc[0].msgs.size()): * msg = self.dbc[0].msgs[i] * name = msg.name.decode("utf8") # <<<<<<<<<<<<<< * address = msg.address * address_to_msg_name[address] = name */ - __pyx_t_3 = __Pyx_decode_cpp_string(__pyx_v_msg.name, 0, PY_SSIZE_T_MAX, NULL, NULL, PyUnicode_DecodeUTF8); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 165, __pyx_L1_error) + __pyx_t_3 = __Pyx_decode_cpp_string(__pyx_v_msg.name, 0, PY_SSIZE_T_MAX, NULL, NULL, PyUnicode_DecodeUTF8); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 122, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_XDECREF_SET(__pyx_v_name, __pyx_t_3); __pyx_t_3 = 0; - /* "opendbc/can/parser_pyx.pyx":166 + /* "opendbc/can/parser_pyx.pyx":123 * msg = self.dbc[0].msgs[i] * name = msg.name.decode("utf8") * address = msg.address # <<<<<<<<<<<<<< @@ -6961,27 +5472,27 @@ static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine___init__(struct __pyx_ __pyx_t_10 = __pyx_v_msg.address; __pyx_v_address = __pyx_t_10; - /* "opendbc/can/parser_pyx.pyx":167 + /* "opendbc/can/parser_pyx.pyx":124 * name = msg.name.decode("utf8") * address = msg.address * address_to_msg_name[address] = name # <<<<<<<<<<<<<< * * dv = defaultdict(dict) */ - __pyx_t_3 = __Pyx_PyInt_From_uint32_t(__pyx_v_address); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 167, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyInt_From_uint32_t(__pyx_v_address); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 124, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); - if (unlikely((PyDict_SetItem(__pyx_v_address_to_msg_name, __pyx_t_3, __pyx_v_name) < 0))) __PYX_ERR(0, 167, __pyx_L1_error) + if (unlikely((PyDict_SetItem(__pyx_v_address_to_msg_name, __pyx_t_3, __pyx_v_name) < 0))) __PYX_ERR(0, 124, __pyx_L1_error) __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; } - /* "opendbc/can/parser_pyx.pyx":169 + /* "opendbc/can/parser_pyx.pyx":126 * address_to_msg_name[address] = name * * dv = defaultdict(dict) # <<<<<<<<<<<<<< * * for i in range(self.dbc[0].vals.size()): */ - __Pyx_GetModuleGlobalName(__pyx_t_6, __pyx_n_s_defaultdict); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 169, __pyx_L1_error) + __Pyx_GetModuleGlobalName(__pyx_t_6, __pyx_n_s_defaultdict); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 126, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_6); __pyx_t_11 = NULL; __pyx_t_12 = 0; @@ -6999,14 +5510,14 @@ static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine___init__(struct __pyx_ PyObject *__pyx_callargs[2] = {__pyx_t_11, ((PyObject *)(&PyDict_Type))}; __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_6, __pyx_callargs+1-__pyx_t_12, 1+__pyx_t_12); __Pyx_XDECREF(__pyx_t_11); __pyx_t_11 = 0; - if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 169, __pyx_L1_error) + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 126, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; } __pyx_v_dv = __pyx_t_3; __pyx_t_3 = 0; - /* "opendbc/can/parser_pyx.pyx":171 + /* "opendbc/can/parser_pyx.pyx":128 * dv = defaultdict(dict) * * for i in range(self.dbc[0].vals.size()): # <<<<<<<<<<<<<< @@ -7018,7 +5529,7 @@ static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine___init__(struct __pyx_ for (__pyx_t_14 = 0; __pyx_t_14 < __pyx_t_13; __pyx_t_14+=1) { __pyx_v_i = __pyx_t_14; - /* "opendbc/can/parser_pyx.pyx":172 + /* "opendbc/can/parser_pyx.pyx":129 * * for i in range(self.dbc[0].vals.size()): * val = self.dbc[0].vals[i] # <<<<<<<<<<<<<< @@ -7027,31 +5538,31 @@ static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine___init__(struct __pyx_ */ __pyx_v_val = ((__pyx_v_self->dbc[0]).vals[__pyx_v_i]); - /* "opendbc/can/parser_pyx.pyx":174 + /* "opendbc/can/parser_pyx.pyx":131 * val = self.dbc[0].vals[i] * * sgname = val.name.decode("utf8") # <<<<<<<<<<<<<< * def_val = val.def_val.decode("utf8") * address = val.address */ - __pyx_t_3 = __Pyx_decode_cpp_string(__pyx_v_val.name, 0, PY_SSIZE_T_MAX, NULL, NULL, PyUnicode_DecodeUTF8); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 174, __pyx_L1_error) + __pyx_t_3 = __Pyx_decode_cpp_string(__pyx_v_val.name, 0, PY_SSIZE_T_MAX, NULL, NULL, PyUnicode_DecodeUTF8); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 131, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_XDECREF_SET(__pyx_v_sgname, __pyx_t_3); __pyx_t_3 = 0; - /* "opendbc/can/parser_pyx.pyx":175 + /* "opendbc/can/parser_pyx.pyx":132 * * sgname = val.name.decode("utf8") * def_val = val.def_val.decode("utf8") # <<<<<<<<<<<<<< * address = val.address * msgname = address_to_msg_name[address] */ - __pyx_t_3 = __Pyx_decode_cpp_string(__pyx_v_val.def_val, 0, PY_SSIZE_T_MAX, NULL, NULL, PyUnicode_DecodeUTF8); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 175, __pyx_L1_error) + __pyx_t_3 = __Pyx_decode_cpp_string(__pyx_v_val.def_val, 0, PY_SSIZE_T_MAX, NULL, NULL, PyUnicode_DecodeUTF8); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 132, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_XDECREF_SET(__pyx_v_def_val, __pyx_t_3); __pyx_t_3 = 0; - /* "opendbc/can/parser_pyx.pyx":176 + /* "opendbc/can/parser_pyx.pyx":133 * sgname = val.name.decode("utf8") * def_val = val.def_val.decode("utf8") * address = val.address # <<<<<<<<<<<<<< @@ -7061,29 +5572,29 @@ static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine___init__(struct __pyx_ __pyx_t_10 = __pyx_v_val.address; __pyx_v_address = __pyx_t_10; - /* "opendbc/can/parser_pyx.pyx":177 + /* "opendbc/can/parser_pyx.pyx":134 * def_val = val.def_val.decode("utf8") * address = val.address * msgname = address_to_msg_name[address] # <<<<<<<<<<<<<< * * # separate definition/value pairs */ - __pyx_t_3 = __Pyx_PyInt_From_uint32_t(__pyx_v_address); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 177, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyInt_From_uint32_t(__pyx_v_address); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 134, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); - __pyx_t_6 = __Pyx_PyDict_GetItem(__pyx_v_address_to_msg_name, __pyx_t_3); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 177, __pyx_L1_error) + __pyx_t_6 = __Pyx_PyDict_GetItem(__pyx_v_address_to_msg_name, __pyx_t_3); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 134, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_6); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; __Pyx_XDECREF_SET(__pyx_v_msgname, __pyx_t_6); __pyx_t_6 = 0; - /* "opendbc/can/parser_pyx.pyx":180 + /* "opendbc/can/parser_pyx.pyx":137 * * # separate definition/value pairs * def_val = def_val.split() # <<<<<<<<<<<<<< * values = [int(v) for v in def_val[::2]] * defs = def_val[1::2] */ - __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_v_def_val, __pyx_n_s_split); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 180, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_v_def_val, __pyx_n_s_split); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 137, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __pyx_t_11 = NULL; __pyx_t_12 = 0; @@ -7101,14 +5612,14 @@ static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine___init__(struct __pyx_ PyObject *__pyx_callargs[1] = {__pyx_t_11, }; __pyx_t_6 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_12, 0+__pyx_t_12); __Pyx_XDECREF(__pyx_t_11); __pyx_t_11 = 0; - if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 180, __pyx_L1_error) + if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 137, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_6); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; } __Pyx_DECREF_SET(__pyx_v_def_val, __pyx_t_6); __pyx_t_6 = 0; - /* "opendbc/can/parser_pyx.pyx":181 + /* "opendbc/can/parser_pyx.pyx":138 * # separate definition/value pairs * def_val = def_val.split() * values = [int(v) for v in def_val[::2]] # <<<<<<<<<<<<<< @@ -7116,17 +5627,17 @@ static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine___init__(struct __pyx_ * */ { /* enter inner scope */ - __pyx_t_6 = PyList_New(0); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 181, __pyx_L10_error) + __pyx_t_6 = PyList_New(0); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 138, __pyx_L10_error) __Pyx_GOTREF(__pyx_t_6); - __pyx_t_3 = __Pyx_PyObject_GetItem(__pyx_v_def_val, __pyx_slice__5); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 181, __pyx_L10_error) + __pyx_t_3 = __Pyx_PyObject_GetItem(__pyx_v_def_val, __pyx_slice__2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 138, __pyx_L10_error) __Pyx_GOTREF(__pyx_t_3); if (likely(PyList_CheckExact(__pyx_t_3)) || PyTuple_CheckExact(__pyx_t_3)) { __pyx_t_11 = __pyx_t_3; __Pyx_INCREF(__pyx_t_11); __pyx_t_4 = 0; __pyx_t_15 = NULL; } else { - __pyx_t_4 = -1; __pyx_t_11 = PyObject_GetIter(__pyx_t_3); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 181, __pyx_L10_error) + __pyx_t_4 = -1; __pyx_t_11 = PyObject_GetIter(__pyx_t_3); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 138, __pyx_L10_error) __Pyx_GOTREF(__pyx_t_11); - __pyx_t_15 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_11); if (unlikely(!__pyx_t_15)) __PYX_ERR(0, 181, __pyx_L10_error) + __pyx_t_15 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_11); if (unlikely(!__pyx_t_15)) __PYX_ERR(0, 138, __pyx_L10_error) } __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; for (;;) { @@ -7134,17 +5645,17 @@ static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine___init__(struct __pyx_ if (likely(PyList_CheckExact(__pyx_t_11))) { if (__pyx_t_4 >= PyList_GET_SIZE(__pyx_t_11)) break; #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - __pyx_t_3 = PyList_GET_ITEM(__pyx_t_11, __pyx_t_4); __Pyx_INCREF(__pyx_t_3); __pyx_t_4++; if (unlikely((0 < 0))) __PYX_ERR(0, 181, __pyx_L10_error) + __pyx_t_3 = PyList_GET_ITEM(__pyx_t_11, __pyx_t_4); __Pyx_INCREF(__pyx_t_3); __pyx_t_4++; if (unlikely((0 < 0))) __PYX_ERR(0, 138, __pyx_L10_error) #else - __pyx_t_3 = PySequence_ITEM(__pyx_t_11, __pyx_t_4); __pyx_t_4++; if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 181, __pyx_L10_error) + __pyx_t_3 = PySequence_ITEM(__pyx_t_11, __pyx_t_4); __pyx_t_4++; if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 138, __pyx_L10_error) __Pyx_GOTREF(__pyx_t_3); #endif } else { if (__pyx_t_4 >= PyTuple_GET_SIZE(__pyx_t_11)) break; #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - __pyx_t_3 = PyTuple_GET_ITEM(__pyx_t_11, __pyx_t_4); __Pyx_INCREF(__pyx_t_3); __pyx_t_4++; if (unlikely((0 < 0))) __PYX_ERR(0, 181, __pyx_L10_error) + __pyx_t_3 = PyTuple_GET_ITEM(__pyx_t_11, __pyx_t_4); __Pyx_INCREF(__pyx_t_3); __pyx_t_4++; if (unlikely((0 < 0))) __PYX_ERR(0, 138, __pyx_L10_error) #else - __pyx_t_3 = PySequence_ITEM(__pyx_t_11, __pyx_t_4); __pyx_t_4++; if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 181, __pyx_L10_error) + __pyx_t_3 = PySequence_ITEM(__pyx_t_11, __pyx_t_4); __pyx_t_4++; if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 138, __pyx_L10_error) __Pyx_GOTREF(__pyx_t_3); #endif } @@ -7154,50 +5665,50 @@ static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine___init__(struct __pyx_ PyObject* exc_type = PyErr_Occurred(); if (exc_type) { if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); - else __PYX_ERR(0, 181, __pyx_L10_error) + else __PYX_ERR(0, 138, __pyx_L10_error) } break; } __Pyx_GOTREF(__pyx_t_3); } - __Pyx_XDECREF_SET(__pyx_8genexpr4__pyx_v_v, __pyx_t_3); + __Pyx_XDECREF_SET(__pyx_7genexpr__pyx_v_v, __pyx_t_3); __pyx_t_3 = 0; - __pyx_t_3 = __Pyx_PyNumber_Int(__pyx_8genexpr4__pyx_v_v); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 181, __pyx_L10_error) + __pyx_t_3 = __Pyx_PyNumber_Int(__pyx_7genexpr__pyx_v_v); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 138, __pyx_L10_error) __Pyx_GOTREF(__pyx_t_3); - if (unlikely(__Pyx_ListComp_Append(__pyx_t_6, (PyObject*)__pyx_t_3))) __PYX_ERR(0, 181, __pyx_L10_error) + if (unlikely(__Pyx_ListComp_Append(__pyx_t_6, (PyObject*)__pyx_t_3))) __PYX_ERR(0, 138, __pyx_L10_error) __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; } __Pyx_DECREF(__pyx_t_11); __pyx_t_11 = 0; - __Pyx_XDECREF(__pyx_8genexpr4__pyx_v_v); __pyx_8genexpr4__pyx_v_v = 0; + __Pyx_XDECREF(__pyx_7genexpr__pyx_v_v); __pyx_7genexpr__pyx_v_v = 0; goto __pyx_L14_exit_scope; __pyx_L10_error:; - __Pyx_XDECREF(__pyx_8genexpr4__pyx_v_v); __pyx_8genexpr4__pyx_v_v = 0; + __Pyx_XDECREF(__pyx_7genexpr__pyx_v_v); __pyx_7genexpr__pyx_v_v = 0; goto __pyx_L1_error; __pyx_L14_exit_scope:; } /* exit inner scope */ __Pyx_XDECREF_SET(__pyx_v_values, ((PyObject*)__pyx_t_6)); __pyx_t_6 = 0; - /* "opendbc/can/parser_pyx.pyx":182 + /* "opendbc/can/parser_pyx.pyx":139 * def_val = def_val.split() * values = [int(v) for v in def_val[::2]] * defs = def_val[1::2] # <<<<<<<<<<<<<< * * # two ways to lookup: address or msg name */ - __pyx_t_6 = __Pyx_PyObject_GetItem(__pyx_v_def_val, __pyx_slice__6); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 182, __pyx_L1_error) + __pyx_t_6 = __Pyx_PyObject_GetItem(__pyx_v_def_val, __pyx_slice__3); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 139, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_6); __Pyx_XDECREF_SET(__pyx_v_defs, __pyx_t_6); __pyx_t_6 = 0; - /* "opendbc/can/parser_pyx.pyx":185 + /* "opendbc/can/parser_pyx.pyx":142 * * # two ways to lookup: address or msg name * dv[address][sgname] = dict(zip(values, defs)) # <<<<<<<<<<<<<< * dv[msgname][sgname] = dv[address][sgname] * */ - __pyx_t_6 = PyTuple_New(2); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 185, __pyx_L1_error) + __pyx_t_6 = PyTuple_New(2); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 142, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_6); __Pyx_INCREF(__pyx_v_values); __Pyx_GIVEREF(__pyx_v_values); @@ -7205,43 +5716,43 @@ static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine___init__(struct __pyx_ __Pyx_INCREF(__pyx_v_defs); __Pyx_GIVEREF(__pyx_v_defs); PyTuple_SET_ITEM(__pyx_t_6, 1, __pyx_v_defs); - __pyx_t_11 = __Pyx_PyObject_Call(__pyx_builtin_zip, __pyx_t_6, NULL); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 185, __pyx_L1_error) + __pyx_t_11 = __Pyx_PyObject_Call(__pyx_builtin_zip, __pyx_t_6, NULL); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 142, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_11); __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; - __pyx_t_6 = __Pyx_PyObject_CallOneArg(((PyObject *)(&PyDict_Type)), __pyx_t_11); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 185, __pyx_L1_error) + __pyx_t_6 = __Pyx_PyObject_CallOneArg(((PyObject *)(&PyDict_Type)), __pyx_t_11); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 142, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_6); __Pyx_DECREF(__pyx_t_11); __pyx_t_11 = 0; - __pyx_t_11 = __Pyx_GetItemInt(__pyx_v_dv, __pyx_v_address, uint32_t, 0, __Pyx_PyInt_From_uint32_t, 0, 0, 1); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 185, __pyx_L1_error) + __pyx_t_11 = __Pyx_GetItemInt(__pyx_v_dv, __pyx_v_address, uint32_t, 0, __Pyx_PyInt_From_uint32_t, 0, 0, 1); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 142, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_11); - if (unlikely((PyObject_SetItem(__pyx_t_11, __pyx_v_sgname, __pyx_t_6) < 0))) __PYX_ERR(0, 185, __pyx_L1_error) + if (unlikely((PyObject_SetItem(__pyx_t_11, __pyx_v_sgname, __pyx_t_6) < 0))) __PYX_ERR(0, 142, __pyx_L1_error) __Pyx_DECREF(__pyx_t_11); __pyx_t_11 = 0; __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; - /* "opendbc/can/parser_pyx.pyx":186 + /* "opendbc/can/parser_pyx.pyx":143 * # two ways to lookup: address or msg name * dv[address][sgname] = dict(zip(values, defs)) * dv[msgname][sgname] = dv[address][sgname] # <<<<<<<<<<<<<< * * self.dv = dict(dv) */ - __pyx_t_6 = __Pyx_GetItemInt(__pyx_v_dv, __pyx_v_address, uint32_t, 0, __Pyx_PyInt_From_uint32_t, 0, 0, 1); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 186, __pyx_L1_error) + __pyx_t_6 = __Pyx_GetItemInt(__pyx_v_dv, __pyx_v_address, uint32_t, 0, __Pyx_PyInt_From_uint32_t, 0, 0, 1); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 143, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_6); - __pyx_t_11 = __Pyx_PyObject_GetItem(__pyx_t_6, __pyx_v_sgname); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 186, __pyx_L1_error) + __pyx_t_11 = __Pyx_PyObject_GetItem(__pyx_t_6, __pyx_v_sgname); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 143, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_11); __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; - __pyx_t_6 = __Pyx_PyObject_GetItem(__pyx_v_dv, __pyx_v_msgname); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 186, __pyx_L1_error) + __pyx_t_6 = __Pyx_PyObject_GetItem(__pyx_v_dv, __pyx_v_msgname); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 143, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_6); - if (unlikely((PyObject_SetItem(__pyx_t_6, __pyx_v_sgname, __pyx_t_11) < 0))) __PYX_ERR(0, 186, __pyx_L1_error) + if (unlikely((PyObject_SetItem(__pyx_t_6, __pyx_v_sgname, __pyx_t_11) < 0))) __PYX_ERR(0, 143, __pyx_L1_error) __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; __Pyx_DECREF(__pyx_t_11); __pyx_t_11 = 0; } - /* "opendbc/can/parser_pyx.pyx":188 + /* "opendbc/can/parser_pyx.pyx":145 * dv[msgname][sgname] = dv[address][sgname] * * self.dv = dict(dv) # <<<<<<<<<<<<<< */ - __pyx_t_11 = __Pyx_PyObject_CallOneArg(((PyObject *)(&PyDict_Type)), __pyx_v_dv); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 188, __pyx_L1_error) + __pyx_t_11 = __Pyx_PyObject_CallOneArg(((PyObject *)(&PyDict_Type)), __pyx_v_dv); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 145, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_11); __Pyx_GIVEREF(__pyx_t_11); __Pyx_GOTREF(__pyx_v_self->dv); @@ -7249,7 +5760,7 @@ static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine___init__(struct __pyx_ __pyx_v_self->dv = ((PyObject*)__pyx_t_11); __pyx_t_11 = 0; - /* "opendbc/can/parser_pyx.pyx":155 + /* "opendbc/can/parser_pyx.pyx":112 * string dbc_name * * def __init__(self, dbc_name): # <<<<<<<<<<<<<< @@ -7275,12 +5786,12 @@ static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine___init__(struct __pyx_ __Pyx_XDECREF(__pyx_v_msgname); __Pyx_XDECREF(__pyx_v_values); __Pyx_XDECREF(__pyx_v_defs); - __Pyx_XDECREF(__pyx_8genexpr4__pyx_v_v); + __Pyx_XDECREF(__pyx_7genexpr__pyx_v_v); __Pyx_RefNannyFinishContext(); return __pyx_r; } -/* "opendbc/can/parser_pyx.pyx":152 +/* "opendbc/can/parser_pyx.pyx":109 * * cdef public: * dict dv # <<<<<<<<<<<<<< @@ -7340,7 +5851,7 @@ static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_2dv_2__set__(struct __ const char *__pyx_filename = NULL; int __pyx_clineno = 0; __Pyx_RefNannySetupContext("__set__", 0); - if (!(likely(PyDict_CheckExact(__pyx_v_value))||((__pyx_v_value) == Py_None) || __Pyx_RaiseUnexpectedTypeError("dict", __pyx_v_value))) __PYX_ERR(0, 152, __pyx_L1_error) + if (!(likely(PyDict_CheckExact(__pyx_v_value))||((__pyx_v_value) == Py_None) || __Pyx_RaiseUnexpectedTypeError("dict", __pyx_v_value))) __PYX_ERR(0, 109, __pyx_L1_error) __pyx_t_1 = __pyx_v_value; __Pyx_INCREF(__pyx_t_1); __Pyx_GIVEREF(__pyx_t_1); @@ -7391,7 +5902,7 @@ static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_2dv_4__del__(struct __ return __pyx_r; } -/* "opendbc/can/parser_pyx.pyx":153 +/* "opendbc/can/parser_pyx.pyx":110 * cdef public: * dict dv * string dbc_name # <<<<<<<<<<<<<< @@ -7422,7 +5933,7 @@ static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_8dbc_name___get_ int __pyx_clineno = 0; __Pyx_RefNannySetupContext("__get__", 0); __Pyx_XDECREF(__pyx_r); - __pyx_t_1 = __pyx_convert_PyBytes_string_to_py_std__in_string(__pyx_v_self->dbc_name); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 153, __pyx_L1_error) + __pyx_t_1 = __pyx_convert_PyBytes_string_to_py_std__in_string(__pyx_v_self->dbc_name); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 110, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __pyx_r = __pyx_t_1; __pyx_t_1 = 0; @@ -7461,7 +5972,7 @@ static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_8dbc_name_2__set__(str const char *__pyx_filename = NULL; int __pyx_clineno = 0; __Pyx_RefNannySetupContext("__set__", 0); - __pyx_t_1 = __pyx_convert_string_from_py_std__in_string(__pyx_v_value); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 153, __pyx_L1_error) + __pyx_t_1 = __pyx_convert_string_from_py_std__in_string(__pyx_v_value); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 110, __pyx_L1_error) __pyx_v_self->dbc_name = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_1); /* function exit code */ @@ -7671,7 +6182,6 @@ static PyObject *__pyx_tp_new_7opendbc_3can_10parser_pyx_CANParser(PyTypeObject if (unlikely(!o)) return 0; #endif p = ((struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *)o); - new((void*)&(p->address_to_msg_name)) std::map (); new((void*)&(p->can_values)) std::vector (); new((void*)&(p->dbc_name)) std::string(); p->vl = ((PyObject*)Py_None); Py_INCREF(Py_None); @@ -7690,7 +6200,6 @@ static void __pyx_tp_dealloc_7opendbc_3can_10parser_pyx_CANParser(PyObject *o) { } #endif PyObject_GC_UnTrack(o); - __Pyx_call_destructor(p->address_to_msg_name); __Pyx_call_destructor(p->can_values); __Pyx_call_destructor(p->dbc_name); Py_CLEAR(p->vl); @@ -8064,470 +6573,6 @@ static PyTypeObject __pyx_type_7opendbc_3can_10parser_pyx_CANDefine = { }; #endif -static struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ *__pyx_freelist_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__[8]; -static int __pyx_freecount_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ = 0; - -static PyObject *__pyx_tp_new_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { - PyObject *o; - #if CYTHON_COMPILING_IN_LIMITED_API - allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); - o = alloc_func(t, 0); - #else - if (CYTHON_COMPILING_IN_CPYTHON && likely((int)(__pyx_freecount_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ > 0) & (int)(t->tp_basicsize == sizeof(struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__)))) { - o = (PyObject*)__pyx_freelist_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__[--__pyx_freecount_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__]; - memset(o, 0, sizeof(struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__)); - (void) PyObject_INIT(o, t); - PyObject_GC_Track(o); - } else { - o = (*t->tp_alloc)(t, 0); - if (unlikely(!o)) return 0; - } - #endif - return o; -} - -static void __pyx_tp_dealloc_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__(PyObject *o) { - struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ *p = (struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ *)o; - #if CYTHON_USE_TP_FINALIZE - if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { - if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__) { - if (PyObject_CallFinalizerFromDealloc(o)) return; - } - } - #endif - PyObject_GC_UnTrack(o); - Py_CLEAR(p->__pyx_v_self); - if (CYTHON_COMPILING_IN_CPYTHON && ((int)(__pyx_freecount_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ < 8) & (int)(Py_TYPE(o)->tp_basicsize == sizeof(struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__)))) { - __pyx_freelist_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__[__pyx_freecount_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__++] = ((struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ *)o); - } else { - (*Py_TYPE(o)->tp_free)(o); - } -} - -static int __pyx_tp_traverse_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__(PyObject *o, visitproc v, void *a) { - int e; - struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ *p = (struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ *)o; - if (p->__pyx_v_self) { - e = (*v)(((PyObject *)p->__pyx_v_self), a); if (e) return e; - } - return 0; -} - -static int __pyx_tp_clear_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__(PyObject *o) { - PyObject* tmp; - struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ *p = (struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ *)o; - tmp = ((PyObject*)p->__pyx_v_self); - p->__pyx_v_self = ((struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *)Py_None); Py_INCREF(Py_None); - Py_XDECREF(tmp); - return 0; -} -#if CYTHON_USE_TYPE_SPECS -static PyType_Slot __pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct____init___slots[] = { - {Py_tp_dealloc, (void *)__pyx_tp_dealloc_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__}, - {Py_tp_traverse, (void *)__pyx_tp_traverse_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__}, - {Py_tp_clear, (void *)__pyx_tp_clear_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__}, - {Py_tp_new, (void *)__pyx_tp_new_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__}, - {0, 0}, -}; -static PyType_Spec __pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct____init___spec = { - "opendbc.can.parser_pyx.__pyx_scope_struct____init__", - sizeof(struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__), - 0, - Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_HAVE_FINALIZE, - __pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct____init___slots, -}; -#else - -static PyTypeObject __pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ = { - PyVarObject_HEAD_INIT(0, 0) - "opendbc.can.parser_pyx.""__pyx_scope_struct____init__", /*tp_name*/ - sizeof(struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__), /*tp_basicsize*/ - 0, /*tp_itemsize*/ - __pyx_tp_dealloc_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__, /*tp_dealloc*/ - #if PY_VERSION_HEX < 0x030800b4 - 0, /*tp_print*/ - #endif - #if PY_VERSION_HEX >= 0x030800b4 - 0, /*tp_vectorcall_offset*/ - #endif - 0, /*tp_getattr*/ - 0, /*tp_setattr*/ - #if PY_MAJOR_VERSION < 3 - 0, /*tp_compare*/ - #endif - #if PY_MAJOR_VERSION >= 3 - 0, /*tp_as_async*/ - #endif - 0, /*tp_repr*/ - 0, /*tp_as_number*/ - 0, /*tp_as_sequence*/ - 0, /*tp_as_mapping*/ - 0, /*tp_hash*/ - 0, /*tp_call*/ - 0, /*tp_str*/ - 0, /*tp_getattro*/ - 0, /*tp_setattro*/ - 0, /*tp_as_buffer*/ - Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_HAVE_FINALIZE, /*tp_flags*/ - 0, /*tp_doc*/ - __pyx_tp_traverse_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__, /*tp_traverse*/ - __pyx_tp_clear_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__, /*tp_clear*/ - 0, /*tp_richcompare*/ - 0, /*tp_weaklistoffset*/ - 0, /*tp_iter*/ - 0, /*tp_iternext*/ - 0, /*tp_methods*/ - 0, /*tp_members*/ - 0, /*tp_getset*/ - 0, /*tp_base*/ - 0, /*tp_dict*/ - 0, /*tp_descr_get*/ - 0, /*tp_descr_set*/ - #if !CYTHON_USE_TYPE_SPECS - 0, /*tp_dictoffset*/ - #endif - 0, /*tp_init*/ - 0, /*tp_alloc*/ - __pyx_tp_new_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__, /*tp_new*/ - 0, /*tp_free*/ - 0, /*tp_is_gc*/ - 0, /*tp_bases*/ - 0, /*tp_mro*/ - 0, /*tp_cache*/ - 0, /*tp_subclasses*/ - 0, /*tp_weaklist*/ - 0, /*tp_del*/ - 0, /*tp_version_tag*/ - #if PY_VERSION_HEX >= 0x030400a1 - #if CYTHON_USE_TP_FINALIZE - 0, /*tp_finalize*/ - #else - NULL, /*tp_finalize*/ - #endif - #endif - #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) - 0, /*tp_vectorcall*/ - #endif - #if __PYX_NEED_TP_PRINT_SLOT == 1 - 0, /*tp_print*/ - #endif - #if PY_VERSION_HEX >= 0x030C0000 - 0, /*tp_watched*/ - #endif - #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 - 0, /*tp_pypy_flags*/ - #endif -}; -#endif - -static struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr *__pyx_freelist_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr[8]; -static int __pyx_freecount_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr = 0; - -static PyObject *__pyx_tp_new_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { - PyObject *o; - #if CYTHON_COMPILING_IN_LIMITED_API - allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); - o = alloc_func(t, 0); - #else - if (CYTHON_COMPILING_IN_CPYTHON && likely((int)(__pyx_freecount_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr > 0) & (int)(t->tp_basicsize == sizeof(struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr)))) { - o = (PyObject*)__pyx_freelist_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr[--__pyx_freecount_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr]; - memset(o, 0, sizeof(struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr)); - (void) PyObject_INIT(o, t); - PyObject_GC_Track(o); - } else { - o = (*t->tp_alloc)(t, 0); - if (unlikely(!o)) return 0; - } - #endif - return o; -} - -static void __pyx_tp_dealloc_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr(PyObject *o) { - struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr *p = (struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr *)o; - #if CYTHON_USE_TP_FINALIZE - if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { - if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr) { - if (PyObject_CallFinalizerFromDealloc(o)) return; - } - } - #endif - PyObject_GC_UnTrack(o); - Py_CLEAR(p->__pyx_outer_scope); - Py_CLEAR(p->__pyx_genexpr_arg_0); - Py_CLEAR(p->__pyx_v_addr); - if (CYTHON_COMPILING_IN_CPYTHON && ((int)(__pyx_freecount_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr < 8) & (int)(Py_TYPE(o)->tp_basicsize == sizeof(struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr)))) { - __pyx_freelist_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr[__pyx_freecount_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr++] = ((struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr *)o); - } else { - (*Py_TYPE(o)->tp_free)(o); - } -} - -static int __pyx_tp_traverse_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr(PyObject *o, visitproc v, void *a) { - int e; - struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr *p = (struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr *)o; - if (p->__pyx_outer_scope) { - e = (*v)(((PyObject *)p->__pyx_outer_scope), a); if (e) return e; - } - if (p->__pyx_genexpr_arg_0) { - e = (*v)(p->__pyx_genexpr_arg_0, a); if (e) return e; - } - if (p->__pyx_v_addr) { - e = (*v)(p->__pyx_v_addr, a); if (e) return e; - } - return 0; -} -#if CYTHON_USE_TYPE_SPECS -static PyType_Slot __pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr_slots[] = { - {Py_tp_dealloc, (void *)__pyx_tp_dealloc_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr}, - {Py_tp_traverse, (void *)__pyx_tp_traverse_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr}, - {Py_tp_new, (void *)__pyx_tp_new_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr}, - {0, 0}, -}; -static PyType_Spec __pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr_spec = { - "opendbc.can.parser_pyx.__pyx_scope_struct_1_genexpr", - sizeof(struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr), - 0, - Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_HAVE_FINALIZE, - __pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr_slots, -}; -#else - -static PyTypeObject __pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr = { - PyVarObject_HEAD_INIT(0, 0) - "opendbc.can.parser_pyx.""__pyx_scope_struct_1_genexpr", /*tp_name*/ - sizeof(struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr), /*tp_basicsize*/ - 0, /*tp_itemsize*/ - __pyx_tp_dealloc_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr, /*tp_dealloc*/ - #if PY_VERSION_HEX < 0x030800b4 - 0, /*tp_print*/ - #endif - #if PY_VERSION_HEX >= 0x030800b4 - 0, /*tp_vectorcall_offset*/ - #endif - 0, /*tp_getattr*/ - 0, /*tp_setattr*/ - #if PY_MAJOR_VERSION < 3 - 0, /*tp_compare*/ - #endif - #if PY_MAJOR_VERSION >= 3 - 0, /*tp_as_async*/ - #endif - 0, /*tp_repr*/ - 0, /*tp_as_number*/ - 0, /*tp_as_sequence*/ - 0, /*tp_as_mapping*/ - 0, /*tp_hash*/ - 0, /*tp_call*/ - 0, /*tp_str*/ - 0, /*tp_getattro*/ - 0, /*tp_setattro*/ - 0, /*tp_as_buffer*/ - Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_HAVE_FINALIZE, /*tp_flags*/ - 0, /*tp_doc*/ - __pyx_tp_traverse_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr, /*tp_traverse*/ - 0, /*tp_clear*/ - 0, /*tp_richcompare*/ - 0, /*tp_weaklistoffset*/ - 0, /*tp_iter*/ - 0, /*tp_iternext*/ - 0, /*tp_methods*/ - 0, /*tp_members*/ - 0, /*tp_getset*/ - 0, /*tp_base*/ - 0, /*tp_dict*/ - 0, /*tp_descr_get*/ - 0, /*tp_descr_set*/ - #if !CYTHON_USE_TYPE_SPECS - 0, /*tp_dictoffset*/ - #endif - 0, /*tp_init*/ - 0, /*tp_alloc*/ - __pyx_tp_new_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr, /*tp_new*/ - 0, /*tp_free*/ - 0, /*tp_is_gc*/ - 0, /*tp_bases*/ - 0, /*tp_mro*/ - 0, /*tp_cache*/ - 0, /*tp_subclasses*/ - 0, /*tp_weaklist*/ - 0, /*tp_del*/ - 0, /*tp_version_tag*/ - #if PY_VERSION_HEX >= 0x030400a1 - #if CYTHON_USE_TP_FINALIZE - 0, /*tp_finalize*/ - #else - NULL, /*tp_finalize*/ - #endif - #endif - #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) - 0, /*tp_vectorcall*/ - #endif - #if __PYX_NEED_TP_PRINT_SLOT == 1 - 0, /*tp_print*/ - #endif - #if PY_VERSION_HEX >= 0x030C0000 - 0, /*tp_watched*/ - #endif - #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 - 0, /*tp_pypy_flags*/ - #endif -}; -#endif - -static struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr *__pyx_freelist_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr[8]; -static int __pyx_freecount_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr = 0; - -static PyObject *__pyx_tp_new_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { - PyObject *o; - #if CYTHON_COMPILING_IN_LIMITED_API - allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); - o = alloc_func(t, 0); - #else - if (CYTHON_COMPILING_IN_CPYTHON && likely((int)(__pyx_freecount_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr > 0) & (int)(t->tp_basicsize == sizeof(struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr)))) { - o = (PyObject*)__pyx_freelist_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr[--__pyx_freecount_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr]; - memset(o, 0, sizeof(struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr)); - (void) PyObject_INIT(o, t); - PyObject_GC_Track(o); - } else { - o = (*t->tp_alloc)(t, 0); - if (unlikely(!o)) return 0; - } - #endif - return o; -} - -static void __pyx_tp_dealloc_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr(PyObject *o) { - struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr *p = (struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr *)o; - #if CYTHON_USE_TP_FINALIZE - if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { - if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr) { - if (PyObject_CallFinalizerFromDealloc(o)) return; - } - } - #endif - PyObject_GC_UnTrack(o); - Py_CLEAR(p->__pyx_genexpr_arg_0); - Py_CLEAR(p->__pyx_v__); - Py_CLEAR(p->__pyx_v_address); - if (CYTHON_COMPILING_IN_CPYTHON && ((int)(__pyx_freecount_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr < 8) & (int)(Py_TYPE(o)->tp_basicsize == sizeof(struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr)))) { - __pyx_freelist_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr[__pyx_freecount_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr++] = ((struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr *)o); - } else { - (*Py_TYPE(o)->tp_free)(o); - } -} - -static int __pyx_tp_traverse_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr(PyObject *o, visitproc v, void *a) { - int e; - struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr *p = (struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr *)o; - if (p->__pyx_genexpr_arg_0) { - e = (*v)(p->__pyx_genexpr_arg_0, a); if (e) return e; - } - if (p->__pyx_v__) { - e = (*v)(p->__pyx_v__, a); if (e) return e; - } - if (p->__pyx_v_address) { - e = (*v)(p->__pyx_v_address, a); if (e) return e; - } - return 0; -} -#if CYTHON_USE_TYPE_SPECS -static PyType_Slot __pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr_slots[] = { - {Py_tp_dealloc, (void *)__pyx_tp_dealloc_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr}, - {Py_tp_traverse, (void *)__pyx_tp_traverse_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr}, - {Py_tp_new, (void *)__pyx_tp_new_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr}, - {0, 0}, -}; -static PyType_Spec __pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr_spec = { - "opendbc.can.parser_pyx.__pyx_scope_struct_2_genexpr", - sizeof(struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr), - 0, - Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_HAVE_FINALIZE, - __pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr_slots, -}; -#else - -static PyTypeObject __pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr = { - PyVarObject_HEAD_INIT(0, 0) - "opendbc.can.parser_pyx.""__pyx_scope_struct_2_genexpr", /*tp_name*/ - sizeof(struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr), /*tp_basicsize*/ - 0, /*tp_itemsize*/ - __pyx_tp_dealloc_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr, /*tp_dealloc*/ - #if PY_VERSION_HEX < 0x030800b4 - 0, /*tp_print*/ - #endif - #if PY_VERSION_HEX >= 0x030800b4 - 0, /*tp_vectorcall_offset*/ - #endif - 0, /*tp_getattr*/ - 0, /*tp_setattr*/ - #if PY_MAJOR_VERSION < 3 - 0, /*tp_compare*/ - #endif - #if PY_MAJOR_VERSION >= 3 - 0, /*tp_as_async*/ - #endif - 0, /*tp_repr*/ - 0, /*tp_as_number*/ - 0, /*tp_as_sequence*/ - 0, /*tp_as_mapping*/ - 0, /*tp_hash*/ - 0, /*tp_call*/ - 0, /*tp_str*/ - 0, /*tp_getattro*/ - 0, /*tp_setattro*/ - 0, /*tp_as_buffer*/ - Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_HAVE_FINALIZE, /*tp_flags*/ - 0, /*tp_doc*/ - __pyx_tp_traverse_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr, /*tp_traverse*/ - 0, /*tp_clear*/ - 0, /*tp_richcompare*/ - 0, /*tp_weaklistoffset*/ - 0, /*tp_iter*/ - 0, /*tp_iternext*/ - 0, /*tp_methods*/ - 0, /*tp_members*/ - 0, /*tp_getset*/ - 0, /*tp_base*/ - 0, /*tp_dict*/ - 0, /*tp_descr_get*/ - 0, /*tp_descr_set*/ - #if !CYTHON_USE_TYPE_SPECS - 0, /*tp_dictoffset*/ - #endif - 0, /*tp_init*/ - 0, /*tp_alloc*/ - __pyx_tp_new_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr, /*tp_new*/ - 0, /*tp_free*/ - 0, /*tp_is_gc*/ - 0, /*tp_bases*/ - 0, /*tp_mro*/ - 0, /*tp_cache*/ - 0, /*tp_subclasses*/ - 0, /*tp_weaklist*/ - 0, /*tp_del*/ - 0, /*tp_version_tag*/ - #if PY_VERSION_HEX >= 0x030400a1 - #if CYTHON_USE_TP_FINALIZE - 0, /*tp_finalize*/ - #else - NULL, /*tp_finalize*/ - #endif - #endif - #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) - 0, /*tp_vectorcall*/ - #endif - #if __PYX_NEED_TP_PRINT_SLOT == 1 - 0, /*tp_print*/ - #endif - #if PY_VERSION_HEX >= 0x030C0000 - 0, /*tp_watched*/ - #endif - #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 - 0, /*tp_pypy_flags*/ - #endif -}; -#endif - static PyMethodDef __pyx_methods[] = { {0, 0, 0, 0} }; @@ -8554,60 +6599,43 @@ static int __Pyx_CreateStringTabAndInitStrings(void) { {&__pyx_n_s_CANParser_update_strings, __pyx_k_CANParser_update_strings, sizeof(__pyx_k_CANParser_update_strings), 0, 0, 1, 1}, {&__pyx_kp_u_Can_t_find_DBC, __pyx_k_Can_t_find_DBC, sizeof(__pyx_k_Can_t_find_DBC), 0, 1, 0, 0}, {&__pyx_kp_u_Can_t_find_DBC_2, __pyx_k_Can_t_find_DBC_2, sizeof(__pyx_k_Can_t_find_DBC_2), 0, 1, 0, 0}, - {&__pyx_kp_u_DBC, __pyx_k_DBC, sizeof(__pyx_k_DBC), 0, 1, 0, 0}, {&__pyx_n_s_MemoryError, __pyx_k_MemoryError, sizeof(__pyx_k_MemoryError), 0, 0, 1, 1}, - {&__pyx_kp_u_None, __pyx_k_None, sizeof(__pyx_k_None), 0, 1, 0, 0}, {&__pyx_n_s_Number, __pyx_k_Number, sizeof(__pyx_k_Number), 0, 0, 1, 1}, {&__pyx_n_s_RuntimeError, __pyx_k_RuntimeError, sizeof(__pyx_k_RuntimeError), 0, 0, 1, 1}, {&__pyx_n_s_TypeError, __pyx_k_TypeError, sizeof(__pyx_k_TypeError), 0, 0, 1, 1}, - {&__pyx_kp_u_Unchecked_addrs, __pyx_k_Unchecked_addrs, sizeof(__pyx_k_Unchecked_addrs), 0, 1, 0, 0}, - {&__pyx_n_s__18, __pyx_k__18, sizeof(__pyx_k__18), 0, 0, 1, 1}, - {&__pyx_kp_u__2, __pyx_k__2, sizeof(__pyx_k__2), 0, 1, 0, 0}, - {&__pyx_kp_u__3, __pyx_k__3, sizeof(__pyx_k__3), 0, 1, 0, 0}, - {&__pyx_kp_u__4, __pyx_k__4, sizeof(__pyx_k__4), 0, 1, 0, 0}, - {&__pyx_n_s__7, __pyx_k__7, sizeof(__pyx_k__7), 0, 0, 1, 1}, - {&__pyx_kp_u__8, __pyx_k__8, sizeof(__pyx_k__8), 0, 1, 0, 0}, - {&__pyx_n_s_add, __pyx_k_add, sizeof(__pyx_k_add), 0, 0, 1, 1}, - {&__pyx_n_s_args, __pyx_k_args, sizeof(__pyx_k_args), 0, 0, 1, 1}, + {&__pyx_n_s__15, __pyx_k__15, sizeof(__pyx_k__15), 0, 0, 1, 1}, + {&__pyx_n_s__4, __pyx_k__4, sizeof(__pyx_k__4), 0, 0, 1, 1}, + {&__pyx_kp_u__5, __pyx_k__5, sizeof(__pyx_k__5), 0, 1, 0, 0}, {&__pyx_n_s_asyncio_coroutines, __pyx_k_asyncio_coroutines, sizeof(__pyx_k_asyncio_coroutines), 0, 0, 1, 1}, {&__pyx_n_s_bus, __pyx_k_bus, sizeof(__pyx_k_bus), 0, 0, 1, 1}, - {&__pyx_n_s_checks, __pyx_k_checks, sizeof(__pyx_k_checks), 0, 0, 1, 1}, {&__pyx_n_s_class_getitem, __pyx_k_class_getitem, sizeof(__pyx_k_class_getitem), 0, 0, 1, 1}, {&__pyx_n_s_clear, __pyx_k_clear, sizeof(__pyx_k_clear), 0, 0, 1, 1}, {&__pyx_n_s_cline_in_traceback, __pyx_k_cline_in_traceback, sizeof(__pyx_k_cline_in_traceback), 0, 0, 1, 1}, - {&__pyx_n_s_close, __pyx_k_close, sizeof(__pyx_k_close), 0, 0, 1, 1}, {&__pyx_n_s_collections, __pyx_k_collections, sizeof(__pyx_k_collections), 0, 0, 1, 1}, {&__pyx_kp_u_could_not_find_message, __pyx_k_could_not_find_message, sizeof(__pyx_k_could_not_find_message), 0, 1, 0, 0}, - {&__pyx_kp_u_could_not_find_signal, __pyx_k_could_not_find_signal, sizeof(__pyx_k_could_not_find_signal), 0, 1, 0, 0}, {&__pyx_n_s_cv, __pyx_k_cv, sizeof(__pyx_k_cv), 0, 0, 1, 1}, {&__pyx_n_s_cv_name, __pyx_k_cv_name, sizeof(__pyx_k_cv_name), 0, 0, 1, 1}, {&__pyx_n_s_dbc_name, __pyx_k_dbc_name, sizeof(__pyx_k_dbc_name), 0, 0, 1, 1}, {&__pyx_n_s_defaultdict, __pyx_k_defaultdict, sizeof(__pyx_k_defaultdict), 0, 0, 1, 1}, {&__pyx_kp_u_disable, __pyx_k_disable, sizeof(__pyx_k_disable), 0, 1, 0, 0}, {&__pyx_kp_u_enable, __pyx_k_enable, sizeof(__pyx_k_enable), 0, 1, 0, 0}, - {&__pyx_n_s_enforce_checks, __pyx_k_enforce_checks, sizeof(__pyx_k_enforce_checks), 0, 0, 1, 1}, {&__pyx_kp_u_gc, __pyx_k_gc, sizeof(__pyx_k_gc), 0, 1, 0, 0}, - {&__pyx_n_s_genexpr, __pyx_k_genexpr, sizeof(__pyx_k_genexpr), 0, 0, 1, 1}, {&__pyx_n_s_get, __pyx_k_get, sizeof(__pyx_k_get), 0, 0, 1, 1}, {&__pyx_n_s_getstate, __pyx_k_getstate, sizeof(__pyx_k_getstate), 0, 0, 1, 1}, - {&__pyx_n_s_hex, __pyx_k_hex, sizeof(__pyx_k_hex), 0, 0, 1, 1}, {&__pyx_n_s_import, __pyx_k_import, sizeof(__pyx_k_import), 0, 0, 1, 1}, - {&__pyx_kp_u_in, __pyx_k_in, sizeof(__pyx_k_in), 0, 1, 0, 0}, {&__pyx_kp_u_in_DBC, __pyx_k_in_DBC, sizeof(__pyx_k_in_DBC), 0, 1, 0, 0}, - {&__pyx_n_s_init___locals_genexpr, __pyx_k_init___locals_genexpr, sizeof(__pyx_k_init___locals_genexpr), 0, 0, 1, 1}, {&__pyx_n_s_initializing, __pyx_k_initializing, sizeof(__pyx_k_initializing), 0, 0, 1, 1}, {&__pyx_n_s_is_coroutine, __pyx_k_is_coroutine, sizeof(__pyx_k_is_coroutine), 0, 0, 1, 1}, {&__pyx_kp_u_isenabled, __pyx_k_isenabled, sizeof(__pyx_k_isenabled), 0, 1, 0, 0}, {&__pyx_n_s_it, __pyx_k_it, sizeof(__pyx_k_it), 0, 0, 1, 1}, - {&__pyx_n_s_items, __pyx_k_items, sizeof(__pyx_k_items), 0, 0, 1, 1}, {&__pyx_n_s_l, __pyx_k_l, sizeof(__pyx_k_l), 0, 0, 1, 1}, {&__pyx_n_s_main, __pyx_k_main, sizeof(__pyx_k_main), 0, 0, 1, 1}, + {&__pyx_n_s_messages, __pyx_k_messages, sizeof(__pyx_k_messages), 0, 0, 1, 1}, {&__pyx_n_s_name, __pyx_k_name, sizeof(__pyx_k_name), 0, 0, 1, 1}, {&__pyx_n_s_new_vals, __pyx_k_new_vals, sizeof(__pyx_k_new_vals), 0, 0, 1, 1}, {&__pyx_n_s_numbers, __pyx_k_numbers, sizeof(__pyx_k_numbers), 0, 0, 1, 1}, {&__pyx_n_s_opendbc_can_parser_pyx, __pyx_k_opendbc_can_parser_pyx, sizeof(__pyx_k_opendbc_can_parser_pyx), 0, 0, 1, 1}, {&__pyx_kp_s_opendbc_can_parser_pyx_pyx, __pyx_k_opendbc_can_parser_pyx_pyx, sizeof(__pyx_k_opendbc_can_parser_pyx_pyx), 0, 0, 1, 0}, - {&__pyx_n_s_print, __pyx_k_print, sizeof(__pyx_k_print), 0, 0, 1, 1}, {&__pyx_n_s_pyx_state, __pyx_k_pyx_state, sizeof(__pyx_k_pyx_state), 0, 0, 1, 1}, {&__pyx_n_s_range, __pyx_k_range, sizeof(__pyx_k_range), 0, 0, 1, 1}, {&__pyx_n_s_reduce, __pyx_k_reduce, sizeof(__pyx_k_reduce), 0, 0, 1, 1}, @@ -8616,18 +6644,14 @@ static int __Pyx_CreateStringTabAndInitStrings(void) { {&__pyx_n_s_self, __pyx_k_self, sizeof(__pyx_k_self), 0, 0, 1, 1}, {&__pyx_kp_s_self_can_self_dbc_cannot_be_conv, __pyx_k_self_can_self_dbc_cannot_be_conv, sizeof(__pyx_k_self_can_self_dbc_cannot_be_conv), 0, 0, 1, 0}, {&__pyx_kp_s_self_dbc_cannot_be_converted_to, __pyx_k_self_dbc_cannot_be_converted_to, sizeof(__pyx_k_self_dbc_cannot_be_converted_to), 0, 0, 1, 0}, - {&__pyx_n_s_send, __pyx_k_send, sizeof(__pyx_k_send), 0, 0, 1, 1}, {&__pyx_n_s_sendcan, __pyx_k_sendcan, sizeof(__pyx_k_sendcan), 0, 0, 1, 1}, {&__pyx_n_s_setstate, __pyx_k_setstate, sizeof(__pyx_k_setstate), 0, 0, 1, 1}, {&__pyx_n_s_setstate_cython, __pyx_k_setstate_cython, sizeof(__pyx_k_setstate_cython), 0, 0, 1, 1}, - {&__pyx_n_s_signals, __pyx_k_signals, sizeof(__pyx_k_signals), 0, 0, 1, 1}, {&__pyx_n_s_spec, __pyx_k_spec, sizeof(__pyx_k_spec), 0, 0, 1, 1}, {&__pyx_n_s_split, __pyx_k_split, sizeof(__pyx_k_split), 0, 0, 1, 1}, {&__pyx_n_s_strings, __pyx_k_strings, sizeof(__pyx_k_strings), 0, 0, 1, 1}, {&__pyx_kp_s_stringsource, __pyx_k_stringsource, sizeof(__pyx_k_stringsource), 0, 0, 1, 0}, {&__pyx_n_s_test, __pyx_k_test, sizeof(__pyx_k_test), 0, 0, 1, 1}, - {&__pyx_n_s_throw, __pyx_k_throw, sizeof(__pyx_k_throw), 0, 0, 1, 1}, - {&__pyx_n_s_update, __pyx_k_update, sizeof(__pyx_k_update), 0, 0, 1, 1}, {&__pyx_n_s_update_strings, __pyx_k_update_strings, sizeof(__pyx_k_update_strings), 0, 0, 1, 1}, {&__pyx_n_s_updated_addrs, __pyx_k_updated_addrs, sizeof(__pyx_k_updated_addrs), 0, 0, 1, 1}, {&__pyx_n_s_v, __pyx_k_v, sizeof(__pyx_k_v), 0, 0, 1, 1}, @@ -8639,12 +6663,10 @@ static int __Pyx_CreateStringTabAndInitStrings(void) { } /* #### Code section: cached_builtins ### */ static CYTHON_SMALL_CODE int __Pyx_InitCachedBuiltins(void) { - __pyx_builtin_RuntimeError = __Pyx_GetBuiltinName(__pyx_n_s_RuntimeError); if (!__pyx_builtin_RuntimeError) __PYX_ERR(0, 38, __pyx_L1_error) - __pyx_builtin_range = __Pyx_GetBuiltinName(__pyx_n_s_range); if (!__pyx_builtin_range) __PYX_ERR(0, 50, __pyx_L1_error) - __pyx_builtin_print = __Pyx_GetBuiltinName(__pyx_n_s_print); if (!__pyx_builtin_print) __PYX_ERR(0, 82, __pyx_L1_error) - __pyx_builtin_hex = __Pyx_GetBuiltinName(__pyx_n_s_hex); if (!__pyx_builtin_hex) __PYX_ERR(0, 92, __pyx_L1_error) + __pyx_builtin_RuntimeError = __Pyx_GetBuiltinName(__pyx_n_s_RuntimeError); if (!__pyx_builtin_RuntimeError) __PYX_ERR(0, 34, __pyx_L1_error) + __pyx_builtin_range = __Pyx_GetBuiltinName(__pyx_n_s_range); if (!__pyx_builtin_range) __PYX_ERR(0, 46, __pyx_L1_error) __pyx_builtin_TypeError = __Pyx_GetBuiltinName(__pyx_n_s_TypeError); if (!__pyx_builtin_TypeError) __PYX_ERR(1, 2, __pyx_L1_error) - __pyx_builtin_zip = __Pyx_GetBuiltinName(__pyx_n_s_zip); if (!__pyx_builtin_zip) __PYX_ERR(0, 185, __pyx_L1_error) + __pyx_builtin_zip = __Pyx_GetBuiltinName(__pyx_n_s_zip); if (!__pyx_builtin_zip) __PYX_ERR(0, 142, __pyx_L1_error) __pyx_builtin_MemoryError = __Pyx_GetBuiltinName(__pyx_n_s_MemoryError); if (!__pyx_builtin_MemoryError) __PYX_ERR(1, 68, __pyx_L1_error) return 0; __pyx_L1_error:; @@ -8656,70 +6678,70 @@ static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { __Pyx_RefNannyDeclarations __Pyx_RefNannySetupContext("__Pyx_InitCachedConstants", 0); - /* "opendbc/can/parser_pyx.pyx":181 + /* "opendbc/can/parser_pyx.pyx":138 * # separate definition/value pairs * def_val = def_val.split() * values = [int(v) for v in def_val[::2]] # <<<<<<<<<<<<<< * defs = def_val[1::2] * */ - __pyx_slice__5 = PySlice_New(Py_None, Py_None, __pyx_int_2); if (unlikely(!__pyx_slice__5)) __PYX_ERR(0, 181, __pyx_L1_error) - __Pyx_GOTREF(__pyx_slice__5); - __Pyx_GIVEREF(__pyx_slice__5); + __pyx_slice__2 = PySlice_New(Py_None, Py_None, __pyx_int_2); if (unlikely(!__pyx_slice__2)) __PYX_ERR(0, 138, __pyx_L1_error) + __Pyx_GOTREF(__pyx_slice__2); + __Pyx_GIVEREF(__pyx_slice__2); - /* "opendbc/can/parser_pyx.pyx":182 + /* "opendbc/can/parser_pyx.pyx":139 * def_val = def_val.split() * values = [int(v) for v in def_val[::2]] * defs = def_val[1::2] # <<<<<<<<<<<<<< * * # two ways to lookup: address or msg name */ - __pyx_slice__6 = PySlice_New(__pyx_int_1, Py_None, __pyx_int_2); if (unlikely(!__pyx_slice__6)) __PYX_ERR(0, 182, __pyx_L1_error) - __Pyx_GOTREF(__pyx_slice__6); - __Pyx_GIVEREF(__pyx_slice__6); + __pyx_slice__3 = PySlice_New(__pyx_int_1, Py_None, __pyx_int_2); if (unlikely(!__pyx_slice__3)) __PYX_ERR(0, 139, __pyx_L1_error) + __Pyx_GOTREF(__pyx_slice__3); + __Pyx_GIVEREF(__pyx_slice__3); - /* "opendbc/can/parser_pyx.pyx":115 + /* "opendbc/can/parser_pyx.pyx":72 * self.update_strings([]) * * def update_strings(self, strings, sendcan=False): # <<<<<<<<<<<<<< * for v in self.vl_all.values(): * for l in v.values(): # no-cython-lint */ - __pyx_tuple__9 = PyTuple_Pack(10, __pyx_n_s_self, __pyx_n_s_strings, __pyx_n_s_sendcan, __pyx_n_s_v, __pyx_n_s_l, __pyx_n_s_new_vals, __pyx_n_s_updated_addrs, __pyx_n_s_it, __pyx_n_s_cv, __pyx_n_s_cv_name); if (unlikely(!__pyx_tuple__9)) __PYX_ERR(0, 115, __pyx_L1_error) + __pyx_tuple__6 = PyTuple_Pack(10, __pyx_n_s_self, __pyx_n_s_strings, __pyx_n_s_sendcan, __pyx_n_s_v, __pyx_n_s_l, __pyx_n_s_new_vals, __pyx_n_s_updated_addrs, __pyx_n_s_it, __pyx_n_s_cv, __pyx_n_s_cv_name); if (unlikely(!__pyx_tuple__6)) __PYX_ERR(0, 72, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__6); + __Pyx_GIVEREF(__pyx_tuple__6); + __pyx_codeobj__7 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 10, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__6, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_opendbc_can_parser_pyx_pyx, __pyx_n_s_update_strings, 72, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__7)) __PYX_ERR(0, 72, __pyx_L1_error) + __pyx_tuple__8 = PyTuple_Pack(1, Py_False); if (unlikely(!__pyx_tuple__8)) __PYX_ERR(0, 72, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__8); + __Pyx_GIVEREF(__pyx_tuple__8); + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.can,self.dbc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_tuple__9 = PyTuple_Pack(1, __pyx_n_s_self); if (unlikely(!__pyx_tuple__9)) __PYX_ERR(1, 1, __pyx_L1_error) __Pyx_GOTREF(__pyx_tuple__9); __Pyx_GIVEREF(__pyx_tuple__9); - __pyx_codeobj__10 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 10, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__9, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_opendbc_can_parser_pyx_pyx, __pyx_n_s_update_strings, 115, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__10)) __PYX_ERR(0, 115, __pyx_L1_error) - __pyx_tuple__11 = PyTuple_Pack(1, Py_False); if (unlikely(!__pyx_tuple__11)) __PYX_ERR(0, 115, __pyx_L1_error) + __pyx_codeobj__10 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__9, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__10)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.can,self.dbc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.can,self.dbc cannot be converted to a Python object for pickling" + */ + __pyx_tuple__11 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_pyx_state); if (unlikely(!__pyx_tuple__11)) __PYX_ERR(1, 3, __pyx_L1_error) __Pyx_GOTREF(__pyx_tuple__11); __Pyx_GIVEREF(__pyx_tuple__11); - - /* "(tree fragment)":1 - * def __reduce_cython__(self): # <<<<<<<<<<<<<< - * raise TypeError, "self.can,self.dbc cannot be converted to a Python object for pickling" - * def __setstate_cython__(self, __pyx_state): - */ - __pyx_tuple__12 = PyTuple_Pack(1, __pyx_n_s_self); if (unlikely(!__pyx_tuple__12)) __PYX_ERR(1, 1, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__12); - __Pyx_GIVEREF(__pyx_tuple__12); - __pyx_codeobj__13 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__12, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__13)) __PYX_ERR(1, 1, __pyx_L1_error) - - /* "(tree fragment)":3 - * def __reduce_cython__(self): - * raise TypeError, "self.can,self.dbc cannot be converted to a Python object for pickling" - * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< - * raise TypeError, "self.can,self.dbc cannot be converted to a Python object for pickling" - */ - __pyx_tuple__14 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_pyx_state); if (unlikely(!__pyx_tuple__14)) __PYX_ERR(1, 3, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__14); - __Pyx_GIVEREF(__pyx_tuple__14); - __pyx_codeobj__15 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__14, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__15)) __PYX_ERR(1, 3, __pyx_L1_error) + __pyx_codeobj__12 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__11, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__12)) __PYX_ERR(1, 3, __pyx_L1_error) /* "(tree fragment)":1 * def __reduce_cython__(self): # <<<<<<<<<<<<<< * raise TypeError, "self.dbc cannot be converted to a Python object for pickling" * def __setstate_cython__(self, __pyx_state): */ - __pyx_codeobj__16 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__12, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__16)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_codeobj__13 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__9, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__13)) __PYX_ERR(1, 1, __pyx_L1_error) /* "(tree fragment)":3 * def __reduce_cython__(self): @@ -8727,7 +6749,7 @@ static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< * raise TypeError, "self.dbc cannot be converted to a Python object for pickling" */ - __pyx_codeobj__17 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__14, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__17)) __PYX_ERR(1, 3, __pyx_L1_error) + __pyx_codeobj__14 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__11, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__14)) __PYX_ERR(1, 3, __pyx_L1_error) __Pyx_RefNannyFinishContext(); return 0; __pyx_L1_error:; @@ -8739,8 +6761,6 @@ static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { static CYTHON_SMALL_CODE int __Pyx_InitConstants(void) { __pyx_umethod_PyDict_Type_get.type = (PyObject*)&PyDict_Type; __pyx_umethod_PyDict_Type_get.method_name = &__pyx_n_s_get; - __pyx_umethod_PyDict_Type_update.type = (PyObject*)&PyDict_Type; - __pyx_umethod_PyDict_Type_update.method_name = &__pyx_n_s_update; if (__Pyx_CreateStringTabAndInitStrings() < 0) __PYX_ERR(0, 1, __pyx_L1_error); __pyx_int_0 = PyInt_FromLong(0); if (unlikely(!__pyx_int_0)) __PYX_ERR(0, 1, __pyx_L1_error) __pyx_int_1 = PyInt_FromLong(1); if (unlikely(!__pyx_int_1)) __PYX_ERR(0, 1, __pyx_L1_error) @@ -8819,15 +6839,15 @@ static int __Pyx_modinit_type_init_code(void) { if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_7opendbc_3can_10parser_pyx_CANParser) < 0) __PYX_ERR(0, 18, __pyx_L1_error) #endif #if CYTHON_USE_TYPE_SPECS - __pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_7opendbc_3can_10parser_pyx_CANDefine_spec, NULL); if (unlikely(!__pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine)) __PYX_ERR(0, 147, __pyx_L1_error) - if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_7opendbc_3can_10parser_pyx_CANDefine_spec, __pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine) < 0) __PYX_ERR(0, 147, __pyx_L1_error) + __pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_7opendbc_3can_10parser_pyx_CANDefine_spec, NULL); if (unlikely(!__pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine)) __PYX_ERR(0, 104, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_7opendbc_3can_10parser_pyx_CANDefine_spec, __pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine) < 0) __PYX_ERR(0, 104, __pyx_L1_error) #else __pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine = &__pyx_type_7opendbc_3can_10parser_pyx_CANDefine; #endif #if !CYTHON_COMPILING_IN_LIMITED_API #endif #if !CYTHON_USE_TYPE_SPECS - if (__Pyx_PyType_Ready(__pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine) < 0) __PYX_ERR(0, 147, __pyx_L1_error) + if (__Pyx_PyType_Ready(__pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine) < 0) __PYX_ERR(0, 104, __pyx_L1_error) #endif #if PY_MAJOR_VERSION < 3 __pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine->tp_print = 0; @@ -8837,66 +6857,9 @@ static int __Pyx_modinit_type_init_code(void) { __pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine->tp_getattro = __Pyx_PyObject_GenericGetAttr; } #endif - if (PyObject_SetAttr(__pyx_m, __pyx_n_s_CANDefine, (PyObject *) __pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine) < 0) __PYX_ERR(0, 147, __pyx_L1_error) + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_CANDefine, (PyObject *) __pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine) < 0) __PYX_ERR(0, 104, __pyx_L1_error) #if !CYTHON_COMPILING_IN_LIMITED_API - if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine) < 0) __PYX_ERR(0, 147, __pyx_L1_error) - #endif - #if CYTHON_USE_TYPE_SPECS - __pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct____init___spec, NULL); if (unlikely(!__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__)) __PYX_ERR(0, 31, __pyx_L1_error) - if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct____init___spec, __pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__) < 0) __PYX_ERR(0, 31, __pyx_L1_error) - #else - __pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ = &__pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__; - #endif - #if !CYTHON_COMPILING_IN_LIMITED_API - #endif - #if !CYTHON_USE_TYPE_SPECS - if (__Pyx_PyType_Ready(__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__) < 0) __PYX_ERR(0, 31, __pyx_L1_error) - #endif - #if PY_MAJOR_VERSION < 3 - __pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__->tp_print = 0; - #endif - #if !CYTHON_COMPILING_IN_LIMITED_API - if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__->tp_dictoffset && __pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__->tp_getattro == PyObject_GenericGetAttr)) { - __pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__->tp_getattro = __Pyx_PyObject_GenericGetAttrNoDict; - } - #endif - #if CYTHON_USE_TYPE_SPECS - __pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr_spec, NULL); if (unlikely(!__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr)) __PYX_ERR(0, 92, __pyx_L1_error) - if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr_spec, __pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr) < 0) __PYX_ERR(0, 92, __pyx_L1_error) - #else - __pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr = &__pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr; - #endif - #if !CYTHON_COMPILING_IN_LIMITED_API - #endif - #if !CYTHON_USE_TYPE_SPECS - if (__Pyx_PyType_Ready(__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr) < 0) __PYX_ERR(0, 92, __pyx_L1_error) - #endif - #if PY_MAJOR_VERSION < 3 - __pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr->tp_print = 0; - #endif - #if !CYTHON_COMPILING_IN_LIMITED_API - if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr->tp_dictoffset && __pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr->tp_getattro == PyObject_GenericGetAttr)) { - __pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr->tp_getattro = __Pyx_PyObject_GenericGetAttrNoDict; - } - #endif - #if CYTHON_USE_TYPE_SPECS - __pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr_spec, NULL); if (unlikely(!__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr)) __PYX_ERR(0, 102, __pyx_L1_error) - if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr_spec, __pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr) < 0) __PYX_ERR(0, 102, __pyx_L1_error) - #else - __pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr = &__pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr; - #endif - #if !CYTHON_COMPILING_IN_LIMITED_API - #endif - #if !CYTHON_USE_TYPE_SPECS - if (__Pyx_PyType_Ready(__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr) < 0) __PYX_ERR(0, 102, __pyx_L1_error) - #endif - #if PY_MAJOR_VERSION < 3 - __pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr->tp_print = 0; - #endif - #if !CYTHON_COMPILING_IN_LIMITED_API - if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr->tp_dictoffset && __pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr->tp_getattro == PyObject_GenericGetAttr)) { - __pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr->tp_getattro = __Pyx_PyObject_GenericGetAttrNoDict; - } + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine) < 0) __PYX_ERR(0, 104, __pyx_L1_error) #endif __Pyx_RefNannyFinishContext(); return 0; @@ -9211,7 +7174,7 @@ if (!__Pyx_RefNanny) { #endif /* "opendbc/can/parser_pyx.pyx":14 - * from .common cimport SignalParseOptions, MessageParseOptions, dbc_lookup, SignalValue, DBC + * from .common cimport dbc_lookup, SignalValue, DBC * * import numbers # <<<<<<<<<<<<<< * from collections import defaultdict @@ -9243,17 +7206,17 @@ if (!__Pyx_RefNanny) { __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - /* "opendbc/can/parser_pyx.pyx":115 + /* "opendbc/can/parser_pyx.pyx":72 * self.update_strings([]) * * def update_strings(self, strings, sendcan=False): # <<<<<<<<<<<<<< * for v in self.vl_all.values(): * for l in v.values(): # no-cython-lint */ - __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_7opendbc_3can_10parser_pyx_9CANParser_3update_strings, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_CANParser_update_strings, NULL, __pyx_n_s_opendbc_can_parser_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__10)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 115, __pyx_L1_error) + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_7opendbc_3can_10parser_pyx_9CANParser_3update_strings, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_CANParser_update_strings, NULL, __pyx_n_s_opendbc_can_parser_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__7)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 72, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); - __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_3, __pyx_tuple__11); - if (PyDict_SetItem((PyObject *)__pyx_ptype_7opendbc_3can_10parser_pyx_CANParser->tp_dict, __pyx_n_s_update_strings, __pyx_t_3) < 0) __PYX_ERR(0, 115, __pyx_L1_error) + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_3, __pyx_tuple__8); + if (PyDict_SetItem((PyObject *)__pyx_ptype_7opendbc_3can_10parser_pyx_CANParser->tp_dict, __pyx_n_s_update_strings, __pyx_t_3) < 0) __PYX_ERR(0, 72, __pyx_L1_error) __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; PyType_Modified(__pyx_ptype_7opendbc_3can_10parser_pyx_CANParser); @@ -9262,7 +7225,7 @@ if (!__Pyx_RefNanny) { * raise TypeError, "self.can,self.dbc cannot be converted to a Python object for pickling" * def __setstate_cython__(self, __pyx_state): */ - __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_7opendbc_3can_10parser_pyx_9CANParser_5__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_CANParser___reduce_cython, NULL, __pyx_n_s_opendbc_can_parser_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__13)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_7opendbc_3can_10parser_pyx_9CANParser_5__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_CANParser___reduce_cython, NULL, __pyx_n_s_opendbc_can_parser_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__10)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 1, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); if (PyDict_SetItem(__pyx_d, __pyx_n_s_reduce_cython, __pyx_t_3) < 0) __PYX_ERR(1, 1, __pyx_L1_error) __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; @@ -9273,7 +7236,7 @@ if (!__Pyx_RefNanny) { * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< * raise TypeError, "self.can,self.dbc cannot be converted to a Python object for pickling" */ - __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_7opendbc_3can_10parser_pyx_9CANParser_7__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_CANParser___setstate_cython, NULL, __pyx_n_s_opendbc_can_parser_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__15)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 3, __pyx_L1_error) + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_7opendbc_3can_10parser_pyx_9CANParser_7__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_CANParser___setstate_cython, NULL, __pyx_n_s_opendbc_can_parser_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__12)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 3, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); if (PyDict_SetItem(__pyx_d, __pyx_n_s_setstate_cython, __pyx_t_3) < 0) __PYX_ERR(1, 3, __pyx_L1_error) __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; @@ -9283,7 +7246,7 @@ if (!__Pyx_RefNanny) { * raise TypeError, "self.dbc cannot be converted to a Python object for pickling" * def __setstate_cython__(self, __pyx_state): */ - __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_7opendbc_3can_10parser_pyx_9CANDefine_3__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_CANDefine___reduce_cython, NULL, __pyx_n_s_opendbc_can_parser_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__16)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_7opendbc_3can_10parser_pyx_9CANDefine_3__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_CANDefine___reduce_cython, NULL, __pyx_n_s_opendbc_can_parser_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__13)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 1, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); if (PyDict_SetItem(__pyx_d, __pyx_n_s_reduce_cython, __pyx_t_3) < 0) __PYX_ERR(1, 1, __pyx_L1_error) __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; @@ -9294,7 +7257,7 @@ if (!__Pyx_RefNanny) { * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< * raise TypeError, "self.dbc cannot be converted to a Python object for pickling" */ - __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_7opendbc_3can_10parser_pyx_9CANDefine_5__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_CANDefine___setstate_cython, NULL, __pyx_n_s_opendbc_can_parser_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__17)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 3, __pyx_L1_error) + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_7opendbc_3can_10parser_pyx_9CANDefine_5__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_CANDefine___setstate_cython, NULL, __pyx_n_s_opendbc_can_parser_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__14)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 3, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); if (PyDict_SetItem(__pyx_d, __pyx_n_s_setstate_cython, __pyx_t_3) < 0) __PYX_ERR(1, 3, __pyx_L1_error) __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; @@ -9528,6 +7491,43 @@ static PyObject *__Pyx_GetBuiltinName(PyObject *name) { return result; } +/* RaiseTooManyValuesToUnpack */ +static CYTHON_INLINE void __Pyx_RaiseTooManyValuesError(Py_ssize_t expected) { + PyErr_Format(PyExc_ValueError, + "too many values to unpack (expected %" CYTHON_FORMAT_SSIZE_T "d)", expected); +} + +/* RaiseNeedMoreValuesToUnpack */ +static CYTHON_INLINE void __Pyx_RaiseNeedMoreValuesError(Py_ssize_t index) { + PyErr_Format(PyExc_ValueError, + "need more than %" CYTHON_FORMAT_SSIZE_T "d value%.1s to unpack", + index, (index == 1) ? "" : "s"); +} + +/* IterFinish */ +static CYTHON_INLINE int __Pyx_IterFinish(void) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + PyObject* exc_type = __Pyx_PyErr_CurrentExceptionType(); + if (unlikely(exc_type)) { + if (unlikely(!__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) + return -1; + __Pyx_PyErr_Clear(); + return 0; + } + return 0; +} + +/* UnpackItemEndCheck */ +static int __Pyx_IternextUnpackEndCheck(PyObject *retval, Py_ssize_t expected) { + if (unlikely(retval)) { + Py_DECREF(retval); + __Pyx_RaiseTooManyValuesError(expected); + return -1; + } + return __Pyx_IterFinish(); +} + /* TupleAndListFromArray */ #if CYTHON_COMPILING_IN_CPYTHON static CYTHON_INLINE void __Pyx_copy_object_array(PyObject *const *CYTHON_RESTRICT src, PyObject** CYTHON_RESTRICT dest, Py_ssize_t length) { @@ -9891,43 +7891,6 @@ bad: return -1; } -/* RaiseUnboundLocalError */ -static CYTHON_INLINE void __Pyx_RaiseUnboundLocalError(const char *varname) { - PyErr_Format(PyExc_UnboundLocalError, "local variable '%s' referenced before assignment", varname); -} - -/* decode_c_bytes */ -static CYTHON_INLINE PyObject* __Pyx_decode_c_bytes( - const char* cstring, Py_ssize_t length, Py_ssize_t start, Py_ssize_t stop, - const char* encoding, const char* errors, - PyObject* (*decode_func)(const char *s, Py_ssize_t size, const char *errors)) { - if (unlikely((start < 0) | (stop < 0))) { - if (start < 0) { - start += length; - if (start < 0) - start = 0; - } - if (stop < 0) - stop += length; - } - if (stop > length) - stop = length; - if (unlikely(stop <= start)) - return __Pyx_NewRef(__pyx_empty_unicode); - length = stop - start; - cstring += start; - if (decode_func) { - return decode_func(cstring, length, errors); - } else { - return PyUnicode_Decode(cstring, length, encoding, errors); - } -} - -/* RaiseClosureNameError */ -static CYTHON_INLINE void __Pyx_RaiseClosureNameError(const char *varname) { - PyErr_Format(PyExc_NameError, "free variable '%s' referenced before assignment in enclosing scope", varname); -} - /* PyFunctionFastCall */ #if CYTHON_FAST_PYCALL && !CYTHON_VECTORCALL static PyObject* __Pyx_PyFunction_FastCallNoKw(PyCodeObject *co, PyObject **args, Py_ssize_t na, @@ -10168,235 +8131,6 @@ static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObjec return __Pyx_PyObject_FastCall(func, args+1, 1 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); } -/* JoinPyUnicode */ -static PyObject* __Pyx_PyUnicode_Join(PyObject* value_tuple, Py_ssize_t value_count, Py_ssize_t result_ulength, - Py_UCS4 max_char) { -#if CYTHON_USE_UNICODE_INTERNALS && CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - PyObject *result_uval; - int result_ukind, kind_shift; - Py_ssize_t i, char_pos; - void *result_udata; - CYTHON_MAYBE_UNUSED_VAR(max_char); -#if CYTHON_PEP393_ENABLED - result_uval = PyUnicode_New(result_ulength, max_char); - if (unlikely(!result_uval)) return NULL; - result_ukind = (max_char <= 255) ? PyUnicode_1BYTE_KIND : (max_char <= 65535) ? PyUnicode_2BYTE_KIND : PyUnicode_4BYTE_KIND; - kind_shift = (result_ukind == PyUnicode_4BYTE_KIND) ? 2 : result_ukind - 1; - result_udata = PyUnicode_DATA(result_uval); -#else - result_uval = PyUnicode_FromUnicode(NULL, result_ulength); - if (unlikely(!result_uval)) return NULL; - result_ukind = sizeof(Py_UNICODE); - kind_shift = (result_ukind == 4) ? 2 : result_ukind - 1; - result_udata = PyUnicode_AS_UNICODE(result_uval); -#endif - assert(kind_shift == 2 || kind_shift == 1 || kind_shift == 0); - char_pos = 0; - for (i=0; i < value_count; i++) { - int ukind; - Py_ssize_t ulength; - void *udata; - PyObject *uval = PyTuple_GET_ITEM(value_tuple, i); - if (unlikely(__Pyx_PyUnicode_READY(uval))) - goto bad; - ulength = __Pyx_PyUnicode_GET_LENGTH(uval); - if (unlikely(!ulength)) - continue; - if (unlikely((PY_SSIZE_T_MAX >> kind_shift) - ulength < char_pos)) - goto overflow; - ukind = __Pyx_PyUnicode_KIND(uval); - udata = __Pyx_PyUnicode_DATA(uval); - if (!CYTHON_PEP393_ENABLED || ukind == result_ukind) { - memcpy((char *)result_udata + (char_pos << kind_shift), udata, (size_t) (ulength << kind_shift)); - } else { - #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030300F0 || defined(_PyUnicode_FastCopyCharacters) - _PyUnicode_FastCopyCharacters(result_uval, char_pos, uval, 0, ulength); - #else - Py_ssize_t j; - for (j=0; j < ulength; j++) { - Py_UCS4 uchar = __Pyx_PyUnicode_READ(ukind, udata, j); - __Pyx_PyUnicode_WRITE(result_ukind, result_udata, char_pos+j, uchar); - } - #endif - } - char_pos += ulength; - } - return result_uval; -overflow: - PyErr_SetString(PyExc_OverflowError, "join() result is too long for a Python string"); -bad: - Py_DECREF(result_uval); - return NULL; -#else - CYTHON_UNUSED_VAR(max_char); - CYTHON_UNUSED_VAR(result_ulength); - CYTHON_UNUSED_VAR(value_count); - return PyUnicode_Join(__pyx_empty_unicode, value_tuple); -#endif -} - -/* GetException */ -#if CYTHON_FAST_THREAD_STATE -static int __Pyx__GetException(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) -#else -static int __Pyx_GetException(PyObject **type, PyObject **value, PyObject **tb) -#endif -{ - PyObject *local_type = NULL, *local_value, *local_tb = NULL; -#if CYTHON_FAST_THREAD_STATE - PyObject *tmp_type, *tmp_value, *tmp_tb; - #if PY_VERSION_HEX >= 0x030C00A6 - local_value = tstate->current_exception; - tstate->current_exception = 0; - if (likely(local_value)) { - local_type = (PyObject*) Py_TYPE(local_value); - Py_INCREF(local_type); - local_tb = PyException_GetTraceback(local_value); - } - #else - local_type = tstate->curexc_type; - local_value = tstate->curexc_value; - local_tb = tstate->curexc_traceback; - tstate->curexc_type = 0; - tstate->curexc_value = 0; - tstate->curexc_traceback = 0; - #endif -#else - PyErr_Fetch(&local_type, &local_value, &local_tb); -#endif - PyErr_NormalizeException(&local_type, &local_value, &local_tb); -#if CYTHON_FAST_THREAD_STATE && PY_VERSION_HEX >= 0x030C00A6 - if (unlikely(tstate->current_exception)) -#elif CYTHON_FAST_THREAD_STATE - if (unlikely(tstate->curexc_type)) -#else - if (unlikely(PyErr_Occurred())) -#endif - goto bad; - #if PY_MAJOR_VERSION >= 3 - if (local_tb) { - if (unlikely(PyException_SetTraceback(local_value, local_tb) < 0)) - goto bad; - } - #endif - Py_XINCREF(local_tb); - Py_XINCREF(local_type); - Py_XINCREF(local_value); - *type = local_type; - *value = local_value; - *tb = local_tb; -#if CYTHON_FAST_THREAD_STATE - #if CYTHON_USE_EXC_INFO_STACK - { - _PyErr_StackItem *exc_info = tstate->exc_info; - #if PY_VERSION_HEX >= 0x030B00a4 - tmp_value = exc_info->exc_value; - exc_info->exc_value = local_value; - tmp_type = NULL; - tmp_tb = NULL; - Py_XDECREF(local_type); - Py_XDECREF(local_tb); - #else - tmp_type = exc_info->exc_type; - tmp_value = exc_info->exc_value; - tmp_tb = exc_info->exc_traceback; - exc_info->exc_type = local_type; - exc_info->exc_value = local_value; - exc_info->exc_traceback = local_tb; - #endif - } - #else - tmp_type = tstate->exc_type; - tmp_value = tstate->exc_value; - tmp_tb = tstate->exc_traceback; - tstate->exc_type = local_type; - tstate->exc_value = local_value; - tstate->exc_traceback = local_tb; - #endif - Py_XDECREF(tmp_type); - Py_XDECREF(tmp_value); - Py_XDECREF(tmp_tb); -#else - PyErr_SetExcInfo(local_type, local_value, local_tb); -#endif - return 0; -bad: - *type = 0; - *value = 0; - *tb = 0; - Py_XDECREF(local_type); - Py_XDECREF(local_value); - Py_XDECREF(local_tb); - return -1; -} - -/* pep479 */ -static void __Pyx_Generator_Replace_StopIteration(int in_async_gen) { - PyObject *exc, *val, *tb, *cur_exc; - __Pyx_PyThreadState_declare - #ifdef __Pyx_StopAsyncIteration_USED - int is_async_stopiteration = 0; - #endif - CYTHON_MAYBE_UNUSED_VAR(in_async_gen); - cur_exc = PyErr_Occurred(); - if (likely(!__Pyx_PyErr_GivenExceptionMatches(cur_exc, PyExc_StopIteration))) { - #ifdef __Pyx_StopAsyncIteration_USED - if (in_async_gen && unlikely(__Pyx_PyErr_GivenExceptionMatches(cur_exc, __Pyx_PyExc_StopAsyncIteration))) { - is_async_stopiteration = 1; - } else - #endif - return; - } - __Pyx_PyThreadState_assign - __Pyx_GetException(&exc, &val, &tb); - Py_XDECREF(exc); - Py_XDECREF(val); - Py_XDECREF(tb); - PyErr_SetString(PyExc_RuntimeError, - #ifdef __Pyx_StopAsyncIteration_USED - is_async_stopiteration ? "async generator raised StopAsyncIteration" : - in_async_gen ? "async generator raised StopIteration" : - #endif - "generator raised StopIteration"); -} - -/* RaiseTooManyValuesToUnpack */ -static CYTHON_INLINE void __Pyx_RaiseTooManyValuesError(Py_ssize_t expected) { - PyErr_Format(PyExc_ValueError, - "too many values to unpack (expected %" CYTHON_FORMAT_SSIZE_T "d)", expected); -} - -/* RaiseNeedMoreValuesToUnpack */ -static CYTHON_INLINE void __Pyx_RaiseNeedMoreValuesError(Py_ssize_t index) { - PyErr_Format(PyExc_ValueError, - "need more than %" CYTHON_FORMAT_SSIZE_T "d value%.1s to unpack", - index, (index == 1) ? "" : "s"); -} - -/* IterFinish */ -static CYTHON_INLINE int __Pyx_IterFinish(void) { - __Pyx_PyThreadState_declare - __Pyx_PyThreadState_assign - PyObject* exc_type = __Pyx_PyErr_CurrentExceptionType(); - if (unlikely(exc_type)) { - if (unlikely(!__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) - return -1; - __Pyx_PyErr_Clear(); - return 0; - } - return 0; -} - -/* UnpackItemEndCheck */ -static int __Pyx_IternextUnpackEndCheck(PyObject *retval, Py_ssize_t expected) { - if (unlikely(retval)) { - Py_DECREF(retval); - __Pyx_RaiseTooManyValuesError(expected); - return -1; - } - return __Pyx_IterFinish(); -} - /* RaiseException */ #if PY_MAJOR_VERSION < 3 static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { @@ -10558,6 +8292,33 @@ bad: } #endif +/* decode_c_bytes */ +static CYTHON_INLINE PyObject* __Pyx_decode_c_bytes( + const char* cstring, Py_ssize_t length, Py_ssize_t start, Py_ssize_t stop, + const char* encoding, const char* errors, + PyObject* (*decode_func)(const char *s, Py_ssize_t size, const char *errors)) { + if (unlikely((start < 0) | (stop < 0))) { + if (start < 0) { + start += length; + if (start < 0) + start = 0; + } + if (stop < 0) + stop += length; + } + if (stop > length) + stop = length; + if (unlikely(stop <= start)) + return __Pyx_NewRef(__pyx_empty_unicode); + length = stop - start; + cstring += start; + if (decode_func) { + return decode_func(cstring, length, errors); + } else { + return PyUnicode_Decode(cstring, length, encoding, errors); + } +} + /* DictGetItem */ #if PY_MAJOR_VERSION >= 3 && !CYTHON_COMPILING_IN_PYPY static PyObject *__Pyx_PyDict_GetItem(PyObject *d, PyObject* key) { @@ -10947,69 +8708,71 @@ static PyObject* __Pyx_PyDict_GetItemDefault(PyObject* d, PyObject* key, PyObjec return value; } -/* SetItemInt */ -static int __Pyx_SetItemInt_Generic(PyObject *o, PyObject *j, PyObject *v) { - int r; - if (unlikely(!j)) return -1; - r = PyObject_SetItem(o, j, v); - Py_DECREF(j); - return r; -} -static CYTHON_INLINE int __Pyx_SetItemInt_Fast(PyObject *o, Py_ssize_t i, PyObject *v, int is_list, - CYTHON_NCP_UNUSED int wraparound, CYTHON_NCP_UNUSED int boundscheck) { -#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS && CYTHON_USE_TYPE_SLOTS - if (is_list || PyList_CheckExact(o)) { - Py_ssize_t n = (!wraparound) ? i : ((likely(i >= 0)) ? i : i + PyList_GET_SIZE(o)); - if ((!boundscheck) || likely(__Pyx_is_valid_index(n, PyList_GET_SIZE(o)))) { - PyObject* old = PyList_GET_ITEM(o, n); - Py_INCREF(v); - PyList_SET_ITEM(o, n, v); - Py_DECREF(old); - return 1; - } - } else { - PyMappingMethods *mm = Py_TYPE(o)->tp_as_mapping; - PySequenceMethods *sm = Py_TYPE(o)->tp_as_sequence; - if (mm && mm->mp_ass_subscript) { - int r; - PyObject *key = PyInt_FromSsize_t(i); - if (unlikely(!key)) return -1; - r = mm->mp_ass_subscript(o, key, v); - Py_DECREF(key); - return r; - } - if (likely(sm && sm->sq_ass_item)) { - if (wraparound && unlikely(i < 0) && likely(sm->sq_length)) { - Py_ssize_t l = sm->sq_length(o); - if (likely(l >= 0)) { - i += l; - } else { - if (!PyErr_ExceptionMatches(PyExc_OverflowError)) - return -1; - PyErr_Clear(); - } +/* JoinPyUnicode */ +static PyObject* __Pyx_PyUnicode_Join(PyObject* value_tuple, Py_ssize_t value_count, Py_ssize_t result_ulength, + Py_UCS4 max_char) { +#if CYTHON_USE_UNICODE_INTERNALS && CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + PyObject *result_uval; + int result_ukind, kind_shift; + Py_ssize_t i, char_pos; + void *result_udata; + CYTHON_MAYBE_UNUSED_VAR(max_char); +#if CYTHON_PEP393_ENABLED + result_uval = PyUnicode_New(result_ulength, max_char); + if (unlikely(!result_uval)) return NULL; + result_ukind = (max_char <= 255) ? PyUnicode_1BYTE_KIND : (max_char <= 65535) ? PyUnicode_2BYTE_KIND : PyUnicode_4BYTE_KIND; + kind_shift = (result_ukind == PyUnicode_4BYTE_KIND) ? 2 : result_ukind - 1; + result_udata = PyUnicode_DATA(result_uval); +#else + result_uval = PyUnicode_FromUnicode(NULL, result_ulength); + if (unlikely(!result_uval)) return NULL; + result_ukind = sizeof(Py_UNICODE); + kind_shift = (result_ukind == 4) ? 2 : result_ukind - 1; + result_udata = PyUnicode_AS_UNICODE(result_uval); +#endif + assert(kind_shift == 2 || kind_shift == 1 || kind_shift == 0); + char_pos = 0; + for (i=0; i < value_count; i++) { + int ukind; + Py_ssize_t ulength; + void *udata; + PyObject *uval = PyTuple_GET_ITEM(value_tuple, i); + if (unlikely(__Pyx_PyUnicode_READY(uval))) + goto bad; + ulength = __Pyx_PyUnicode_GET_LENGTH(uval); + if (unlikely(!ulength)) + continue; + if (unlikely((PY_SSIZE_T_MAX >> kind_shift) - ulength < char_pos)) + goto overflow; + ukind = __Pyx_PyUnicode_KIND(uval); + udata = __Pyx_PyUnicode_DATA(uval); + if (!CYTHON_PEP393_ENABLED || ukind == result_ukind) { + memcpy((char *)result_udata + (char_pos << kind_shift), udata, (size_t) (ulength << kind_shift)); + } else { + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030300F0 || defined(_PyUnicode_FastCopyCharacters) + _PyUnicode_FastCopyCharacters(result_uval, char_pos, uval, 0, ulength); + #else + Py_ssize_t j; + for (j=0; j < ulength; j++) { + Py_UCS4 uchar = __Pyx_PyUnicode_READ(ukind, udata, j); + __Pyx_PyUnicode_WRITE(result_ukind, result_udata, char_pos+j, uchar); } - return sm->sq_ass_item(o, i, v); + #endif } + char_pos += ulength; } + return result_uval; +overflow: + PyErr_SetString(PyExc_OverflowError, "join() result is too long for a Python string"); +bad: + Py_DECREF(result_uval); + return NULL; #else -#if CYTHON_COMPILING_IN_PYPY - if (is_list || (PySequence_Check(o) && !PyDict_Check(o))) -#else - if (is_list || PySequence_Check(o)) + CYTHON_UNUSED_VAR(max_char); + CYTHON_UNUSED_VAR(result_ulength); + CYTHON_UNUSED_VAR(value_count); + return PyUnicode_Join(__pyx_empty_unicode, value_tuple); #endif - { - return PySequence_SetItem(o, i, v); - } -#endif - return __Pyx_SetItemInt_Generic(o, PyInt_FromSsize_t(i), v); -} - -/* PyUnicode_Unicode */ -static CYTHON_INLINE PyObject* __Pyx_PyUnicode_Unicode(PyObject *obj) { - if (unlikely(obj == Py_None)) - obj = __pyx_kp_u_None; - return __Pyx_NewRef(obj); } /* PyObjectCallNoArg */ @@ -11938,7 +9701,7 @@ static PyObject *__Pyx_ImportDottedModule_WalkParts(PyObject *module, PyObject * #endif static PyObject *__Pyx__ImportDottedModule(PyObject *name, PyObject *parts_tuple) { #if PY_MAJOR_VERSION < 3 - PyObject *module, *from_list, *star = __pyx_n_s__7; + PyObject *module, *from_list, *star = __pyx_n_s__4; CYTHON_UNUSED_VAR(parts_tuple); from_list = PyList_New(1); if (unlikely(!from_list)) @@ -12001,7 +9764,7 @@ static PyObject* __Pyx_ImportFrom(PyObject* module, PyObject* name) { if (unlikely(!module_name_str)) { goto modbad; } module_name = PyUnicode_FromString(module_name_str); if (unlikely(!module_name)) { goto modbad; } - module_dot = PyUnicode_Concat(module_name, __pyx_kp_u__8); + module_dot = PyUnicode_Concat(module_name, __pyx_kp_u__5); if (unlikely(!module_dot)) { goto modbad; } full_name = PyUnicode_Concat(module_dot, name); if (unlikely(!full_name)) { goto modbad; } @@ -14288,7 +12051,7 @@ __Pyx_PyType_GetName(PyTypeObject* tp) __pyx_n_s_name); if (unlikely(name == NULL) || unlikely(!PyUnicode_Check(name))) { PyErr_Clear(); - Py_XSETREF(name, __Pyx_NewRef(__pyx_n_s__18)); + Py_XSETREF(name, __Pyx_NewRef(__pyx_n_s__15)); } return name; } @@ -14683,1233 +12446,6 @@ static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches2(PyObject *err, PyObj } #endif -/* GetTopmostException */ -#if CYTHON_USE_EXC_INFO_STACK && CYTHON_FAST_THREAD_STATE -static _PyErr_StackItem * -__Pyx_PyErr_GetTopmostException(PyThreadState *tstate) -{ - _PyErr_StackItem *exc_info = tstate->exc_info; - while ((exc_info->exc_value == NULL || exc_info->exc_value == Py_None) && - exc_info->previous_item != NULL) - { - exc_info = exc_info->previous_item; - } - return exc_info; -} -#endif - -/* SaveResetException */ -#if CYTHON_FAST_THREAD_STATE -static CYTHON_INLINE void __Pyx__ExceptionSave(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { - #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 - _PyErr_StackItem *exc_info = __Pyx_PyErr_GetTopmostException(tstate); - PyObject *exc_value = exc_info->exc_value; - if (exc_value == NULL || exc_value == Py_None) { - *value = NULL; - *type = NULL; - *tb = NULL; - } else { - *value = exc_value; - Py_INCREF(*value); - *type = (PyObject*) Py_TYPE(exc_value); - Py_INCREF(*type); - *tb = PyException_GetTraceback(exc_value); - } - #elif CYTHON_USE_EXC_INFO_STACK - _PyErr_StackItem *exc_info = __Pyx_PyErr_GetTopmostException(tstate); - *type = exc_info->exc_type; - *value = exc_info->exc_value; - *tb = exc_info->exc_traceback; - Py_XINCREF(*type); - Py_XINCREF(*value); - Py_XINCREF(*tb); - #else - *type = tstate->exc_type; - *value = tstate->exc_value; - *tb = tstate->exc_traceback; - Py_XINCREF(*type); - Py_XINCREF(*value); - Py_XINCREF(*tb); - #endif -} -static CYTHON_INLINE void __Pyx__ExceptionReset(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb) { - #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 - _PyErr_StackItem *exc_info = tstate->exc_info; - PyObject *tmp_value = exc_info->exc_value; - exc_info->exc_value = value; - Py_XDECREF(tmp_value); - Py_XDECREF(type); - Py_XDECREF(tb); - #else - PyObject *tmp_type, *tmp_value, *tmp_tb; - #if CYTHON_USE_EXC_INFO_STACK - _PyErr_StackItem *exc_info = tstate->exc_info; - tmp_type = exc_info->exc_type; - tmp_value = exc_info->exc_value; - tmp_tb = exc_info->exc_traceback; - exc_info->exc_type = type; - exc_info->exc_value = value; - exc_info->exc_traceback = tb; - #else - tmp_type = tstate->exc_type; - tmp_value = tstate->exc_value; - tmp_tb = tstate->exc_traceback; - tstate->exc_type = type; - tstate->exc_value = value; - tstate->exc_traceback = tb; - #endif - Py_XDECREF(tmp_type); - Py_XDECREF(tmp_value); - Py_XDECREF(tmp_tb); - #endif -} -#endif - -/* SwapException */ -#if CYTHON_FAST_THREAD_STATE -static CYTHON_INLINE void __Pyx__ExceptionSwap(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { - PyObject *tmp_type, *tmp_value, *tmp_tb; - #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 - _PyErr_StackItem *exc_info = tstate->exc_info; - tmp_value = exc_info->exc_value; - exc_info->exc_value = *value; - if (tmp_value == NULL || tmp_value == Py_None) { - Py_XDECREF(tmp_value); - tmp_value = NULL; - tmp_type = NULL; - tmp_tb = NULL; - } else { - tmp_type = (PyObject*) Py_TYPE(tmp_value); - Py_INCREF(tmp_type); - #if CYTHON_COMPILING_IN_CPYTHON - tmp_tb = ((PyBaseExceptionObject*) tmp_value)->traceback; - Py_XINCREF(tmp_tb); - #else - tmp_tb = PyException_GetTraceback(tmp_value); - #endif - } - #elif CYTHON_USE_EXC_INFO_STACK - _PyErr_StackItem *exc_info = tstate->exc_info; - tmp_type = exc_info->exc_type; - tmp_value = exc_info->exc_value; - tmp_tb = exc_info->exc_traceback; - exc_info->exc_type = *type; - exc_info->exc_value = *value; - exc_info->exc_traceback = *tb; - #else - tmp_type = tstate->exc_type; - tmp_value = tstate->exc_value; - tmp_tb = tstate->exc_traceback; - tstate->exc_type = *type; - tstate->exc_value = *value; - tstate->exc_traceback = *tb; - #endif - *type = tmp_type; - *value = tmp_value; - *tb = tmp_tb; -} -#else -static CYTHON_INLINE void __Pyx_ExceptionSwap(PyObject **type, PyObject **value, PyObject **tb) { - PyObject *tmp_type, *tmp_value, *tmp_tb; - PyErr_GetExcInfo(&tmp_type, &tmp_value, &tmp_tb); - PyErr_SetExcInfo(*type, *value, *tb); - *type = tmp_type; - *value = tmp_value; - *tb = tmp_tb; -} -#endif - -/* PyObjectCall2Args */ -static CYTHON_INLINE PyObject* __Pyx_PyObject_Call2Args(PyObject* function, PyObject* arg1, PyObject* arg2) { - PyObject *args[3] = {NULL, arg1, arg2}; - return __Pyx_PyObject_FastCall(function, args+1, 2 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); -} - -/* PyObjectCallMethod1 */ -static PyObject* __Pyx__PyObject_CallMethod1(PyObject* method, PyObject* arg) { - PyObject *result = __Pyx_PyObject_CallOneArg(method, arg); - Py_DECREF(method); - return result; -} -static PyObject* __Pyx_PyObject_CallMethod1(PyObject* obj, PyObject* method_name, PyObject* arg) { - PyObject *method = NULL, *result; - int is_method = __Pyx_PyObject_GetMethod(obj, method_name, &method); - if (likely(is_method)) { - result = __Pyx_PyObject_Call2Args(method, obj, arg); - Py_DECREF(method); - return result; - } - if (unlikely(!method)) return NULL; - return __Pyx__PyObject_CallMethod1(method, arg); -} - -/* CoroutineBase */ -#include -#if PY_VERSION_HEX >= 0x030b00a6 - #ifndef Py_BUILD_CORE - #define Py_BUILD_CORE 1 - #endif - #include "internal/pycore_frame.h" -#endif -#define __Pyx_Coroutine_Undelegate(gen) Py_CLEAR((gen)->yieldfrom) -static int __Pyx_PyGen__FetchStopIterationValue(PyThreadState *__pyx_tstate, PyObject **pvalue) { - PyObject *et, *ev, *tb; - PyObject *value = NULL; - CYTHON_UNUSED_VAR(__pyx_tstate); - __Pyx_ErrFetch(&et, &ev, &tb); - if (!et) { - Py_XDECREF(tb); - Py_XDECREF(ev); - Py_INCREF(Py_None); - *pvalue = Py_None; - return 0; - } - if (likely(et == PyExc_StopIteration)) { - if (!ev) { - Py_INCREF(Py_None); - value = Py_None; - } -#if PY_VERSION_HEX >= 0x030300A0 - else if (likely(__Pyx_IS_TYPE(ev, (PyTypeObject*)PyExc_StopIteration))) { - value = ((PyStopIterationObject *)ev)->value; - Py_INCREF(value); - Py_DECREF(ev); - } -#endif - else if (unlikely(PyTuple_Check(ev))) { - if (PyTuple_GET_SIZE(ev) >= 1) { -#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - value = PyTuple_GET_ITEM(ev, 0); - Py_INCREF(value); -#else - value = PySequence_ITEM(ev, 0); -#endif - } else { - Py_INCREF(Py_None); - value = Py_None; - } - Py_DECREF(ev); - } - else if (!__Pyx_TypeCheck(ev, (PyTypeObject*)PyExc_StopIteration)) { - value = ev; - } - if (likely(value)) { - Py_XDECREF(tb); - Py_DECREF(et); - *pvalue = value; - return 0; - } - } else if (!__Pyx_PyErr_GivenExceptionMatches(et, PyExc_StopIteration)) { - __Pyx_ErrRestore(et, ev, tb); - return -1; - } - PyErr_NormalizeException(&et, &ev, &tb); - if (unlikely(!PyObject_TypeCheck(ev, (PyTypeObject*)PyExc_StopIteration))) { - __Pyx_ErrRestore(et, ev, tb); - return -1; - } - Py_XDECREF(tb); - Py_DECREF(et); -#if PY_VERSION_HEX >= 0x030300A0 - value = ((PyStopIterationObject *)ev)->value; - Py_INCREF(value); - Py_DECREF(ev); -#else - { - PyObject* args = __Pyx_PyObject_GetAttrStr(ev, __pyx_n_s_args); - Py_DECREF(ev); - if (likely(args)) { - value = PySequence_GetItem(args, 0); - Py_DECREF(args); - } - if (unlikely(!value)) { - __Pyx_ErrRestore(NULL, NULL, NULL); - Py_INCREF(Py_None); - value = Py_None; - } - } -#endif - *pvalue = value; - return 0; -} -static CYTHON_INLINE -void __Pyx_Coroutine_ExceptionClear(__Pyx_ExcInfoStruct *exc_state) { -#if PY_VERSION_HEX >= 0x030B00a4 - Py_CLEAR(exc_state->exc_value); -#else - PyObject *t, *v, *tb; - t = exc_state->exc_type; - v = exc_state->exc_value; - tb = exc_state->exc_traceback; - exc_state->exc_type = NULL; - exc_state->exc_value = NULL; - exc_state->exc_traceback = NULL; - Py_XDECREF(t); - Py_XDECREF(v); - Py_XDECREF(tb); -#endif -} -#define __Pyx_Coroutine_AlreadyRunningError(gen) (__Pyx__Coroutine_AlreadyRunningError(gen), (PyObject*)NULL) -static void __Pyx__Coroutine_AlreadyRunningError(__pyx_CoroutineObject *gen) { - const char *msg; - CYTHON_MAYBE_UNUSED_VAR(gen); - if ((0)) { - #ifdef __Pyx_Coroutine_USED - } else if (__Pyx_Coroutine_Check((PyObject*)gen)) { - msg = "coroutine already executing"; - #endif - #ifdef __Pyx_AsyncGen_USED - } else if (__Pyx_AsyncGen_CheckExact((PyObject*)gen)) { - msg = "async generator already executing"; - #endif - } else { - msg = "generator already executing"; - } - PyErr_SetString(PyExc_ValueError, msg); -} -#define __Pyx_Coroutine_NotStartedError(gen) (__Pyx__Coroutine_NotStartedError(gen), (PyObject*)NULL) -static void __Pyx__Coroutine_NotStartedError(PyObject *gen) { - const char *msg; - CYTHON_MAYBE_UNUSED_VAR(gen); - if ((0)) { - #ifdef __Pyx_Coroutine_USED - } else if (__Pyx_Coroutine_Check(gen)) { - msg = "can't send non-None value to a just-started coroutine"; - #endif - #ifdef __Pyx_AsyncGen_USED - } else if (__Pyx_AsyncGen_CheckExact(gen)) { - msg = "can't send non-None value to a just-started async generator"; - #endif - } else { - msg = "can't send non-None value to a just-started generator"; - } - PyErr_SetString(PyExc_TypeError, msg); -} -#define __Pyx_Coroutine_AlreadyTerminatedError(gen, value, closing) (__Pyx__Coroutine_AlreadyTerminatedError(gen, value, closing), (PyObject*)NULL) -static void __Pyx__Coroutine_AlreadyTerminatedError(PyObject *gen, PyObject *value, int closing) { - CYTHON_MAYBE_UNUSED_VAR(gen); - CYTHON_MAYBE_UNUSED_VAR(closing); - #ifdef __Pyx_Coroutine_USED - if (!closing && __Pyx_Coroutine_Check(gen)) { - PyErr_SetString(PyExc_RuntimeError, "cannot reuse already awaited coroutine"); - } else - #endif - if (value) { - #ifdef __Pyx_AsyncGen_USED - if (__Pyx_AsyncGen_CheckExact(gen)) - PyErr_SetNone(__Pyx_PyExc_StopAsyncIteration); - else - #endif - PyErr_SetNone(PyExc_StopIteration); - } -} -static -PyObject *__Pyx_Coroutine_SendEx(__pyx_CoroutineObject *self, PyObject *value, int closing) { - __Pyx_PyThreadState_declare - PyThreadState *tstate; - __Pyx_ExcInfoStruct *exc_state; - PyObject *retval; - assert(!self->is_running); - if (unlikely(self->resume_label == 0)) { - if (unlikely(value && value != Py_None)) { - return __Pyx_Coroutine_NotStartedError((PyObject*)self); - } - } - if (unlikely(self->resume_label == -1)) { - return __Pyx_Coroutine_AlreadyTerminatedError((PyObject*)self, value, closing); - } -#if CYTHON_FAST_THREAD_STATE - __Pyx_PyThreadState_assign - tstate = __pyx_tstate; -#else - tstate = __Pyx_PyThreadState_Current; -#endif - exc_state = &self->gi_exc_state; - if (exc_state->exc_value) { - #if CYTHON_COMPILING_IN_PYPY - #else - PyObject *exc_tb; - #if PY_VERSION_HEX >= 0x030B00a4 && !CYTHON_COMPILING_IN_CPYTHON - exc_tb = PyException_GetTraceback(exc_state->exc_value); - #elif PY_VERSION_HEX >= 0x030B00a4 - exc_tb = ((PyBaseExceptionObject*) exc_state->exc_value)->traceback; - #else - exc_tb = exc_state->exc_traceback; - #endif - if (exc_tb) { - PyTracebackObject *tb = (PyTracebackObject *) exc_tb; - PyFrameObject *f = tb->tb_frame; - assert(f->f_back == NULL); - #if PY_VERSION_HEX >= 0x030B00A1 - f->f_back = PyThreadState_GetFrame(tstate); - #else - Py_XINCREF(tstate->frame); - f->f_back = tstate->frame; - #endif - #if PY_VERSION_HEX >= 0x030B00a4 && !CYTHON_COMPILING_IN_CPYTHON - Py_DECREF(exc_tb); - #endif - } - #endif - } -#if CYTHON_USE_EXC_INFO_STACK - exc_state->previous_item = tstate->exc_info; - tstate->exc_info = exc_state; -#else - if (exc_state->exc_type) { - __Pyx_ExceptionSwap(&exc_state->exc_type, &exc_state->exc_value, &exc_state->exc_traceback); - } else { - __Pyx_Coroutine_ExceptionClear(exc_state); - __Pyx_ExceptionSave(&exc_state->exc_type, &exc_state->exc_value, &exc_state->exc_traceback); - } -#endif - self->is_running = 1; - retval = self->body(self, tstate, value); - self->is_running = 0; -#if CYTHON_USE_EXC_INFO_STACK - exc_state = &self->gi_exc_state; - tstate->exc_info = exc_state->previous_item; - exc_state->previous_item = NULL; - __Pyx_Coroutine_ResetFrameBackpointer(exc_state); -#endif - return retval; -} -static CYTHON_INLINE void __Pyx_Coroutine_ResetFrameBackpointer(__Pyx_ExcInfoStruct *exc_state) { -#if CYTHON_COMPILING_IN_PYPY - CYTHON_UNUSED_VAR(exc_state); -#else - PyObject *exc_tb; - #if PY_VERSION_HEX >= 0x030B00a4 - if (!exc_state->exc_value) return; - exc_tb = PyException_GetTraceback(exc_state->exc_value); - #else - exc_tb = exc_state->exc_traceback; - #endif - if (likely(exc_tb)) { - PyTracebackObject *tb = (PyTracebackObject *) exc_tb; - PyFrameObject *f = tb->tb_frame; - Py_CLEAR(f->f_back); - #if PY_VERSION_HEX >= 0x030B00a4 - Py_DECREF(exc_tb); - #endif - } -#endif -} -static CYTHON_INLINE -PyObject *__Pyx_Coroutine_MethodReturn(PyObject* gen, PyObject *retval) { - CYTHON_MAYBE_UNUSED_VAR(gen); - if (unlikely(!retval)) { - __Pyx_PyThreadState_declare - __Pyx_PyThreadState_assign - if (!__Pyx_PyErr_Occurred()) { - PyObject *exc = PyExc_StopIteration; - #ifdef __Pyx_AsyncGen_USED - if (__Pyx_AsyncGen_CheckExact(gen)) - exc = __Pyx_PyExc_StopAsyncIteration; - #endif - __Pyx_PyErr_SetNone(exc); - } - } - return retval; -} -#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x03030000 && (defined(__linux__) || PY_VERSION_HEX >= 0x030600B3) -static CYTHON_INLINE -PyObject *__Pyx_PyGen_Send(PyGenObject *gen, PyObject *arg) { -#if PY_VERSION_HEX <= 0x030A00A1 - return _PyGen_Send(gen, arg); -#else - PyObject *result; - if (PyIter_Send((PyObject*)gen, arg ? arg : Py_None, &result) == PYGEN_RETURN) { - if (PyAsyncGen_CheckExact(gen)) { - assert(result == Py_None); - PyErr_SetNone(PyExc_StopAsyncIteration); - } - else if (result == Py_None) { - PyErr_SetNone(PyExc_StopIteration); - } - else { - _PyGen_SetStopIterationValue(result); - } - Py_CLEAR(result); - } - return result; -#endif -} -#endif -static CYTHON_INLINE -PyObject *__Pyx_Coroutine_FinishDelegation(__pyx_CoroutineObject *gen) { - PyObject *ret; - PyObject *val = NULL; - __Pyx_Coroutine_Undelegate(gen); - __Pyx_PyGen__FetchStopIterationValue(__Pyx_PyThreadState_Current, &val); - ret = __Pyx_Coroutine_SendEx(gen, val, 0); - Py_XDECREF(val); - return ret; -} -static PyObject *__Pyx_Coroutine_Send(PyObject *self, PyObject *value) { - PyObject *retval; - __pyx_CoroutineObject *gen = (__pyx_CoroutineObject*) self; - PyObject *yf = gen->yieldfrom; - if (unlikely(gen->is_running)) - return __Pyx_Coroutine_AlreadyRunningError(gen); - if (yf) { - PyObject *ret; - gen->is_running = 1; - #ifdef __Pyx_Generator_USED - if (__Pyx_Generator_CheckExact(yf)) { - ret = __Pyx_Coroutine_Send(yf, value); - } else - #endif - #ifdef __Pyx_Coroutine_USED - if (__Pyx_Coroutine_Check(yf)) { - ret = __Pyx_Coroutine_Send(yf, value); - } else - #endif - #ifdef __Pyx_AsyncGen_USED - if (__pyx_PyAsyncGenASend_CheckExact(yf)) { - ret = __Pyx_async_gen_asend_send(yf, value); - } else - #endif - #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x03030000 && (defined(__linux__) || PY_VERSION_HEX >= 0x030600B3) - if (PyGen_CheckExact(yf)) { - ret = __Pyx_PyGen_Send((PyGenObject*)yf, value == Py_None ? NULL : value); - } else - #endif - #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x03050000 && defined(PyCoro_CheckExact) && (defined(__linux__) || PY_VERSION_HEX >= 0x030600B3) - if (PyCoro_CheckExact(yf)) { - ret = __Pyx_PyGen_Send((PyGenObject*)yf, value == Py_None ? NULL : value); - } else - #endif - { - if (value == Py_None) - ret = __Pyx_PyObject_GetIterNextFunc(yf)(yf); - else - ret = __Pyx_PyObject_CallMethod1(yf, __pyx_n_s_send, value); - } - gen->is_running = 0; - if (likely(ret)) { - return ret; - } - retval = __Pyx_Coroutine_FinishDelegation(gen); - } else { - retval = __Pyx_Coroutine_SendEx(gen, value, 0); - } - return __Pyx_Coroutine_MethodReturn(self, retval); -} -static int __Pyx_Coroutine_CloseIter(__pyx_CoroutineObject *gen, PyObject *yf) { - PyObject *retval = NULL; - int err = 0; - #ifdef __Pyx_Generator_USED - if (__Pyx_Generator_CheckExact(yf)) { - retval = __Pyx_Coroutine_Close(yf); - if (!retval) - return -1; - } else - #endif - #ifdef __Pyx_Coroutine_USED - if (__Pyx_Coroutine_Check(yf)) { - retval = __Pyx_Coroutine_Close(yf); - if (!retval) - return -1; - } else - if (__Pyx_CoroutineAwait_CheckExact(yf)) { - retval = __Pyx_CoroutineAwait_Close((__pyx_CoroutineAwaitObject*)yf, NULL); - if (!retval) - return -1; - } else - #endif - #ifdef __Pyx_AsyncGen_USED - if (__pyx_PyAsyncGenASend_CheckExact(yf)) { - retval = __Pyx_async_gen_asend_close(yf, NULL); - } else - if (__pyx_PyAsyncGenAThrow_CheckExact(yf)) { - retval = __Pyx_async_gen_athrow_close(yf, NULL); - } else - #endif - { - PyObject *meth; - gen->is_running = 1; - meth = __Pyx_PyObject_GetAttrStrNoError(yf, __pyx_n_s_close); - if (unlikely(!meth)) { - if (unlikely(PyErr_Occurred())) { - PyErr_WriteUnraisable(yf); - } - } else { - retval = __Pyx_PyObject_CallNoArg(meth); - Py_DECREF(meth); - if (unlikely(!retval)) - err = -1; - } - gen->is_running = 0; - } - Py_XDECREF(retval); - return err; -} -static PyObject *__Pyx_Generator_Next(PyObject *self) { - __pyx_CoroutineObject *gen = (__pyx_CoroutineObject*) self; - PyObject *yf = gen->yieldfrom; - if (unlikely(gen->is_running)) - return __Pyx_Coroutine_AlreadyRunningError(gen); - if (yf) { - PyObject *ret; - gen->is_running = 1; - #ifdef __Pyx_Generator_USED - if (__Pyx_Generator_CheckExact(yf)) { - ret = __Pyx_Generator_Next(yf); - } else - #endif - #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x03030000 && (defined(__linux__) || PY_VERSION_HEX >= 0x030600B3) - if (PyGen_CheckExact(yf)) { - ret = __Pyx_PyGen_Send((PyGenObject*)yf, NULL); - } else - #endif - #ifdef __Pyx_Coroutine_USED - if (__Pyx_Coroutine_Check(yf)) { - ret = __Pyx_Coroutine_Send(yf, Py_None); - } else - #endif - ret = __Pyx_PyObject_GetIterNextFunc(yf)(yf); - gen->is_running = 0; - if (likely(ret)) { - return ret; - } - return __Pyx_Coroutine_FinishDelegation(gen); - } - return __Pyx_Coroutine_SendEx(gen, Py_None, 0); -} -static PyObject *__Pyx_Coroutine_Close_Method(PyObject *self, PyObject *arg) { - CYTHON_UNUSED_VAR(arg); - return __Pyx_Coroutine_Close(self); -} -static PyObject *__Pyx_Coroutine_Close(PyObject *self) { - __pyx_CoroutineObject *gen = (__pyx_CoroutineObject *) self; - PyObject *retval, *raised_exception; - PyObject *yf = gen->yieldfrom; - int err = 0; - if (unlikely(gen->is_running)) - return __Pyx_Coroutine_AlreadyRunningError(gen); - if (yf) { - Py_INCREF(yf); - err = __Pyx_Coroutine_CloseIter(gen, yf); - __Pyx_Coroutine_Undelegate(gen); - Py_DECREF(yf); - } - if (err == 0) - PyErr_SetNone(PyExc_GeneratorExit); - retval = __Pyx_Coroutine_SendEx(gen, NULL, 1); - if (unlikely(retval)) { - const char *msg; - Py_DECREF(retval); - if ((0)) { - #ifdef __Pyx_Coroutine_USED - } else if (__Pyx_Coroutine_Check(self)) { - msg = "coroutine ignored GeneratorExit"; - #endif - #ifdef __Pyx_AsyncGen_USED - } else if (__Pyx_AsyncGen_CheckExact(self)) { -#if PY_VERSION_HEX < 0x03060000 - msg = "async generator ignored GeneratorExit - might require Python 3.6+ finalisation (PEP 525)"; -#else - msg = "async generator ignored GeneratorExit"; -#endif - #endif - } else { - msg = "generator ignored GeneratorExit"; - } - PyErr_SetString(PyExc_RuntimeError, msg); - return NULL; - } - raised_exception = PyErr_Occurred(); - if (likely(!raised_exception || __Pyx_PyErr_GivenExceptionMatches2(raised_exception, PyExc_GeneratorExit, PyExc_StopIteration))) { - if (raised_exception) PyErr_Clear(); - Py_INCREF(Py_None); - return Py_None; - } - return NULL; -} -static PyObject *__Pyx__Coroutine_Throw(PyObject *self, PyObject *typ, PyObject *val, PyObject *tb, - PyObject *args, int close_on_genexit) { - __pyx_CoroutineObject *gen = (__pyx_CoroutineObject *) self; - PyObject *yf = gen->yieldfrom; - if (unlikely(gen->is_running)) - return __Pyx_Coroutine_AlreadyRunningError(gen); - if (yf) { - PyObject *ret; - Py_INCREF(yf); - if (__Pyx_PyErr_GivenExceptionMatches(typ, PyExc_GeneratorExit) && close_on_genexit) { - int err = __Pyx_Coroutine_CloseIter(gen, yf); - Py_DECREF(yf); - __Pyx_Coroutine_Undelegate(gen); - if (err < 0) - return __Pyx_Coroutine_MethodReturn(self, __Pyx_Coroutine_SendEx(gen, NULL, 0)); - goto throw_here; - } - gen->is_running = 1; - if (0 - #ifdef __Pyx_Generator_USED - || __Pyx_Generator_CheckExact(yf) - #endif - #ifdef __Pyx_Coroutine_USED - || __Pyx_Coroutine_Check(yf) - #endif - ) { - ret = __Pyx__Coroutine_Throw(yf, typ, val, tb, args, close_on_genexit); - #ifdef __Pyx_Coroutine_USED - } else if (__Pyx_CoroutineAwait_CheckExact(yf)) { - ret = __Pyx__Coroutine_Throw(((__pyx_CoroutineAwaitObject*)yf)->coroutine, typ, val, tb, args, close_on_genexit); - #endif - } else { - PyObject *meth = __Pyx_PyObject_GetAttrStrNoError(yf, __pyx_n_s_throw); - if (unlikely(!meth)) { - Py_DECREF(yf); - if (unlikely(PyErr_Occurred())) { - gen->is_running = 0; - return NULL; - } - __Pyx_Coroutine_Undelegate(gen); - gen->is_running = 0; - goto throw_here; - } - if (likely(args)) { - ret = __Pyx_PyObject_Call(meth, args, NULL); - } else { - PyObject *cargs[4] = {NULL, typ, val, tb}; - ret = __Pyx_PyObject_FastCall(meth, cargs+1, 3 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); - } - Py_DECREF(meth); - } - gen->is_running = 0; - Py_DECREF(yf); - if (!ret) { - ret = __Pyx_Coroutine_FinishDelegation(gen); - } - return __Pyx_Coroutine_MethodReturn(self, ret); - } -throw_here: - __Pyx_Raise(typ, val, tb, NULL); - return __Pyx_Coroutine_MethodReturn(self, __Pyx_Coroutine_SendEx(gen, NULL, 0)); -} -static PyObject *__Pyx_Coroutine_Throw(PyObject *self, PyObject *args) { - PyObject *typ; - PyObject *val = NULL; - PyObject *tb = NULL; - if (unlikely(!PyArg_UnpackTuple(args, (char *)"throw", 1, 3, &typ, &val, &tb))) - return NULL; - return __Pyx__Coroutine_Throw(self, typ, val, tb, args, 1); -} -static CYTHON_INLINE int __Pyx_Coroutine_traverse_excstate(__Pyx_ExcInfoStruct *exc_state, visitproc visit, void *arg) { -#if PY_VERSION_HEX >= 0x030B00a4 - Py_VISIT(exc_state->exc_value); -#else - Py_VISIT(exc_state->exc_type); - Py_VISIT(exc_state->exc_value); - Py_VISIT(exc_state->exc_traceback); -#endif - return 0; -} -static int __Pyx_Coroutine_traverse(__pyx_CoroutineObject *gen, visitproc visit, void *arg) { - Py_VISIT(gen->closure); - Py_VISIT(gen->classobj); - Py_VISIT(gen->yieldfrom); - return __Pyx_Coroutine_traverse_excstate(&gen->gi_exc_state, visit, arg); -} -static int __Pyx_Coroutine_clear(PyObject *self) { - __pyx_CoroutineObject *gen = (__pyx_CoroutineObject *) self; - Py_CLEAR(gen->closure); - Py_CLEAR(gen->classobj); - Py_CLEAR(gen->yieldfrom); - __Pyx_Coroutine_ExceptionClear(&gen->gi_exc_state); -#ifdef __Pyx_AsyncGen_USED - if (__Pyx_AsyncGen_CheckExact(self)) { - Py_CLEAR(((__pyx_PyAsyncGenObject*)gen)->ag_finalizer); - } -#endif - Py_CLEAR(gen->gi_code); - Py_CLEAR(gen->gi_frame); - Py_CLEAR(gen->gi_name); - Py_CLEAR(gen->gi_qualname); - Py_CLEAR(gen->gi_modulename); - return 0; -} -static void __Pyx_Coroutine_dealloc(PyObject *self) { - __pyx_CoroutineObject *gen = (__pyx_CoroutineObject *) self; - PyObject_GC_UnTrack(gen); - if (gen->gi_weakreflist != NULL) - PyObject_ClearWeakRefs(self); - if (gen->resume_label >= 0) { - PyObject_GC_Track(self); -#if PY_VERSION_HEX >= 0x030400a1 && CYTHON_USE_TP_FINALIZE - if (unlikely(PyObject_CallFinalizerFromDealloc(self))) -#else - Py_TYPE(gen)->tp_del(self); - if (unlikely(Py_REFCNT(self) > 0)) -#endif - { - return; - } - PyObject_GC_UnTrack(self); - } -#ifdef __Pyx_AsyncGen_USED - if (__Pyx_AsyncGen_CheckExact(self)) { - /* We have to handle this case for asynchronous generators - right here, because this code has to be between UNTRACK - and GC_Del. */ - Py_CLEAR(((__pyx_PyAsyncGenObject*)self)->ag_finalizer); - } -#endif - __Pyx_Coroutine_clear(self); - __Pyx_PyHeapTypeObject_GC_Del(gen); -} -static void __Pyx_Coroutine_del(PyObject *self) { - PyObject *error_type, *error_value, *error_traceback; - __pyx_CoroutineObject *gen = (__pyx_CoroutineObject *) self; - __Pyx_PyThreadState_declare - if (gen->resume_label < 0) { - return; - } -#if !CYTHON_USE_TP_FINALIZE - assert(self->ob_refcnt == 0); - __Pyx_SET_REFCNT(self, 1); -#endif - __Pyx_PyThreadState_assign - __Pyx_ErrFetch(&error_type, &error_value, &error_traceback); -#ifdef __Pyx_AsyncGen_USED - if (__Pyx_AsyncGen_CheckExact(self)) { - __pyx_PyAsyncGenObject *agen = (__pyx_PyAsyncGenObject*)self; - PyObject *finalizer = agen->ag_finalizer; - if (finalizer && !agen->ag_closed) { - PyObject *res = __Pyx_PyObject_CallOneArg(finalizer, self); - if (unlikely(!res)) { - PyErr_WriteUnraisable(self); - } else { - Py_DECREF(res); - } - __Pyx_ErrRestore(error_type, error_value, error_traceback); - return; - } - } -#endif - if (unlikely(gen->resume_label == 0 && !error_value)) { -#ifdef __Pyx_Coroutine_USED -#ifdef __Pyx_Generator_USED - if (!__Pyx_Generator_CheckExact(self)) -#endif - { - PyObject_GC_UnTrack(self); -#if PY_MAJOR_VERSION >= 3 || defined(PyErr_WarnFormat) - if (unlikely(PyErr_WarnFormat(PyExc_RuntimeWarning, 1, "coroutine '%.50S' was never awaited", gen->gi_qualname) < 0)) - PyErr_WriteUnraisable(self); -#else - {PyObject *msg; - char *cmsg; - #if CYTHON_COMPILING_IN_PYPY - msg = NULL; - cmsg = (char*) "coroutine was never awaited"; - #else - char *cname; - PyObject *qualname; - qualname = gen->gi_qualname; - cname = PyString_AS_STRING(qualname); - msg = PyString_FromFormat("coroutine '%.50s' was never awaited", cname); - if (unlikely(!msg)) { - PyErr_Clear(); - cmsg = (char*) "coroutine was never awaited"; - } else { - cmsg = PyString_AS_STRING(msg); - } - #endif - if (unlikely(PyErr_WarnEx(PyExc_RuntimeWarning, cmsg, 1) < 0)) - PyErr_WriteUnraisable(self); - Py_XDECREF(msg);} -#endif - PyObject_GC_Track(self); - } -#endif - } else { - PyObject *res = __Pyx_Coroutine_Close(self); - if (unlikely(!res)) { - if (PyErr_Occurred()) - PyErr_WriteUnraisable(self); - } else { - Py_DECREF(res); - } - } - __Pyx_ErrRestore(error_type, error_value, error_traceback); -#if !CYTHON_USE_TP_FINALIZE - assert(Py_REFCNT(self) > 0); - if (likely(--self->ob_refcnt == 0)) { - return; - } - { - Py_ssize_t refcnt = Py_REFCNT(self); - _Py_NewReference(self); - __Pyx_SET_REFCNT(self, refcnt); - } -#if CYTHON_COMPILING_IN_CPYTHON - assert(PyType_IS_GC(Py_TYPE(self)) && - _Py_AS_GC(self)->gc.gc_refs != _PyGC_REFS_UNTRACKED); - _Py_DEC_REFTOTAL; -#endif -#ifdef COUNT_ALLOCS - --Py_TYPE(self)->tp_frees; - --Py_TYPE(self)->tp_allocs; -#endif -#endif -} -static PyObject * -__Pyx_Coroutine_get_name(__pyx_CoroutineObject *self, void *context) -{ - PyObject *name = self->gi_name; - CYTHON_UNUSED_VAR(context); - if (unlikely(!name)) name = Py_None; - Py_INCREF(name); - return name; -} -static int -__Pyx_Coroutine_set_name(__pyx_CoroutineObject *self, PyObject *value, void *context) -{ - CYTHON_UNUSED_VAR(context); -#if PY_MAJOR_VERSION >= 3 - if (unlikely(value == NULL || !PyUnicode_Check(value))) -#else - if (unlikely(value == NULL || !PyString_Check(value))) -#endif - { - PyErr_SetString(PyExc_TypeError, - "__name__ must be set to a string object"); - return -1; - } - Py_INCREF(value); - __Pyx_Py_XDECREF_SET(self->gi_name, value); - return 0; -} -static PyObject * -__Pyx_Coroutine_get_qualname(__pyx_CoroutineObject *self, void *context) -{ - PyObject *name = self->gi_qualname; - CYTHON_UNUSED_VAR(context); - if (unlikely(!name)) name = Py_None; - Py_INCREF(name); - return name; -} -static int -__Pyx_Coroutine_set_qualname(__pyx_CoroutineObject *self, PyObject *value, void *context) -{ - CYTHON_UNUSED_VAR(context); -#if PY_MAJOR_VERSION >= 3 - if (unlikely(value == NULL || !PyUnicode_Check(value))) -#else - if (unlikely(value == NULL || !PyString_Check(value))) -#endif - { - PyErr_SetString(PyExc_TypeError, - "__qualname__ must be set to a string object"); - return -1; - } - Py_INCREF(value); - __Pyx_Py_XDECREF_SET(self->gi_qualname, value); - return 0; -} -static PyObject * -__Pyx_Coroutine_get_frame(__pyx_CoroutineObject *self, void *context) -{ - PyObject *frame = self->gi_frame; - CYTHON_UNUSED_VAR(context); - if (!frame) { - if (unlikely(!self->gi_code)) { - Py_RETURN_NONE; - } - frame = (PyObject *) PyFrame_New( - PyThreadState_Get(), /*PyThreadState *tstate,*/ - (PyCodeObject*) self->gi_code, /*PyCodeObject *code,*/ - __pyx_d, /*PyObject *globals,*/ - 0 /*PyObject *locals*/ - ); - if (unlikely(!frame)) - return NULL; - self->gi_frame = frame; - } - Py_INCREF(frame); - return frame; -} -static __pyx_CoroutineObject *__Pyx__Coroutine_New( - PyTypeObject* type, __pyx_coroutine_body_t body, PyObject *code, PyObject *closure, - PyObject *name, PyObject *qualname, PyObject *module_name) { - __pyx_CoroutineObject *gen = PyObject_GC_New(__pyx_CoroutineObject, type); - if (unlikely(!gen)) - return NULL; - return __Pyx__Coroutine_NewInit(gen, body, code, closure, name, qualname, module_name); -} -static __pyx_CoroutineObject *__Pyx__Coroutine_NewInit( - __pyx_CoroutineObject *gen, __pyx_coroutine_body_t body, PyObject *code, PyObject *closure, - PyObject *name, PyObject *qualname, PyObject *module_name) { - gen->body = body; - gen->closure = closure; - Py_XINCREF(closure); - gen->is_running = 0; - gen->resume_label = 0; - gen->classobj = NULL; - gen->yieldfrom = NULL; - #if PY_VERSION_HEX >= 0x030B00a4 - gen->gi_exc_state.exc_value = NULL; - #else - gen->gi_exc_state.exc_type = NULL; - gen->gi_exc_state.exc_value = NULL; - gen->gi_exc_state.exc_traceback = NULL; - #endif -#if CYTHON_USE_EXC_INFO_STACK - gen->gi_exc_state.previous_item = NULL; -#endif - gen->gi_weakreflist = NULL; - Py_XINCREF(qualname); - gen->gi_qualname = qualname; - Py_XINCREF(name); - gen->gi_name = name; - Py_XINCREF(module_name); - gen->gi_modulename = module_name; - Py_XINCREF(code); - gen->gi_code = code; - gen->gi_frame = NULL; - PyObject_GC_Track(gen); - return gen; -} - -/* PatchModuleWithCoroutine */ -static PyObject* __Pyx_Coroutine_patch_module(PyObject* module, const char* py_code) { -#if defined(__Pyx_Generator_USED) || defined(__Pyx_Coroutine_USED) - int result; - PyObject *globals, *result_obj; - globals = PyDict_New(); if (unlikely(!globals)) goto ignore; - result = PyDict_SetItemString(globals, "_cython_coroutine_type", - #ifdef __Pyx_Coroutine_USED - (PyObject*)__pyx_CoroutineType); - #else - Py_None); - #endif - if (unlikely(result < 0)) goto ignore; - result = PyDict_SetItemString(globals, "_cython_generator_type", - #ifdef __Pyx_Generator_USED - (PyObject*)__pyx_GeneratorType); - #else - Py_None); - #endif - if (unlikely(result < 0)) goto ignore; - if (unlikely(PyDict_SetItemString(globals, "_module", module) < 0)) goto ignore; - if (unlikely(PyDict_SetItemString(globals, "__builtins__", __pyx_b) < 0)) goto ignore; - result_obj = PyRun_String(py_code, Py_file_input, globals, globals); - if (unlikely(!result_obj)) goto ignore; - Py_DECREF(result_obj); - Py_DECREF(globals); - return module; -ignore: - Py_XDECREF(globals); - PyErr_WriteUnraisable(module); - if (unlikely(PyErr_WarnEx(PyExc_RuntimeWarning, "Cython module failed to patch module with custom type", 1) < 0)) { - Py_DECREF(module); - module = NULL; - } -#else - py_code++; -#endif - return module; -} - -/* PatchGeneratorABC */ -#ifndef CYTHON_REGISTER_ABCS -#define CYTHON_REGISTER_ABCS 1 -#endif -#if defined(__Pyx_Generator_USED) || defined(__Pyx_Coroutine_USED) -static PyObject* __Pyx_patch_abc_module(PyObject *module); -static PyObject* __Pyx_patch_abc_module(PyObject *module) { - module = __Pyx_Coroutine_patch_module( - module, "" -"if _cython_generator_type is not None:\n" -" try: Generator = _module.Generator\n" -" except AttributeError: pass\n" -" else: Generator.register(_cython_generator_type)\n" -"if _cython_coroutine_type is not None:\n" -" try: Coroutine = _module.Coroutine\n" -" except AttributeError: pass\n" -" else: Coroutine.register(_cython_coroutine_type)\n" - ); - return module; -} -#endif -static int __Pyx_patch_abc(void) { -#if defined(__Pyx_Generator_USED) || defined(__Pyx_Coroutine_USED) - static int abc_patched = 0; - if (CYTHON_REGISTER_ABCS && !abc_patched) { - PyObject *module; - module = PyImport_ImportModule((PY_MAJOR_VERSION >= 3) ? "collections.abc" : "collections"); - if (unlikely(!module)) { - PyErr_WriteUnraisable(NULL); - if (unlikely(PyErr_WarnEx(PyExc_RuntimeWarning, - ((PY_MAJOR_VERSION >= 3) ? - "Cython module failed to register with collections.abc module" : - "Cython module failed to register with collections module"), 1) < 0)) { - return -1; - } - } else { - module = __Pyx_patch_abc_module(module); - abc_patched = 1; - if (unlikely(!module)) - return -1; - Py_DECREF(module); - } - module = PyImport_ImportModule("backports_abc"); - if (module) { - module = __Pyx_patch_abc_module(module); - Py_XDECREF(module); - } - if (!module) { - PyErr_Clear(); - } - } -#else - if ((0)) __Pyx_Coroutine_patch_module(NULL, NULL); -#endif - return 0; -} - -/* Generator */ -static PyMethodDef __pyx_Generator_methods[] = { - {"send", (PyCFunction) __Pyx_Coroutine_Send, METH_O, - (char*) PyDoc_STR("send(arg) -> send 'arg' into generator,\nreturn next yielded value or raise StopIteration.")}, - {"throw", (PyCFunction) __Pyx_Coroutine_Throw, METH_VARARGS, - (char*) PyDoc_STR("throw(typ[,val[,tb]]) -> raise exception in generator,\nreturn next yielded value or raise StopIteration.")}, - {"close", (PyCFunction) __Pyx_Coroutine_Close_Method, METH_NOARGS, - (char*) PyDoc_STR("close() -> raise GeneratorExit inside generator.")}, - {0, 0, 0, 0} -}; -static PyMemberDef __pyx_Generator_memberlist[] = { - {(char *) "gi_running", T_BOOL, offsetof(__pyx_CoroutineObject, is_running), READONLY, NULL}, - {(char*) "gi_yieldfrom", T_OBJECT, offsetof(__pyx_CoroutineObject, yieldfrom), READONLY, - (char*) PyDoc_STR("object being iterated by 'yield from', or None")}, - {(char*) "gi_code", T_OBJECT, offsetof(__pyx_CoroutineObject, gi_code), READONLY, NULL}, - {(char *) "__module__", T_OBJECT, offsetof(__pyx_CoroutineObject, gi_modulename), 0, 0}, -#if CYTHON_USE_TYPE_SPECS - {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(__pyx_CoroutineObject, gi_weakreflist), READONLY, 0}, -#endif - {0, 0, 0, 0, 0} -}; -static PyGetSetDef __pyx_Generator_getsets[] = { - {(char *) "__name__", (getter)__Pyx_Coroutine_get_name, (setter)__Pyx_Coroutine_set_name, - (char*) PyDoc_STR("name of the generator"), 0}, - {(char *) "__qualname__", (getter)__Pyx_Coroutine_get_qualname, (setter)__Pyx_Coroutine_set_qualname, - (char*) PyDoc_STR("qualified name of the generator"), 0}, - {(char *) "gi_frame", (getter)__Pyx_Coroutine_get_frame, NULL, - (char*) PyDoc_STR("Frame of the generator"), 0}, - {0, 0, 0, 0, 0} -}; -#if CYTHON_USE_TYPE_SPECS -static PyType_Slot __pyx_GeneratorType_slots[] = { - {Py_tp_dealloc, (void *)__Pyx_Coroutine_dealloc}, - {Py_tp_traverse, (void *)__Pyx_Coroutine_traverse}, - {Py_tp_iter, (void *)PyObject_SelfIter}, - {Py_tp_iternext, (void *)__Pyx_Generator_Next}, - {Py_tp_methods, (void *)__pyx_Generator_methods}, - {Py_tp_members, (void *)__pyx_Generator_memberlist}, - {Py_tp_getset, (void *)__pyx_Generator_getsets}, - {Py_tp_getattro, (void *) __Pyx_PyObject_GenericGetAttrNoDict}, -#if CYTHON_USE_TP_FINALIZE - {Py_tp_finalize, (void *)__Pyx_Coroutine_del}, -#endif - {0, 0}, -}; -static PyType_Spec __pyx_GeneratorType_spec = { - __PYX_TYPE_MODULE_PREFIX "generator", - sizeof(__pyx_CoroutineObject), - 0, - Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_HAVE_FINALIZE, - __pyx_GeneratorType_slots -}; -#else -static PyTypeObject __pyx_GeneratorType_type = { - PyVarObject_HEAD_INIT(0, 0) - __PYX_TYPE_MODULE_PREFIX "generator", - sizeof(__pyx_CoroutineObject), - 0, - (destructor) __Pyx_Coroutine_dealloc, - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0, - Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_HAVE_FINALIZE, - 0, - (traverseproc) __Pyx_Coroutine_traverse, - 0, - 0, - offsetof(__pyx_CoroutineObject, gi_weakreflist), - 0, - (iternextfunc) __Pyx_Generator_Next, - __pyx_Generator_methods, - __pyx_Generator_memberlist, - __pyx_Generator_getsets, - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0, -#if CYTHON_USE_TP_FINALIZE - 0, -#else - __Pyx_Coroutine_del, -#endif - 0, -#if CYTHON_USE_TP_FINALIZE - __Pyx_Coroutine_del, -#elif PY_VERSION_HEX >= 0x030400a1 - 0, -#endif -#if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) - 0, -#endif -#if __PYX_NEED_TP_PRINT_SLOT - 0, -#endif -#if PY_VERSION_HEX >= 0x030C0000 - 0, -#endif -#if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 - 0, -#endif -}; -#endif -static int __pyx_Generator_init(PyObject *module) { -#if CYTHON_USE_TYPE_SPECS - __pyx_GeneratorType = __Pyx_FetchCommonTypeFromSpec(module, &__pyx_GeneratorType_spec, NULL); -#else - CYTHON_UNUSED_VAR(module); - __pyx_GeneratorType_type.tp_getattro = __Pyx_PyObject_GenericGetAttrNoDict; - __pyx_GeneratorType_type.tp_iter = PyObject_SelfIter; - __pyx_GeneratorType = __Pyx_FetchCommonType(&__pyx_GeneratorType_type); -#endif - if (unlikely(!__pyx_GeneratorType)) { - return -1; - } - return 0; -} - /* CheckBinaryVersion */ static int __Pyx_check_binary_version(void) { char ctversion[5]; diff --git a/opendbc/can/parser_pyx.so b/opendbc/can/parser_pyx.so index 921d31a63..64cf38603 100755 Binary files a/opendbc/can/parser_pyx.so and b/opendbc/can/parser_pyx.so differ diff --git a/panda/board/jungle/__init__.py b/panda/board/jungle/__init__.py index c6e005a59..1c90fa00c 100644 --- a/panda/board/jungle/__init__.py +++ b/panda/board/jungle/__init__.py @@ -138,6 +138,9 @@ class PandaJungle(Panda): def set_ignition(self, enabled): self._handle.controlWrite(PandaJungle.REQUEST_OUT, 0xa2, int(enabled), 0, b'') + def set_can_silent(self, silent): + self._handle.controlWrite(PandaJungle.REQUEST_OUT, 0xf5, int(silent), 0, b'') + # ******************* serial ******************* def debug_read(self): @@ -148,3 +151,8 @@ class PandaJungle(Panda): break ret.append(lret) return b''.join(ret) + + # ******************* header pins ******************* + + def set_header_pin(self, pin_num, enabled): + self._handle.controlWrite(Panda.REQUEST_OUT, 0xf7, int(pin_num), int(enabled), b'') diff --git a/panda/board/jungle/boards/board_declarations.h b/panda/board/jungle/boards/board_declarations.h index dcb6ac24e..3fe4c2fab 100644 --- a/panda/board/jungle/boards/board_declarations.h +++ b/panda/board/jungle/boards/board_declarations.h @@ -9,6 +9,7 @@ typedef void (*board_set_individual_ignition)(uint8_t bitmask); typedef void (*board_set_harness_orientation)(uint8_t orientation); typedef void (*board_set_can_mode)(uint8_t mode); typedef void (*board_enable_can_transciever)(uint8_t transciever, bool enabled); +typedef void (*board_enable_header_pin)(uint8_t pin_num, bool enabled); typedef float (*board_get_channel_power)(uint8_t channel); typedef uint16_t (*board_get_sbu_mV)(uint8_t channel, uint8_t sbu); @@ -27,6 +28,7 @@ struct board { board_set_harness_orientation set_harness_orientation; board_set_can_mode set_can_mode; board_enable_can_transciever enable_can_transciever; + board_enable_header_pin enable_header_pin; board_get_channel_power get_channel_power; board_get_sbu_mV get_sbu_mV; @@ -67,4 +69,9 @@ uint8_t ignition = 0U; void unused_set_individual_ignition(uint8_t bitmask) { UNUSED(bitmask); -} \ No newline at end of file +} + +void unused_board_enable_header_pin(uint8_t pin_num, bool enabled) { + UNUSED(pin_num); + UNUSED(enabled); +} diff --git a/panda/board/jungle/boards/board_v1.h b/panda/board/jungle/boards/board_v1.h index d1a6299a4..8d41b9452 100644 --- a/panda/board/jungle/boards/board_v1.h +++ b/panda/board/jungle/boards/board_v1.h @@ -1,6 +1,6 @@ void board_v1_set_led(uint8_t color, bool enabled) { - switch (color){ + switch (color) { case LED_RED: set_gpio_output(GPIOC, 9, !enabled); break; @@ -16,7 +16,7 @@ void board_v1_set_led(uint8_t color, bool enabled) { } void board_v1_enable_can_transciever(uint8_t transciever, bool enabled) { - switch (transciever){ + switch (transciever) { case 1U: set_gpio_output(GPIOC, 1, !enabled); break; @@ -169,6 +169,7 @@ const board board_v1 = { .set_harness_orientation = &board_v1_set_harness_orientation, .set_can_mode = &board_v1_set_can_mode, .enable_can_transciever = &board_v1_enable_can_transciever, + .enable_header_pin = &unused_board_enable_header_pin, .get_channel_power = &board_v1_get_channel_power, .get_sbu_mV = &board_v1_get_sbu_mV, }; diff --git a/panda/board/jungle/boards/board_v2.h b/panda/board/jungle/boards/board_v2.h index 73a8a0bed..0a6e27368 100644 --- a/panda/board/jungle/boards/board_v2.h +++ b/panda/board/jungle/boards/board_v2.h @@ -108,7 +108,7 @@ void board_v2_set_harness_orientation(uint8_t orientation) { } void board_v2_enable_can_transciever(uint8_t transciever, bool enabled) { - switch (transciever){ + switch (transciever) { case 1U: set_gpio_output(GPIOG, 11, !enabled); break; @@ -127,6 +127,14 @@ void board_v2_enable_can_transciever(uint8_t transciever, bool enabled) { } } +void board_v2_enable_header_pin(uint8_t pin_num, bool enabled) { + if (pin_num < 8U) { + set_gpio_output(GPIOG, pin_num, enabled); + } else { + print("Invalid pin number ("); puth(pin_num); print("): enabling failed\n"); + } +} + void board_v2_set_can_mode(uint8_t mode) { board_v2_enable_can_transciever(2U, false); board_v2_enable_can_transciever(4U, false); @@ -265,6 +273,16 @@ void board_v2_init(void) { set_gpio_mode(GPIOF, 4, MODE_ANALOG); set_gpio_mode(GPIOC, 0, MODE_ANALOG); set_gpio_mode(GPIOC, 1, MODE_ANALOG); + + // Header pins + set_gpio_mode(GPIOG, 0, MODE_OUTPUT); + set_gpio_mode(GPIOG, 1, MODE_OUTPUT); + set_gpio_mode(GPIOG, 2, MODE_OUTPUT); + set_gpio_mode(GPIOG, 3, MODE_OUTPUT); + set_gpio_mode(GPIOG, 4, MODE_OUTPUT); + set_gpio_mode(GPIOG, 5, MODE_OUTPUT); + set_gpio_mode(GPIOG, 6, MODE_OUTPUT); + set_gpio_mode(GPIOG, 7, MODE_OUTPUT); } void board_v2_tick(void) {} @@ -284,6 +302,7 @@ const board board_v2 = { .set_harness_orientation = &board_v2_set_harness_orientation, .set_can_mode = &board_v2_set_can_mode, .enable_can_transciever = &board_v2_enable_can_transciever, + .enable_header_pin = &board_v2_enable_header_pin, .get_channel_power = &board_v2_get_channel_power, .get_sbu_mV = &board_v2_get_sbu_mV, }; diff --git a/panda/board/jungle/main_comms.h b/panda/board/jungle/main_comms.h index 36ed6e79e..252c2d509 100644 --- a/panda/board/jungle/main_comms.h +++ b/panda/board/jungle/main_comms.h @@ -222,6 +222,10 @@ int comms_control_handler(ControlPacket_t *req, uint8_t *resp) { can_silent = (req->param1 > 0U) ? ALL_CAN_SILENT : ALL_CAN_LIVE; can_init_all(); break; + // **** 0xf7: enable/disable header pin by number + case 0xf7: + current_board->enable_header_pin(req->param1, req->param2 > 0U); + break; // **** 0xf9: set CAN FD data bitrate case 0xf9: if ((req->param1 < PANDA_CAN_CNT) && diff --git a/panda/board/jungle/obj/bootstub.panda_jungle.bin b/panda/board/jungle/obj/bootstub.panda_jungle.bin index 1c0d5642a..9680cbb15 100755 Binary files a/panda/board/jungle/obj/bootstub.panda_jungle.bin and b/panda/board/jungle/obj/bootstub.panda_jungle.bin differ diff --git a/panda/board/jungle/obj/bootstub.panda_jungle.elf b/panda/board/jungle/obj/bootstub.panda_jungle.elf index 61e07e997..b360a9680 100755 Binary files a/panda/board/jungle/obj/bootstub.panda_jungle.elf and b/panda/board/jungle/obj/bootstub.panda_jungle.elf differ diff --git a/panda/board/jungle/obj/bootstub.panda_jungle_h7.bin b/panda/board/jungle/obj/bootstub.panda_jungle_h7.bin index 5ca0617c3..ac131f0b3 100755 Binary files a/panda/board/jungle/obj/bootstub.panda_jungle_h7.bin and b/panda/board/jungle/obj/bootstub.panda_jungle_h7.bin differ diff --git a/panda/board/jungle/obj/bootstub.panda_jungle_h7.elf b/panda/board/jungle/obj/bootstub.panda_jungle_h7.elf index 28c9dfc35..ac52d910d 100755 Binary files a/panda/board/jungle/obj/bootstub.panda_jungle_h7.elf and b/panda/board/jungle/obj/bootstub.panda_jungle_h7.elf differ diff --git a/panda/board/jungle/obj/panda_jungle.bin b/panda/board/jungle/obj/panda_jungle.bin index 238ed0d0c..6311a50ee 100755 Binary files a/panda/board/jungle/obj/panda_jungle.bin and b/panda/board/jungle/obj/panda_jungle.bin differ diff --git a/panda/board/jungle/obj/panda_jungle.bin.signed b/panda/board/jungle/obj/panda_jungle.bin.signed index 00099df43..2b2a9439b 100644 Binary files a/panda/board/jungle/obj/panda_jungle.bin.signed and b/panda/board/jungle/obj/panda_jungle.bin.signed differ diff --git a/panda/board/jungle/obj/panda_jungle.elf b/panda/board/jungle/obj/panda_jungle.elf index 6c1d0367c..702c26f01 100755 Binary files a/panda/board/jungle/obj/panda_jungle.elf and b/panda/board/jungle/obj/panda_jungle.elf differ diff --git a/panda/board/jungle/obj/panda_jungle_h7.bin b/panda/board/jungle/obj/panda_jungle_h7.bin index cd9221c4e..1058c8eb2 100755 Binary files a/panda/board/jungle/obj/panda_jungle_h7.bin and b/panda/board/jungle/obj/panda_jungle_h7.bin differ diff --git a/panda/board/jungle/obj/panda_jungle_h7.bin.signed b/panda/board/jungle/obj/panda_jungle_h7.bin.signed index 5c0bbd019..3f4fba679 100644 Binary files a/panda/board/jungle/obj/panda_jungle_h7.bin.signed and b/panda/board/jungle/obj/panda_jungle_h7.bin.signed differ diff --git a/panda/board/jungle/obj/panda_jungle_h7.elf b/panda/board/jungle/obj/panda_jungle_h7.elf index 366b2413a..e4ba9f0e2 100755 Binary files a/panda/board/jungle/obj/panda_jungle_h7.elf and b/panda/board/jungle/obj/panda_jungle_h7.elf differ diff --git a/panda/board/jungle/scripts/debug_console.py b/panda/board/jungle/scripts/debug_console.py index f8dd24ed2..f35388796 100755 --- a/panda/board/jungle/scripts/debug_console.py +++ b/panda/board/jungle/scripts/debug_console.py @@ -17,7 +17,7 @@ if __name__ == "__main__": if os.getenv("SERIAL"): serials = [x for x in serials if x==os.getenv("SERIAL")] - panda_jungles = list([PandaJungle(x, claim=claim) for x in serials]) + panda_jungles = [PandaJungle(x, claim=claim) for x in serials] if not len(panda_jungles): sys.exit("no panda jungles found") diff --git a/panda/board/obj/bootstub.panda.bin b/panda/board/obj/bootstub.panda.bin index b42454ff1..ae2f75ea2 100755 Binary files a/panda/board/obj/bootstub.panda.bin and b/panda/board/obj/bootstub.panda.bin differ diff --git a/panda/board/obj/bootstub.panda.elf b/panda/board/obj/bootstub.panda.elf index eccb50465..832f2392a 100755 Binary files a/panda/board/obj/bootstub.panda.elf and b/panda/board/obj/bootstub.panda.elf differ diff --git a/panda/board/obj/bootstub.panda_h7.bin b/panda/board/obj/bootstub.panda_h7.bin index 743a68b7a..e3e6386a5 100755 Binary files a/panda/board/obj/bootstub.panda_h7.bin and b/panda/board/obj/bootstub.panda_h7.bin differ diff --git a/panda/board/obj/bootstub.panda_h7.elf b/panda/board/obj/bootstub.panda_h7.elf index 97575fe7e..b47eed84a 100755 Binary files a/panda/board/obj/bootstub.panda_h7.elf and b/panda/board/obj/bootstub.panda_h7.elf differ diff --git a/panda/board/obj/bootstub.pedal.bin b/panda/board/obj/bootstub.pedal.bin deleted file mode 100755 index e58f20d24..000000000 Binary files a/panda/board/obj/bootstub.pedal.bin and /dev/null differ diff --git a/panda/board/obj/bootstub.pedal.elf b/panda/board/obj/bootstub.pedal.elf deleted file mode 100755 index 1bb5d3b93..000000000 Binary files a/panda/board/obj/bootstub.pedal.elf and /dev/null differ diff --git a/panda/board/obj/bootstub.pedal_usb.bin b/panda/board/obj/bootstub.pedal_usb.bin deleted file mode 100755 index e58f20d24..000000000 Binary files a/panda/board/obj/bootstub.pedal_usb.bin and /dev/null differ diff --git a/panda/board/obj/bootstub.pedal_usb.elf b/panda/board/obj/bootstub.pedal_usb.elf deleted file mode 100755 index a9d351a37..000000000 Binary files a/panda/board/obj/bootstub.pedal_usb.elf and /dev/null differ diff --git a/panda/board/obj/gitversion.h b/panda/board/obj/gitversion.h index 136d9e56f..a5266aa3f 100644 --- a/panda/board/obj/gitversion.h +++ b/panda/board/obj/gitversion.h @@ -1 +1 @@ -const uint8_t gitversion[] = "DEV-929c52ce-DEBUG"; +const uint8_t gitversion[] = "DEV-501626f0-DEBUG"; diff --git a/panda/board/obj/panda.bin b/panda/board/obj/panda.bin index 65a60a354..61564bfe3 100755 Binary files a/panda/board/obj/panda.bin and b/panda/board/obj/panda.bin differ diff --git a/panda/board/obj/panda.bin.signed b/panda/board/obj/panda.bin.signed index 4ae1cdec8..3b92aa346 100644 Binary files a/panda/board/obj/panda.bin.signed and b/panda/board/obj/panda.bin.signed differ diff --git a/panda/board/obj/panda.elf b/panda/board/obj/panda.elf index e0f74556c..bfc783446 100755 Binary files a/panda/board/obj/panda.elf and b/panda/board/obj/panda.elf differ diff --git a/panda/board/obj/panda_h7.bin b/panda/board/obj/panda_h7.bin index d49c95e94..93b7e5d79 100755 Binary files a/panda/board/obj/panda_h7.bin and b/panda/board/obj/panda_h7.bin differ diff --git a/panda/board/obj/panda_h7.bin.signed b/panda/board/obj/panda_h7.bin.signed index e8c2b4c89..7a913e065 100644 Binary files a/panda/board/obj/panda_h7.bin.signed and b/panda/board/obj/panda_h7.bin.signed differ diff --git a/panda/board/obj/panda_h7.elf b/panda/board/obj/panda_h7.elf index 61ebdba45..73c617a48 100755 Binary files a/panda/board/obj/panda_h7.elf and b/panda/board/obj/panda_h7.elf differ diff --git a/panda/board/obj/pedal.bin b/panda/board/obj/pedal.bin deleted file mode 100755 index d40756fa0..000000000 Binary files a/panda/board/obj/pedal.bin and /dev/null differ diff --git a/panda/board/obj/pedal.bin.signed b/panda/board/obj/pedal.bin.signed deleted file mode 100644 index 186bb538a..000000000 Binary files a/panda/board/obj/pedal.bin.signed and /dev/null differ diff --git a/panda/board/obj/pedal.elf b/panda/board/obj/pedal.elf deleted file mode 100755 index d5fd28177..000000000 Binary files a/panda/board/obj/pedal.elf and /dev/null differ diff --git a/panda/board/obj/pedal_usb.bin b/panda/board/obj/pedal_usb.bin deleted file mode 100755 index eb798fadc..000000000 Binary files a/panda/board/obj/pedal_usb.bin and /dev/null differ diff --git a/panda/board/obj/pedal_usb.bin.signed b/panda/board/obj/pedal_usb.bin.signed deleted file mode 100644 index 1f588fdf1..000000000 Binary files a/panda/board/obj/pedal_usb.bin.signed and /dev/null differ diff --git a/panda/board/obj/pedal_usb.elf b/panda/board/obj/pedal_usb.elf deleted file mode 100755 index e3f7c8bf8..000000000 Binary files a/panda/board/obj/pedal_usb.elf and /dev/null differ diff --git a/panda/board/obj/version b/panda/board/obj/version index d2f1d942f..fa2b5f434 100644 --- a/panda/board/obj/version +++ b/panda/board/obj/version @@ -1 +1 @@ -DEV-929c52ce-DEBUG \ No newline at end of file +DEV-501626f0-DEBUG \ No newline at end of file diff --git a/panda/board/pedal/obj/bootstub.pedal.bin b/panda/board/pedal/obj/bootstub.pedal.bin index 3fc7b1791..606b3eb88 100755 Binary files a/panda/board/pedal/obj/bootstub.pedal.bin and b/panda/board/pedal/obj/bootstub.pedal.bin differ diff --git a/panda/board/pedal/obj/bootstub.pedal.elf b/panda/board/pedal/obj/bootstub.pedal.elf index 8f67dd1e2..af1d07294 100755 Binary files a/panda/board/pedal/obj/bootstub.pedal.elf and b/panda/board/pedal/obj/bootstub.pedal.elf differ diff --git a/panda/board/pedal/obj/bootstub.pedal_usb.bin b/panda/board/pedal/obj/bootstub.pedal_usb.bin index 3fc7b1791..606b3eb88 100755 Binary files a/panda/board/pedal/obj/bootstub.pedal_usb.bin and b/panda/board/pedal/obj/bootstub.pedal_usb.bin differ diff --git a/panda/board/pedal/obj/bootstub.pedal_usb.elf b/panda/board/pedal/obj/bootstub.pedal_usb.elf index 0d1d5bc42..d3506fe61 100755 Binary files a/panda/board/pedal/obj/bootstub.pedal_usb.elf and b/panda/board/pedal/obj/bootstub.pedal_usb.elf differ diff --git a/panda/board/stm32fx/board.h b/panda/board/stm32fx/board.h deleted file mode 100644 index 76593a529..000000000 --- a/panda/board/stm32fx/board.h +++ /dev/null @@ -1,55 +0,0 @@ -// ///////////////////////////////////////////////////////////// // -// Hardware abstraction layer for all different supported boards // -// ///////////////////////////////////////////////////////////// // -#include "boards/board_declarations.h" -#include "boards/unused_funcs.h" - -// ///// Board definition and detection ///// // -#include "stm32fx/lladc.h" -#include "drivers/harness.h" -#ifdef PANDA - #include "drivers/fan.h" - #include "stm32fx/llfan.h" - #include "stm32fx/llrtc.h" - #include "drivers/rtc.h" - #include "drivers/clock_source.h" - #include "boards/white.h" - #include "boards/grey.h" - #include "boards/black.h" - #include "boards/uno.h" - #include "boards/dos.h" -#else - #include "boards/pedal.h" -#endif - -void detect_board_type(void) { - #ifdef PANDA - // SPI lines floating: white (TODO: is this reliable? Not really, we have to enable ESP/GPS to be able to detect this on the UART) - set_gpio_output(GPIOC, 14, 1); - set_gpio_output(GPIOC, 5, 1); - if(!detect_with_pull(GPIOB, 1, PULL_UP) && !detect_with_pull(GPIOB, 7, PULL_UP)){ - hw_type = HW_TYPE_DOS; - current_board = &board_dos; - } else if((detect_with_pull(GPIOA, 4, PULL_DOWN)) || (detect_with_pull(GPIOA, 5, PULL_DOWN)) || (detect_with_pull(GPIOA, 6, PULL_DOWN)) || (detect_with_pull(GPIOA, 7, PULL_DOWN))){ - hw_type = HW_TYPE_WHITE_PANDA; - current_board = &board_white; - } else if(detect_with_pull(GPIOA, 13, PULL_DOWN)) { // Rev AB deprecated, so no pullup means black. In REV C, A13 is pulled up to 5V with a 10K - hw_type = HW_TYPE_GREY_PANDA; - current_board = &board_grey; - } else if(!detect_with_pull(GPIOB, 15, PULL_UP)) { - hw_type = HW_TYPE_UNO; - current_board = &board_uno; - } else { - hw_type = HW_TYPE_BLACK_PANDA; - current_board = &board_black; - } - #else - #ifdef PEDAL - hw_type = HW_TYPE_PEDAL; - current_board = &board_pedal; - #else - hw_type = HW_TYPE_UNKNOWN; - print("Hardware type is UNKNOWN!\n"); - #endif - #endif -} diff --git a/panda/board/stm32fx/clock.h b/panda/board/stm32fx/clock.h deleted file mode 100644 index 19be57443..000000000 --- a/panda/board/stm32fx/clock.h +++ /dev/null @@ -1,34 +0,0 @@ -void clock_init(void) { - // enable external oscillator - register_set_bits(&(RCC->CR), RCC_CR_HSEON); - while ((RCC->CR & RCC_CR_HSERDY) == 0); - - // divide things - // AHB = 96MHz - // APB1 = 48MHz - // APB2 = 48MHz - register_set(&(RCC->CFGR), RCC_CFGR_HPRE_DIV1 | RCC_CFGR_PPRE2_DIV2 | RCC_CFGR_PPRE1_DIV2, 0xFF7FFCF3U); - - // 16MHz crystal - // PLLM: 8 - // PLLN: 96 - // PLLP: 2 - // PLLQ: 4 - // P output: 96MHz - // Q output: 48MHz - register_set(&(RCC->PLLCFGR), RCC_PLLCFGR_PLLQ_2 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLN_6 | RCC_PLLCFGR_PLLN_5 | RCC_PLLCFGR_PLLSRC_HSE, 0x7F437FFFU); - - // start PLL - register_set_bits(&(RCC->CR), RCC_CR_PLLON); - while ((RCC->CR & RCC_CR_PLLRDY) == 0); - - // Configure Flash prefetch, Instruction cache, Data cache and wait state - // *** without this, it breaks *** - register_set(&(FLASH->ACR), FLASH_ACR_ICEN | FLASH_ACR_DCEN | FLASH_ACR_LATENCY_5WS, 0x1F0FU); - - // switch to PLL - register_set_bits(&(RCC->CFGR), RCC_CFGR_SW_PLL); - while ((RCC->CFGR & RCC_CFGR_SWS) != RCC_CFGR_SWS_PLL); - - // *** running on PLL *** -} diff --git a/panda/board/stm32fx/inc/cmsis_compiler.h b/panda/board/stm32fx/inc/cmsis_compiler.h deleted file mode 100644 index d0f39eef6..000000000 --- a/panda/board/stm32fx/inc/cmsis_compiler.h +++ /dev/null @@ -1,284 +0,0 @@ -/**************************************************************************//** - * @file cmsis_compiler.h - * @brief CMSIS compiler generic header file - * @version V5.1.0 - * @date 09. October 2018 - ******************************************************************************/ -/* - * Copyright (c) 2009-2018 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed under the Apache License, Version 2.0 (the License); you may - * not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an AS IS BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#ifndef __CMSIS_COMPILER_H -#define __CMSIS_COMPILER_H - -#include - -/* - * Arm Compiler 4/5 - */ -#if defined ( __CC_ARM ) - #include "cmsis_armcc.h" - - -/* - * Arm Compiler 6.6 LTM (armclang) - */ -#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) && (__ARMCC_VERSION < 6100100) - #include "cmsis_armclang_ltm.h" - - /* - * Arm Compiler above 6.10.1 (armclang) - */ -#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6100100) - #include "cmsis_armclang.h" - - -/* - * GNU Compiler - */ -#elif defined ( __GNUC__ ) - #include "cmsis_gcc.h" - - -/* - * IAR Compiler - */ -#elif defined ( __ICCARM__ ) - #include - - -/* - * TI Arm Compiler - */ -#elif defined ( __TI_ARM__ ) - #include - - #ifndef __ASM - #define __ASM __asm - #endif - #ifndef __INLINE - #define __INLINE inline - #endif - #ifndef __STATIC_INLINE - #define __STATIC_INLINE static inline - #endif - #ifndef __STATIC_FORCEINLINE - #define __STATIC_FORCEINLINE __STATIC_INLINE - #endif - #ifndef __NO_RETURN - #define __NO_RETURN __attribute__((noreturn)) - #endif - #ifndef __USED - #define __USED __attribute__((used)) - #endif - #ifndef __WEAK - #define __WEAK __attribute__((weak)) - #endif - #ifndef __PACKED - #define __PACKED __attribute__((packed)) - #endif - #ifndef __PACKED_STRUCT - #define __PACKED_STRUCT struct __attribute__((packed)) - #endif - #ifndef __PACKED_UNION - #define __PACKED_UNION union __attribute__((packed)) - #endif - #ifndef __UNALIGNED_UINT32 /* deprecated */ - struct __attribute__((packed)) T_UINT32 { uint32_t v; }; - #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) - #endif - #ifndef __UNALIGNED_UINT16_WRITE - __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; - #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void*)(addr))->v) = (val)) - #endif - #ifndef __UNALIGNED_UINT16_READ - __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; - #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) - #endif - #ifndef __UNALIGNED_UINT32_WRITE - __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; - #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) - #endif - #ifndef __UNALIGNED_UINT32_READ - __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; - #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) - #endif - #ifndef __ALIGNED - #define __ALIGNED(x) __attribute__((aligned(x))) - #endif - #ifndef __RESTRICT - #define __RESTRICT __restrict - #endif - #ifndef __COMPILER_BARRIER - #warning No compiler specific solution for __COMPILER_BARRIER. __COMPILER_BARRIER is ignored. - #define __COMPILER_BARRIER() (void)0 - #endif - - -/* - * TASKING Compiler - */ -#elif defined ( __TASKING__ ) - /* - * The CMSIS functions have been implemented as intrinsics in the compiler. - * Please use "carm -?i" to get an up to date list of all intrinsics, - * Including the CMSIS ones. - */ - - #ifndef __ASM - #define __ASM __asm - #endif - #ifndef __INLINE - #define __INLINE inline - #endif - #ifndef __STATIC_INLINE - #define __STATIC_INLINE static inline - #endif - #ifndef __STATIC_FORCEINLINE - #define __STATIC_FORCEINLINE __STATIC_INLINE - #endif - #ifndef __NO_RETURN - #define __NO_RETURN __attribute__((noreturn)) - #endif - #ifndef __USED - #define __USED __attribute__((used)) - #endif - #ifndef __WEAK - #define __WEAK __attribute__((weak)) - #endif - #ifndef __PACKED - #define __PACKED __packed__ - #endif - #ifndef __PACKED_STRUCT - #define __PACKED_STRUCT struct __packed__ - #endif - #ifndef __PACKED_UNION - #define __PACKED_UNION union __packed__ - #endif - #ifndef __UNALIGNED_UINT32 /* deprecated */ - struct __packed__ T_UINT32 { uint32_t v; }; - #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) - #endif - #ifndef __UNALIGNED_UINT16_WRITE - __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; - #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val)) - #endif - #ifndef __UNALIGNED_UINT16_READ - __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; - #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) - #endif - #ifndef __UNALIGNED_UINT32_WRITE - __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; - #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) - #endif - #ifndef __UNALIGNED_UINT32_READ - __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; - #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) - #endif - #ifndef __ALIGNED - #define __ALIGNED(x) __align(x) - #endif - #ifndef __RESTRICT - #warning No compiler specific solution for __RESTRICT. __RESTRICT is ignored. - #define __RESTRICT - #endif - #ifndef __COMPILER_BARRIER - #warning No compiler specific solution for __COMPILER_BARRIER. __COMPILER_BARRIER is ignored. - #define __COMPILER_BARRIER() (void)0 - #endif - - -/* - * COSMIC Compiler - */ -#elif defined ( __CSMC__ ) - #include - - #ifndef __ASM - #define __ASM _asm - #endif - #ifndef __INLINE - #define __INLINE inline - #endif - #ifndef __STATIC_INLINE - #define __STATIC_INLINE static inline - #endif - #ifndef __STATIC_FORCEINLINE - #define __STATIC_FORCEINLINE __STATIC_INLINE - #endif - #ifndef __NO_RETURN - // NO RETURN is automatically detected hence no warning here - #define __NO_RETURN - #endif - #ifndef __USED - #warning No compiler specific solution for __USED. __USED is ignored. - #define __USED - #endif - #ifndef __WEAK - #define __WEAK __weak - #endif - #ifndef __PACKED - #define __PACKED @packed - #endif - #ifndef __PACKED_STRUCT - #define __PACKED_STRUCT @packed struct - #endif - #ifndef __PACKED_UNION - #define __PACKED_UNION @packed union - #endif - #ifndef __UNALIGNED_UINT32 /* deprecated */ - @packed struct T_UINT32 { uint32_t v; }; - #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) - #endif - #ifndef __UNALIGNED_UINT16_WRITE - __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; - #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val)) - #endif - #ifndef __UNALIGNED_UINT16_READ - __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; - #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) - #endif - #ifndef __UNALIGNED_UINT32_WRITE - __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; - #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) - #endif - #ifndef __UNALIGNED_UINT32_READ - __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; - #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) - #endif - #ifndef __ALIGNED - #warning No compiler specific solution for __ALIGNED. __ALIGNED is ignored. - #define __ALIGNED(x) - #endif - #ifndef __RESTRICT - #warning No compiler specific solution for __RESTRICT. __RESTRICT is ignored. - #define __RESTRICT - #endif - #ifndef __COMPILER_BARRIER - #warning No compiler specific solution for __COMPILER_BARRIER. __COMPILER_BARRIER is ignored. - #define __COMPILER_BARRIER() (void)0 - #endif - - -#else - #error Unknown compiler. -#endif - - -#endif /* __CMSIS_COMPILER_H */ - - diff --git a/panda/board/stm32fx/inc/cmsis_gcc.h b/panda/board/stm32fx/inc/cmsis_gcc.h deleted file mode 100644 index 2f68473f6..000000000 --- a/panda/board/stm32fx/inc/cmsis_gcc.h +++ /dev/null @@ -1,2169 +0,0 @@ -/**************************************************************************//** - * @file cmsis_gcc.h - * @brief CMSIS compiler GCC header file - * @version V5.2.0 - * @date 08. May 2019 - ******************************************************************************/ -/* - * Copyright (c) 2009-2019 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed under the Apache License, Version 2.0 (the License); you may - * not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an AS IS BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#ifndef __CMSIS_GCC_H -#define __CMSIS_GCC_H - -/* ignore some GCC warnings */ -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wsign-conversion" -#pragma GCC diagnostic ignored "-Wconversion" -#pragma GCC diagnostic ignored "-Wunused-parameter" - -/* Fallback for __has_builtin */ -#ifndef __has_builtin - #define __has_builtin(x) (0) -#endif - -/* CMSIS compiler specific defines */ -#ifndef __ASM - #define __ASM __asm -#endif -#ifndef __INLINE - #define __INLINE inline -#endif -#ifndef __STATIC_INLINE - #define __STATIC_INLINE static inline -#endif -#ifndef __STATIC_FORCEINLINE - #define __STATIC_FORCEINLINE __attribute__((always_inline)) static inline -#endif -#ifndef __NO_RETURN - #define __NO_RETURN __attribute__((__noreturn__)) -#endif -#ifndef __USED - #define __USED __attribute__((used)) -#endif -#ifndef __WEAK - #define __WEAK __attribute__((weak)) -#endif -#ifndef __PACKED - #define __PACKED __attribute__((packed, aligned(1))) -#endif -#ifndef __PACKED_STRUCT - #define __PACKED_STRUCT struct __attribute__((packed, aligned(1))) -#endif -#ifndef __PACKED_UNION - #define __PACKED_UNION union __attribute__((packed, aligned(1))) -#endif -#ifndef __UNALIGNED_UINT32 /* deprecated */ - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wpacked" - #pragma GCC diagnostic ignored "-Wattributes" - struct __attribute__((packed)) T_UINT32 { uint32_t v; }; - #pragma GCC diagnostic pop - #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) -#endif -#ifndef __UNALIGNED_UINT16_WRITE - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wpacked" - #pragma GCC diagnostic ignored "-Wattributes" - __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; - #pragma GCC diagnostic pop - #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val)) -#endif -#ifndef __UNALIGNED_UINT16_READ - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wpacked" - #pragma GCC diagnostic ignored "-Wattributes" - __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; - #pragma GCC diagnostic pop - #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) -#endif -#ifndef __UNALIGNED_UINT32_WRITE - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wpacked" - #pragma GCC diagnostic ignored "-Wattributes" - __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; - #pragma GCC diagnostic pop - #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) -#endif -#ifndef __UNALIGNED_UINT32_READ - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wpacked" - #pragma GCC diagnostic ignored "-Wattributes" - __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; - #pragma GCC diagnostic pop - #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) -#endif -#ifndef __ALIGNED - #define __ALIGNED(x) __attribute__((aligned(x))) -#endif -#ifndef __RESTRICT - #define __RESTRICT __restrict -#endif -#ifndef __COMPILER_BARRIER - #define __COMPILER_BARRIER() __ASM volatile("":::"memory") -#endif - -/* ######################### Startup and Lowlevel Init ######################## */ - -#ifndef __PROGRAM_START - -/** - \brief Initializes data and bss sections - \details This default implementations initialized all data and additional bss - sections relying on .copy.table and .zero.table specified properly - in the used linker script. - - */ -__STATIC_FORCEINLINE __NO_RETURN void __cmsis_start(void) -{ - extern void _start(void) __NO_RETURN; - - typedef struct { - uint32_t const* src; - uint32_t* dest; - uint32_t wlen; - } __copy_table_t; - - typedef struct { - uint32_t* dest; - uint32_t wlen; - } __zero_table_t; - - extern const __copy_table_t __copy_table_start__; - extern const __copy_table_t __copy_table_end__; - extern const __zero_table_t __zero_table_start__; - extern const __zero_table_t __zero_table_end__; - - for (__copy_table_t const* pTable = &__copy_table_start__; pTable < &__copy_table_end__; ++pTable) { - for(uint32_t i=0u; iwlen; ++i) { - pTable->dest[i] = pTable->src[i]; - } - } - - for (__zero_table_t const* pTable = &__zero_table_start__; pTable < &__zero_table_end__; ++pTable) { - for(uint32_t i=0u; iwlen; ++i) { - pTable->dest[i] = 0u; - } - } - - _start(); -} - -#define __PROGRAM_START __cmsis_start -#endif - -#ifndef __INITIAL_SP -#define __INITIAL_SP __StackTop -#endif - -#ifndef __STACK_LIMIT -#define __STACK_LIMIT __StackLimit -#endif - -#ifndef __VECTOR_TABLE -#define __VECTOR_TABLE __Vectors -#endif - -#ifndef __VECTOR_TABLE_ATTRIBUTE -#define __VECTOR_TABLE_ATTRIBUTE __attribute((used, section(".vectors"))) -#endif - -/* ########################### Core Function Access ########################### */ -/** \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions - @{ - */ - -/** - \brief Enable IRQ Interrupts - \details Enables IRQ interrupts by clearing the I-bit in the CPSR. - Can only be executed in Privileged modes. - */ -__STATIC_FORCEINLINE void __enable_irq(void) -{ - __ASM volatile ("cpsie i" : : : "memory"); -} - - -/** - \brief Disable IRQ Interrupts - \details Disables IRQ interrupts by setting the I-bit in the CPSR. - Can only be executed in Privileged modes. - */ -__STATIC_FORCEINLINE void __disable_irq(void) -{ - __ASM volatile ("cpsid i" : : : "memory"); -} - - -/** - \brief Get Control Register - \details Returns the content of the Control Register. - \return Control Register value - */ -__STATIC_FORCEINLINE uint32_t __get_CONTROL(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, control" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Control Register (non-secure) - \details Returns the content of the non-secure Control Register when in secure mode. - \return non-secure Control Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_CONTROL_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, control_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Control Register - \details Writes the given value to the Control Register. - \param [in] control Control Register value to set - */ -__STATIC_FORCEINLINE void __set_CONTROL(uint32_t control) -{ - __ASM volatile ("MSR control, %0" : : "r" (control) : "memory"); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Control Register (non-secure) - \details Writes the given value to the non-secure Control Register when in secure state. - \param [in] control Control Register value to set - */ -__STATIC_FORCEINLINE void __TZ_set_CONTROL_NS(uint32_t control) -{ - __ASM volatile ("MSR control_ns, %0" : : "r" (control) : "memory"); -} -#endif - - -/** - \brief Get IPSR Register - \details Returns the content of the IPSR Register. - \return IPSR Register value - */ -__STATIC_FORCEINLINE uint32_t __get_IPSR(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, ipsr" : "=r" (result) ); - return(result); -} - - -/** - \brief Get APSR Register - \details Returns the content of the APSR Register. - \return APSR Register value - */ -__STATIC_FORCEINLINE uint32_t __get_APSR(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, apsr" : "=r" (result) ); - return(result); -} - - -/** - \brief Get xPSR Register - \details Returns the content of the xPSR Register. - \return xPSR Register value - */ -__STATIC_FORCEINLINE uint32_t __get_xPSR(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, xpsr" : "=r" (result) ); - return(result); -} - - -/** - \brief Get Process Stack Pointer - \details Returns the current value of the Process Stack Pointer (PSP). - \return PSP Register value - */ -__STATIC_FORCEINLINE uint32_t __get_PSP(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, psp" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Process Stack Pointer (non-secure) - \details Returns the current value of the non-secure Process Stack Pointer (PSP) when in secure state. - \return PSP Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_PSP_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, psp_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Process Stack Pointer - \details Assigns the given value to the Process Stack Pointer (PSP). - \param [in] topOfProcStack Process Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __set_PSP(uint32_t topOfProcStack) -{ - __ASM volatile ("MSR psp, %0" : : "r" (topOfProcStack) : ); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Process Stack Pointer (non-secure) - \details Assigns the given value to the non-secure Process Stack Pointer (PSP) when in secure state. - \param [in] topOfProcStack Process Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __TZ_set_PSP_NS(uint32_t topOfProcStack) -{ - __ASM volatile ("MSR psp_ns, %0" : : "r" (topOfProcStack) : ); -} -#endif - - -/** - \brief Get Main Stack Pointer - \details Returns the current value of the Main Stack Pointer (MSP). - \return MSP Register value - */ -__STATIC_FORCEINLINE uint32_t __get_MSP(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, msp" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Main Stack Pointer (non-secure) - \details Returns the current value of the non-secure Main Stack Pointer (MSP) when in secure state. - \return MSP Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_MSP_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, msp_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Main Stack Pointer - \details Assigns the given value to the Main Stack Pointer (MSP). - \param [in] topOfMainStack Main Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __set_MSP(uint32_t topOfMainStack) -{ - __ASM volatile ("MSR msp, %0" : : "r" (topOfMainStack) : ); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Main Stack Pointer (non-secure) - \details Assigns the given value to the non-secure Main Stack Pointer (MSP) when in secure state. - \param [in] topOfMainStack Main Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __TZ_set_MSP_NS(uint32_t topOfMainStack) -{ - __ASM volatile ("MSR msp_ns, %0" : : "r" (topOfMainStack) : ); -} -#endif - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Stack Pointer (non-secure) - \details Returns the current value of the non-secure Stack Pointer (SP) when in secure state. - \return SP Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_SP_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, sp_ns" : "=r" (result) ); - return(result); -} - - -/** - \brief Set Stack Pointer (non-secure) - \details Assigns the given value to the non-secure Stack Pointer (SP) when in secure state. - \param [in] topOfStack Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __TZ_set_SP_NS(uint32_t topOfStack) -{ - __ASM volatile ("MSR sp_ns, %0" : : "r" (topOfStack) : ); -} -#endif - - -/** - \brief Get Priority Mask - \details Returns the current state of the priority mask bit from the Priority Mask Register. - \return Priority Mask value - */ -__STATIC_FORCEINLINE uint32_t __get_PRIMASK(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, primask" : "=r" (result) :: "memory"); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Priority Mask (non-secure) - \details Returns the current state of the non-secure priority mask bit from the Priority Mask Register when in secure state. - \return Priority Mask value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_PRIMASK_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, primask_ns" : "=r" (result) :: "memory"); - return(result); -} -#endif - - -/** - \brief Set Priority Mask - \details Assigns the given value to the Priority Mask Register. - \param [in] priMask Priority Mask - */ -__STATIC_FORCEINLINE void __set_PRIMASK(uint32_t priMask) -{ - __ASM volatile ("MSR primask, %0" : : "r" (priMask) : "memory"); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Priority Mask (non-secure) - \details Assigns the given value to the non-secure Priority Mask Register when in secure state. - \param [in] priMask Priority Mask - */ -__STATIC_FORCEINLINE void __TZ_set_PRIMASK_NS(uint32_t priMask) -{ - __ASM volatile ("MSR primask_ns, %0" : : "r" (priMask) : "memory"); -} -#endif - - -#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) -/** - \brief Enable FIQ - \details Enables FIQ interrupts by clearing the F-bit in the CPSR. - Can only be executed in Privileged modes. - */ -__STATIC_FORCEINLINE void __enable_fault_irq(void) -{ - __ASM volatile ("cpsie f" : : : "memory"); -} - - -/** - \brief Disable FIQ - \details Disables FIQ interrupts by setting the F-bit in the CPSR. - Can only be executed in Privileged modes. - */ -__STATIC_FORCEINLINE void __disable_fault_irq(void) -{ - __ASM volatile ("cpsid f" : : : "memory"); -} - - -/** - \brief Get Base Priority - \details Returns the current value of the Base Priority register. - \return Base Priority register value - */ -__STATIC_FORCEINLINE uint32_t __get_BASEPRI(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, basepri" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Base Priority (non-secure) - \details Returns the current value of the non-secure Base Priority register when in secure state. - \return Base Priority register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_BASEPRI_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, basepri_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Base Priority - \details Assigns the given value to the Base Priority register. - \param [in] basePri Base Priority value to set - */ -__STATIC_FORCEINLINE void __set_BASEPRI(uint32_t basePri) -{ - __ASM volatile ("MSR basepri, %0" : : "r" (basePri) : "memory"); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Base Priority (non-secure) - \details Assigns the given value to the non-secure Base Priority register when in secure state. - \param [in] basePri Base Priority value to set - */ -__STATIC_FORCEINLINE void __TZ_set_BASEPRI_NS(uint32_t basePri) -{ - __ASM volatile ("MSR basepri_ns, %0" : : "r" (basePri) : "memory"); -} -#endif - - -/** - \brief Set Base Priority with condition - \details Assigns the given value to the Base Priority register only if BASEPRI masking is disabled, - or the new value increases the BASEPRI priority level. - \param [in] basePri Base Priority value to set - */ -__STATIC_FORCEINLINE void __set_BASEPRI_MAX(uint32_t basePri) -{ - __ASM volatile ("MSR basepri_max, %0" : : "r" (basePri) : "memory"); -} - - -/** - \brief Get Fault Mask - \details Returns the current value of the Fault Mask register. - \return Fault Mask register value - */ -__STATIC_FORCEINLINE uint32_t __get_FAULTMASK(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, faultmask" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Fault Mask (non-secure) - \details Returns the current value of the non-secure Fault Mask register when in secure state. - \return Fault Mask register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_FAULTMASK_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, faultmask_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Fault Mask - \details Assigns the given value to the Fault Mask register. - \param [in] faultMask Fault Mask value to set - */ -__STATIC_FORCEINLINE void __set_FAULTMASK(uint32_t faultMask) -{ - __ASM volatile ("MSR faultmask, %0" : : "r" (faultMask) : "memory"); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Fault Mask (non-secure) - \details Assigns the given value to the non-secure Fault Mask register when in secure state. - \param [in] faultMask Fault Mask value to set - */ -__STATIC_FORCEINLINE void __TZ_set_FAULTMASK_NS(uint32_t faultMask) -{ - __ASM volatile ("MSR faultmask_ns, %0" : : "r" (faultMask) : "memory"); -} -#endif - -#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ - - -#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) - -/** - \brief Get Process Stack Pointer Limit - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence zero is returned always in non-secure - mode. - - \details Returns the current value of the Process Stack Pointer Limit (PSPLIM). - \return PSPLIM Register value - */ -__STATIC_FORCEINLINE uint32_t __get_PSPLIM(void) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - return 0U; -#else - uint32_t result; - __ASM volatile ("MRS %0, psplim" : "=r" (result) ); - return result; -#endif -} - -#if (defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Process Stack Pointer Limit (non-secure) - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence zero is returned always. - - \details Returns the current value of the non-secure Process Stack Pointer Limit (PSPLIM) when in secure state. - \return PSPLIM Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_PSPLIM_NS(void) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - return 0U; -#else - uint32_t result; - __ASM volatile ("MRS %0, psplim_ns" : "=r" (result) ); - return result; -#endif -} -#endif - - -/** - \brief Set Process Stack Pointer Limit - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence the write is silently ignored in non-secure - mode. - - \details Assigns the given value to the Process Stack Pointer Limit (PSPLIM). - \param [in] ProcStackPtrLimit Process Stack Pointer Limit value to set - */ -__STATIC_FORCEINLINE void __set_PSPLIM(uint32_t ProcStackPtrLimit) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - (void)ProcStackPtrLimit; -#else - __ASM volatile ("MSR psplim, %0" : : "r" (ProcStackPtrLimit)); -#endif -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Process Stack Pointer (non-secure) - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence the write is silently ignored. - - \details Assigns the given value to the non-secure Process Stack Pointer Limit (PSPLIM) when in secure state. - \param [in] ProcStackPtrLimit Process Stack Pointer Limit value to set - */ -__STATIC_FORCEINLINE void __TZ_set_PSPLIM_NS(uint32_t ProcStackPtrLimit) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - (void)ProcStackPtrLimit; -#else - __ASM volatile ("MSR psplim_ns, %0\n" : : "r" (ProcStackPtrLimit)); -#endif -} -#endif - - -/** - \brief Get Main Stack Pointer Limit - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence zero is returned always in non-secure - mode. - - \details Returns the current value of the Main Stack Pointer Limit (MSPLIM). - \return MSPLIM Register value - */ -__STATIC_FORCEINLINE uint32_t __get_MSPLIM(void) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - return 0U; -#else - uint32_t result; - __ASM volatile ("MRS %0, msplim" : "=r" (result) ); - return result; -#endif -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Main Stack Pointer Limit (non-secure) - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence zero is returned always. - - \details Returns the current value of the non-secure Main Stack Pointer Limit(MSPLIM) when in secure state. - \return MSPLIM Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_MSPLIM_NS(void) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - return 0U; -#else - uint32_t result; - __ASM volatile ("MRS %0, msplim_ns" : "=r" (result) ); - return result; -#endif -} -#endif - - -/** - \brief Set Main Stack Pointer Limit - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence the write is silently ignored in non-secure - mode. - - \details Assigns the given value to the Main Stack Pointer Limit (MSPLIM). - \param [in] MainStackPtrLimit Main Stack Pointer Limit value to set - */ -__STATIC_FORCEINLINE void __set_MSPLIM(uint32_t MainStackPtrLimit) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - (void)MainStackPtrLimit; -#else - __ASM volatile ("MSR msplim, %0" : : "r" (MainStackPtrLimit)); -#endif -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Main Stack Pointer Limit (non-secure) - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence the write is silently ignored. - - \details Assigns the given value to the non-secure Main Stack Pointer Limit (MSPLIM) when in secure state. - \param [in] MainStackPtrLimit Main Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __TZ_set_MSPLIM_NS(uint32_t MainStackPtrLimit) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - (void)MainStackPtrLimit; -#else - __ASM volatile ("MSR msplim_ns, %0" : : "r" (MainStackPtrLimit)); -#endif -} -#endif - -#endif /* ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ - - -/** - \brief Get FPSCR - \details Returns the current value of the Floating Point Status/Control register. - \return Floating Point Status/Control register value - */ -__STATIC_FORCEINLINE uint32_t __get_FPSCR(void) -{ -#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ - (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) -#if __has_builtin(__builtin_arm_get_fpscr) -// Re-enable using built-in when GCC has been fixed -// || (__GNUC__ > 7) || (__GNUC__ == 7 && __GNUC_MINOR__ >= 2) - /* see https://gcc.gnu.org/ml/gcc-patches/2017-04/msg00443.html */ - return __builtin_arm_get_fpscr(); -#else - uint32_t result; - - __ASM volatile ("VMRS %0, fpscr" : "=r" (result) ); - return(result); -#endif -#else - return(0U); -#endif -} - - -/** - \brief Set FPSCR - \details Assigns the given value to the Floating Point Status/Control register. - \param [in] fpscr Floating Point Status/Control value to set - */ -__STATIC_FORCEINLINE void __set_FPSCR(uint32_t fpscr) -{ -#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ - (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) -#if __has_builtin(__builtin_arm_set_fpscr) -// Re-enable using built-in when GCC has been fixed -// || (__GNUC__ > 7) || (__GNUC__ == 7 && __GNUC_MINOR__ >= 2) - /* see https://gcc.gnu.org/ml/gcc-patches/2017-04/msg00443.html */ - __builtin_arm_set_fpscr(fpscr); -#else - __ASM volatile ("VMSR fpscr, %0" : : "r" (fpscr) : "vfpcc", "memory"); -#endif -#else - (void)fpscr; -#endif -} - - -/*@} end of CMSIS_Core_RegAccFunctions */ - - -/* ########################## Core Instruction Access ######################### */ -/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface - Access to dedicated instructions - @{ -*/ - -/* Define macros for porting to both thumb1 and thumb2. - * For thumb1, use low register (r0-r7), specified by constraint "l" - * Otherwise, use general registers, specified by constraint "r" */ -#if defined (__thumb__) && !defined (__thumb2__) -#define __CMSIS_GCC_OUT_REG(r) "=l" (r) -#define __CMSIS_GCC_RW_REG(r) "+l" (r) -#define __CMSIS_GCC_USE_REG(r) "l" (r) -#else -#define __CMSIS_GCC_OUT_REG(r) "=r" (r) -#define __CMSIS_GCC_RW_REG(r) "+r" (r) -#define __CMSIS_GCC_USE_REG(r) "r" (r) -#endif - -/** - \brief No Operation - \details No Operation does nothing. This instruction can be used for code alignment purposes. - */ -#define __NOP() __ASM volatile ("nop") - -/** - \brief Wait For Interrupt - \details Wait For Interrupt is a hint instruction that suspends execution until one of a number of events occurs. - */ -#define __WFI() __ASM volatile ("wfi") - - -/** - \brief Wait For Event - \details Wait For Event is a hint instruction that permits the processor to enter - a low-power state until one of a number of events occurs. - */ -#define __WFE() __ASM volatile ("wfe") - - -/** - \brief Send Event - \details Send Event is a hint instruction. It causes an event to be signaled to the CPU. - */ -#define __SEV() __ASM volatile ("sev") - - -/** - \brief Instruction Synchronization Barrier - \details Instruction Synchronization Barrier flushes the pipeline in the processor, - so that all instructions following the ISB are fetched from cache or memory, - after the instruction has been completed. - */ -__STATIC_FORCEINLINE void __ISB(void) -{ - __ASM volatile ("isb 0xF":::"memory"); -} - - -/** - \brief Data Synchronization Barrier - \details Acts as a special kind of Data Memory Barrier. - It completes when all explicit memory accesses before this instruction complete. - */ -__STATIC_FORCEINLINE void __DSB(void) -{ - __ASM volatile ("dsb 0xF":::"memory"); -} - - -/** - \brief Data Memory Barrier - \details Ensures the apparent order of the explicit memory operations before - and after the instruction, without ensuring their completion. - */ -__STATIC_FORCEINLINE void __DMB(void) -{ - __ASM volatile ("dmb 0xF":::"memory"); -} - - -/** - \brief Reverse byte order (32 bit) - \details Reverses the byte order in unsigned integer value. For example, 0x12345678 becomes 0x78563412. - \param [in] value Value to reverse - \return Reversed value - */ -__STATIC_FORCEINLINE uint32_t __REV(uint32_t value) -{ -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 5) - return __builtin_bswap32(value); -#else - uint32_t result; - - __ASM volatile ("rev %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); - return result; -#endif -} - - -/** - \brief Reverse byte order (16 bit) - \details Reverses the byte order within each halfword of a word. For example, 0x12345678 becomes 0x34127856. - \param [in] value Value to reverse - \return Reversed value - */ -__STATIC_FORCEINLINE uint32_t __REV16(uint32_t value) -{ - uint32_t result; - - __ASM volatile ("rev16 %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); - return result; -} - - -/** - \brief Reverse byte order (16 bit) - \details Reverses the byte order in a 16-bit value and returns the signed 16-bit result. For example, 0x0080 becomes 0x8000. - \param [in] value Value to reverse - \return Reversed value - */ -__STATIC_FORCEINLINE int16_t __REVSH(int16_t value) -{ -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) - return (int16_t)__builtin_bswap16(value); -#else - int16_t result; - - __ASM volatile ("revsh %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); - return result; -#endif -} - - -/** - \brief Rotate Right in unsigned value (32 bit) - \details Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits. - \param [in] op1 Value to rotate - \param [in] op2 Number of Bits to rotate - \return Rotated value - */ -__STATIC_FORCEINLINE uint32_t __ROR(uint32_t op1, uint32_t op2) -{ - op2 %= 32U; - if (op2 == 0U) - { - return op1; - } - return (op1 >> op2) | (op1 << (32U - op2)); -} - - -/** - \brief Breakpoint - \details Causes the processor to enter Debug state. - Debug tools can use this to investigate system state when the instruction at a particular address is reached. - \param [in] value is ignored by the processor. - If required, a debugger can use it to store additional information about the breakpoint. - */ -#define __BKPT(value) __ASM volatile ("bkpt "#value) - - -/** - \brief Reverse bit order of value - \details Reverses the bit order of the given value. - \param [in] value Value to reverse - \return Reversed value - */ -__STATIC_FORCEINLINE uint32_t __RBIT(uint32_t value) -{ - uint32_t result; - -#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) - __ASM volatile ("rbit %0, %1" : "=r" (result) : "r" (value) ); -#else - uint32_t s = (4U /*sizeof(v)*/ * 8U) - 1U; /* extra shift needed at end */ - - result = value; /* r will be reversed bits of v; first get LSB of v */ - for (value >>= 1U; value != 0U; value >>= 1U) - { - result <<= 1U; - result |= value & 1U; - s--; - } - result <<= s; /* shift when v's highest bits are zero */ -#endif - return result; -} - - -/** - \brief Count leading zeros - \details Counts the number of leading zeros of a data value. - \param [in] value Value to count the leading zeros - \return number of leading zeros in value - */ -__STATIC_FORCEINLINE uint8_t __CLZ(uint32_t value) -{ - /* Even though __builtin_clz produces a CLZ instruction on ARM, formally - __builtin_clz(0) is undefined behaviour, so handle this case specially. - This guarantees ARM-compatible results if happening to compile on a non-ARM - target, and ensures the compiler doesn't decide to activate any - optimisations using the logic "value was passed to __builtin_clz, so it - is non-zero". - ARM GCC 7.3 and possibly earlier will optimise this test away, leaving a - single CLZ instruction. - */ - if (value == 0U) - { - return 32U; - } - return __builtin_clz(value); -} - - -#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) -/** - \brief LDR Exclusive (8 bit) - \details Executes a exclusive LDR instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -__STATIC_FORCEINLINE uint8_t __LDREXB(volatile uint8_t *addr) -{ - uint32_t result; - -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) - __ASM volatile ("ldrexb %0, %1" : "=r" (result) : "Q" (*addr) ); -#else - /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not - accepted by assembler. So has to use following less efficient pattern. - */ - __ASM volatile ("ldrexb %0, [%1]" : "=r" (result) : "r" (addr) : "memory" ); -#endif - return ((uint8_t) result); /* Add explicit type cast here */ -} - - -/** - \brief LDR Exclusive (16 bit) - \details Executes a exclusive LDR instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -__STATIC_FORCEINLINE uint16_t __LDREXH(volatile uint16_t *addr) -{ - uint32_t result; - -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) - __ASM volatile ("ldrexh %0, %1" : "=r" (result) : "Q" (*addr) ); -#else - /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not - accepted by assembler. So has to use following less efficient pattern. - */ - __ASM volatile ("ldrexh %0, [%1]" : "=r" (result) : "r" (addr) : "memory" ); -#endif - return ((uint16_t) result); /* Add explicit type cast here */ -} - - -/** - \brief LDR Exclusive (32 bit) - \details Executes a exclusive LDR instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -__STATIC_FORCEINLINE uint32_t __LDREXW(volatile uint32_t *addr) -{ - uint32_t result; - - __ASM volatile ("ldrex %0, %1" : "=r" (result) : "Q" (*addr) ); - return(result); -} - - -/** - \brief STR Exclusive (8 bit) - \details Executes a exclusive STR instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__STATIC_FORCEINLINE uint32_t __STREXB(uint8_t value, volatile uint8_t *addr) -{ - uint32_t result; - - __ASM volatile ("strexb %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" ((uint32_t)value) ); - return(result); -} - - -/** - \brief STR Exclusive (16 bit) - \details Executes a exclusive STR instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__STATIC_FORCEINLINE uint32_t __STREXH(uint16_t value, volatile uint16_t *addr) -{ - uint32_t result; - - __ASM volatile ("strexh %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" ((uint32_t)value) ); - return(result); -} - - -/** - \brief STR Exclusive (32 bit) - \details Executes a exclusive STR instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__STATIC_FORCEINLINE uint32_t __STREXW(uint32_t value, volatile uint32_t *addr) -{ - uint32_t result; - - __ASM volatile ("strex %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" (value) ); - return(result); -} - - -/** - \brief Remove the exclusive lock - \details Removes the exclusive lock which is created by LDREX. - */ -__STATIC_FORCEINLINE void __CLREX(void) -{ - __ASM volatile ("clrex" ::: "memory"); -} - -#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ - - -#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) -/** - \brief Signed Saturate - \details Saturates a signed value. - \param [in] ARG1 Value to be saturated - \param [in] ARG2 Bit position to saturate to (1..32) - \return Saturated value - */ -#define __SSAT(ARG1,ARG2) \ -__extension__ \ -({ \ - int32_t __RES, __ARG1 = (ARG1); \ - __ASM ("ssat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ - __RES; \ - }) - - -/** - \brief Unsigned Saturate - \details Saturates an unsigned value. - \param [in] ARG1 Value to be saturated - \param [in] ARG2 Bit position to saturate to (0..31) - \return Saturated value - */ -#define __USAT(ARG1,ARG2) \ - __extension__ \ -({ \ - uint32_t __RES, __ARG1 = (ARG1); \ - __ASM ("usat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ - __RES; \ - }) - - -/** - \brief Rotate Right with Extend (32 bit) - \details Moves each bit of a bitstring right by one bit. - The carry input is shifted in at the left end of the bitstring. - \param [in] value Value to rotate - \return Rotated value - */ -__STATIC_FORCEINLINE uint32_t __RRX(uint32_t value) -{ - uint32_t result; - - __ASM volatile ("rrx %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); - return(result); -} - - -/** - \brief LDRT Unprivileged (8 bit) - \details Executes a Unprivileged LDRT instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -__STATIC_FORCEINLINE uint8_t __LDRBT(volatile uint8_t *ptr) -{ - uint32_t result; - -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) - __ASM volatile ("ldrbt %0, %1" : "=r" (result) : "Q" (*ptr) ); -#else - /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not - accepted by assembler. So has to use following less efficient pattern. - */ - __ASM volatile ("ldrbt %0, [%1]" : "=r" (result) : "r" (ptr) : "memory" ); -#endif - return ((uint8_t) result); /* Add explicit type cast here */ -} - - -/** - \brief LDRT Unprivileged (16 bit) - \details Executes a Unprivileged LDRT instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -__STATIC_FORCEINLINE uint16_t __LDRHT(volatile uint16_t *ptr) -{ - uint32_t result; - -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) - __ASM volatile ("ldrht %0, %1" : "=r" (result) : "Q" (*ptr) ); -#else - /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not - accepted by assembler. So has to use following less efficient pattern. - */ - __ASM volatile ("ldrht %0, [%1]" : "=r" (result) : "r" (ptr) : "memory" ); -#endif - return ((uint16_t) result); /* Add explicit type cast here */ -} - - -/** - \brief LDRT Unprivileged (32 bit) - \details Executes a Unprivileged LDRT instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -__STATIC_FORCEINLINE uint32_t __LDRT(volatile uint32_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldrt %0, %1" : "=r" (result) : "Q" (*ptr) ); - return(result); -} - - -/** - \brief STRT Unprivileged (8 bit) - \details Executes a Unprivileged STRT instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STRBT(uint8_t value, volatile uint8_t *ptr) -{ - __ASM volatile ("strbt %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief STRT Unprivileged (16 bit) - \details Executes a Unprivileged STRT instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STRHT(uint16_t value, volatile uint16_t *ptr) -{ - __ASM volatile ("strht %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief STRT Unprivileged (32 bit) - \details Executes a Unprivileged STRT instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STRT(uint32_t value, volatile uint32_t *ptr) -{ - __ASM volatile ("strt %1, %0" : "=Q" (*ptr) : "r" (value) ); -} - -#else /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ - -/** - \brief Signed Saturate - \details Saturates a signed value. - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (1..32) - \return Saturated value - */ -__STATIC_FORCEINLINE int32_t __SSAT(int32_t val, uint32_t sat) -{ - if ((sat >= 1U) && (sat <= 32U)) - { - const int32_t max = (int32_t)((1U << (sat - 1U)) - 1U); - const int32_t min = -1 - max ; - if (val > max) - { - return max; - } - else if (val < min) - { - return min; - } - } - return val; -} - -/** - \brief Unsigned Saturate - \details Saturates an unsigned value. - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (0..31) - \return Saturated value - */ -__STATIC_FORCEINLINE uint32_t __USAT(int32_t val, uint32_t sat) -{ - if (sat <= 31U) - { - const uint32_t max = ((1U << sat) - 1U); - if (val > (int32_t)max) - { - return max; - } - else if (val < 0) - { - return 0U; - } - } - return (uint32_t)val; -} - -#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ - - -#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) -/** - \brief Load-Acquire (8 bit) - \details Executes a LDAB instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -__STATIC_FORCEINLINE uint8_t __LDAB(volatile uint8_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldab %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint8_t) result); -} - - -/** - \brief Load-Acquire (16 bit) - \details Executes a LDAH instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -__STATIC_FORCEINLINE uint16_t __LDAH(volatile uint16_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldah %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint16_t) result); -} - - -/** - \brief Load-Acquire (32 bit) - \details Executes a LDA instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -__STATIC_FORCEINLINE uint32_t __LDA(volatile uint32_t *ptr) -{ - uint32_t result; - - __ASM volatile ("lda %0, %1" : "=r" (result) : "Q" (*ptr) ); - return(result); -} - - -/** - \brief Store-Release (8 bit) - \details Executes a STLB instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STLB(uint8_t value, volatile uint8_t *ptr) -{ - __ASM volatile ("stlb %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief Store-Release (16 bit) - \details Executes a STLH instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STLH(uint16_t value, volatile uint16_t *ptr) -{ - __ASM volatile ("stlh %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief Store-Release (32 bit) - \details Executes a STL instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STL(uint32_t value, volatile uint32_t *ptr) -{ - __ASM volatile ("stl %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief Load-Acquire Exclusive (8 bit) - \details Executes a LDAB exclusive instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -__STATIC_FORCEINLINE uint8_t __LDAEXB(volatile uint8_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldaexb %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint8_t) result); -} - - -/** - \brief Load-Acquire Exclusive (16 bit) - \details Executes a LDAH exclusive instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -__STATIC_FORCEINLINE uint16_t __LDAEXH(volatile uint16_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldaexh %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint16_t) result); -} - - -/** - \brief Load-Acquire Exclusive (32 bit) - \details Executes a LDA exclusive instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -__STATIC_FORCEINLINE uint32_t __LDAEX(volatile uint32_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldaex %0, %1" : "=r" (result) : "Q" (*ptr) ); - return(result); -} - - -/** - \brief Store-Release Exclusive (8 bit) - \details Executes a STLB exclusive instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__STATIC_FORCEINLINE uint32_t __STLEXB(uint8_t value, volatile uint8_t *ptr) -{ - uint32_t result; - - __ASM volatile ("stlexb %0, %2, %1" : "=&r" (result), "=Q" (*ptr) : "r" ((uint32_t)value) ); - return(result); -} - - -/** - \brief Store-Release Exclusive (16 bit) - \details Executes a STLH exclusive instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__STATIC_FORCEINLINE uint32_t __STLEXH(uint16_t value, volatile uint16_t *ptr) -{ - uint32_t result; - - __ASM volatile ("stlexh %0, %2, %1" : "=&r" (result), "=Q" (*ptr) : "r" ((uint32_t)value) ); - return(result); -} - - -/** - \brief Store-Release Exclusive (32 bit) - \details Executes a STL exclusive instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__STATIC_FORCEINLINE uint32_t __STLEX(uint32_t value, volatile uint32_t *ptr) -{ - uint32_t result; - - __ASM volatile ("stlex %0, %2, %1" : "=&r" (result), "=Q" (*ptr) : "r" ((uint32_t)value) ); - return(result); -} - -#endif /* ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ - -/*@}*/ /* end of group CMSIS_Core_InstructionInterface */ - - -/* ################### Compiler specific Intrinsics ########################### */ -/** \defgroup CMSIS_SIMD_intrinsics CMSIS SIMD Intrinsics - Access to dedicated SIMD instructions - @{ -*/ - -#if (defined (__ARM_FEATURE_DSP) && (__ARM_FEATURE_DSP == 1)) - -__STATIC_FORCEINLINE uint32_t __SADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - - -__STATIC_FORCEINLINE uint32_t __SSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("ssub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - - -__STATIC_FORCEINLINE uint32_t __SADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("ssub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("ssax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USAD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usad8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USADA8(uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("usada8 %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -#define __SSAT16(ARG1,ARG2) \ -({ \ - int32_t __RES, __ARG1 = (ARG1); \ - __ASM ("ssat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ - __RES; \ - }) - -#define __USAT16(ARG1,ARG2) \ -({ \ - uint32_t __RES, __ARG1 = (ARG1); \ - __ASM ("usat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ - __RES; \ - }) - -__STATIC_FORCEINLINE uint32_t __UXTB16(uint32_t op1) -{ - uint32_t result; - - __ASM volatile ("uxtb16 %0, %1" : "=r" (result) : "r" (op1)); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UXTAB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SXTB16(uint32_t op1) -{ - uint32_t result; - - __ASM volatile ("sxtb16 %0, %1" : "=r" (result) : "r" (op1)); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SXTAB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMUAD (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smuad %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMUADX (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smuadx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMLAD (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smlad %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMLADX (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smladx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__STATIC_FORCEINLINE uint64_t __SMLALD (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__STATIC_FORCEINLINE uint64_t __SMLALDX (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__STATIC_FORCEINLINE uint32_t __SMUSD (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smusd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMUSDX (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smusdx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMLSD (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smlsd %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMLSDX (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smlsdx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__STATIC_FORCEINLINE uint64_t __SMLSLD (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__STATIC_FORCEINLINE uint64_t __SMLSLDX (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__STATIC_FORCEINLINE uint32_t __SEL (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sel %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE int32_t __QADD( int32_t op1, int32_t op2) -{ - int32_t result; - - __ASM volatile ("qadd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE int32_t __QSUB( int32_t op1, int32_t op2) -{ - int32_t result; - - __ASM volatile ("qsub %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -#if 0 -#define __PKHBT(ARG1,ARG2,ARG3) \ -({ \ - uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \ - __ASM ("pkhbt %0, %1, %2, lsl %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \ - __RES; \ - }) - -#define __PKHTB(ARG1,ARG2,ARG3) \ -({ \ - uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \ - if (ARG3 == 0) \ - __ASM ("pkhtb %0, %1, %2" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2) ); \ - else \ - __ASM ("pkhtb %0, %1, %2, asr %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \ - __RES; \ - }) -#endif - -#define __PKHBT(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0x0000FFFFUL) | \ - ((((uint32_t)(ARG2)) << (ARG3)) & 0xFFFF0000UL) ) - -#define __PKHTB(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0xFFFF0000UL) | \ - ((((uint32_t)(ARG2)) >> (ARG3)) & 0x0000FFFFUL) ) - -__STATIC_FORCEINLINE int32_t __SMMLA (int32_t op1, int32_t op2, int32_t op3) -{ - int32_t result; - - __ASM volatile ("smmla %0, %1, %2, %3" : "=r" (result): "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -#endif /* (__ARM_FEATURE_DSP == 1) */ -/*@} end of group CMSIS_SIMD_intrinsics */ - - -#pragma GCC diagnostic pop - -#endif /* __CMSIS_GCC_H */ - diff --git a/panda/board/stm32fx/inc/cmsis_version.h b/panda/board/stm32fx/inc/cmsis_version.h deleted file mode 100644 index bf57cf3e8..000000000 --- a/panda/board/stm32fx/inc/cmsis_version.h +++ /dev/null @@ -1,40 +0,0 @@ -/**************************************************************************//** - * @file cmsis_version.h - * @brief CMSIS Core(M) Version definitions - * @version V5.0.3 - * @date 24. June 2019 - ******************************************************************************/ -/* - * Copyright (c) 2009-2019 ARM Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed under the Apache License, Version 2.0 (the License); you may - * not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an AS IS BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined (__clang__) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef __CMSIS_VERSION_H -#define __CMSIS_VERSION_H - -/* CMSIS Version definitions */ -#define __CM_CMSIS_VERSION_MAIN ( 5U) /*!< [31:16] CMSIS Core(M) main version */ -#define __CM_CMSIS_VERSION_SUB ( 3U) /*!< [15:0] CMSIS Core(M) sub version */ -#define __CM_CMSIS_VERSION ((__CM_CMSIS_VERSION_MAIN << 16U) | \ - __CM_CMSIS_VERSION_SUB ) /*!< CMSIS Core(M) version number */ -#endif - diff --git a/panda/board/stm32fx/inc/core_cm3.h b/panda/board/stm32fx/inc/core_cm3.h deleted file mode 100644 index 0918c5eb4..000000000 --- a/panda/board/stm32fx/inc/core_cm3.h +++ /dev/null @@ -1,1938 +0,0 @@ -/**************************************************************************//** - * @file core_cm3.h - * @brief CMSIS Cortex-M3 Core Peripheral Access Layer Header File - * @version V5.1.0 - * @date 13. March 2019 - ******************************************************************************/ -/* - * Copyright (c) 2009-2019 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed under the Apache License, Version 2.0 (the License); you may - * not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an AS IS BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined (__clang__) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef __CORE_CM3_H_GENERIC -#define __CORE_CM3_H_GENERIC - -#include - -#ifdef __cplusplus - extern "C" { -#endif - -/** - \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions - CMSIS violates the following MISRA-C:2004 rules: - - \li Required Rule 8.5, object/function definition in header file.
- Function definitions in header files are used to allow 'inlining'. - - \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
- Unions are used for effective representation of core registers. - - \li Advisory Rule 19.7, Function-like macro defined.
- Function-like macros are used to allow more efficient code. - */ - - -/******************************************************************************* - * CMSIS definitions - ******************************************************************************/ -/** - \ingroup Cortex_M3 - @{ - */ - -#include "cmsis_version.h" - -/* CMSIS CM3 definitions */ -#define __CM3_CMSIS_VERSION_MAIN (__CM_CMSIS_VERSION_MAIN) /*!< \deprecated [31:16] CMSIS HAL main version */ -#define __CM3_CMSIS_VERSION_SUB (__CM_CMSIS_VERSION_SUB) /*!< \deprecated [15:0] CMSIS HAL sub version */ -#define __CM3_CMSIS_VERSION ((__CM3_CMSIS_VERSION_MAIN << 16U) | \ - __CM3_CMSIS_VERSION_SUB ) /*!< \deprecated CMSIS HAL version number */ - -#define __CORTEX_M (3U) /*!< Cortex-M Core */ - -/** __FPU_USED indicates whether an FPU is used or not. - This core does not support an FPU at all -*/ -#define __FPU_USED 0U - -#if defined ( __CC_ARM ) - #if defined __TARGET_FPU_VFP - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) - #if defined __ARM_FP - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __GNUC__ ) - #if defined (__VFP_FP__) && !defined(__SOFTFP__) - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __ICCARM__ ) - #if defined __ARMVFP__ - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __TI_ARM__ ) - #if defined __TI_VFP_SUPPORT__ - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __TASKING__ ) - #if defined __FPU_VFP__ - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __CSMC__ ) - #if ( __CSMC__ & 0x400U) - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#endif - -#include "cmsis_compiler.h" /* CMSIS compiler specific defines */ - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_CM3_H_GENERIC */ - -#ifndef __CMSIS_GENERIC - -#ifndef __CORE_CM3_H_DEPENDANT -#define __CORE_CM3_H_DEPENDANT - -#ifdef __cplusplus - extern "C" { -#endif - -/* check device defines and use defaults */ -#if defined __CHECK_DEVICE_DEFINES - #ifndef __CM3_REV - #define __CM3_REV 0x0200U - #warning "__CM3_REV not defined in device header file; using default!" - #endif - - #ifndef __MPU_PRESENT - #define __MPU_PRESENT 0U - #warning "__MPU_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __NVIC_PRIO_BITS - #define __NVIC_PRIO_BITS 3U - #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" - #endif - - #ifndef __Vendor_SysTickConfig - #define __Vendor_SysTickConfig 0U - #warning "__Vendor_SysTickConfig not defined in device header file; using default!" - #endif -#endif - -/* IO definitions (access restrictions to peripheral registers) */ -/** - \defgroup CMSIS_glob_defs CMSIS Global Defines - - IO Type Qualifiers are used - \li to specify the access to peripheral variables. - \li for automatic generation of peripheral register debug information. -*/ -#ifdef __cplusplus - #define __I volatile /*!< Defines 'read only' permissions */ -#else - #define __I volatile const /*!< Defines 'read only' permissions */ -#endif -#define __O volatile /*!< Defines 'write only' permissions */ -#define __IO volatile /*!< Defines 'read / write' permissions */ - -/* following defines should be used for structure members */ -#define __IM volatile const /*! Defines 'read only' structure member permissions */ -#define __OM volatile /*! Defines 'write only' structure member permissions */ -#define __IOM volatile /*! Defines 'read / write' structure member permissions */ - -/*@} end of group Cortex_M3 */ - - - -/******************************************************************************* - * Register Abstraction - Core Register contain: - - Core Register - - Core NVIC Register - - Core SCB Register - - Core SysTick Register - - Core Debug Register - - Core MPU Register - ******************************************************************************/ -/** - \defgroup CMSIS_core_register Defines and Type Definitions - \brief Type definitions and defines for Cortex-M processor based devices. -*/ - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CORE Status and Control Registers - \brief Core Register type definitions. - @{ - */ - -/** - \brief Union type to access the Application Program Status Register (APSR). - */ -typedef union -{ - struct - { - uint32_t _reserved0:27; /*!< bit: 0..26 Reserved */ - uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} APSR_Type; - -/* APSR Register Definitions */ -#define APSR_N_Pos 31U /*!< APSR: N Position */ -#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ - -#define APSR_Z_Pos 30U /*!< APSR: Z Position */ -#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ - -#define APSR_C_Pos 29U /*!< APSR: C Position */ -#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ - -#define APSR_V_Pos 28U /*!< APSR: V Position */ -#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ - -#define APSR_Q_Pos 27U /*!< APSR: Q Position */ -#define APSR_Q_Msk (1UL << APSR_Q_Pos) /*!< APSR: Q Mask */ - - -/** - \brief Union type to access the Interrupt Program Status Register (IPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} IPSR_Type; - -/* IPSR Register Definitions */ -#define IPSR_ISR_Pos 0U /*!< IPSR: ISR Position */ -#define IPSR_ISR_Msk (0x1FFUL /*<< IPSR_ISR_Pos*/) /*!< IPSR: ISR Mask */ - - -/** - \brief Union type to access the Special-Purpose Program Status Registers (xPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:1; /*!< bit: 9 Reserved */ - uint32_t ICI_IT_1:6; /*!< bit: 10..15 ICI/IT part 1 */ - uint32_t _reserved1:8; /*!< bit: 16..23 Reserved */ - uint32_t T:1; /*!< bit: 24 Thumb bit */ - uint32_t ICI_IT_2:2; /*!< bit: 25..26 ICI/IT part 2 */ - uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} xPSR_Type; - -/* xPSR Register Definitions */ -#define xPSR_N_Pos 31U /*!< xPSR: N Position */ -#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ - -#define xPSR_Z_Pos 30U /*!< xPSR: Z Position */ -#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ - -#define xPSR_C_Pos 29U /*!< xPSR: C Position */ -#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ - -#define xPSR_V_Pos 28U /*!< xPSR: V Position */ -#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ - -#define xPSR_Q_Pos 27U /*!< xPSR: Q Position */ -#define xPSR_Q_Msk (1UL << xPSR_Q_Pos) /*!< xPSR: Q Mask */ - -#define xPSR_ICI_IT_2_Pos 25U /*!< xPSR: ICI/IT part 2 Position */ -#define xPSR_ICI_IT_2_Msk (3UL << xPSR_ICI_IT_2_Pos) /*!< xPSR: ICI/IT part 2 Mask */ - -#define xPSR_T_Pos 24U /*!< xPSR: T Position */ -#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ - -#define xPSR_ICI_IT_1_Pos 10U /*!< xPSR: ICI/IT part 1 Position */ -#define xPSR_ICI_IT_1_Msk (0x3FUL << xPSR_ICI_IT_1_Pos) /*!< xPSR: ICI/IT part 1 Mask */ - -#define xPSR_ISR_Pos 0U /*!< xPSR: ISR Position */ -#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ - - -/** - \brief Union type to access the Control Registers (CONTROL). - */ -typedef union -{ - struct - { - uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */ - uint32_t SPSEL:1; /*!< bit: 1 Stack to be used */ - uint32_t _reserved1:30; /*!< bit: 2..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} CONTROL_Type; - -/* CONTROL Register Definitions */ -#define CONTROL_SPSEL_Pos 1U /*!< CONTROL: SPSEL Position */ -#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ - -#define CONTROL_nPRIV_Pos 0U /*!< CONTROL: nPRIV Position */ -#define CONTROL_nPRIV_Msk (1UL /*<< CONTROL_nPRIV_Pos*/) /*!< CONTROL: nPRIV Mask */ - -/*@} end of group CMSIS_CORE */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC) - \brief Type definitions for the NVIC Registers - @{ - */ - -/** - \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). - */ -typedef struct -{ - __IOM uint32_t ISER[8U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ - uint32_t RESERVED0[24U]; - __IOM uint32_t ICER[8U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ - uint32_t RESERVED1[24U]; - __IOM uint32_t ISPR[8U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ - uint32_t RESERVED2[24U]; - __IOM uint32_t ICPR[8U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ - uint32_t RESERVED3[24U]; - __IOM uint32_t IABR[8U]; /*!< Offset: 0x200 (R/W) Interrupt Active bit Register */ - uint32_t RESERVED4[56U]; - __IOM uint8_t IP[240U]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register (8Bit wide) */ - uint32_t RESERVED5[644U]; - __OM uint32_t STIR; /*!< Offset: 0xE00 ( /W) Software Trigger Interrupt Register */ -} NVIC_Type; - -/* Software Triggered Interrupt Register Definitions */ -#define NVIC_STIR_INTID_Pos 0U /*!< STIR: INTLINESNUM Position */ -#define NVIC_STIR_INTID_Msk (0x1FFUL /*<< NVIC_STIR_INTID_Pos*/) /*!< STIR: INTLINESNUM Mask */ - -/*@} end of group CMSIS_NVIC */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SCB System Control Block (SCB) - \brief Type definitions for the System Control Block Registers - @{ - */ - -/** - \brief Structure type to access the System Control Block (SCB). - */ -typedef struct -{ - __IM uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ - __IOM uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ - __IOM uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ - __IOM uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ - __IOM uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ - __IOM uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ - __IOM uint8_t SHP[12U]; /*!< Offset: 0x018 (R/W) System Handlers Priority Registers (4-7, 8-11, 12-15) */ - __IOM uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ - __IOM uint32_t CFSR; /*!< Offset: 0x028 (R/W) Configurable Fault Status Register */ - __IOM uint32_t HFSR; /*!< Offset: 0x02C (R/W) HardFault Status Register */ - __IOM uint32_t DFSR; /*!< Offset: 0x030 (R/W) Debug Fault Status Register */ - __IOM uint32_t MMFAR; /*!< Offset: 0x034 (R/W) MemManage Fault Address Register */ - __IOM uint32_t BFAR; /*!< Offset: 0x038 (R/W) BusFault Address Register */ - __IOM uint32_t AFSR; /*!< Offset: 0x03C (R/W) Auxiliary Fault Status Register */ - __IM uint32_t PFR[2U]; /*!< Offset: 0x040 (R/ ) Processor Feature Register */ - __IM uint32_t DFR; /*!< Offset: 0x048 (R/ ) Debug Feature Register */ - __IM uint32_t ADR; /*!< Offset: 0x04C (R/ ) Auxiliary Feature Register */ - __IM uint32_t MMFR[4U]; /*!< Offset: 0x050 (R/ ) Memory Model Feature Register */ - __IM uint32_t ISAR[5U]; /*!< Offset: 0x060 (R/ ) Instruction Set Attributes Register */ - uint32_t RESERVED0[5U]; - __IOM uint32_t CPACR; /*!< Offset: 0x088 (R/W) Coprocessor Access Control Register */ -} SCB_Type; - -/* SCB CPUID Register Definitions */ -#define SCB_CPUID_IMPLEMENTER_Pos 24U /*!< SCB CPUID: IMPLEMENTER Position */ -#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ - -#define SCB_CPUID_VARIANT_Pos 20U /*!< SCB CPUID: VARIANT Position */ -#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ - -#define SCB_CPUID_ARCHITECTURE_Pos 16U /*!< SCB CPUID: ARCHITECTURE Position */ -#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ - -#define SCB_CPUID_PARTNO_Pos 4U /*!< SCB CPUID: PARTNO Position */ -#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ - -#define SCB_CPUID_REVISION_Pos 0U /*!< SCB CPUID: REVISION Position */ -#define SCB_CPUID_REVISION_Msk (0xFUL /*<< SCB_CPUID_REVISION_Pos*/) /*!< SCB CPUID: REVISION Mask */ - -/* SCB Interrupt Control State Register Definitions */ -#define SCB_ICSR_NMIPENDSET_Pos 31U /*!< SCB ICSR: NMIPENDSET Position */ -#define SCB_ICSR_NMIPENDSET_Msk (1UL << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */ - -#define SCB_ICSR_PENDSVSET_Pos 28U /*!< SCB ICSR: PENDSVSET Position */ -#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ - -#define SCB_ICSR_PENDSVCLR_Pos 27U /*!< SCB ICSR: PENDSVCLR Position */ -#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ - -#define SCB_ICSR_PENDSTSET_Pos 26U /*!< SCB ICSR: PENDSTSET Position */ -#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ - -#define SCB_ICSR_PENDSTCLR_Pos 25U /*!< SCB ICSR: PENDSTCLR Position */ -#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ - -#define SCB_ICSR_ISRPREEMPT_Pos 23U /*!< SCB ICSR: ISRPREEMPT Position */ -#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ - -#define SCB_ICSR_ISRPENDING_Pos 22U /*!< SCB ICSR: ISRPENDING Position */ -#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ - -#define SCB_ICSR_VECTPENDING_Pos 12U /*!< SCB ICSR: VECTPENDING Position */ -#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ - -#define SCB_ICSR_RETTOBASE_Pos 11U /*!< SCB ICSR: RETTOBASE Position */ -#define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */ - -#define SCB_ICSR_VECTACTIVE_Pos 0U /*!< SCB ICSR: VECTACTIVE Position */ -#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */ - -/* SCB Vector Table Offset Register Definitions */ -#if defined (__CM3_REV) && (__CM3_REV < 0x0201U) /* core r2p1 */ -#define SCB_VTOR_TBLBASE_Pos 29U /*!< SCB VTOR: TBLBASE Position */ -#define SCB_VTOR_TBLBASE_Msk (1UL << SCB_VTOR_TBLBASE_Pos) /*!< SCB VTOR: TBLBASE Mask */ - -#define SCB_VTOR_TBLOFF_Pos 7U /*!< SCB VTOR: TBLOFF Position */ -#define SCB_VTOR_TBLOFF_Msk (0x3FFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ -#else -#define SCB_VTOR_TBLOFF_Pos 7U /*!< SCB VTOR: TBLOFF Position */ -#define SCB_VTOR_TBLOFF_Msk (0x1FFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ -#endif - -/* SCB Application Interrupt and Reset Control Register Definitions */ -#define SCB_AIRCR_VECTKEY_Pos 16U /*!< SCB AIRCR: VECTKEY Position */ -#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ - -#define SCB_AIRCR_VECTKEYSTAT_Pos 16U /*!< SCB AIRCR: VECTKEYSTAT Position */ -#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ - -#define SCB_AIRCR_ENDIANESS_Pos 15U /*!< SCB AIRCR: ENDIANESS Position */ -#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ - -#define SCB_AIRCR_PRIGROUP_Pos 8U /*!< SCB AIRCR: PRIGROUP Position */ -#define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */ - -#define SCB_AIRCR_SYSRESETREQ_Pos 2U /*!< SCB AIRCR: SYSRESETREQ Position */ -#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ - -#define SCB_AIRCR_VECTCLRACTIVE_Pos 1U /*!< SCB AIRCR: VECTCLRACTIVE Position */ -#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ - -#define SCB_AIRCR_VECTRESET_Pos 0U /*!< SCB AIRCR: VECTRESET Position */ -#define SCB_AIRCR_VECTRESET_Msk (1UL /*<< SCB_AIRCR_VECTRESET_Pos*/) /*!< SCB AIRCR: VECTRESET Mask */ - -/* SCB System Control Register Definitions */ -#define SCB_SCR_SEVONPEND_Pos 4U /*!< SCB SCR: SEVONPEND Position */ -#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ - -#define SCB_SCR_SLEEPDEEP_Pos 2U /*!< SCB SCR: SLEEPDEEP Position */ -#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ - -#define SCB_SCR_SLEEPONEXIT_Pos 1U /*!< SCB SCR: SLEEPONEXIT Position */ -#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ - -/* SCB Configuration Control Register Definitions */ -#define SCB_CCR_STKALIGN_Pos 9U /*!< SCB CCR: STKALIGN Position */ -#define SCB_CCR_STKALIGN_Msk (1UL << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */ - -#define SCB_CCR_BFHFNMIGN_Pos 8U /*!< SCB CCR: BFHFNMIGN Position */ -#define SCB_CCR_BFHFNMIGN_Msk (1UL << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */ - -#define SCB_CCR_DIV_0_TRP_Pos 4U /*!< SCB CCR: DIV_0_TRP Position */ -#define SCB_CCR_DIV_0_TRP_Msk (1UL << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP Mask */ - -#define SCB_CCR_UNALIGN_TRP_Pos 3U /*!< SCB CCR: UNALIGN_TRP Position */ -#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ - -#define SCB_CCR_USERSETMPEND_Pos 1U /*!< SCB CCR: USERSETMPEND Position */ -#define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */ - -#define SCB_CCR_NONBASETHRDENA_Pos 0U /*!< SCB CCR: NONBASETHRDENA Position */ -#define SCB_CCR_NONBASETHRDENA_Msk (1UL /*<< SCB_CCR_NONBASETHRDENA_Pos*/) /*!< SCB CCR: NONBASETHRDENA Mask */ - -/* SCB System Handler Control and State Register Definitions */ -#define SCB_SHCSR_USGFAULTENA_Pos 18U /*!< SCB SHCSR: USGFAULTENA Position */ -#define SCB_SHCSR_USGFAULTENA_Msk (1UL << SCB_SHCSR_USGFAULTENA_Pos) /*!< SCB SHCSR: USGFAULTENA Mask */ - -#define SCB_SHCSR_BUSFAULTENA_Pos 17U /*!< SCB SHCSR: BUSFAULTENA Position */ -#define SCB_SHCSR_BUSFAULTENA_Msk (1UL << SCB_SHCSR_BUSFAULTENA_Pos) /*!< SCB SHCSR: BUSFAULTENA Mask */ - -#define SCB_SHCSR_MEMFAULTENA_Pos 16U /*!< SCB SHCSR: MEMFAULTENA Position */ -#define SCB_SHCSR_MEMFAULTENA_Msk (1UL << SCB_SHCSR_MEMFAULTENA_Pos) /*!< SCB SHCSR: MEMFAULTENA Mask */ - -#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */ -#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ - -#define SCB_SHCSR_BUSFAULTPENDED_Pos 14U /*!< SCB SHCSR: BUSFAULTPENDED Position */ -#define SCB_SHCSR_BUSFAULTPENDED_Msk (1UL << SCB_SHCSR_BUSFAULTPENDED_Pos) /*!< SCB SHCSR: BUSFAULTPENDED Mask */ - -#define SCB_SHCSR_MEMFAULTPENDED_Pos 13U /*!< SCB SHCSR: MEMFAULTPENDED Position */ -#define SCB_SHCSR_MEMFAULTPENDED_Msk (1UL << SCB_SHCSR_MEMFAULTPENDED_Pos) /*!< SCB SHCSR: MEMFAULTPENDED Mask */ - -#define SCB_SHCSR_USGFAULTPENDED_Pos 12U /*!< SCB SHCSR: USGFAULTPENDED Position */ -#define SCB_SHCSR_USGFAULTPENDED_Msk (1UL << SCB_SHCSR_USGFAULTPENDED_Pos) /*!< SCB SHCSR: USGFAULTPENDED Mask */ - -#define SCB_SHCSR_SYSTICKACT_Pos 11U /*!< SCB SHCSR: SYSTICKACT Position */ -#define SCB_SHCSR_SYSTICKACT_Msk (1UL << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */ - -#define SCB_SHCSR_PENDSVACT_Pos 10U /*!< SCB SHCSR: PENDSVACT Position */ -#define SCB_SHCSR_PENDSVACT_Msk (1UL << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */ - -#define SCB_SHCSR_MONITORACT_Pos 8U /*!< SCB SHCSR: MONITORACT Position */ -#define SCB_SHCSR_MONITORACT_Msk (1UL << SCB_SHCSR_MONITORACT_Pos) /*!< SCB SHCSR: MONITORACT Mask */ - -#define SCB_SHCSR_SVCALLACT_Pos 7U /*!< SCB SHCSR: SVCALLACT Position */ -#define SCB_SHCSR_SVCALLACT_Msk (1UL << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */ - -#define SCB_SHCSR_USGFAULTACT_Pos 3U /*!< SCB SHCSR: USGFAULTACT Position */ -#define SCB_SHCSR_USGFAULTACT_Msk (1UL << SCB_SHCSR_USGFAULTACT_Pos) /*!< SCB SHCSR: USGFAULTACT Mask */ - -#define SCB_SHCSR_BUSFAULTACT_Pos 1U /*!< SCB SHCSR: BUSFAULTACT Position */ -#define SCB_SHCSR_BUSFAULTACT_Msk (1UL << SCB_SHCSR_BUSFAULTACT_Pos) /*!< SCB SHCSR: BUSFAULTACT Mask */ - -#define SCB_SHCSR_MEMFAULTACT_Pos 0U /*!< SCB SHCSR: MEMFAULTACT Position */ -#define SCB_SHCSR_MEMFAULTACT_Msk (1UL /*<< SCB_SHCSR_MEMFAULTACT_Pos*/) /*!< SCB SHCSR: MEMFAULTACT Mask */ - -/* SCB Configurable Fault Status Register Definitions */ -#define SCB_CFSR_USGFAULTSR_Pos 16U /*!< SCB CFSR: Usage Fault Status Register Position */ -#define SCB_CFSR_USGFAULTSR_Msk (0xFFFFUL << SCB_CFSR_USGFAULTSR_Pos) /*!< SCB CFSR: Usage Fault Status Register Mask */ - -#define SCB_CFSR_BUSFAULTSR_Pos 8U /*!< SCB CFSR: Bus Fault Status Register Position */ -#define SCB_CFSR_BUSFAULTSR_Msk (0xFFUL << SCB_CFSR_BUSFAULTSR_Pos) /*!< SCB CFSR: Bus Fault Status Register Mask */ - -#define SCB_CFSR_MEMFAULTSR_Pos 0U /*!< SCB CFSR: Memory Manage Fault Status Register Position */ -#define SCB_CFSR_MEMFAULTSR_Msk (0xFFUL /*<< SCB_CFSR_MEMFAULTSR_Pos*/) /*!< SCB CFSR: Memory Manage Fault Status Register Mask */ - -/* MemManage Fault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_MMARVALID_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 7U) /*!< SCB CFSR (MMFSR): MMARVALID Position */ -#define SCB_CFSR_MMARVALID_Msk (1UL << SCB_CFSR_MMARVALID_Pos) /*!< SCB CFSR (MMFSR): MMARVALID Mask */ - -#define SCB_CFSR_MSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 4U) /*!< SCB CFSR (MMFSR): MSTKERR Position */ -#define SCB_CFSR_MSTKERR_Msk (1UL << SCB_CFSR_MSTKERR_Pos) /*!< SCB CFSR (MMFSR): MSTKERR Mask */ - -#define SCB_CFSR_MUNSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 3U) /*!< SCB CFSR (MMFSR): MUNSTKERR Position */ -#define SCB_CFSR_MUNSTKERR_Msk (1UL << SCB_CFSR_MUNSTKERR_Pos) /*!< SCB CFSR (MMFSR): MUNSTKERR Mask */ - -#define SCB_CFSR_DACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 1U) /*!< SCB CFSR (MMFSR): DACCVIOL Position */ -#define SCB_CFSR_DACCVIOL_Msk (1UL << SCB_CFSR_DACCVIOL_Pos) /*!< SCB CFSR (MMFSR): DACCVIOL Mask */ - -#define SCB_CFSR_IACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 0U) /*!< SCB CFSR (MMFSR): IACCVIOL Position */ -#define SCB_CFSR_IACCVIOL_Msk (1UL /*<< SCB_CFSR_IACCVIOL_Pos*/) /*!< SCB CFSR (MMFSR): IACCVIOL Mask */ - -/* BusFault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_BFARVALID_Pos (SCB_CFSR_BUSFAULTSR_Pos + 7U) /*!< SCB CFSR (BFSR): BFARVALID Position */ -#define SCB_CFSR_BFARVALID_Msk (1UL << SCB_CFSR_BFARVALID_Pos) /*!< SCB CFSR (BFSR): BFARVALID Mask */ - -#define SCB_CFSR_STKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 4U) /*!< SCB CFSR (BFSR): STKERR Position */ -#define SCB_CFSR_STKERR_Msk (1UL << SCB_CFSR_STKERR_Pos) /*!< SCB CFSR (BFSR): STKERR Mask */ - -#define SCB_CFSR_UNSTKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 3U) /*!< SCB CFSR (BFSR): UNSTKERR Position */ -#define SCB_CFSR_UNSTKERR_Msk (1UL << SCB_CFSR_UNSTKERR_Pos) /*!< SCB CFSR (BFSR): UNSTKERR Mask */ - -#define SCB_CFSR_IMPRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 2U) /*!< SCB CFSR (BFSR): IMPRECISERR Position */ -#define SCB_CFSR_IMPRECISERR_Msk (1UL << SCB_CFSR_IMPRECISERR_Pos) /*!< SCB CFSR (BFSR): IMPRECISERR Mask */ - -#define SCB_CFSR_PRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 1U) /*!< SCB CFSR (BFSR): PRECISERR Position */ -#define SCB_CFSR_PRECISERR_Msk (1UL << SCB_CFSR_PRECISERR_Pos) /*!< SCB CFSR (BFSR): PRECISERR Mask */ - -#define SCB_CFSR_IBUSERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 0U) /*!< SCB CFSR (BFSR): IBUSERR Position */ -#define SCB_CFSR_IBUSERR_Msk (1UL << SCB_CFSR_IBUSERR_Pos) /*!< SCB CFSR (BFSR): IBUSERR Mask */ - -/* UsageFault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_DIVBYZERO_Pos (SCB_CFSR_USGFAULTSR_Pos + 9U) /*!< SCB CFSR (UFSR): DIVBYZERO Position */ -#define SCB_CFSR_DIVBYZERO_Msk (1UL << SCB_CFSR_DIVBYZERO_Pos) /*!< SCB CFSR (UFSR): DIVBYZERO Mask */ - -#define SCB_CFSR_UNALIGNED_Pos (SCB_CFSR_USGFAULTSR_Pos + 8U) /*!< SCB CFSR (UFSR): UNALIGNED Position */ -#define SCB_CFSR_UNALIGNED_Msk (1UL << SCB_CFSR_UNALIGNED_Pos) /*!< SCB CFSR (UFSR): UNALIGNED Mask */ - -#define SCB_CFSR_NOCP_Pos (SCB_CFSR_USGFAULTSR_Pos + 3U) /*!< SCB CFSR (UFSR): NOCP Position */ -#define SCB_CFSR_NOCP_Msk (1UL << SCB_CFSR_NOCP_Pos) /*!< SCB CFSR (UFSR): NOCP Mask */ - -#define SCB_CFSR_INVPC_Pos (SCB_CFSR_USGFAULTSR_Pos + 2U) /*!< SCB CFSR (UFSR): INVPC Position */ -#define SCB_CFSR_INVPC_Msk (1UL << SCB_CFSR_INVPC_Pos) /*!< SCB CFSR (UFSR): INVPC Mask */ - -#define SCB_CFSR_INVSTATE_Pos (SCB_CFSR_USGFAULTSR_Pos + 1U) /*!< SCB CFSR (UFSR): INVSTATE Position */ -#define SCB_CFSR_INVSTATE_Msk (1UL << SCB_CFSR_INVSTATE_Pos) /*!< SCB CFSR (UFSR): INVSTATE Mask */ - -#define SCB_CFSR_UNDEFINSTR_Pos (SCB_CFSR_USGFAULTSR_Pos + 0U) /*!< SCB CFSR (UFSR): UNDEFINSTR Position */ -#define SCB_CFSR_UNDEFINSTR_Msk (1UL << SCB_CFSR_UNDEFINSTR_Pos) /*!< SCB CFSR (UFSR): UNDEFINSTR Mask */ - -/* SCB Hard Fault Status Register Definitions */ -#define SCB_HFSR_DEBUGEVT_Pos 31U /*!< SCB HFSR: DEBUGEVT Position */ -#define SCB_HFSR_DEBUGEVT_Msk (1UL << SCB_HFSR_DEBUGEVT_Pos) /*!< SCB HFSR: DEBUGEVT Mask */ - -#define SCB_HFSR_FORCED_Pos 30U /*!< SCB HFSR: FORCED Position */ -#define SCB_HFSR_FORCED_Msk (1UL << SCB_HFSR_FORCED_Pos) /*!< SCB HFSR: FORCED Mask */ - -#define SCB_HFSR_VECTTBL_Pos 1U /*!< SCB HFSR: VECTTBL Position */ -#define SCB_HFSR_VECTTBL_Msk (1UL << SCB_HFSR_VECTTBL_Pos) /*!< SCB HFSR: VECTTBL Mask */ - -/* SCB Debug Fault Status Register Definitions */ -#define SCB_DFSR_EXTERNAL_Pos 4U /*!< SCB DFSR: EXTERNAL Position */ -#define SCB_DFSR_EXTERNAL_Msk (1UL << SCB_DFSR_EXTERNAL_Pos) /*!< SCB DFSR: EXTERNAL Mask */ - -#define SCB_DFSR_VCATCH_Pos 3U /*!< SCB DFSR: VCATCH Position */ -#define SCB_DFSR_VCATCH_Msk (1UL << SCB_DFSR_VCATCH_Pos) /*!< SCB DFSR: VCATCH Mask */ - -#define SCB_DFSR_DWTTRAP_Pos 2U /*!< SCB DFSR: DWTTRAP Position */ -#define SCB_DFSR_DWTTRAP_Msk (1UL << SCB_DFSR_DWTTRAP_Pos) /*!< SCB DFSR: DWTTRAP Mask */ - -#define SCB_DFSR_BKPT_Pos 1U /*!< SCB DFSR: BKPT Position */ -#define SCB_DFSR_BKPT_Msk (1UL << SCB_DFSR_BKPT_Pos) /*!< SCB DFSR: BKPT Mask */ - -#define SCB_DFSR_HALTED_Pos 0U /*!< SCB DFSR: HALTED Position */ -#define SCB_DFSR_HALTED_Msk (1UL /*<< SCB_DFSR_HALTED_Pos*/) /*!< SCB DFSR: HALTED Mask */ - -/*@} end of group CMSIS_SCB */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SCnSCB System Controls not in SCB (SCnSCB) - \brief Type definitions for the System Control and ID Register not in the SCB - @{ - */ - -/** - \brief Structure type to access the System Control and ID Register not in the SCB. - */ -typedef struct -{ - uint32_t RESERVED0[1U]; - __IM uint32_t ICTR; /*!< Offset: 0x004 (R/ ) Interrupt Controller Type Register */ -#if defined (__CM3_REV) && (__CM3_REV >= 0x200U) - __IOM uint32_t ACTLR; /*!< Offset: 0x008 (R/W) Auxiliary Control Register */ -#else - uint32_t RESERVED1[1U]; -#endif -} SCnSCB_Type; - -/* Interrupt Controller Type Register Definitions */ -#define SCnSCB_ICTR_INTLINESNUM_Pos 0U /*!< ICTR: INTLINESNUM Position */ -#define SCnSCB_ICTR_INTLINESNUM_Msk (0xFUL /*<< SCnSCB_ICTR_INTLINESNUM_Pos*/) /*!< ICTR: INTLINESNUM Mask */ - -/* Auxiliary Control Register Definitions */ -#if defined (__CM3_REV) && (__CM3_REV >= 0x200U) -#define SCnSCB_ACTLR_DISOOFP_Pos 9U /*!< ACTLR: DISOOFP Position */ -#define SCnSCB_ACTLR_DISOOFP_Msk (1UL << SCnSCB_ACTLR_DISOOFP_Pos) /*!< ACTLR: DISOOFP Mask */ - -#define SCnSCB_ACTLR_DISFPCA_Pos 8U /*!< ACTLR: DISFPCA Position */ -#define SCnSCB_ACTLR_DISFPCA_Msk (1UL << SCnSCB_ACTLR_DISFPCA_Pos) /*!< ACTLR: DISFPCA Mask */ - -#define SCnSCB_ACTLR_DISFOLD_Pos 2U /*!< ACTLR: DISFOLD Position */ -#define SCnSCB_ACTLR_DISFOLD_Msk (1UL << SCnSCB_ACTLR_DISFOLD_Pos) /*!< ACTLR: DISFOLD Mask */ - -#define SCnSCB_ACTLR_DISDEFWBUF_Pos 1U /*!< ACTLR: DISDEFWBUF Position */ -#define SCnSCB_ACTLR_DISDEFWBUF_Msk (1UL << SCnSCB_ACTLR_DISDEFWBUF_Pos) /*!< ACTLR: DISDEFWBUF Mask */ - -#define SCnSCB_ACTLR_DISMCYCINT_Pos 0U /*!< ACTLR: DISMCYCINT Position */ -#define SCnSCB_ACTLR_DISMCYCINT_Msk (1UL /*<< SCnSCB_ACTLR_DISMCYCINT_Pos*/) /*!< ACTLR: DISMCYCINT Mask */ -#endif - -/*@} end of group CMSIS_SCnotSCB */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SysTick System Tick Timer (SysTick) - \brief Type definitions for the System Timer Registers. - @{ - */ - -/** - \brief Structure type to access the System Timer (SysTick). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ - __IOM uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ - __IOM uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ - __IM uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ -} SysTick_Type; - -/* SysTick Control / Status Register Definitions */ -#define SysTick_CTRL_COUNTFLAG_Pos 16U /*!< SysTick CTRL: COUNTFLAG Position */ -#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ - -#define SysTick_CTRL_CLKSOURCE_Pos 2U /*!< SysTick CTRL: CLKSOURCE Position */ -#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ - -#define SysTick_CTRL_TICKINT_Pos 1U /*!< SysTick CTRL: TICKINT Position */ -#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ - -#define SysTick_CTRL_ENABLE_Pos 0U /*!< SysTick CTRL: ENABLE Position */ -#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ - -/* SysTick Reload Register Definitions */ -#define SysTick_LOAD_RELOAD_Pos 0U /*!< SysTick LOAD: RELOAD Position */ -#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ - -/* SysTick Current Register Definitions */ -#define SysTick_VAL_CURRENT_Pos 0U /*!< SysTick VAL: CURRENT Position */ -#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ - -/* SysTick Calibration Register Definitions */ -#define SysTick_CALIB_NOREF_Pos 31U /*!< SysTick CALIB: NOREF Position */ -#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ - -#define SysTick_CALIB_SKEW_Pos 30U /*!< SysTick CALIB: SKEW Position */ -#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ - -#define SysTick_CALIB_TENMS_Pos 0U /*!< SysTick CALIB: TENMS Position */ -#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ - -/*@} end of group CMSIS_SysTick */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_ITM Instrumentation Trace Macrocell (ITM) - \brief Type definitions for the Instrumentation Trace Macrocell (ITM) - @{ - */ - -/** - \brief Structure type to access the Instrumentation Trace Macrocell Register (ITM). - */ -typedef struct -{ - __OM union - { - __OM uint8_t u8; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 8-bit */ - __OM uint16_t u16; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 16-bit */ - __OM uint32_t u32; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 32-bit */ - } PORT [32U]; /*!< Offset: 0x000 ( /W) ITM Stimulus Port Registers */ - uint32_t RESERVED0[864U]; - __IOM uint32_t TER; /*!< Offset: 0xE00 (R/W) ITM Trace Enable Register */ - uint32_t RESERVED1[15U]; - __IOM uint32_t TPR; /*!< Offset: 0xE40 (R/W) ITM Trace Privilege Register */ - uint32_t RESERVED2[15U]; - __IOM uint32_t TCR; /*!< Offset: 0xE80 (R/W) ITM Trace Control Register */ - uint32_t RESERVED3[32U]; - uint32_t RESERVED4[43U]; - __OM uint32_t LAR; /*!< Offset: 0xFB0 ( /W) ITM Lock Access Register */ - __IM uint32_t LSR; /*!< Offset: 0xFB4 (R/ ) ITM Lock Status Register */ - uint32_t RESERVED5[6U]; - __IM uint32_t PID4; /*!< Offset: 0xFD0 (R/ ) ITM Peripheral Identification Register #4 */ - __IM uint32_t PID5; /*!< Offset: 0xFD4 (R/ ) ITM Peripheral Identification Register #5 */ - __IM uint32_t PID6; /*!< Offset: 0xFD8 (R/ ) ITM Peripheral Identification Register #6 */ - __IM uint32_t PID7; /*!< Offset: 0xFDC (R/ ) ITM Peripheral Identification Register #7 */ - __IM uint32_t PID0; /*!< Offset: 0xFE0 (R/ ) ITM Peripheral Identification Register #0 */ - __IM uint32_t PID1; /*!< Offset: 0xFE4 (R/ ) ITM Peripheral Identification Register #1 */ - __IM uint32_t PID2; /*!< Offset: 0xFE8 (R/ ) ITM Peripheral Identification Register #2 */ - __IM uint32_t PID3; /*!< Offset: 0xFEC (R/ ) ITM Peripheral Identification Register #3 */ - __IM uint32_t CID0; /*!< Offset: 0xFF0 (R/ ) ITM Component Identification Register #0 */ - __IM uint32_t CID1; /*!< Offset: 0xFF4 (R/ ) ITM Component Identification Register #1 */ - __IM uint32_t CID2; /*!< Offset: 0xFF8 (R/ ) ITM Component Identification Register #2 */ - __IM uint32_t CID3; /*!< Offset: 0xFFC (R/ ) ITM Component Identification Register #3 */ -} ITM_Type; - -/* ITM Trace Privilege Register Definitions */ -#define ITM_TPR_PRIVMASK_Pos 0U /*!< ITM TPR: PRIVMASK Position */ -#define ITM_TPR_PRIVMASK_Msk (0xFFFFFFFFUL /*<< ITM_TPR_PRIVMASK_Pos*/) /*!< ITM TPR: PRIVMASK Mask */ - -/* ITM Trace Control Register Definitions */ -#define ITM_TCR_BUSY_Pos 23U /*!< ITM TCR: BUSY Position */ -#define ITM_TCR_BUSY_Msk (1UL << ITM_TCR_BUSY_Pos) /*!< ITM TCR: BUSY Mask */ - -#define ITM_TCR_TraceBusID_Pos 16U /*!< ITM TCR: ATBID Position */ -#define ITM_TCR_TraceBusID_Msk (0x7FUL << ITM_TCR_TraceBusID_Pos) /*!< ITM TCR: ATBID Mask */ - -#define ITM_TCR_GTSFREQ_Pos 10U /*!< ITM TCR: Global timestamp frequency Position */ -#define ITM_TCR_GTSFREQ_Msk (3UL << ITM_TCR_GTSFREQ_Pos) /*!< ITM TCR: Global timestamp frequency Mask */ - -#define ITM_TCR_TSPrescale_Pos 8U /*!< ITM TCR: TSPrescale Position */ -#define ITM_TCR_TSPrescale_Msk (3UL << ITM_TCR_TSPrescale_Pos) /*!< ITM TCR: TSPrescale Mask */ - -#define ITM_TCR_SWOENA_Pos 4U /*!< ITM TCR: SWOENA Position */ -#define ITM_TCR_SWOENA_Msk (1UL << ITM_TCR_SWOENA_Pos) /*!< ITM TCR: SWOENA Mask */ - -#define ITM_TCR_DWTENA_Pos 3U /*!< ITM TCR: DWTENA Position */ -#define ITM_TCR_DWTENA_Msk (1UL << ITM_TCR_DWTENA_Pos) /*!< ITM TCR: DWTENA Mask */ - -#define ITM_TCR_SYNCENA_Pos 2U /*!< ITM TCR: SYNCENA Position */ -#define ITM_TCR_SYNCENA_Msk (1UL << ITM_TCR_SYNCENA_Pos) /*!< ITM TCR: SYNCENA Mask */ - -#define ITM_TCR_TSENA_Pos 1U /*!< ITM TCR: TSENA Position */ -#define ITM_TCR_TSENA_Msk (1UL << ITM_TCR_TSENA_Pos) /*!< ITM TCR: TSENA Mask */ - -#define ITM_TCR_ITMENA_Pos 0U /*!< ITM TCR: ITM Enable bit Position */ -#define ITM_TCR_ITMENA_Msk (1UL /*<< ITM_TCR_ITMENA_Pos*/) /*!< ITM TCR: ITM Enable bit Mask */ - -/* ITM Lock Status Register Definitions */ -#define ITM_LSR_ByteAcc_Pos 2U /*!< ITM LSR: ByteAcc Position */ -#define ITM_LSR_ByteAcc_Msk (1UL << ITM_LSR_ByteAcc_Pos) /*!< ITM LSR: ByteAcc Mask */ - -#define ITM_LSR_Access_Pos 1U /*!< ITM LSR: Access Position */ -#define ITM_LSR_Access_Msk (1UL << ITM_LSR_Access_Pos) /*!< ITM LSR: Access Mask */ - -#define ITM_LSR_Present_Pos 0U /*!< ITM LSR: Present Position */ -#define ITM_LSR_Present_Msk (1UL /*<< ITM_LSR_Present_Pos*/) /*!< ITM LSR: Present Mask */ - -/*@}*/ /* end of group CMSIS_ITM */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_DWT Data Watchpoint and Trace (DWT) - \brief Type definitions for the Data Watchpoint and Trace (DWT) - @{ - */ - -/** - \brief Structure type to access the Data Watchpoint and Trace Register (DWT). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) Control Register */ - __IOM uint32_t CYCCNT; /*!< Offset: 0x004 (R/W) Cycle Count Register */ - __IOM uint32_t CPICNT; /*!< Offset: 0x008 (R/W) CPI Count Register */ - __IOM uint32_t EXCCNT; /*!< Offset: 0x00C (R/W) Exception Overhead Count Register */ - __IOM uint32_t SLEEPCNT; /*!< Offset: 0x010 (R/W) Sleep Count Register */ - __IOM uint32_t LSUCNT; /*!< Offset: 0x014 (R/W) LSU Count Register */ - __IOM uint32_t FOLDCNT; /*!< Offset: 0x018 (R/W) Folded-instruction Count Register */ - __IM uint32_t PCSR; /*!< Offset: 0x01C (R/ ) Program Counter Sample Register */ - __IOM uint32_t COMP0; /*!< Offset: 0x020 (R/W) Comparator Register 0 */ - __IOM uint32_t MASK0; /*!< Offset: 0x024 (R/W) Mask Register 0 */ - __IOM uint32_t FUNCTION0; /*!< Offset: 0x028 (R/W) Function Register 0 */ - uint32_t RESERVED0[1U]; - __IOM uint32_t COMP1; /*!< Offset: 0x030 (R/W) Comparator Register 1 */ - __IOM uint32_t MASK1; /*!< Offset: 0x034 (R/W) Mask Register 1 */ - __IOM uint32_t FUNCTION1; /*!< Offset: 0x038 (R/W) Function Register 1 */ - uint32_t RESERVED1[1U]; - __IOM uint32_t COMP2; /*!< Offset: 0x040 (R/W) Comparator Register 2 */ - __IOM uint32_t MASK2; /*!< Offset: 0x044 (R/W) Mask Register 2 */ - __IOM uint32_t FUNCTION2; /*!< Offset: 0x048 (R/W) Function Register 2 */ - uint32_t RESERVED2[1U]; - __IOM uint32_t COMP3; /*!< Offset: 0x050 (R/W) Comparator Register 3 */ - __IOM uint32_t MASK3; /*!< Offset: 0x054 (R/W) Mask Register 3 */ - __IOM uint32_t FUNCTION3; /*!< Offset: 0x058 (R/W) Function Register 3 */ -} DWT_Type; - -/* DWT Control Register Definitions */ -#define DWT_CTRL_NUMCOMP_Pos 28U /*!< DWT CTRL: NUMCOMP Position */ -#define DWT_CTRL_NUMCOMP_Msk (0xFUL << DWT_CTRL_NUMCOMP_Pos) /*!< DWT CTRL: NUMCOMP Mask */ - -#define DWT_CTRL_NOTRCPKT_Pos 27U /*!< DWT CTRL: NOTRCPKT Position */ -#define DWT_CTRL_NOTRCPKT_Msk (0x1UL << DWT_CTRL_NOTRCPKT_Pos) /*!< DWT CTRL: NOTRCPKT Mask */ - -#define DWT_CTRL_NOEXTTRIG_Pos 26U /*!< DWT CTRL: NOEXTTRIG Position */ -#define DWT_CTRL_NOEXTTRIG_Msk (0x1UL << DWT_CTRL_NOEXTTRIG_Pos) /*!< DWT CTRL: NOEXTTRIG Mask */ - -#define DWT_CTRL_NOCYCCNT_Pos 25U /*!< DWT CTRL: NOCYCCNT Position */ -#define DWT_CTRL_NOCYCCNT_Msk (0x1UL << DWT_CTRL_NOCYCCNT_Pos) /*!< DWT CTRL: NOCYCCNT Mask */ - -#define DWT_CTRL_NOPRFCNT_Pos 24U /*!< DWT CTRL: NOPRFCNT Position */ -#define DWT_CTRL_NOPRFCNT_Msk (0x1UL << DWT_CTRL_NOPRFCNT_Pos) /*!< DWT CTRL: NOPRFCNT Mask */ - -#define DWT_CTRL_CYCEVTENA_Pos 22U /*!< DWT CTRL: CYCEVTENA Position */ -#define DWT_CTRL_CYCEVTENA_Msk (0x1UL << DWT_CTRL_CYCEVTENA_Pos) /*!< DWT CTRL: CYCEVTENA Mask */ - -#define DWT_CTRL_FOLDEVTENA_Pos 21U /*!< DWT CTRL: FOLDEVTENA Position */ -#define DWT_CTRL_FOLDEVTENA_Msk (0x1UL << DWT_CTRL_FOLDEVTENA_Pos) /*!< DWT CTRL: FOLDEVTENA Mask */ - -#define DWT_CTRL_LSUEVTENA_Pos 20U /*!< DWT CTRL: LSUEVTENA Position */ -#define DWT_CTRL_LSUEVTENA_Msk (0x1UL << DWT_CTRL_LSUEVTENA_Pos) /*!< DWT CTRL: LSUEVTENA Mask */ - -#define DWT_CTRL_SLEEPEVTENA_Pos 19U /*!< DWT CTRL: SLEEPEVTENA Position */ -#define DWT_CTRL_SLEEPEVTENA_Msk (0x1UL << DWT_CTRL_SLEEPEVTENA_Pos) /*!< DWT CTRL: SLEEPEVTENA Mask */ - -#define DWT_CTRL_EXCEVTENA_Pos 18U /*!< DWT CTRL: EXCEVTENA Position */ -#define DWT_CTRL_EXCEVTENA_Msk (0x1UL << DWT_CTRL_EXCEVTENA_Pos) /*!< DWT CTRL: EXCEVTENA Mask */ - -#define DWT_CTRL_CPIEVTENA_Pos 17U /*!< DWT CTRL: CPIEVTENA Position */ -#define DWT_CTRL_CPIEVTENA_Msk (0x1UL << DWT_CTRL_CPIEVTENA_Pos) /*!< DWT CTRL: CPIEVTENA Mask */ - -#define DWT_CTRL_EXCTRCENA_Pos 16U /*!< DWT CTRL: EXCTRCENA Position */ -#define DWT_CTRL_EXCTRCENA_Msk (0x1UL << DWT_CTRL_EXCTRCENA_Pos) /*!< DWT CTRL: EXCTRCENA Mask */ - -#define DWT_CTRL_PCSAMPLENA_Pos 12U /*!< DWT CTRL: PCSAMPLENA Position */ -#define DWT_CTRL_PCSAMPLENA_Msk (0x1UL << DWT_CTRL_PCSAMPLENA_Pos) /*!< DWT CTRL: PCSAMPLENA Mask */ - -#define DWT_CTRL_SYNCTAP_Pos 10U /*!< DWT CTRL: SYNCTAP Position */ -#define DWT_CTRL_SYNCTAP_Msk (0x3UL << DWT_CTRL_SYNCTAP_Pos) /*!< DWT CTRL: SYNCTAP Mask */ - -#define DWT_CTRL_CYCTAP_Pos 9U /*!< DWT CTRL: CYCTAP Position */ -#define DWT_CTRL_CYCTAP_Msk (0x1UL << DWT_CTRL_CYCTAP_Pos) /*!< DWT CTRL: CYCTAP Mask */ - -#define DWT_CTRL_POSTINIT_Pos 5U /*!< DWT CTRL: POSTINIT Position */ -#define DWT_CTRL_POSTINIT_Msk (0xFUL << DWT_CTRL_POSTINIT_Pos) /*!< DWT CTRL: POSTINIT Mask */ - -#define DWT_CTRL_POSTPRESET_Pos 1U /*!< DWT CTRL: POSTPRESET Position */ -#define DWT_CTRL_POSTPRESET_Msk (0xFUL << DWT_CTRL_POSTPRESET_Pos) /*!< DWT CTRL: POSTPRESET Mask */ - -#define DWT_CTRL_CYCCNTENA_Pos 0U /*!< DWT CTRL: CYCCNTENA Position */ -#define DWT_CTRL_CYCCNTENA_Msk (0x1UL /*<< DWT_CTRL_CYCCNTENA_Pos*/) /*!< DWT CTRL: CYCCNTENA Mask */ - -/* DWT CPI Count Register Definitions */ -#define DWT_CPICNT_CPICNT_Pos 0U /*!< DWT CPICNT: CPICNT Position */ -#define DWT_CPICNT_CPICNT_Msk (0xFFUL /*<< DWT_CPICNT_CPICNT_Pos*/) /*!< DWT CPICNT: CPICNT Mask */ - -/* DWT Exception Overhead Count Register Definitions */ -#define DWT_EXCCNT_EXCCNT_Pos 0U /*!< DWT EXCCNT: EXCCNT Position */ -#define DWT_EXCCNT_EXCCNT_Msk (0xFFUL /*<< DWT_EXCCNT_EXCCNT_Pos*/) /*!< DWT EXCCNT: EXCCNT Mask */ - -/* DWT Sleep Count Register Definitions */ -#define DWT_SLEEPCNT_SLEEPCNT_Pos 0U /*!< DWT SLEEPCNT: SLEEPCNT Position */ -#define DWT_SLEEPCNT_SLEEPCNT_Msk (0xFFUL /*<< DWT_SLEEPCNT_SLEEPCNT_Pos*/) /*!< DWT SLEEPCNT: SLEEPCNT Mask */ - -/* DWT LSU Count Register Definitions */ -#define DWT_LSUCNT_LSUCNT_Pos 0U /*!< DWT LSUCNT: LSUCNT Position */ -#define DWT_LSUCNT_LSUCNT_Msk (0xFFUL /*<< DWT_LSUCNT_LSUCNT_Pos*/) /*!< DWT LSUCNT: LSUCNT Mask */ - -/* DWT Folded-instruction Count Register Definitions */ -#define DWT_FOLDCNT_FOLDCNT_Pos 0U /*!< DWT FOLDCNT: FOLDCNT Position */ -#define DWT_FOLDCNT_FOLDCNT_Msk (0xFFUL /*<< DWT_FOLDCNT_FOLDCNT_Pos*/) /*!< DWT FOLDCNT: FOLDCNT Mask */ - -/* DWT Comparator Mask Register Definitions */ -#define DWT_MASK_MASK_Pos 0U /*!< DWT MASK: MASK Position */ -#define DWT_MASK_MASK_Msk (0x1FUL /*<< DWT_MASK_MASK_Pos*/) /*!< DWT MASK: MASK Mask */ - -/* DWT Comparator Function Register Definitions */ -#define DWT_FUNCTION_MATCHED_Pos 24U /*!< DWT FUNCTION: MATCHED Position */ -#define DWT_FUNCTION_MATCHED_Msk (0x1UL << DWT_FUNCTION_MATCHED_Pos) /*!< DWT FUNCTION: MATCHED Mask */ - -#define DWT_FUNCTION_DATAVADDR1_Pos 16U /*!< DWT FUNCTION: DATAVADDR1 Position */ -#define DWT_FUNCTION_DATAVADDR1_Msk (0xFUL << DWT_FUNCTION_DATAVADDR1_Pos) /*!< DWT FUNCTION: DATAVADDR1 Mask */ - -#define DWT_FUNCTION_DATAVADDR0_Pos 12U /*!< DWT FUNCTION: DATAVADDR0 Position */ -#define DWT_FUNCTION_DATAVADDR0_Msk (0xFUL << DWT_FUNCTION_DATAVADDR0_Pos) /*!< DWT FUNCTION: DATAVADDR0 Mask */ - -#define DWT_FUNCTION_DATAVSIZE_Pos 10U /*!< DWT FUNCTION: DATAVSIZE Position */ -#define DWT_FUNCTION_DATAVSIZE_Msk (0x3UL << DWT_FUNCTION_DATAVSIZE_Pos) /*!< DWT FUNCTION: DATAVSIZE Mask */ - -#define DWT_FUNCTION_LNK1ENA_Pos 9U /*!< DWT FUNCTION: LNK1ENA Position */ -#define DWT_FUNCTION_LNK1ENA_Msk (0x1UL << DWT_FUNCTION_LNK1ENA_Pos) /*!< DWT FUNCTION: LNK1ENA Mask */ - -#define DWT_FUNCTION_DATAVMATCH_Pos 8U /*!< DWT FUNCTION: DATAVMATCH Position */ -#define DWT_FUNCTION_DATAVMATCH_Msk (0x1UL << DWT_FUNCTION_DATAVMATCH_Pos) /*!< DWT FUNCTION: DATAVMATCH Mask */ - -#define DWT_FUNCTION_CYCMATCH_Pos 7U /*!< DWT FUNCTION: CYCMATCH Position */ -#define DWT_FUNCTION_CYCMATCH_Msk (0x1UL << DWT_FUNCTION_CYCMATCH_Pos) /*!< DWT FUNCTION: CYCMATCH Mask */ - -#define DWT_FUNCTION_EMITRANGE_Pos 5U /*!< DWT FUNCTION: EMITRANGE Position */ -#define DWT_FUNCTION_EMITRANGE_Msk (0x1UL << DWT_FUNCTION_EMITRANGE_Pos) /*!< DWT FUNCTION: EMITRANGE Mask */ - -#define DWT_FUNCTION_FUNCTION_Pos 0U /*!< DWT FUNCTION: FUNCTION Position */ -#define DWT_FUNCTION_FUNCTION_Msk (0xFUL /*<< DWT_FUNCTION_FUNCTION_Pos*/) /*!< DWT FUNCTION: FUNCTION Mask */ - -/*@}*/ /* end of group CMSIS_DWT */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_TPI Trace Port Interface (TPI) - \brief Type definitions for the Trace Port Interface (TPI) - @{ - */ - -/** - \brief Structure type to access the Trace Port Interface Register (TPI). - */ -typedef struct -{ - __IM uint32_t SSPSR; /*!< Offset: 0x000 (R/ ) Supported Parallel Port Size Register */ - __IOM uint32_t CSPSR; /*!< Offset: 0x004 (R/W) Current Parallel Port Size Register */ - uint32_t RESERVED0[2U]; - __IOM uint32_t ACPR; /*!< Offset: 0x010 (R/W) Asynchronous Clock Prescaler Register */ - uint32_t RESERVED1[55U]; - __IOM uint32_t SPPR; /*!< Offset: 0x0F0 (R/W) Selected Pin Protocol Register */ - uint32_t RESERVED2[131U]; - __IM uint32_t FFSR; /*!< Offset: 0x300 (R/ ) Formatter and Flush Status Register */ - __IOM uint32_t FFCR; /*!< Offset: 0x304 (R/W) Formatter and Flush Control Register */ - __IM uint32_t FSCR; /*!< Offset: 0x308 (R/ ) Formatter Synchronization Counter Register */ - uint32_t RESERVED3[759U]; - __IM uint32_t TRIGGER; /*!< Offset: 0xEE8 (R/ ) TRIGGER Register */ - __IM uint32_t FIFO0; /*!< Offset: 0xEEC (R/ ) Integration ETM Data */ - __IM uint32_t ITATBCTR2; /*!< Offset: 0xEF0 (R/ ) ITATBCTR2 */ - uint32_t RESERVED4[1U]; - __IM uint32_t ITATBCTR0; /*!< Offset: 0xEF8 (R/ ) ITATBCTR0 */ - __IM uint32_t FIFO1; /*!< Offset: 0xEFC (R/ ) Integration ITM Data */ - __IOM uint32_t ITCTRL; /*!< Offset: 0xF00 (R/W) Integration Mode Control */ - uint32_t RESERVED5[39U]; - __IOM uint32_t CLAIMSET; /*!< Offset: 0xFA0 (R/W) Claim tag set */ - __IOM uint32_t CLAIMCLR; /*!< Offset: 0xFA4 (R/W) Claim tag clear */ - uint32_t RESERVED7[8U]; - __IM uint32_t DEVID; /*!< Offset: 0xFC8 (R/ ) TPIU_DEVID */ - __IM uint32_t DEVTYPE; /*!< Offset: 0xFCC (R/ ) TPIU_DEVTYPE */ -} TPI_Type; - -/* TPI Asynchronous Clock Prescaler Register Definitions */ -#define TPI_ACPR_PRESCALER_Pos 0U /*!< TPI ACPR: PRESCALER Position */ -#define TPI_ACPR_PRESCALER_Msk (0x1FFFUL /*<< TPI_ACPR_PRESCALER_Pos*/) /*!< TPI ACPR: PRESCALER Mask */ - -/* TPI Selected Pin Protocol Register Definitions */ -#define TPI_SPPR_TXMODE_Pos 0U /*!< TPI SPPR: TXMODE Position */ -#define TPI_SPPR_TXMODE_Msk (0x3UL /*<< TPI_SPPR_TXMODE_Pos*/) /*!< TPI SPPR: TXMODE Mask */ - -/* TPI Formatter and Flush Status Register Definitions */ -#define TPI_FFSR_FtNonStop_Pos 3U /*!< TPI FFSR: FtNonStop Position */ -#define TPI_FFSR_FtNonStop_Msk (0x1UL << TPI_FFSR_FtNonStop_Pos) /*!< TPI FFSR: FtNonStop Mask */ - -#define TPI_FFSR_TCPresent_Pos 2U /*!< TPI FFSR: TCPresent Position */ -#define TPI_FFSR_TCPresent_Msk (0x1UL << TPI_FFSR_TCPresent_Pos) /*!< TPI FFSR: TCPresent Mask */ - -#define TPI_FFSR_FtStopped_Pos 1U /*!< TPI FFSR: FtStopped Position */ -#define TPI_FFSR_FtStopped_Msk (0x1UL << TPI_FFSR_FtStopped_Pos) /*!< TPI FFSR: FtStopped Mask */ - -#define TPI_FFSR_FlInProg_Pos 0U /*!< TPI FFSR: FlInProg Position */ -#define TPI_FFSR_FlInProg_Msk (0x1UL /*<< TPI_FFSR_FlInProg_Pos*/) /*!< TPI FFSR: FlInProg Mask */ - -/* TPI Formatter and Flush Control Register Definitions */ -#define TPI_FFCR_TrigIn_Pos 8U /*!< TPI FFCR: TrigIn Position */ -#define TPI_FFCR_TrigIn_Msk (0x1UL << TPI_FFCR_TrigIn_Pos) /*!< TPI FFCR: TrigIn Mask */ - -#define TPI_FFCR_EnFCont_Pos 1U /*!< TPI FFCR: EnFCont Position */ -#define TPI_FFCR_EnFCont_Msk (0x1UL << TPI_FFCR_EnFCont_Pos) /*!< TPI FFCR: EnFCont Mask */ - -/* TPI TRIGGER Register Definitions */ -#define TPI_TRIGGER_TRIGGER_Pos 0U /*!< TPI TRIGGER: TRIGGER Position */ -#define TPI_TRIGGER_TRIGGER_Msk (0x1UL /*<< TPI_TRIGGER_TRIGGER_Pos*/) /*!< TPI TRIGGER: TRIGGER Mask */ - -/* TPI Integration ETM Data Register Definitions (FIFO0) */ -#define TPI_FIFO0_ITM_ATVALID_Pos 29U /*!< TPI FIFO0: ITM_ATVALID Position */ -#define TPI_FIFO0_ITM_ATVALID_Msk (0x1UL << TPI_FIFO0_ITM_ATVALID_Pos) /*!< TPI FIFO0: ITM_ATVALID Mask */ - -#define TPI_FIFO0_ITM_bytecount_Pos 27U /*!< TPI FIFO0: ITM_bytecount Position */ -#define TPI_FIFO0_ITM_bytecount_Msk (0x3UL << TPI_FIFO0_ITM_bytecount_Pos) /*!< TPI FIFO0: ITM_bytecount Mask */ - -#define TPI_FIFO0_ETM_ATVALID_Pos 26U /*!< TPI FIFO0: ETM_ATVALID Position */ -#define TPI_FIFO0_ETM_ATVALID_Msk (0x1UL << TPI_FIFO0_ETM_ATVALID_Pos) /*!< TPI FIFO0: ETM_ATVALID Mask */ - -#define TPI_FIFO0_ETM_bytecount_Pos 24U /*!< TPI FIFO0: ETM_bytecount Position */ -#define TPI_FIFO0_ETM_bytecount_Msk (0x3UL << TPI_FIFO0_ETM_bytecount_Pos) /*!< TPI FIFO0: ETM_bytecount Mask */ - -#define TPI_FIFO0_ETM2_Pos 16U /*!< TPI FIFO0: ETM2 Position */ -#define TPI_FIFO0_ETM2_Msk (0xFFUL << TPI_FIFO0_ETM2_Pos) /*!< TPI FIFO0: ETM2 Mask */ - -#define TPI_FIFO0_ETM1_Pos 8U /*!< TPI FIFO0: ETM1 Position */ -#define TPI_FIFO0_ETM1_Msk (0xFFUL << TPI_FIFO0_ETM1_Pos) /*!< TPI FIFO0: ETM1 Mask */ - -#define TPI_FIFO0_ETM0_Pos 0U /*!< TPI FIFO0: ETM0 Position */ -#define TPI_FIFO0_ETM0_Msk (0xFFUL /*<< TPI_FIFO0_ETM0_Pos*/) /*!< TPI FIFO0: ETM0 Mask */ - -/* TPI ITATBCTR2 Register Definitions */ -#define TPI_ITATBCTR2_ATREADY2_Pos 0U /*!< TPI ITATBCTR2: ATREADY2 Position */ -#define TPI_ITATBCTR2_ATREADY2_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY2_Pos*/) /*!< TPI ITATBCTR2: ATREADY2 Mask */ - -#define TPI_ITATBCTR2_ATREADY1_Pos 0U /*!< TPI ITATBCTR2: ATREADY1 Position */ -#define TPI_ITATBCTR2_ATREADY1_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY1_Pos*/) /*!< TPI ITATBCTR2: ATREADY1 Mask */ - -/* TPI Integration ITM Data Register Definitions (FIFO1) */ -#define TPI_FIFO1_ITM_ATVALID_Pos 29U /*!< TPI FIFO1: ITM_ATVALID Position */ -#define TPI_FIFO1_ITM_ATVALID_Msk (0x1UL << TPI_FIFO1_ITM_ATVALID_Pos) /*!< TPI FIFO1: ITM_ATVALID Mask */ - -#define TPI_FIFO1_ITM_bytecount_Pos 27U /*!< TPI FIFO1: ITM_bytecount Position */ -#define TPI_FIFO1_ITM_bytecount_Msk (0x3UL << TPI_FIFO1_ITM_bytecount_Pos) /*!< TPI FIFO1: ITM_bytecount Mask */ - -#define TPI_FIFO1_ETM_ATVALID_Pos 26U /*!< TPI FIFO1: ETM_ATVALID Position */ -#define TPI_FIFO1_ETM_ATVALID_Msk (0x1UL << TPI_FIFO1_ETM_ATVALID_Pos) /*!< TPI FIFO1: ETM_ATVALID Mask */ - -#define TPI_FIFO1_ETM_bytecount_Pos 24U /*!< TPI FIFO1: ETM_bytecount Position */ -#define TPI_FIFO1_ETM_bytecount_Msk (0x3UL << TPI_FIFO1_ETM_bytecount_Pos) /*!< TPI FIFO1: ETM_bytecount Mask */ - -#define TPI_FIFO1_ITM2_Pos 16U /*!< TPI FIFO1: ITM2 Position */ -#define TPI_FIFO1_ITM2_Msk (0xFFUL << TPI_FIFO1_ITM2_Pos) /*!< TPI FIFO1: ITM2 Mask */ - -#define TPI_FIFO1_ITM1_Pos 8U /*!< TPI FIFO1: ITM1 Position */ -#define TPI_FIFO1_ITM1_Msk (0xFFUL << TPI_FIFO1_ITM1_Pos) /*!< TPI FIFO1: ITM1 Mask */ - -#define TPI_FIFO1_ITM0_Pos 0U /*!< TPI FIFO1: ITM0 Position */ -#define TPI_FIFO1_ITM0_Msk (0xFFUL /*<< TPI_FIFO1_ITM0_Pos*/) /*!< TPI FIFO1: ITM0 Mask */ - -/* TPI ITATBCTR0 Register Definitions */ -#define TPI_ITATBCTR0_ATREADY2_Pos 0U /*!< TPI ITATBCTR0: ATREADY2 Position */ -#define TPI_ITATBCTR0_ATREADY2_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY2_Pos*/) /*!< TPI ITATBCTR0: ATREADY2 Mask */ - -#define TPI_ITATBCTR0_ATREADY1_Pos 0U /*!< TPI ITATBCTR0: ATREADY1 Position */ -#define TPI_ITATBCTR0_ATREADY1_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY1_Pos*/) /*!< TPI ITATBCTR0: ATREADY1 Mask */ - -/* TPI Integration Mode Control Register Definitions */ -#define TPI_ITCTRL_Mode_Pos 0U /*!< TPI ITCTRL: Mode Position */ -#define TPI_ITCTRL_Mode_Msk (0x3UL /*<< TPI_ITCTRL_Mode_Pos*/) /*!< TPI ITCTRL: Mode Mask */ - -/* TPI DEVID Register Definitions */ -#define TPI_DEVID_NRZVALID_Pos 11U /*!< TPI DEVID: NRZVALID Position */ -#define TPI_DEVID_NRZVALID_Msk (0x1UL << TPI_DEVID_NRZVALID_Pos) /*!< TPI DEVID: NRZVALID Mask */ - -#define TPI_DEVID_MANCVALID_Pos 10U /*!< TPI DEVID: MANCVALID Position */ -#define TPI_DEVID_MANCVALID_Msk (0x1UL << TPI_DEVID_MANCVALID_Pos) /*!< TPI DEVID: MANCVALID Mask */ - -#define TPI_DEVID_PTINVALID_Pos 9U /*!< TPI DEVID: PTINVALID Position */ -#define TPI_DEVID_PTINVALID_Msk (0x1UL << TPI_DEVID_PTINVALID_Pos) /*!< TPI DEVID: PTINVALID Mask */ - -#define TPI_DEVID_MinBufSz_Pos 6U /*!< TPI DEVID: MinBufSz Position */ -#define TPI_DEVID_MinBufSz_Msk (0x7UL << TPI_DEVID_MinBufSz_Pos) /*!< TPI DEVID: MinBufSz Mask */ - -#define TPI_DEVID_AsynClkIn_Pos 5U /*!< TPI DEVID: AsynClkIn Position */ -#define TPI_DEVID_AsynClkIn_Msk (0x1UL << TPI_DEVID_AsynClkIn_Pos) /*!< TPI DEVID: AsynClkIn Mask */ - -#define TPI_DEVID_NrTraceInput_Pos 0U /*!< TPI DEVID: NrTraceInput Position */ -#define TPI_DEVID_NrTraceInput_Msk (0x1FUL /*<< TPI_DEVID_NrTraceInput_Pos*/) /*!< TPI DEVID: NrTraceInput Mask */ - -/* TPI DEVTYPE Register Definitions */ -#define TPI_DEVTYPE_SubType_Pos 4U /*!< TPI DEVTYPE: SubType Position */ -#define TPI_DEVTYPE_SubType_Msk (0xFUL /*<< TPI_DEVTYPE_SubType_Pos*/) /*!< TPI DEVTYPE: SubType Mask */ - -#define TPI_DEVTYPE_MajorType_Pos 0U /*!< TPI DEVTYPE: MajorType Position */ -#define TPI_DEVTYPE_MajorType_Msk (0xFUL << TPI_DEVTYPE_MajorType_Pos) /*!< TPI DEVTYPE: MajorType Mask */ - -/*@}*/ /* end of group CMSIS_TPI */ - - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_MPU Memory Protection Unit (MPU) - \brief Type definitions for the Memory Protection Unit (MPU) - @{ - */ - -/** - \brief Structure type to access the Memory Protection Unit (MPU). - */ -typedef struct -{ - __IM uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */ - __IOM uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */ - __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region RNRber Register */ - __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */ - __IOM uint32_t RASR; /*!< Offset: 0x010 (R/W) MPU Region Attribute and Size Register */ - __IOM uint32_t RBAR_A1; /*!< Offset: 0x014 (R/W) MPU Alias 1 Region Base Address Register */ - __IOM uint32_t RASR_A1; /*!< Offset: 0x018 (R/W) MPU Alias 1 Region Attribute and Size Register */ - __IOM uint32_t RBAR_A2; /*!< Offset: 0x01C (R/W) MPU Alias 2 Region Base Address Register */ - __IOM uint32_t RASR_A2; /*!< Offset: 0x020 (R/W) MPU Alias 2 Region Attribute and Size Register */ - __IOM uint32_t RBAR_A3; /*!< Offset: 0x024 (R/W) MPU Alias 3 Region Base Address Register */ - __IOM uint32_t RASR_A3; /*!< Offset: 0x028 (R/W) MPU Alias 3 Region Attribute and Size Register */ -} MPU_Type; - -#define MPU_TYPE_RALIASES 4U - -/* MPU Type Register Definitions */ -#define MPU_TYPE_IREGION_Pos 16U /*!< MPU TYPE: IREGION Position */ -#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */ - -#define MPU_TYPE_DREGION_Pos 8U /*!< MPU TYPE: DREGION Position */ -#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ - -#define MPU_TYPE_SEPARATE_Pos 0U /*!< MPU TYPE: SEPARATE Position */ -#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */ - -/* MPU Control Register Definitions */ -#define MPU_CTRL_PRIVDEFENA_Pos 2U /*!< MPU CTRL: PRIVDEFENA Position */ -#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */ - -#define MPU_CTRL_HFNMIENA_Pos 1U /*!< MPU CTRL: HFNMIENA Position */ -#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ - -#define MPU_CTRL_ENABLE_Pos 0U /*!< MPU CTRL: ENABLE Position */ -#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */ - -/* MPU Region Number Register Definitions */ -#define MPU_RNR_REGION_Pos 0U /*!< MPU RNR: REGION Position */ -#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */ - -/* MPU Region Base Address Register Definitions */ -#define MPU_RBAR_ADDR_Pos 5U /*!< MPU RBAR: ADDR Position */ -#define MPU_RBAR_ADDR_Msk (0x7FFFFFFUL << MPU_RBAR_ADDR_Pos) /*!< MPU RBAR: ADDR Mask */ - -#define MPU_RBAR_VALID_Pos 4U /*!< MPU RBAR: VALID Position */ -#define MPU_RBAR_VALID_Msk (1UL << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */ - -#define MPU_RBAR_REGION_Pos 0U /*!< MPU RBAR: REGION Position */ -#define MPU_RBAR_REGION_Msk (0xFUL /*<< MPU_RBAR_REGION_Pos*/) /*!< MPU RBAR: REGION Mask */ - -/* MPU Region Attribute and Size Register Definitions */ -#define MPU_RASR_ATTRS_Pos 16U /*!< MPU RASR: MPU Region Attribute field Position */ -#define MPU_RASR_ATTRS_Msk (0xFFFFUL << MPU_RASR_ATTRS_Pos) /*!< MPU RASR: MPU Region Attribute field Mask */ - -#define MPU_RASR_XN_Pos 28U /*!< MPU RASR: ATTRS.XN Position */ -#define MPU_RASR_XN_Msk (1UL << MPU_RASR_XN_Pos) /*!< MPU RASR: ATTRS.XN Mask */ - -#define MPU_RASR_AP_Pos 24U /*!< MPU RASR: ATTRS.AP Position */ -#define MPU_RASR_AP_Msk (0x7UL << MPU_RASR_AP_Pos) /*!< MPU RASR: ATTRS.AP Mask */ - -#define MPU_RASR_TEX_Pos 19U /*!< MPU RASR: ATTRS.TEX Position */ -#define MPU_RASR_TEX_Msk (0x7UL << MPU_RASR_TEX_Pos) /*!< MPU RASR: ATTRS.TEX Mask */ - -#define MPU_RASR_S_Pos 18U /*!< MPU RASR: ATTRS.S Position */ -#define MPU_RASR_S_Msk (1UL << MPU_RASR_S_Pos) /*!< MPU RASR: ATTRS.S Mask */ - -#define MPU_RASR_C_Pos 17U /*!< MPU RASR: ATTRS.C Position */ -#define MPU_RASR_C_Msk (1UL << MPU_RASR_C_Pos) /*!< MPU RASR: ATTRS.C Mask */ - -#define MPU_RASR_B_Pos 16U /*!< MPU RASR: ATTRS.B Position */ -#define MPU_RASR_B_Msk (1UL << MPU_RASR_B_Pos) /*!< MPU RASR: ATTRS.B Mask */ - -#define MPU_RASR_SRD_Pos 8U /*!< MPU RASR: Sub-Region Disable Position */ -#define MPU_RASR_SRD_Msk (0xFFUL << MPU_RASR_SRD_Pos) /*!< MPU RASR: Sub-Region Disable Mask */ - -#define MPU_RASR_SIZE_Pos 1U /*!< MPU RASR: Region Size Field Position */ -#define MPU_RASR_SIZE_Msk (0x1FUL << MPU_RASR_SIZE_Pos) /*!< MPU RASR: Region Size Field Mask */ - -#define MPU_RASR_ENABLE_Pos 0U /*!< MPU RASR: Region enable bit Position */ -#define MPU_RASR_ENABLE_Msk (1UL /*<< MPU_RASR_ENABLE_Pos*/) /*!< MPU RASR: Region enable bit Disable Mask */ - -/*@} end of group CMSIS_MPU */ -#endif - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug) - \brief Type definitions for the Core Debug Registers - @{ - */ - -/** - \brief Structure type to access the Core Debug Register (CoreDebug). - */ -typedef struct -{ - __IOM uint32_t DHCSR; /*!< Offset: 0x000 (R/W) Debug Halting Control and Status Register */ - __OM uint32_t DCRSR; /*!< Offset: 0x004 ( /W) Debug Core Register Selector Register */ - __IOM uint32_t DCRDR; /*!< Offset: 0x008 (R/W) Debug Core Register Data Register */ - __IOM uint32_t DEMCR; /*!< Offset: 0x00C (R/W) Debug Exception and Monitor Control Register */ -} CoreDebug_Type; - -/* Debug Halting Control and Status Register Definitions */ -#define CoreDebug_DHCSR_DBGKEY_Pos 16U /*!< CoreDebug DHCSR: DBGKEY Position */ -#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFUL << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */ - -#define CoreDebug_DHCSR_S_RESET_ST_Pos 25U /*!< CoreDebug DHCSR: S_RESET_ST Position */ -#define CoreDebug_DHCSR_S_RESET_ST_Msk (1UL << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */ - -#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24U /*!< CoreDebug DHCSR: S_RETIRE_ST Position */ -#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1UL << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */ - -#define CoreDebug_DHCSR_S_LOCKUP_Pos 19U /*!< CoreDebug DHCSR: S_LOCKUP Position */ -#define CoreDebug_DHCSR_S_LOCKUP_Msk (1UL << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */ - -#define CoreDebug_DHCSR_S_SLEEP_Pos 18U /*!< CoreDebug DHCSR: S_SLEEP Position */ -#define CoreDebug_DHCSR_S_SLEEP_Msk (1UL << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */ - -#define CoreDebug_DHCSR_S_HALT_Pos 17U /*!< CoreDebug DHCSR: S_HALT Position */ -#define CoreDebug_DHCSR_S_HALT_Msk (1UL << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */ - -#define CoreDebug_DHCSR_S_REGRDY_Pos 16U /*!< CoreDebug DHCSR: S_REGRDY Position */ -#define CoreDebug_DHCSR_S_REGRDY_Msk (1UL << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */ - -#define CoreDebug_DHCSR_C_SNAPSTALL_Pos 5U /*!< CoreDebug DHCSR: C_SNAPSTALL Position */ -#define CoreDebug_DHCSR_C_SNAPSTALL_Msk (1UL << CoreDebug_DHCSR_C_SNAPSTALL_Pos) /*!< CoreDebug DHCSR: C_SNAPSTALL Mask */ - -#define CoreDebug_DHCSR_C_MASKINTS_Pos 3U /*!< CoreDebug DHCSR: C_MASKINTS Position */ -#define CoreDebug_DHCSR_C_MASKINTS_Msk (1UL << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */ - -#define CoreDebug_DHCSR_C_STEP_Pos 2U /*!< CoreDebug DHCSR: C_STEP Position */ -#define CoreDebug_DHCSR_C_STEP_Msk (1UL << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */ - -#define CoreDebug_DHCSR_C_HALT_Pos 1U /*!< CoreDebug DHCSR: C_HALT Position */ -#define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */ - -#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0U /*!< CoreDebug DHCSR: C_DEBUGEN Position */ -#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL /*<< CoreDebug_DHCSR_C_DEBUGEN_Pos*/) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ - -/* Debug Core Register Selector Register Definitions */ -#define CoreDebug_DCRSR_REGWnR_Pos 16U /*!< CoreDebug DCRSR: REGWnR Position */ -#define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */ - -#define CoreDebug_DCRSR_REGSEL_Pos 0U /*!< CoreDebug DCRSR: REGSEL Position */ -#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL /*<< CoreDebug_DCRSR_REGSEL_Pos*/) /*!< CoreDebug DCRSR: REGSEL Mask */ - -/* Debug Exception and Monitor Control Register Definitions */ -#define CoreDebug_DEMCR_TRCENA_Pos 24U /*!< CoreDebug DEMCR: TRCENA Position */ -#define CoreDebug_DEMCR_TRCENA_Msk (1UL << CoreDebug_DEMCR_TRCENA_Pos) /*!< CoreDebug DEMCR: TRCENA Mask */ - -#define CoreDebug_DEMCR_MON_REQ_Pos 19U /*!< CoreDebug DEMCR: MON_REQ Position */ -#define CoreDebug_DEMCR_MON_REQ_Msk (1UL << CoreDebug_DEMCR_MON_REQ_Pos) /*!< CoreDebug DEMCR: MON_REQ Mask */ - -#define CoreDebug_DEMCR_MON_STEP_Pos 18U /*!< CoreDebug DEMCR: MON_STEP Position */ -#define CoreDebug_DEMCR_MON_STEP_Msk (1UL << CoreDebug_DEMCR_MON_STEP_Pos) /*!< CoreDebug DEMCR: MON_STEP Mask */ - -#define CoreDebug_DEMCR_MON_PEND_Pos 17U /*!< CoreDebug DEMCR: MON_PEND Position */ -#define CoreDebug_DEMCR_MON_PEND_Msk (1UL << CoreDebug_DEMCR_MON_PEND_Pos) /*!< CoreDebug DEMCR: MON_PEND Mask */ - -#define CoreDebug_DEMCR_MON_EN_Pos 16U /*!< CoreDebug DEMCR: MON_EN Position */ -#define CoreDebug_DEMCR_MON_EN_Msk (1UL << CoreDebug_DEMCR_MON_EN_Pos) /*!< CoreDebug DEMCR: MON_EN Mask */ - -#define CoreDebug_DEMCR_VC_HARDERR_Pos 10U /*!< CoreDebug DEMCR: VC_HARDERR Position */ -#define CoreDebug_DEMCR_VC_HARDERR_Msk (1UL << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */ - -#define CoreDebug_DEMCR_VC_INTERR_Pos 9U /*!< CoreDebug DEMCR: VC_INTERR Position */ -#define CoreDebug_DEMCR_VC_INTERR_Msk (1UL << CoreDebug_DEMCR_VC_INTERR_Pos) /*!< CoreDebug DEMCR: VC_INTERR Mask */ - -#define CoreDebug_DEMCR_VC_BUSERR_Pos 8U /*!< CoreDebug DEMCR: VC_BUSERR Position */ -#define CoreDebug_DEMCR_VC_BUSERR_Msk (1UL << CoreDebug_DEMCR_VC_BUSERR_Pos) /*!< CoreDebug DEMCR: VC_BUSERR Mask */ - -#define CoreDebug_DEMCR_VC_STATERR_Pos 7U /*!< CoreDebug DEMCR: VC_STATERR Position */ -#define CoreDebug_DEMCR_VC_STATERR_Msk (1UL << CoreDebug_DEMCR_VC_STATERR_Pos) /*!< CoreDebug DEMCR: VC_STATERR Mask */ - -#define CoreDebug_DEMCR_VC_CHKERR_Pos 6U /*!< CoreDebug DEMCR: VC_CHKERR Position */ -#define CoreDebug_DEMCR_VC_CHKERR_Msk (1UL << CoreDebug_DEMCR_VC_CHKERR_Pos) /*!< CoreDebug DEMCR: VC_CHKERR Mask */ - -#define CoreDebug_DEMCR_VC_NOCPERR_Pos 5U /*!< CoreDebug DEMCR: VC_NOCPERR Position */ -#define CoreDebug_DEMCR_VC_NOCPERR_Msk (1UL << CoreDebug_DEMCR_VC_NOCPERR_Pos) /*!< CoreDebug DEMCR: VC_NOCPERR Mask */ - -#define CoreDebug_DEMCR_VC_MMERR_Pos 4U /*!< CoreDebug DEMCR: VC_MMERR Position */ -#define CoreDebug_DEMCR_VC_MMERR_Msk (1UL << CoreDebug_DEMCR_VC_MMERR_Pos) /*!< CoreDebug DEMCR: VC_MMERR Mask */ - -#define CoreDebug_DEMCR_VC_CORERESET_Pos 0U /*!< CoreDebug DEMCR: VC_CORERESET Position */ -#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL /*<< CoreDebug_DEMCR_VC_CORERESET_Pos*/) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ - -/*@} end of group CMSIS_CoreDebug */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_bitfield Core register bit field macros - \brief Macros for use with bit field definitions (xxx_Pos, xxx_Msk). - @{ - */ - -/** - \brief Mask and shift a bit field value for use in a register bit range. - \param[in] field Name of the register bit field. - \param[in] value Value of the bit field. This parameter is interpreted as an uint32_t type. - \return Masked and shifted value. -*/ -#define _VAL2FLD(field, value) (((uint32_t)(value) << field ## _Pos) & field ## _Msk) - -/** - \brief Mask and shift a register value to extract a bit filed value. - \param[in] field Name of the register bit field. - \param[in] value Value of register. This parameter is interpreted as an uint32_t type. - \return Masked and shifted bit field value. -*/ -#define _FLD2VAL(field, value) (((uint32_t)(value) & field ## _Msk) >> field ## _Pos) - -/*@} end of group CMSIS_core_bitfield */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_base Core Definitions - \brief Definitions for base addresses, unions, and structures. - @{ - */ - -/* Memory mapping of Core Hardware */ -#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ -#define ITM_BASE (0xE0000000UL) /*!< ITM Base Address */ -#define DWT_BASE (0xE0001000UL) /*!< DWT Base Address */ -#define TPI_BASE (0xE0040000UL) /*!< TPI Base Address */ -#define CoreDebug_BASE (0xE000EDF0UL) /*!< Core Debug Base Address */ -#define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ -#define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ -#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ - -#define SCnSCB ((SCnSCB_Type *) SCS_BASE ) /*!< System control Register not in SCB */ -#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ -#define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ -#define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ -#define ITM ((ITM_Type *) ITM_BASE ) /*!< ITM configuration struct */ -#define DWT ((DWT_Type *) DWT_BASE ) /*!< DWT configuration struct */ -#define TPI ((TPI_Type *) TPI_BASE ) /*!< TPI configuration struct */ -#define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE) /*!< Core Debug configuration struct */ - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */ - #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */ -#endif - -/*@} */ - - - -/******************************************************************************* - * Hardware Abstraction Layer - Core Function Interface contains: - - Core NVIC Functions - - Core SysTick Functions - - Core Debug Functions - - Core Register Access Functions - ******************************************************************************/ -/** - \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference -*/ - - - -/* ########################## NVIC functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_NVICFunctions NVIC Functions - \brief Functions that manage interrupts and exceptions via the NVIC. - @{ - */ - -#ifdef CMSIS_NVIC_VIRTUAL - #ifndef CMSIS_NVIC_VIRTUAL_HEADER_FILE - #define CMSIS_NVIC_VIRTUAL_HEADER_FILE "cmsis_nvic_virtual.h" - #endif - #include CMSIS_NVIC_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetPriorityGrouping __NVIC_SetPriorityGrouping - #define NVIC_GetPriorityGrouping __NVIC_GetPriorityGrouping - #define NVIC_EnableIRQ __NVIC_EnableIRQ - #define NVIC_GetEnableIRQ __NVIC_GetEnableIRQ - #define NVIC_DisableIRQ __NVIC_DisableIRQ - #define NVIC_GetPendingIRQ __NVIC_GetPendingIRQ - #define NVIC_SetPendingIRQ __NVIC_SetPendingIRQ - #define NVIC_ClearPendingIRQ __NVIC_ClearPendingIRQ - #define NVIC_GetActive __NVIC_GetActive - #define NVIC_SetPriority __NVIC_SetPriority - #define NVIC_GetPriority __NVIC_GetPriority - #define NVIC_SystemReset __NVIC_SystemReset -#endif /* CMSIS_NVIC_VIRTUAL */ - -#ifdef CMSIS_VECTAB_VIRTUAL - #ifndef CMSIS_VECTAB_VIRTUAL_HEADER_FILE - #define CMSIS_VECTAB_VIRTUAL_HEADER_FILE "cmsis_vectab_virtual.h" - #endif - #include CMSIS_VECTAB_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetVector __NVIC_SetVector - #define NVIC_GetVector __NVIC_GetVector -#endif /* (CMSIS_VECTAB_VIRTUAL) */ - -#define NVIC_USER_IRQ_OFFSET 16 - - -/* The following EXC_RETURN values are saved the LR on exception entry */ -#define EXC_RETURN_HANDLER (0xFFFFFFF1UL) /* return to Handler mode, uses MSP after return */ -#define EXC_RETURN_THREAD_MSP (0xFFFFFFF9UL) /* return to Thread mode, uses MSP after return */ -#define EXC_RETURN_THREAD_PSP (0xFFFFFFFDUL) /* return to Thread mode, uses PSP after return */ - - -/** - \brief Set Priority Grouping - \details Sets the priority grouping field using the required unlock sequence. - The parameter PriorityGroup is assigned to the field SCB->AIRCR [10:8] PRIGROUP field. - Only values from 0..7 are used. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. - \param [in] PriorityGroup Priority grouping field. - */ -__STATIC_INLINE void __NVIC_SetPriorityGrouping(uint32_t PriorityGroup) -{ - uint32_t reg_value; - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - - reg_value = SCB->AIRCR; /* read old register configuration */ - reg_value &= ~((uint32_t)(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk)); /* clear bits to change */ - reg_value = (reg_value | - ((uint32_t)0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - (PriorityGroupTmp << SCB_AIRCR_PRIGROUP_Pos) ); /* Insert write key and priority group */ - SCB->AIRCR = reg_value; -} - - -/** - \brief Get Priority Grouping - \details Reads the priority grouping field from the NVIC Interrupt Controller. - \return Priority grouping field (SCB->AIRCR [10:8] PRIGROUP field). - */ -__STATIC_INLINE uint32_t __NVIC_GetPriorityGrouping(void) -{ - return ((uint32_t)((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos)); -} - - -/** - \brief Enable Interrupt - \details Enables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_EnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - __COMPILER_BARRIER(); - NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - __COMPILER_BARRIER(); - } -} - - -/** - \brief Get Interrupt Enable status - \details Returns a device specific interrupt enable status from the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt is not enabled. - \return 1 Interrupt is enabled. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetEnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Disable Interrupt - \details Disables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_DisableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - __DSB(); - __ISB(); - } -} - - -/** - \brief Get Pending Interrupt - \details Reads the NVIC pending register and returns the pending bit for the specified device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not pending. - \return 1 Interrupt status is pending. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Pending Interrupt - \details Sets the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_SetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Clear Pending Interrupt - \details Clears the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_ClearPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Active Interrupt - \details Reads the active register in the NVIC and returns the active bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not active. - \return 1 Interrupt status is active. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetActive(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Interrupt Priority - \details Sets the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \param [in] priority Priority to set. - \note The priority cannot be set for every processor exception. - */ -__STATIC_INLINE void __NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->IP[((uint32_t)IRQn)] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); - } - else - { - SCB->SHP[(((uint32_t)IRQn) & 0xFUL)-4UL] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); - } -} - - -/** - \brief Get Interrupt Priority - \details Reads the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Interrupt Priority. - Value is aligned automatically to the implemented priority bits of the microcontroller. - */ -__STATIC_INLINE uint32_t __NVIC_GetPriority(IRQn_Type IRQn) -{ - - if ((int32_t)(IRQn) >= 0) - { - return(((uint32_t)NVIC->IP[((uint32_t)IRQn)] >> (8U - __NVIC_PRIO_BITS))); - } - else - { - return(((uint32_t)SCB->SHP[(((uint32_t)IRQn) & 0xFUL)-4UL] >> (8U - __NVIC_PRIO_BITS))); - } -} - - -/** - \brief Encode Priority - \details Encodes the priority for an interrupt with the given priority group, - preemptive priority value, and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. - \param [in] PriorityGroup Used priority group. - \param [in] PreemptPriority Preemptive priority value (starting from 0). - \param [in] SubPriority Subpriority value (starting from 0). - \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority(). - */ -__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - return ( - ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | - ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) - ); -} - - -/** - \brief Decode Priority - \details Decodes an interrupt priority value with a given priority group to - preemptive priority value and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set. - \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority(). - \param [in] PriorityGroup Used priority group. - \param [out] pPreemptPriority Preemptive priority value (starting from 0). - \param [out] pSubPriority Subpriority value (starting from 0). - */ -__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* const pPreemptPriority, uint32_t* const pSubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - *pPreemptPriority = (Priority >> SubPriorityBits) & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL); - *pSubPriority = (Priority ) & (uint32_t)((1UL << (SubPriorityBits )) - 1UL); -} - - -/** - \brief Set Interrupt Vector - \details Sets an interrupt vector in SRAM based interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - VTOR must been relocated to SRAM before. - \param [in] IRQn Interrupt number - \param [in] vector Address of interrupt handler function - */ -__STATIC_INLINE void __NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) -{ - uint32_t vectors = (uint32_t )SCB->VTOR; - (* (int *) (vectors + ((int32_t)IRQn + NVIC_USER_IRQ_OFFSET) * 4)) = vector; - /* ARM Application Note 321 states that the M3 does not require the architectural barrier */ -} - - -/** - \brief Get Interrupt Vector - \details Reads an interrupt vector from interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Address of interrupt handler function - */ -__STATIC_INLINE uint32_t __NVIC_GetVector(IRQn_Type IRQn) -{ - uint32_t vectors = (uint32_t )SCB->VTOR; - return (uint32_t)(* (int *) (vectors + ((int32_t)IRQn + NVIC_USER_IRQ_OFFSET) * 4)); -} - - -/** - \brief System Reset - \details Initiates a system reset request to reset the MCU. - */ -__NO_RETURN __STATIC_INLINE void __NVIC_SystemReset(void) -{ - __DSB(); /* Ensure all outstanding memory accesses included - buffered write are completed before reset */ - SCB->AIRCR = (uint32_t)((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) | - SCB_AIRCR_SYSRESETREQ_Msk ); /* Keep priority group unchanged */ - __DSB(); /* Ensure completion of memory access */ - - for(;;) /* wait until reset */ - { - __NOP(); - } -} - -/*@} end of CMSIS_Core_NVICFunctions */ - -/* ########################## MPU functions #################################### */ - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - -#include "mpu_armv7.h" - -#endif - - -/* ########################## FPU functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_FpuFunctions FPU Functions - \brief Function that provides FPU type. - @{ - */ - -/** - \brief get FPU type - \details returns the FPU type - \returns - - \b 0: No FPU - - \b 1: Single precision FPU - - \b 2: Double + Single precision FPU - */ -__STATIC_INLINE uint32_t SCB_GetFPUType(void) -{ - return 0U; /* No FPU */ -} - - -/*@} end of CMSIS_Core_FpuFunctions */ - - - -/* ################################## SysTick function ############################################ */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_SysTickFunctions SysTick Functions - \brief Functions that configure the System. - @{ - */ - -#if defined (__Vendor_SysTickConfig) && (__Vendor_SysTickConfig == 0U) - -/** - \brief System Tick Configuration - \details Initializes the System Timer and its interrupt, and starts the System Tick Timer. - Counter is in free running mode to generate periodic interrupts. - \param [in] ticks Number of ticks between two interrupts. - \return 0 Function succeeded. - \return 1 Function failed. - \note When the variable __Vendor_SysTickConfig is set to 1, then the - function SysTick_Config is not included. In this case, the file device.h - must contain a vendor-specific implementation of this function. - */ -__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) -{ - if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) - { - return (1UL); /* Reload value impossible */ - } - - SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ - NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ - SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ - SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | - SysTick_CTRL_TICKINT_Msk | - SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ - return (0UL); /* Function successful */ -} - -#endif - -/*@} end of CMSIS_Core_SysTickFunctions */ - - - -/* ##################################### Debug In/Output function ########################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_core_DebugFunctions ITM Functions - \brief Functions that access the ITM debug interface. - @{ - */ - -extern volatile int32_t ITM_RxBuffer; /*!< External variable to receive characters. */ -#define ITM_RXBUFFER_EMPTY ((int32_t)0x5AA55AA5U) /*!< Value identifying \ref ITM_RxBuffer is ready for next character. */ - - -/** - \brief ITM Send Character - \details Transmits a character via the ITM channel 0, and - \li Just returns when no debugger is connected that has booked the output. - \li Is blocking when a debugger is connected, but the previous character sent has not been transmitted. - \param [in] ch Character to transmit. - \returns Character to transmit. - */ -__STATIC_INLINE uint32_t ITM_SendChar (uint32_t ch) -{ - if (((ITM->TCR & ITM_TCR_ITMENA_Msk) != 0UL) && /* ITM enabled */ - ((ITM->TER & 1UL ) != 0UL) ) /* ITM Port #0 enabled */ - { - while (ITM->PORT[0U].u32 == 0UL) - { - __NOP(); - } - ITM->PORT[0U].u8 = (uint8_t)ch; - } - return (ch); -} - - -/** - \brief ITM Receive Character - \details Inputs a character via the external variable \ref ITM_RxBuffer. - \return Received character. - \return -1 No character pending. - */ -__STATIC_INLINE int32_t ITM_ReceiveChar (void) -{ - int32_t ch = -1; /* no character available */ - - if (ITM_RxBuffer != ITM_RXBUFFER_EMPTY) - { - ch = ITM_RxBuffer; - ITM_RxBuffer = ITM_RXBUFFER_EMPTY; /* ready for next character */ - } - - return (ch); -} - - -/** - \brief ITM Check Character - \details Checks whether a character is pending for reading in the variable \ref ITM_RxBuffer. - \return 0 No character available. - \return 1 Character available. - */ -__STATIC_INLINE int32_t ITM_CheckChar (void) -{ - - if (ITM_RxBuffer == ITM_RXBUFFER_EMPTY) - { - return (0); /* no character available */ - } - else - { - return (1); /* character available */ - } -} - -/*@} end of CMSIS_core_DebugFunctions */ - - - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_CM3_H_DEPENDANT */ - -#endif /* __CMSIS_GENERIC */ - diff --git a/panda/board/stm32fx/inc/core_cm4.h b/panda/board/stm32fx/inc/core_cm4.h deleted file mode 100644 index 0d40081a3..000000000 --- a/panda/board/stm32fx/inc/core_cm4.h +++ /dev/null @@ -1,2125 +0,0 @@ -/**************************************************************************//** - * @file core_cm4.h - * @brief CMSIS Cortex-M4 Core Peripheral Access Layer Header File - * @version V5.1.0 - * @date 13. March 2019 - ******************************************************************************/ -/* - * Copyright (c) 2009-2019 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed under the Apache License, Version 2.0 (the License); you may - * not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an AS IS BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined (__clang__) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef __CORE_CM4_H_GENERIC -#define __CORE_CM4_H_GENERIC - -#include - -#ifdef __cplusplus - extern "C" { -#endif - -/** - \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions - CMSIS violates the following MISRA-C:2004 rules: - - \li Required Rule 8.5, object/function definition in header file.
- Function definitions in header files are used to allow 'inlining'. - - \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
- Unions are used for effective representation of core registers. - - \li Advisory Rule 19.7, Function-like macro defined.
- Function-like macros are used to allow more efficient code. - */ - - -/******************************************************************************* - * CMSIS definitions - ******************************************************************************/ -/** - \ingroup Cortex_M4 - @{ - */ - -#include "cmsis_version.h" - -/* CMSIS CM4 definitions */ -#define __CM4_CMSIS_VERSION_MAIN (__CM_CMSIS_VERSION_MAIN) /*!< \deprecated [31:16] CMSIS HAL main version */ -#define __CM4_CMSIS_VERSION_SUB (__CM_CMSIS_VERSION_SUB) /*!< \deprecated [15:0] CMSIS HAL sub version */ -#define __CM4_CMSIS_VERSION ((__CM4_CMSIS_VERSION_MAIN << 16U) | \ - __CM4_CMSIS_VERSION_SUB ) /*!< \deprecated CMSIS HAL version number */ - -#define __CORTEX_M (4U) /*!< Cortex-M Core */ - -/** __FPU_USED indicates whether an FPU is used or not. - For this, __FPU_PRESENT has to be checked prior to making use of FPU specific registers and functions. -*/ -#if defined ( __CC_ARM ) - #if defined __TARGET_FPU_VFP - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) - #if defined __ARM_FP - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __GNUC__ ) - #if defined (__VFP_FP__) && !defined(__SOFTFP__) - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __ICCARM__ ) - #if defined __ARMVFP__ - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __TI_ARM__ ) - #if defined __TI_VFP_SUPPORT__ - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __TASKING__ ) - #if defined __FPU_VFP__ - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __CSMC__ ) - #if ( __CSMC__ & 0x400U) - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#endif - -#include "cmsis_compiler.h" /* CMSIS compiler specific defines */ - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_CM4_H_GENERIC */ - -#ifndef __CMSIS_GENERIC - -#ifndef __CORE_CM4_H_DEPENDANT -#define __CORE_CM4_H_DEPENDANT - -#ifdef __cplusplus - extern "C" { -#endif - -/* check device defines and use defaults */ -#if defined __CHECK_DEVICE_DEFINES - #ifndef __CM4_REV - #define __CM4_REV 0x0000U - #warning "__CM4_REV not defined in device header file; using default!" - #endif - - #ifndef __FPU_PRESENT - #define __FPU_PRESENT 0U - #warning "__FPU_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __MPU_PRESENT - #define __MPU_PRESENT 0U - #warning "__MPU_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __NVIC_PRIO_BITS - #define __NVIC_PRIO_BITS 3U - #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" - #endif - - #ifndef __Vendor_SysTickConfig - #define __Vendor_SysTickConfig 0U - #warning "__Vendor_SysTickConfig not defined in device header file; using default!" - #endif -#endif - -/* IO definitions (access restrictions to peripheral registers) */ -/** - \defgroup CMSIS_glob_defs CMSIS Global Defines - - IO Type Qualifiers are used - \li to specify the access to peripheral variables. - \li for automatic generation of peripheral register debug information. -*/ -#ifdef __cplusplus - #define __I volatile /*!< Defines 'read only' permissions */ -#else - #define __I volatile const /*!< Defines 'read only' permissions */ -#endif -#define __O volatile /*!< Defines 'write only' permissions */ -#define __IO volatile /*!< Defines 'read / write' permissions */ - -/* following defines should be used for structure members */ -#define __IM volatile const /*! Defines 'read only' structure member permissions */ -#define __OM volatile /*! Defines 'write only' structure member permissions */ -#define __IOM volatile /*! Defines 'read / write' structure member permissions */ - -/*@} end of group Cortex_M4 */ - - - -/******************************************************************************* - * Register Abstraction - Core Register contain: - - Core Register - - Core NVIC Register - - Core SCB Register - - Core SysTick Register - - Core Debug Register - - Core MPU Register - - Core FPU Register - ******************************************************************************/ -/** - \defgroup CMSIS_core_register Defines and Type Definitions - \brief Type definitions and defines for Cortex-M processor based devices. -*/ - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CORE Status and Control Registers - \brief Core Register type definitions. - @{ - */ - -/** - \brief Union type to access the Application Program Status Register (APSR). - */ -typedef union -{ - struct - { - uint32_t _reserved0:16; /*!< bit: 0..15 Reserved */ - uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ - uint32_t _reserved1:7; /*!< bit: 20..26 Reserved */ - uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} APSR_Type; - -/* APSR Register Definitions */ -#define APSR_N_Pos 31U /*!< APSR: N Position */ -#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ - -#define APSR_Z_Pos 30U /*!< APSR: Z Position */ -#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ - -#define APSR_C_Pos 29U /*!< APSR: C Position */ -#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ - -#define APSR_V_Pos 28U /*!< APSR: V Position */ -#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ - -#define APSR_Q_Pos 27U /*!< APSR: Q Position */ -#define APSR_Q_Msk (1UL << APSR_Q_Pos) /*!< APSR: Q Mask */ - -#define APSR_GE_Pos 16U /*!< APSR: GE Position */ -#define APSR_GE_Msk (0xFUL << APSR_GE_Pos) /*!< APSR: GE Mask */ - - -/** - \brief Union type to access the Interrupt Program Status Register (IPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} IPSR_Type; - -/* IPSR Register Definitions */ -#define IPSR_ISR_Pos 0U /*!< IPSR: ISR Position */ -#define IPSR_ISR_Msk (0x1FFUL /*<< IPSR_ISR_Pos*/) /*!< IPSR: ISR Mask */ - - -/** - \brief Union type to access the Special-Purpose Program Status Registers (xPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:1; /*!< bit: 9 Reserved */ - uint32_t ICI_IT_1:6; /*!< bit: 10..15 ICI/IT part 1 */ - uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ - uint32_t _reserved1:4; /*!< bit: 20..23 Reserved */ - uint32_t T:1; /*!< bit: 24 Thumb bit */ - uint32_t ICI_IT_2:2; /*!< bit: 25..26 ICI/IT part 2 */ - uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} xPSR_Type; - -/* xPSR Register Definitions */ -#define xPSR_N_Pos 31U /*!< xPSR: N Position */ -#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ - -#define xPSR_Z_Pos 30U /*!< xPSR: Z Position */ -#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ - -#define xPSR_C_Pos 29U /*!< xPSR: C Position */ -#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ - -#define xPSR_V_Pos 28U /*!< xPSR: V Position */ -#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ - -#define xPSR_Q_Pos 27U /*!< xPSR: Q Position */ -#define xPSR_Q_Msk (1UL << xPSR_Q_Pos) /*!< xPSR: Q Mask */ - -#define xPSR_ICI_IT_2_Pos 25U /*!< xPSR: ICI/IT part 2 Position */ -#define xPSR_ICI_IT_2_Msk (3UL << xPSR_ICI_IT_2_Pos) /*!< xPSR: ICI/IT part 2 Mask */ - -#define xPSR_T_Pos 24U /*!< xPSR: T Position */ -#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ - -#define xPSR_GE_Pos 16U /*!< xPSR: GE Position */ -#define xPSR_GE_Msk (0xFUL << xPSR_GE_Pos) /*!< xPSR: GE Mask */ - -#define xPSR_ICI_IT_1_Pos 10U /*!< xPSR: ICI/IT part 1 Position */ -#define xPSR_ICI_IT_1_Msk (0x3FUL << xPSR_ICI_IT_1_Pos) /*!< xPSR: ICI/IT part 1 Mask */ - -#define xPSR_ISR_Pos 0U /*!< xPSR: ISR Position */ -#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ - - -/** - \brief Union type to access the Control Registers (CONTROL). - */ -typedef union -{ - struct - { - uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */ - uint32_t SPSEL:1; /*!< bit: 1 Stack to be used */ - uint32_t FPCA:1; /*!< bit: 2 FP extension active flag */ - uint32_t _reserved0:29; /*!< bit: 3..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} CONTROL_Type; - -/* CONTROL Register Definitions */ -#define CONTROL_FPCA_Pos 2U /*!< CONTROL: FPCA Position */ -#define CONTROL_FPCA_Msk (1UL << CONTROL_FPCA_Pos) /*!< CONTROL: FPCA Mask */ - -#define CONTROL_SPSEL_Pos 1U /*!< CONTROL: SPSEL Position */ -#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ - -#define CONTROL_nPRIV_Pos 0U /*!< CONTROL: nPRIV Position */ -#define CONTROL_nPRIV_Msk (1UL /*<< CONTROL_nPRIV_Pos*/) /*!< CONTROL: nPRIV Mask */ - -/*@} end of group CMSIS_CORE */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC) - \brief Type definitions for the NVIC Registers - @{ - */ - -/** - \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). - */ -typedef struct -{ - __IOM uint32_t ISER[8U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ - uint32_t RESERVED0[24U]; - __IOM uint32_t ICER[8U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ - uint32_t RESERVED1[24U]; - __IOM uint32_t ISPR[8U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ - uint32_t RESERVED2[24U]; - __IOM uint32_t ICPR[8U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ - uint32_t RESERVED3[24U]; - __IOM uint32_t IABR[8U]; /*!< Offset: 0x200 (R/W) Interrupt Active bit Register */ - uint32_t RESERVED4[56U]; - __IOM uint8_t IP[240U]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register (8Bit wide) */ - uint32_t RESERVED5[644U]; - __OM uint32_t STIR; /*!< Offset: 0xE00 ( /W) Software Trigger Interrupt Register */ -} NVIC_Type; - -/* Software Triggered Interrupt Register Definitions */ -#define NVIC_STIR_INTID_Pos 0U /*!< STIR: INTLINESNUM Position */ -#define NVIC_STIR_INTID_Msk (0x1FFUL /*<< NVIC_STIR_INTID_Pos*/) /*!< STIR: INTLINESNUM Mask */ - -/*@} end of group CMSIS_NVIC */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SCB System Control Block (SCB) - \brief Type definitions for the System Control Block Registers - @{ - */ - -/** - \brief Structure type to access the System Control Block (SCB). - */ -typedef struct -{ - __IM uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ - __IOM uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ - __IOM uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ - __IOM uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ - __IOM uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ - __IOM uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ - __IOM uint8_t SHP[12U]; /*!< Offset: 0x018 (R/W) System Handlers Priority Registers (4-7, 8-11, 12-15) */ - __IOM uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ - __IOM uint32_t CFSR; /*!< Offset: 0x028 (R/W) Configurable Fault Status Register */ - __IOM uint32_t HFSR; /*!< Offset: 0x02C (R/W) HardFault Status Register */ - __IOM uint32_t DFSR; /*!< Offset: 0x030 (R/W) Debug Fault Status Register */ - __IOM uint32_t MMFAR; /*!< Offset: 0x034 (R/W) MemManage Fault Address Register */ - __IOM uint32_t BFAR; /*!< Offset: 0x038 (R/W) BusFault Address Register */ - __IOM uint32_t AFSR; /*!< Offset: 0x03C (R/W) Auxiliary Fault Status Register */ - __IM uint32_t PFR[2U]; /*!< Offset: 0x040 (R/ ) Processor Feature Register */ - __IM uint32_t DFR; /*!< Offset: 0x048 (R/ ) Debug Feature Register */ - __IM uint32_t ADR; /*!< Offset: 0x04C (R/ ) Auxiliary Feature Register */ - __IM uint32_t MMFR[4U]; /*!< Offset: 0x050 (R/ ) Memory Model Feature Register */ - __IM uint32_t ISAR[5U]; /*!< Offset: 0x060 (R/ ) Instruction Set Attributes Register */ - uint32_t RESERVED0[5U]; - __IOM uint32_t CPACR; /*!< Offset: 0x088 (R/W) Coprocessor Access Control Register */ -} SCB_Type; - -/* SCB CPUID Register Definitions */ -#define SCB_CPUID_IMPLEMENTER_Pos 24U /*!< SCB CPUID: IMPLEMENTER Position */ -#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ - -#define SCB_CPUID_VARIANT_Pos 20U /*!< SCB CPUID: VARIANT Position */ -#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ - -#define SCB_CPUID_ARCHITECTURE_Pos 16U /*!< SCB CPUID: ARCHITECTURE Position */ -#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ - -#define SCB_CPUID_PARTNO_Pos 4U /*!< SCB CPUID: PARTNO Position */ -#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ - -#define SCB_CPUID_REVISION_Pos 0U /*!< SCB CPUID: REVISION Position */ -#define SCB_CPUID_REVISION_Msk (0xFUL /*<< SCB_CPUID_REVISION_Pos*/) /*!< SCB CPUID: REVISION Mask */ - -/* SCB Interrupt Control State Register Definitions */ -#define SCB_ICSR_NMIPENDSET_Pos 31U /*!< SCB ICSR: NMIPENDSET Position */ -#define SCB_ICSR_NMIPENDSET_Msk (1UL << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */ - -#define SCB_ICSR_PENDSVSET_Pos 28U /*!< SCB ICSR: PENDSVSET Position */ -#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ - -#define SCB_ICSR_PENDSVCLR_Pos 27U /*!< SCB ICSR: PENDSVCLR Position */ -#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ - -#define SCB_ICSR_PENDSTSET_Pos 26U /*!< SCB ICSR: PENDSTSET Position */ -#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ - -#define SCB_ICSR_PENDSTCLR_Pos 25U /*!< SCB ICSR: PENDSTCLR Position */ -#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ - -#define SCB_ICSR_ISRPREEMPT_Pos 23U /*!< SCB ICSR: ISRPREEMPT Position */ -#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ - -#define SCB_ICSR_ISRPENDING_Pos 22U /*!< SCB ICSR: ISRPENDING Position */ -#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ - -#define SCB_ICSR_VECTPENDING_Pos 12U /*!< SCB ICSR: VECTPENDING Position */ -#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ - -#define SCB_ICSR_RETTOBASE_Pos 11U /*!< SCB ICSR: RETTOBASE Position */ -#define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */ - -#define SCB_ICSR_VECTACTIVE_Pos 0U /*!< SCB ICSR: VECTACTIVE Position */ -#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */ - -/* SCB Vector Table Offset Register Definitions */ -#define SCB_VTOR_TBLOFF_Pos 7U /*!< SCB VTOR: TBLOFF Position */ -#define SCB_VTOR_TBLOFF_Msk (0x1FFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ - -/* SCB Application Interrupt and Reset Control Register Definitions */ -#define SCB_AIRCR_VECTKEY_Pos 16U /*!< SCB AIRCR: VECTKEY Position */ -#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ - -#define SCB_AIRCR_VECTKEYSTAT_Pos 16U /*!< SCB AIRCR: VECTKEYSTAT Position */ -#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ - -#define SCB_AIRCR_ENDIANESS_Pos 15U /*!< SCB AIRCR: ENDIANESS Position */ -#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ - -#define SCB_AIRCR_PRIGROUP_Pos 8U /*!< SCB AIRCR: PRIGROUP Position */ -#define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */ - -#define SCB_AIRCR_SYSRESETREQ_Pos 2U /*!< SCB AIRCR: SYSRESETREQ Position */ -#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ - -#define SCB_AIRCR_VECTCLRACTIVE_Pos 1U /*!< SCB AIRCR: VECTCLRACTIVE Position */ -#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ - -#define SCB_AIRCR_VECTRESET_Pos 0U /*!< SCB AIRCR: VECTRESET Position */ -#define SCB_AIRCR_VECTRESET_Msk (1UL /*<< SCB_AIRCR_VECTRESET_Pos*/) /*!< SCB AIRCR: VECTRESET Mask */ - -/* SCB System Control Register Definitions */ -#define SCB_SCR_SEVONPEND_Pos 4U /*!< SCB SCR: SEVONPEND Position */ -#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ - -#define SCB_SCR_SLEEPDEEP_Pos 2U /*!< SCB SCR: SLEEPDEEP Position */ -#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ - -#define SCB_SCR_SLEEPONEXIT_Pos 1U /*!< SCB SCR: SLEEPONEXIT Position */ -#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ - -/* SCB Configuration Control Register Definitions */ -#define SCB_CCR_STKALIGN_Pos 9U /*!< SCB CCR: STKALIGN Position */ -#define SCB_CCR_STKALIGN_Msk (1UL << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */ - -#define SCB_CCR_BFHFNMIGN_Pos 8U /*!< SCB CCR: BFHFNMIGN Position */ -#define SCB_CCR_BFHFNMIGN_Msk (1UL << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */ - -#define SCB_CCR_DIV_0_TRP_Pos 4U /*!< SCB CCR: DIV_0_TRP Position */ -#define SCB_CCR_DIV_0_TRP_Msk (1UL << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP Mask */ - -#define SCB_CCR_UNALIGN_TRP_Pos 3U /*!< SCB CCR: UNALIGN_TRP Position */ -#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ - -#define SCB_CCR_USERSETMPEND_Pos 1U /*!< SCB CCR: USERSETMPEND Position */ -#define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */ - -#define SCB_CCR_NONBASETHRDENA_Pos 0U /*!< SCB CCR: NONBASETHRDENA Position */ -#define SCB_CCR_NONBASETHRDENA_Msk (1UL /*<< SCB_CCR_NONBASETHRDENA_Pos*/) /*!< SCB CCR: NONBASETHRDENA Mask */ - -/* SCB System Handler Control and State Register Definitions */ -#define SCB_SHCSR_USGFAULTENA_Pos 18U /*!< SCB SHCSR: USGFAULTENA Position */ -#define SCB_SHCSR_USGFAULTENA_Msk (1UL << SCB_SHCSR_USGFAULTENA_Pos) /*!< SCB SHCSR: USGFAULTENA Mask */ - -#define SCB_SHCSR_BUSFAULTENA_Pos 17U /*!< SCB SHCSR: BUSFAULTENA Position */ -#define SCB_SHCSR_BUSFAULTENA_Msk (1UL << SCB_SHCSR_BUSFAULTENA_Pos) /*!< SCB SHCSR: BUSFAULTENA Mask */ - -#define SCB_SHCSR_MEMFAULTENA_Pos 16U /*!< SCB SHCSR: MEMFAULTENA Position */ -#define SCB_SHCSR_MEMFAULTENA_Msk (1UL << SCB_SHCSR_MEMFAULTENA_Pos) /*!< SCB SHCSR: MEMFAULTENA Mask */ - -#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */ -#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ - -#define SCB_SHCSR_BUSFAULTPENDED_Pos 14U /*!< SCB SHCSR: BUSFAULTPENDED Position */ -#define SCB_SHCSR_BUSFAULTPENDED_Msk (1UL << SCB_SHCSR_BUSFAULTPENDED_Pos) /*!< SCB SHCSR: BUSFAULTPENDED Mask */ - -#define SCB_SHCSR_MEMFAULTPENDED_Pos 13U /*!< SCB SHCSR: MEMFAULTPENDED Position */ -#define SCB_SHCSR_MEMFAULTPENDED_Msk (1UL << SCB_SHCSR_MEMFAULTPENDED_Pos) /*!< SCB SHCSR: MEMFAULTPENDED Mask */ - -#define SCB_SHCSR_USGFAULTPENDED_Pos 12U /*!< SCB SHCSR: USGFAULTPENDED Position */ -#define SCB_SHCSR_USGFAULTPENDED_Msk (1UL << SCB_SHCSR_USGFAULTPENDED_Pos) /*!< SCB SHCSR: USGFAULTPENDED Mask */ - -#define SCB_SHCSR_SYSTICKACT_Pos 11U /*!< SCB SHCSR: SYSTICKACT Position */ -#define SCB_SHCSR_SYSTICKACT_Msk (1UL << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */ - -#define SCB_SHCSR_PENDSVACT_Pos 10U /*!< SCB SHCSR: PENDSVACT Position */ -#define SCB_SHCSR_PENDSVACT_Msk (1UL << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */ - -#define SCB_SHCSR_MONITORACT_Pos 8U /*!< SCB SHCSR: MONITORACT Position */ -#define SCB_SHCSR_MONITORACT_Msk (1UL << SCB_SHCSR_MONITORACT_Pos) /*!< SCB SHCSR: MONITORACT Mask */ - -#define SCB_SHCSR_SVCALLACT_Pos 7U /*!< SCB SHCSR: SVCALLACT Position */ -#define SCB_SHCSR_SVCALLACT_Msk (1UL << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */ - -#define SCB_SHCSR_USGFAULTACT_Pos 3U /*!< SCB SHCSR: USGFAULTACT Position */ -#define SCB_SHCSR_USGFAULTACT_Msk (1UL << SCB_SHCSR_USGFAULTACT_Pos) /*!< SCB SHCSR: USGFAULTACT Mask */ - -#define SCB_SHCSR_BUSFAULTACT_Pos 1U /*!< SCB SHCSR: BUSFAULTACT Position */ -#define SCB_SHCSR_BUSFAULTACT_Msk (1UL << SCB_SHCSR_BUSFAULTACT_Pos) /*!< SCB SHCSR: BUSFAULTACT Mask */ - -#define SCB_SHCSR_MEMFAULTACT_Pos 0U /*!< SCB SHCSR: MEMFAULTACT Position */ -#define SCB_SHCSR_MEMFAULTACT_Msk (1UL /*<< SCB_SHCSR_MEMFAULTACT_Pos*/) /*!< SCB SHCSR: MEMFAULTACT Mask */ - -/* SCB Configurable Fault Status Register Definitions */ -#define SCB_CFSR_USGFAULTSR_Pos 16U /*!< SCB CFSR: Usage Fault Status Register Position */ -#define SCB_CFSR_USGFAULTSR_Msk (0xFFFFUL << SCB_CFSR_USGFAULTSR_Pos) /*!< SCB CFSR: Usage Fault Status Register Mask */ - -#define SCB_CFSR_BUSFAULTSR_Pos 8U /*!< SCB CFSR: Bus Fault Status Register Position */ -#define SCB_CFSR_BUSFAULTSR_Msk (0xFFUL << SCB_CFSR_BUSFAULTSR_Pos) /*!< SCB CFSR: Bus Fault Status Register Mask */ - -#define SCB_CFSR_MEMFAULTSR_Pos 0U /*!< SCB CFSR: Memory Manage Fault Status Register Position */ -#define SCB_CFSR_MEMFAULTSR_Msk (0xFFUL /*<< SCB_CFSR_MEMFAULTSR_Pos*/) /*!< SCB CFSR: Memory Manage Fault Status Register Mask */ - -/* MemManage Fault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_MMARVALID_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 7U) /*!< SCB CFSR (MMFSR): MMARVALID Position */ -#define SCB_CFSR_MMARVALID_Msk (1UL << SCB_CFSR_MMARVALID_Pos) /*!< SCB CFSR (MMFSR): MMARVALID Mask */ - -#define SCB_CFSR_MLSPERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 5U) /*!< SCB CFSR (MMFSR): MLSPERR Position */ -#define SCB_CFSR_MLSPERR_Msk (1UL << SCB_CFSR_MLSPERR_Pos) /*!< SCB CFSR (MMFSR): MLSPERR Mask */ - -#define SCB_CFSR_MSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 4U) /*!< SCB CFSR (MMFSR): MSTKERR Position */ -#define SCB_CFSR_MSTKERR_Msk (1UL << SCB_CFSR_MSTKERR_Pos) /*!< SCB CFSR (MMFSR): MSTKERR Mask */ - -#define SCB_CFSR_MUNSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 3U) /*!< SCB CFSR (MMFSR): MUNSTKERR Position */ -#define SCB_CFSR_MUNSTKERR_Msk (1UL << SCB_CFSR_MUNSTKERR_Pos) /*!< SCB CFSR (MMFSR): MUNSTKERR Mask */ - -#define SCB_CFSR_DACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 1U) /*!< SCB CFSR (MMFSR): DACCVIOL Position */ -#define SCB_CFSR_DACCVIOL_Msk (1UL << SCB_CFSR_DACCVIOL_Pos) /*!< SCB CFSR (MMFSR): DACCVIOL Mask */ - -#define SCB_CFSR_IACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 0U) /*!< SCB CFSR (MMFSR): IACCVIOL Position */ -#define SCB_CFSR_IACCVIOL_Msk (1UL /*<< SCB_CFSR_IACCVIOL_Pos*/) /*!< SCB CFSR (MMFSR): IACCVIOL Mask */ - -/* BusFault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_BFARVALID_Pos (SCB_CFSR_BUSFAULTSR_Pos + 7U) /*!< SCB CFSR (BFSR): BFARVALID Position */ -#define SCB_CFSR_BFARVALID_Msk (1UL << SCB_CFSR_BFARVALID_Pos) /*!< SCB CFSR (BFSR): BFARVALID Mask */ - -#define SCB_CFSR_LSPERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 5U) /*!< SCB CFSR (BFSR): LSPERR Position */ -#define SCB_CFSR_LSPERR_Msk (1UL << SCB_CFSR_LSPERR_Pos) /*!< SCB CFSR (BFSR): LSPERR Mask */ - -#define SCB_CFSR_STKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 4U) /*!< SCB CFSR (BFSR): STKERR Position */ -#define SCB_CFSR_STKERR_Msk (1UL << SCB_CFSR_STKERR_Pos) /*!< SCB CFSR (BFSR): STKERR Mask */ - -#define SCB_CFSR_UNSTKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 3U) /*!< SCB CFSR (BFSR): UNSTKERR Position */ -#define SCB_CFSR_UNSTKERR_Msk (1UL << SCB_CFSR_UNSTKERR_Pos) /*!< SCB CFSR (BFSR): UNSTKERR Mask */ - -#define SCB_CFSR_IMPRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 2U) /*!< SCB CFSR (BFSR): IMPRECISERR Position */ -#define SCB_CFSR_IMPRECISERR_Msk (1UL << SCB_CFSR_IMPRECISERR_Pos) /*!< SCB CFSR (BFSR): IMPRECISERR Mask */ - -#define SCB_CFSR_PRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 1U) /*!< SCB CFSR (BFSR): PRECISERR Position */ -#define SCB_CFSR_PRECISERR_Msk (1UL << SCB_CFSR_PRECISERR_Pos) /*!< SCB CFSR (BFSR): PRECISERR Mask */ - -#define SCB_CFSR_IBUSERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 0U) /*!< SCB CFSR (BFSR): IBUSERR Position */ -#define SCB_CFSR_IBUSERR_Msk (1UL << SCB_CFSR_IBUSERR_Pos) /*!< SCB CFSR (BFSR): IBUSERR Mask */ - -/* UsageFault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_DIVBYZERO_Pos (SCB_CFSR_USGFAULTSR_Pos + 9U) /*!< SCB CFSR (UFSR): DIVBYZERO Position */ -#define SCB_CFSR_DIVBYZERO_Msk (1UL << SCB_CFSR_DIVBYZERO_Pos) /*!< SCB CFSR (UFSR): DIVBYZERO Mask */ - -#define SCB_CFSR_UNALIGNED_Pos (SCB_CFSR_USGFAULTSR_Pos + 8U) /*!< SCB CFSR (UFSR): UNALIGNED Position */ -#define SCB_CFSR_UNALIGNED_Msk (1UL << SCB_CFSR_UNALIGNED_Pos) /*!< SCB CFSR (UFSR): UNALIGNED Mask */ - -#define SCB_CFSR_NOCP_Pos (SCB_CFSR_USGFAULTSR_Pos + 3U) /*!< SCB CFSR (UFSR): NOCP Position */ -#define SCB_CFSR_NOCP_Msk (1UL << SCB_CFSR_NOCP_Pos) /*!< SCB CFSR (UFSR): NOCP Mask */ - -#define SCB_CFSR_INVPC_Pos (SCB_CFSR_USGFAULTSR_Pos + 2U) /*!< SCB CFSR (UFSR): INVPC Position */ -#define SCB_CFSR_INVPC_Msk (1UL << SCB_CFSR_INVPC_Pos) /*!< SCB CFSR (UFSR): INVPC Mask */ - -#define SCB_CFSR_INVSTATE_Pos (SCB_CFSR_USGFAULTSR_Pos + 1U) /*!< SCB CFSR (UFSR): INVSTATE Position */ -#define SCB_CFSR_INVSTATE_Msk (1UL << SCB_CFSR_INVSTATE_Pos) /*!< SCB CFSR (UFSR): INVSTATE Mask */ - -#define SCB_CFSR_UNDEFINSTR_Pos (SCB_CFSR_USGFAULTSR_Pos + 0U) /*!< SCB CFSR (UFSR): UNDEFINSTR Position */ -#define SCB_CFSR_UNDEFINSTR_Msk (1UL << SCB_CFSR_UNDEFINSTR_Pos) /*!< SCB CFSR (UFSR): UNDEFINSTR Mask */ - -/* SCB Hard Fault Status Register Definitions */ -#define SCB_HFSR_DEBUGEVT_Pos 31U /*!< SCB HFSR: DEBUGEVT Position */ -#define SCB_HFSR_DEBUGEVT_Msk (1UL << SCB_HFSR_DEBUGEVT_Pos) /*!< SCB HFSR: DEBUGEVT Mask */ - -#define SCB_HFSR_FORCED_Pos 30U /*!< SCB HFSR: FORCED Position */ -#define SCB_HFSR_FORCED_Msk (1UL << SCB_HFSR_FORCED_Pos) /*!< SCB HFSR: FORCED Mask */ - -#define SCB_HFSR_VECTTBL_Pos 1U /*!< SCB HFSR: VECTTBL Position */ -#define SCB_HFSR_VECTTBL_Msk (1UL << SCB_HFSR_VECTTBL_Pos) /*!< SCB HFSR: VECTTBL Mask */ - -/* SCB Debug Fault Status Register Definitions */ -#define SCB_DFSR_EXTERNAL_Pos 4U /*!< SCB DFSR: EXTERNAL Position */ -#define SCB_DFSR_EXTERNAL_Msk (1UL << SCB_DFSR_EXTERNAL_Pos) /*!< SCB DFSR: EXTERNAL Mask */ - -#define SCB_DFSR_VCATCH_Pos 3U /*!< SCB DFSR: VCATCH Position */ -#define SCB_DFSR_VCATCH_Msk (1UL << SCB_DFSR_VCATCH_Pos) /*!< SCB DFSR: VCATCH Mask */ - -#define SCB_DFSR_DWTTRAP_Pos 2U /*!< SCB DFSR: DWTTRAP Position */ -#define SCB_DFSR_DWTTRAP_Msk (1UL << SCB_DFSR_DWTTRAP_Pos) /*!< SCB DFSR: DWTTRAP Mask */ - -#define SCB_DFSR_BKPT_Pos 1U /*!< SCB DFSR: BKPT Position */ -#define SCB_DFSR_BKPT_Msk (1UL << SCB_DFSR_BKPT_Pos) /*!< SCB DFSR: BKPT Mask */ - -#define SCB_DFSR_HALTED_Pos 0U /*!< SCB DFSR: HALTED Position */ -#define SCB_DFSR_HALTED_Msk (1UL /*<< SCB_DFSR_HALTED_Pos*/) /*!< SCB DFSR: HALTED Mask */ - -/*@} end of group CMSIS_SCB */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SCnSCB System Controls not in SCB (SCnSCB) - \brief Type definitions for the System Control and ID Register not in the SCB - @{ - */ - -/** - \brief Structure type to access the System Control and ID Register not in the SCB. - */ -typedef struct -{ - uint32_t RESERVED0[1U]; - __IM uint32_t ICTR; /*!< Offset: 0x004 (R/ ) Interrupt Controller Type Register */ - __IOM uint32_t ACTLR; /*!< Offset: 0x008 (R/W) Auxiliary Control Register */ -} SCnSCB_Type; - -/* Interrupt Controller Type Register Definitions */ -#define SCnSCB_ICTR_INTLINESNUM_Pos 0U /*!< ICTR: INTLINESNUM Position */ -#define SCnSCB_ICTR_INTLINESNUM_Msk (0xFUL /*<< SCnSCB_ICTR_INTLINESNUM_Pos*/) /*!< ICTR: INTLINESNUM Mask */ - -/* Auxiliary Control Register Definitions */ -#define SCnSCB_ACTLR_DISOOFP_Pos 9U /*!< ACTLR: DISOOFP Position */ -#define SCnSCB_ACTLR_DISOOFP_Msk (1UL << SCnSCB_ACTLR_DISOOFP_Pos) /*!< ACTLR: DISOOFP Mask */ - -#define SCnSCB_ACTLR_DISFPCA_Pos 8U /*!< ACTLR: DISFPCA Position */ -#define SCnSCB_ACTLR_DISFPCA_Msk (1UL << SCnSCB_ACTLR_DISFPCA_Pos) /*!< ACTLR: DISFPCA Mask */ - -#define SCnSCB_ACTLR_DISFOLD_Pos 2U /*!< ACTLR: DISFOLD Position */ -#define SCnSCB_ACTLR_DISFOLD_Msk (1UL << SCnSCB_ACTLR_DISFOLD_Pos) /*!< ACTLR: DISFOLD Mask */ - -#define SCnSCB_ACTLR_DISDEFWBUF_Pos 1U /*!< ACTLR: DISDEFWBUF Position */ -#define SCnSCB_ACTLR_DISDEFWBUF_Msk (1UL << SCnSCB_ACTLR_DISDEFWBUF_Pos) /*!< ACTLR: DISDEFWBUF Mask */ - -#define SCnSCB_ACTLR_DISMCYCINT_Pos 0U /*!< ACTLR: DISMCYCINT Position */ -#define SCnSCB_ACTLR_DISMCYCINT_Msk (1UL /*<< SCnSCB_ACTLR_DISMCYCINT_Pos*/) /*!< ACTLR: DISMCYCINT Mask */ - -/*@} end of group CMSIS_SCnotSCB */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SysTick System Tick Timer (SysTick) - \brief Type definitions for the System Timer Registers. - @{ - */ - -/** - \brief Structure type to access the System Timer (SysTick). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ - __IOM uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ - __IOM uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ - __IM uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ -} SysTick_Type; - -/* SysTick Control / Status Register Definitions */ -#define SysTick_CTRL_COUNTFLAG_Pos 16U /*!< SysTick CTRL: COUNTFLAG Position */ -#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ - -#define SysTick_CTRL_CLKSOURCE_Pos 2U /*!< SysTick CTRL: CLKSOURCE Position */ -#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ - -#define SysTick_CTRL_TICKINT_Pos 1U /*!< SysTick CTRL: TICKINT Position */ -#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ - -#define SysTick_CTRL_ENABLE_Pos 0U /*!< SysTick CTRL: ENABLE Position */ -#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ - -/* SysTick Reload Register Definitions */ -#define SysTick_LOAD_RELOAD_Pos 0U /*!< SysTick LOAD: RELOAD Position */ -#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ - -/* SysTick Current Register Definitions */ -#define SysTick_VAL_CURRENT_Pos 0U /*!< SysTick VAL: CURRENT Position */ -#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ - -/* SysTick Calibration Register Definitions */ -#define SysTick_CALIB_NOREF_Pos 31U /*!< SysTick CALIB: NOREF Position */ -#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ - -#define SysTick_CALIB_SKEW_Pos 30U /*!< SysTick CALIB: SKEW Position */ -#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ - -#define SysTick_CALIB_TENMS_Pos 0U /*!< SysTick CALIB: TENMS Position */ -#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ - -/*@} end of group CMSIS_SysTick */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_ITM Instrumentation Trace Macrocell (ITM) - \brief Type definitions for the Instrumentation Trace Macrocell (ITM) - @{ - */ - -/** - \brief Structure type to access the Instrumentation Trace Macrocell Register (ITM). - */ -typedef struct -{ - __OM union - { - __OM uint8_t u8; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 8-bit */ - __OM uint16_t u16; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 16-bit */ - __OM uint32_t u32; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 32-bit */ - } PORT [32U]; /*!< Offset: 0x000 ( /W) ITM Stimulus Port Registers */ - uint32_t RESERVED0[864U]; - __IOM uint32_t TER; /*!< Offset: 0xE00 (R/W) ITM Trace Enable Register */ - uint32_t RESERVED1[15U]; - __IOM uint32_t TPR; /*!< Offset: 0xE40 (R/W) ITM Trace Privilege Register */ - uint32_t RESERVED2[15U]; - __IOM uint32_t TCR; /*!< Offset: 0xE80 (R/W) ITM Trace Control Register */ - uint32_t RESERVED3[32U]; - uint32_t RESERVED4[43U]; - __OM uint32_t LAR; /*!< Offset: 0xFB0 ( /W) ITM Lock Access Register */ - __IM uint32_t LSR; /*!< Offset: 0xFB4 (R/ ) ITM Lock Status Register */ - uint32_t RESERVED5[6U]; - __IM uint32_t PID4; /*!< Offset: 0xFD0 (R/ ) ITM Peripheral Identification Register #4 */ - __IM uint32_t PID5; /*!< Offset: 0xFD4 (R/ ) ITM Peripheral Identification Register #5 */ - __IM uint32_t PID6; /*!< Offset: 0xFD8 (R/ ) ITM Peripheral Identification Register #6 */ - __IM uint32_t PID7; /*!< Offset: 0xFDC (R/ ) ITM Peripheral Identification Register #7 */ - __IM uint32_t PID0; /*!< Offset: 0xFE0 (R/ ) ITM Peripheral Identification Register #0 */ - __IM uint32_t PID1; /*!< Offset: 0xFE4 (R/ ) ITM Peripheral Identification Register #1 */ - __IM uint32_t PID2; /*!< Offset: 0xFE8 (R/ ) ITM Peripheral Identification Register #2 */ - __IM uint32_t PID3; /*!< Offset: 0xFEC (R/ ) ITM Peripheral Identification Register #3 */ - __IM uint32_t CID0; /*!< Offset: 0xFF0 (R/ ) ITM Component Identification Register #0 */ - __IM uint32_t CID1; /*!< Offset: 0xFF4 (R/ ) ITM Component Identification Register #1 */ - __IM uint32_t CID2; /*!< Offset: 0xFF8 (R/ ) ITM Component Identification Register #2 */ - __IM uint32_t CID3; /*!< Offset: 0xFFC (R/ ) ITM Component Identification Register #3 */ -} ITM_Type; - -/* ITM Trace Privilege Register Definitions */ -#define ITM_TPR_PRIVMASK_Pos 0U /*!< ITM TPR: PRIVMASK Position */ -#define ITM_TPR_PRIVMASK_Msk (0xFFFFFFFFUL /*<< ITM_TPR_PRIVMASK_Pos*/) /*!< ITM TPR: PRIVMASK Mask */ - -/* ITM Trace Control Register Definitions */ -#define ITM_TCR_BUSY_Pos 23U /*!< ITM TCR: BUSY Position */ -#define ITM_TCR_BUSY_Msk (1UL << ITM_TCR_BUSY_Pos) /*!< ITM TCR: BUSY Mask */ - -#define ITM_TCR_TraceBusID_Pos 16U /*!< ITM TCR: ATBID Position */ -#define ITM_TCR_TraceBusID_Msk (0x7FUL << ITM_TCR_TraceBusID_Pos) /*!< ITM TCR: ATBID Mask */ - -#define ITM_TCR_GTSFREQ_Pos 10U /*!< ITM TCR: Global timestamp frequency Position */ -#define ITM_TCR_GTSFREQ_Msk (3UL << ITM_TCR_GTSFREQ_Pos) /*!< ITM TCR: Global timestamp frequency Mask */ - -#define ITM_TCR_TSPrescale_Pos 8U /*!< ITM TCR: TSPrescale Position */ -#define ITM_TCR_TSPrescale_Msk (3UL << ITM_TCR_TSPrescale_Pos) /*!< ITM TCR: TSPrescale Mask */ - -#define ITM_TCR_SWOENA_Pos 4U /*!< ITM TCR: SWOENA Position */ -#define ITM_TCR_SWOENA_Msk (1UL << ITM_TCR_SWOENA_Pos) /*!< ITM TCR: SWOENA Mask */ - -#define ITM_TCR_DWTENA_Pos 3U /*!< ITM TCR: DWTENA Position */ -#define ITM_TCR_DWTENA_Msk (1UL << ITM_TCR_DWTENA_Pos) /*!< ITM TCR: DWTENA Mask */ - -#define ITM_TCR_SYNCENA_Pos 2U /*!< ITM TCR: SYNCENA Position */ -#define ITM_TCR_SYNCENA_Msk (1UL << ITM_TCR_SYNCENA_Pos) /*!< ITM TCR: SYNCENA Mask */ - -#define ITM_TCR_TSENA_Pos 1U /*!< ITM TCR: TSENA Position */ -#define ITM_TCR_TSENA_Msk (1UL << ITM_TCR_TSENA_Pos) /*!< ITM TCR: TSENA Mask */ - -#define ITM_TCR_ITMENA_Pos 0U /*!< ITM TCR: ITM Enable bit Position */ -#define ITM_TCR_ITMENA_Msk (1UL /*<< ITM_TCR_ITMENA_Pos*/) /*!< ITM TCR: ITM Enable bit Mask */ - -/* ITM Lock Status Register Definitions */ -#define ITM_LSR_ByteAcc_Pos 2U /*!< ITM LSR: ByteAcc Position */ -#define ITM_LSR_ByteAcc_Msk (1UL << ITM_LSR_ByteAcc_Pos) /*!< ITM LSR: ByteAcc Mask */ - -#define ITM_LSR_Access_Pos 1U /*!< ITM LSR: Access Position */ -#define ITM_LSR_Access_Msk (1UL << ITM_LSR_Access_Pos) /*!< ITM LSR: Access Mask */ - -#define ITM_LSR_Present_Pos 0U /*!< ITM LSR: Present Position */ -#define ITM_LSR_Present_Msk (1UL /*<< ITM_LSR_Present_Pos*/) /*!< ITM LSR: Present Mask */ - -/*@}*/ /* end of group CMSIS_ITM */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_DWT Data Watchpoint and Trace (DWT) - \brief Type definitions for the Data Watchpoint and Trace (DWT) - @{ - */ - -/** - \brief Structure type to access the Data Watchpoint and Trace Register (DWT). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) Control Register */ - __IOM uint32_t CYCCNT; /*!< Offset: 0x004 (R/W) Cycle Count Register */ - __IOM uint32_t CPICNT; /*!< Offset: 0x008 (R/W) CPI Count Register */ - __IOM uint32_t EXCCNT; /*!< Offset: 0x00C (R/W) Exception Overhead Count Register */ - __IOM uint32_t SLEEPCNT; /*!< Offset: 0x010 (R/W) Sleep Count Register */ - __IOM uint32_t LSUCNT; /*!< Offset: 0x014 (R/W) LSU Count Register */ - __IOM uint32_t FOLDCNT; /*!< Offset: 0x018 (R/W) Folded-instruction Count Register */ - __IM uint32_t PCSR; /*!< Offset: 0x01C (R/ ) Program Counter Sample Register */ - __IOM uint32_t COMP0; /*!< Offset: 0x020 (R/W) Comparator Register 0 */ - __IOM uint32_t MASK0; /*!< Offset: 0x024 (R/W) Mask Register 0 */ - __IOM uint32_t FUNCTION0; /*!< Offset: 0x028 (R/W) Function Register 0 */ - uint32_t RESERVED0[1U]; - __IOM uint32_t COMP1; /*!< Offset: 0x030 (R/W) Comparator Register 1 */ - __IOM uint32_t MASK1; /*!< Offset: 0x034 (R/W) Mask Register 1 */ - __IOM uint32_t FUNCTION1; /*!< Offset: 0x038 (R/W) Function Register 1 */ - uint32_t RESERVED1[1U]; - __IOM uint32_t COMP2; /*!< Offset: 0x040 (R/W) Comparator Register 2 */ - __IOM uint32_t MASK2; /*!< Offset: 0x044 (R/W) Mask Register 2 */ - __IOM uint32_t FUNCTION2; /*!< Offset: 0x048 (R/W) Function Register 2 */ - uint32_t RESERVED2[1U]; - __IOM uint32_t COMP3; /*!< Offset: 0x050 (R/W) Comparator Register 3 */ - __IOM uint32_t MASK3; /*!< Offset: 0x054 (R/W) Mask Register 3 */ - __IOM uint32_t FUNCTION3; /*!< Offset: 0x058 (R/W) Function Register 3 */ -} DWT_Type; - -/* DWT Control Register Definitions */ -#define DWT_CTRL_NUMCOMP_Pos 28U /*!< DWT CTRL: NUMCOMP Position */ -#define DWT_CTRL_NUMCOMP_Msk (0xFUL << DWT_CTRL_NUMCOMP_Pos) /*!< DWT CTRL: NUMCOMP Mask */ - -#define DWT_CTRL_NOTRCPKT_Pos 27U /*!< DWT CTRL: NOTRCPKT Position */ -#define DWT_CTRL_NOTRCPKT_Msk (0x1UL << DWT_CTRL_NOTRCPKT_Pos) /*!< DWT CTRL: NOTRCPKT Mask */ - -#define DWT_CTRL_NOEXTTRIG_Pos 26U /*!< DWT CTRL: NOEXTTRIG Position */ -#define DWT_CTRL_NOEXTTRIG_Msk (0x1UL << DWT_CTRL_NOEXTTRIG_Pos) /*!< DWT CTRL: NOEXTTRIG Mask */ - -#define DWT_CTRL_NOCYCCNT_Pos 25U /*!< DWT CTRL: NOCYCCNT Position */ -#define DWT_CTRL_NOCYCCNT_Msk (0x1UL << DWT_CTRL_NOCYCCNT_Pos) /*!< DWT CTRL: NOCYCCNT Mask */ - -#define DWT_CTRL_NOPRFCNT_Pos 24U /*!< DWT CTRL: NOPRFCNT Position */ -#define DWT_CTRL_NOPRFCNT_Msk (0x1UL << DWT_CTRL_NOPRFCNT_Pos) /*!< DWT CTRL: NOPRFCNT Mask */ - -#define DWT_CTRL_CYCEVTENA_Pos 22U /*!< DWT CTRL: CYCEVTENA Position */ -#define DWT_CTRL_CYCEVTENA_Msk (0x1UL << DWT_CTRL_CYCEVTENA_Pos) /*!< DWT CTRL: CYCEVTENA Mask */ - -#define DWT_CTRL_FOLDEVTENA_Pos 21U /*!< DWT CTRL: FOLDEVTENA Position */ -#define DWT_CTRL_FOLDEVTENA_Msk (0x1UL << DWT_CTRL_FOLDEVTENA_Pos) /*!< DWT CTRL: FOLDEVTENA Mask */ - -#define DWT_CTRL_LSUEVTENA_Pos 20U /*!< DWT CTRL: LSUEVTENA Position */ -#define DWT_CTRL_LSUEVTENA_Msk (0x1UL << DWT_CTRL_LSUEVTENA_Pos) /*!< DWT CTRL: LSUEVTENA Mask */ - -#define DWT_CTRL_SLEEPEVTENA_Pos 19U /*!< DWT CTRL: SLEEPEVTENA Position */ -#define DWT_CTRL_SLEEPEVTENA_Msk (0x1UL << DWT_CTRL_SLEEPEVTENA_Pos) /*!< DWT CTRL: SLEEPEVTENA Mask */ - -#define DWT_CTRL_EXCEVTENA_Pos 18U /*!< DWT CTRL: EXCEVTENA Position */ -#define DWT_CTRL_EXCEVTENA_Msk (0x1UL << DWT_CTRL_EXCEVTENA_Pos) /*!< DWT CTRL: EXCEVTENA Mask */ - -#define DWT_CTRL_CPIEVTENA_Pos 17U /*!< DWT CTRL: CPIEVTENA Position */ -#define DWT_CTRL_CPIEVTENA_Msk (0x1UL << DWT_CTRL_CPIEVTENA_Pos) /*!< DWT CTRL: CPIEVTENA Mask */ - -#define DWT_CTRL_EXCTRCENA_Pos 16U /*!< DWT CTRL: EXCTRCENA Position */ -#define DWT_CTRL_EXCTRCENA_Msk (0x1UL << DWT_CTRL_EXCTRCENA_Pos) /*!< DWT CTRL: EXCTRCENA Mask */ - -#define DWT_CTRL_PCSAMPLENA_Pos 12U /*!< DWT CTRL: PCSAMPLENA Position */ -#define DWT_CTRL_PCSAMPLENA_Msk (0x1UL << DWT_CTRL_PCSAMPLENA_Pos) /*!< DWT CTRL: PCSAMPLENA Mask */ - -#define DWT_CTRL_SYNCTAP_Pos 10U /*!< DWT CTRL: SYNCTAP Position */ -#define DWT_CTRL_SYNCTAP_Msk (0x3UL << DWT_CTRL_SYNCTAP_Pos) /*!< DWT CTRL: SYNCTAP Mask */ - -#define DWT_CTRL_CYCTAP_Pos 9U /*!< DWT CTRL: CYCTAP Position */ -#define DWT_CTRL_CYCTAP_Msk (0x1UL << DWT_CTRL_CYCTAP_Pos) /*!< DWT CTRL: CYCTAP Mask */ - -#define DWT_CTRL_POSTINIT_Pos 5U /*!< DWT CTRL: POSTINIT Position */ -#define DWT_CTRL_POSTINIT_Msk (0xFUL << DWT_CTRL_POSTINIT_Pos) /*!< DWT CTRL: POSTINIT Mask */ - -#define DWT_CTRL_POSTPRESET_Pos 1U /*!< DWT CTRL: POSTPRESET Position */ -#define DWT_CTRL_POSTPRESET_Msk (0xFUL << DWT_CTRL_POSTPRESET_Pos) /*!< DWT CTRL: POSTPRESET Mask */ - -#define DWT_CTRL_CYCCNTENA_Pos 0U /*!< DWT CTRL: CYCCNTENA Position */ -#define DWT_CTRL_CYCCNTENA_Msk (0x1UL /*<< DWT_CTRL_CYCCNTENA_Pos*/) /*!< DWT CTRL: CYCCNTENA Mask */ - -/* DWT CPI Count Register Definitions */ -#define DWT_CPICNT_CPICNT_Pos 0U /*!< DWT CPICNT: CPICNT Position */ -#define DWT_CPICNT_CPICNT_Msk (0xFFUL /*<< DWT_CPICNT_CPICNT_Pos*/) /*!< DWT CPICNT: CPICNT Mask */ - -/* DWT Exception Overhead Count Register Definitions */ -#define DWT_EXCCNT_EXCCNT_Pos 0U /*!< DWT EXCCNT: EXCCNT Position */ -#define DWT_EXCCNT_EXCCNT_Msk (0xFFUL /*<< DWT_EXCCNT_EXCCNT_Pos*/) /*!< DWT EXCCNT: EXCCNT Mask */ - -/* DWT Sleep Count Register Definitions */ -#define DWT_SLEEPCNT_SLEEPCNT_Pos 0U /*!< DWT SLEEPCNT: SLEEPCNT Position */ -#define DWT_SLEEPCNT_SLEEPCNT_Msk (0xFFUL /*<< DWT_SLEEPCNT_SLEEPCNT_Pos*/) /*!< DWT SLEEPCNT: SLEEPCNT Mask */ - -/* DWT LSU Count Register Definitions */ -#define DWT_LSUCNT_LSUCNT_Pos 0U /*!< DWT LSUCNT: LSUCNT Position */ -#define DWT_LSUCNT_LSUCNT_Msk (0xFFUL /*<< DWT_LSUCNT_LSUCNT_Pos*/) /*!< DWT LSUCNT: LSUCNT Mask */ - -/* DWT Folded-instruction Count Register Definitions */ -#define DWT_FOLDCNT_FOLDCNT_Pos 0U /*!< DWT FOLDCNT: FOLDCNT Position */ -#define DWT_FOLDCNT_FOLDCNT_Msk (0xFFUL /*<< DWT_FOLDCNT_FOLDCNT_Pos*/) /*!< DWT FOLDCNT: FOLDCNT Mask */ - -/* DWT Comparator Mask Register Definitions */ -#define DWT_MASK_MASK_Pos 0U /*!< DWT MASK: MASK Position */ -#define DWT_MASK_MASK_Msk (0x1FUL /*<< DWT_MASK_MASK_Pos*/) /*!< DWT MASK: MASK Mask */ - -/* DWT Comparator Function Register Definitions */ -#define DWT_FUNCTION_MATCHED_Pos 24U /*!< DWT FUNCTION: MATCHED Position */ -#define DWT_FUNCTION_MATCHED_Msk (0x1UL << DWT_FUNCTION_MATCHED_Pos) /*!< DWT FUNCTION: MATCHED Mask */ - -#define DWT_FUNCTION_DATAVADDR1_Pos 16U /*!< DWT FUNCTION: DATAVADDR1 Position */ -#define DWT_FUNCTION_DATAVADDR1_Msk (0xFUL << DWT_FUNCTION_DATAVADDR1_Pos) /*!< DWT FUNCTION: DATAVADDR1 Mask */ - -#define DWT_FUNCTION_DATAVADDR0_Pos 12U /*!< DWT FUNCTION: DATAVADDR0 Position */ -#define DWT_FUNCTION_DATAVADDR0_Msk (0xFUL << DWT_FUNCTION_DATAVADDR0_Pos) /*!< DWT FUNCTION: DATAVADDR0 Mask */ - -#define DWT_FUNCTION_DATAVSIZE_Pos 10U /*!< DWT FUNCTION: DATAVSIZE Position */ -#define DWT_FUNCTION_DATAVSIZE_Msk (0x3UL << DWT_FUNCTION_DATAVSIZE_Pos) /*!< DWT FUNCTION: DATAVSIZE Mask */ - -#define DWT_FUNCTION_LNK1ENA_Pos 9U /*!< DWT FUNCTION: LNK1ENA Position */ -#define DWT_FUNCTION_LNK1ENA_Msk (0x1UL << DWT_FUNCTION_LNK1ENA_Pos) /*!< DWT FUNCTION: LNK1ENA Mask */ - -#define DWT_FUNCTION_DATAVMATCH_Pos 8U /*!< DWT FUNCTION: DATAVMATCH Position */ -#define DWT_FUNCTION_DATAVMATCH_Msk (0x1UL << DWT_FUNCTION_DATAVMATCH_Pos) /*!< DWT FUNCTION: DATAVMATCH Mask */ - -#define DWT_FUNCTION_CYCMATCH_Pos 7U /*!< DWT FUNCTION: CYCMATCH Position */ -#define DWT_FUNCTION_CYCMATCH_Msk (0x1UL << DWT_FUNCTION_CYCMATCH_Pos) /*!< DWT FUNCTION: CYCMATCH Mask */ - -#define DWT_FUNCTION_EMITRANGE_Pos 5U /*!< DWT FUNCTION: EMITRANGE Position */ -#define DWT_FUNCTION_EMITRANGE_Msk (0x1UL << DWT_FUNCTION_EMITRANGE_Pos) /*!< DWT FUNCTION: EMITRANGE Mask */ - -#define DWT_FUNCTION_FUNCTION_Pos 0U /*!< DWT FUNCTION: FUNCTION Position */ -#define DWT_FUNCTION_FUNCTION_Msk (0xFUL /*<< DWT_FUNCTION_FUNCTION_Pos*/) /*!< DWT FUNCTION: FUNCTION Mask */ - -/*@}*/ /* end of group CMSIS_DWT */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_TPI Trace Port Interface (TPI) - \brief Type definitions for the Trace Port Interface (TPI) - @{ - */ - -/** - \brief Structure type to access the Trace Port Interface Register (TPI). - */ -typedef struct -{ - __IM uint32_t SSPSR; /*!< Offset: 0x000 (R/ ) Supported Parallel Port Size Register */ - __IOM uint32_t CSPSR; /*!< Offset: 0x004 (R/W) Current Parallel Port Size Register */ - uint32_t RESERVED0[2U]; - __IOM uint32_t ACPR; /*!< Offset: 0x010 (R/W) Asynchronous Clock Prescaler Register */ - uint32_t RESERVED1[55U]; - __IOM uint32_t SPPR; /*!< Offset: 0x0F0 (R/W) Selected Pin Protocol Register */ - uint32_t RESERVED2[131U]; - __IM uint32_t FFSR; /*!< Offset: 0x300 (R/ ) Formatter and Flush Status Register */ - __IOM uint32_t FFCR; /*!< Offset: 0x304 (R/W) Formatter and Flush Control Register */ - __IM uint32_t FSCR; /*!< Offset: 0x308 (R/ ) Formatter Synchronization Counter Register */ - uint32_t RESERVED3[759U]; - __IM uint32_t TRIGGER; /*!< Offset: 0xEE8 (R/ ) TRIGGER Register */ - __IM uint32_t FIFO0; /*!< Offset: 0xEEC (R/ ) Integration ETM Data */ - __IM uint32_t ITATBCTR2; /*!< Offset: 0xEF0 (R/ ) ITATBCTR2 */ - uint32_t RESERVED4[1U]; - __IM uint32_t ITATBCTR0; /*!< Offset: 0xEF8 (R/ ) ITATBCTR0 */ - __IM uint32_t FIFO1; /*!< Offset: 0xEFC (R/ ) Integration ITM Data */ - __IOM uint32_t ITCTRL; /*!< Offset: 0xF00 (R/W) Integration Mode Control */ - uint32_t RESERVED5[39U]; - __IOM uint32_t CLAIMSET; /*!< Offset: 0xFA0 (R/W) Claim tag set */ - __IOM uint32_t CLAIMCLR; /*!< Offset: 0xFA4 (R/W) Claim tag clear */ - uint32_t RESERVED7[8U]; - __IM uint32_t DEVID; /*!< Offset: 0xFC8 (R/ ) TPIU_DEVID */ - __IM uint32_t DEVTYPE; /*!< Offset: 0xFCC (R/ ) TPIU_DEVTYPE */ -} TPI_Type; - -/* TPI Asynchronous Clock Prescaler Register Definitions */ -#define TPI_ACPR_PRESCALER_Pos 0U /*!< TPI ACPR: PRESCALER Position */ -#define TPI_ACPR_PRESCALER_Msk (0x1FFFUL /*<< TPI_ACPR_PRESCALER_Pos*/) /*!< TPI ACPR: PRESCALER Mask */ - -/* TPI Selected Pin Protocol Register Definitions */ -#define TPI_SPPR_TXMODE_Pos 0U /*!< TPI SPPR: TXMODE Position */ -#define TPI_SPPR_TXMODE_Msk (0x3UL /*<< TPI_SPPR_TXMODE_Pos*/) /*!< TPI SPPR: TXMODE Mask */ - -/* TPI Formatter and Flush Status Register Definitions */ -#define TPI_FFSR_FtNonStop_Pos 3U /*!< TPI FFSR: FtNonStop Position */ -#define TPI_FFSR_FtNonStop_Msk (0x1UL << TPI_FFSR_FtNonStop_Pos) /*!< TPI FFSR: FtNonStop Mask */ - -#define TPI_FFSR_TCPresent_Pos 2U /*!< TPI FFSR: TCPresent Position */ -#define TPI_FFSR_TCPresent_Msk (0x1UL << TPI_FFSR_TCPresent_Pos) /*!< TPI FFSR: TCPresent Mask */ - -#define TPI_FFSR_FtStopped_Pos 1U /*!< TPI FFSR: FtStopped Position */ -#define TPI_FFSR_FtStopped_Msk (0x1UL << TPI_FFSR_FtStopped_Pos) /*!< TPI FFSR: FtStopped Mask */ - -#define TPI_FFSR_FlInProg_Pos 0U /*!< TPI FFSR: FlInProg Position */ -#define TPI_FFSR_FlInProg_Msk (0x1UL /*<< TPI_FFSR_FlInProg_Pos*/) /*!< TPI FFSR: FlInProg Mask */ - -/* TPI Formatter and Flush Control Register Definitions */ -#define TPI_FFCR_TrigIn_Pos 8U /*!< TPI FFCR: TrigIn Position */ -#define TPI_FFCR_TrigIn_Msk (0x1UL << TPI_FFCR_TrigIn_Pos) /*!< TPI FFCR: TrigIn Mask */ - -#define TPI_FFCR_EnFCont_Pos 1U /*!< TPI FFCR: EnFCont Position */ -#define TPI_FFCR_EnFCont_Msk (0x1UL << TPI_FFCR_EnFCont_Pos) /*!< TPI FFCR: EnFCont Mask */ - -/* TPI TRIGGER Register Definitions */ -#define TPI_TRIGGER_TRIGGER_Pos 0U /*!< TPI TRIGGER: TRIGGER Position */ -#define TPI_TRIGGER_TRIGGER_Msk (0x1UL /*<< TPI_TRIGGER_TRIGGER_Pos*/) /*!< TPI TRIGGER: TRIGGER Mask */ - -/* TPI Integration ETM Data Register Definitions (FIFO0) */ -#define TPI_FIFO0_ITM_ATVALID_Pos 29U /*!< TPI FIFO0: ITM_ATVALID Position */ -#define TPI_FIFO0_ITM_ATVALID_Msk (0x1UL << TPI_FIFO0_ITM_ATVALID_Pos) /*!< TPI FIFO0: ITM_ATVALID Mask */ - -#define TPI_FIFO0_ITM_bytecount_Pos 27U /*!< TPI FIFO0: ITM_bytecount Position */ -#define TPI_FIFO0_ITM_bytecount_Msk (0x3UL << TPI_FIFO0_ITM_bytecount_Pos) /*!< TPI FIFO0: ITM_bytecount Mask */ - -#define TPI_FIFO0_ETM_ATVALID_Pos 26U /*!< TPI FIFO0: ETM_ATVALID Position */ -#define TPI_FIFO0_ETM_ATVALID_Msk (0x1UL << TPI_FIFO0_ETM_ATVALID_Pos) /*!< TPI FIFO0: ETM_ATVALID Mask */ - -#define TPI_FIFO0_ETM_bytecount_Pos 24U /*!< TPI FIFO0: ETM_bytecount Position */ -#define TPI_FIFO0_ETM_bytecount_Msk (0x3UL << TPI_FIFO0_ETM_bytecount_Pos) /*!< TPI FIFO0: ETM_bytecount Mask */ - -#define TPI_FIFO0_ETM2_Pos 16U /*!< TPI FIFO0: ETM2 Position */ -#define TPI_FIFO0_ETM2_Msk (0xFFUL << TPI_FIFO0_ETM2_Pos) /*!< TPI FIFO0: ETM2 Mask */ - -#define TPI_FIFO0_ETM1_Pos 8U /*!< TPI FIFO0: ETM1 Position */ -#define TPI_FIFO0_ETM1_Msk (0xFFUL << TPI_FIFO0_ETM1_Pos) /*!< TPI FIFO0: ETM1 Mask */ - -#define TPI_FIFO0_ETM0_Pos 0U /*!< TPI FIFO0: ETM0 Position */ -#define TPI_FIFO0_ETM0_Msk (0xFFUL /*<< TPI_FIFO0_ETM0_Pos*/) /*!< TPI FIFO0: ETM0 Mask */ - -/* TPI ITATBCTR2 Register Definitions */ -#define TPI_ITATBCTR2_ATREADY2_Pos 0U /*!< TPI ITATBCTR2: ATREADY2 Position */ -#define TPI_ITATBCTR2_ATREADY2_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY2_Pos*/) /*!< TPI ITATBCTR2: ATREADY2 Mask */ - -#define TPI_ITATBCTR2_ATREADY1_Pos 0U /*!< TPI ITATBCTR2: ATREADY1 Position */ -#define TPI_ITATBCTR2_ATREADY1_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY1_Pos*/) /*!< TPI ITATBCTR2: ATREADY1 Mask */ - -/* TPI Integration ITM Data Register Definitions (FIFO1) */ -#define TPI_FIFO1_ITM_ATVALID_Pos 29U /*!< TPI FIFO1: ITM_ATVALID Position */ -#define TPI_FIFO1_ITM_ATVALID_Msk (0x1UL << TPI_FIFO1_ITM_ATVALID_Pos) /*!< TPI FIFO1: ITM_ATVALID Mask */ - -#define TPI_FIFO1_ITM_bytecount_Pos 27U /*!< TPI FIFO1: ITM_bytecount Position */ -#define TPI_FIFO1_ITM_bytecount_Msk (0x3UL << TPI_FIFO1_ITM_bytecount_Pos) /*!< TPI FIFO1: ITM_bytecount Mask */ - -#define TPI_FIFO1_ETM_ATVALID_Pos 26U /*!< TPI FIFO1: ETM_ATVALID Position */ -#define TPI_FIFO1_ETM_ATVALID_Msk (0x1UL << TPI_FIFO1_ETM_ATVALID_Pos) /*!< TPI FIFO1: ETM_ATVALID Mask */ - -#define TPI_FIFO1_ETM_bytecount_Pos 24U /*!< TPI FIFO1: ETM_bytecount Position */ -#define TPI_FIFO1_ETM_bytecount_Msk (0x3UL << TPI_FIFO1_ETM_bytecount_Pos) /*!< TPI FIFO1: ETM_bytecount Mask */ - -#define TPI_FIFO1_ITM2_Pos 16U /*!< TPI FIFO1: ITM2 Position */ -#define TPI_FIFO1_ITM2_Msk (0xFFUL << TPI_FIFO1_ITM2_Pos) /*!< TPI FIFO1: ITM2 Mask */ - -#define TPI_FIFO1_ITM1_Pos 8U /*!< TPI FIFO1: ITM1 Position */ -#define TPI_FIFO1_ITM1_Msk (0xFFUL << TPI_FIFO1_ITM1_Pos) /*!< TPI FIFO1: ITM1 Mask */ - -#define TPI_FIFO1_ITM0_Pos 0U /*!< TPI FIFO1: ITM0 Position */ -#define TPI_FIFO1_ITM0_Msk (0xFFUL /*<< TPI_FIFO1_ITM0_Pos*/) /*!< TPI FIFO1: ITM0 Mask */ - -/* TPI ITATBCTR0 Register Definitions */ -#define TPI_ITATBCTR0_ATREADY2_Pos 0U /*!< TPI ITATBCTR0: ATREADY2 Position */ -#define TPI_ITATBCTR0_ATREADY2_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY2_Pos*/) /*!< TPI ITATBCTR0: ATREADY2 Mask */ - -#define TPI_ITATBCTR0_ATREADY1_Pos 0U /*!< TPI ITATBCTR0: ATREADY1 Position */ -#define TPI_ITATBCTR0_ATREADY1_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY1_Pos*/) /*!< TPI ITATBCTR0: ATREADY1 Mask */ - -/* TPI Integration Mode Control Register Definitions */ -#define TPI_ITCTRL_Mode_Pos 0U /*!< TPI ITCTRL: Mode Position */ -#define TPI_ITCTRL_Mode_Msk (0x3UL /*<< TPI_ITCTRL_Mode_Pos*/) /*!< TPI ITCTRL: Mode Mask */ - -/* TPI DEVID Register Definitions */ -#define TPI_DEVID_NRZVALID_Pos 11U /*!< TPI DEVID: NRZVALID Position */ -#define TPI_DEVID_NRZVALID_Msk (0x1UL << TPI_DEVID_NRZVALID_Pos) /*!< TPI DEVID: NRZVALID Mask */ - -#define TPI_DEVID_MANCVALID_Pos 10U /*!< TPI DEVID: MANCVALID Position */ -#define TPI_DEVID_MANCVALID_Msk (0x1UL << TPI_DEVID_MANCVALID_Pos) /*!< TPI DEVID: MANCVALID Mask */ - -#define TPI_DEVID_PTINVALID_Pos 9U /*!< TPI DEVID: PTINVALID Position */ -#define TPI_DEVID_PTINVALID_Msk (0x1UL << TPI_DEVID_PTINVALID_Pos) /*!< TPI DEVID: PTINVALID Mask */ - -#define TPI_DEVID_MinBufSz_Pos 6U /*!< TPI DEVID: MinBufSz Position */ -#define TPI_DEVID_MinBufSz_Msk (0x7UL << TPI_DEVID_MinBufSz_Pos) /*!< TPI DEVID: MinBufSz Mask */ - -#define TPI_DEVID_AsynClkIn_Pos 5U /*!< TPI DEVID: AsynClkIn Position */ -#define TPI_DEVID_AsynClkIn_Msk (0x1UL << TPI_DEVID_AsynClkIn_Pos) /*!< TPI DEVID: AsynClkIn Mask */ - -#define TPI_DEVID_NrTraceInput_Pos 0U /*!< TPI DEVID: NrTraceInput Position */ -#define TPI_DEVID_NrTraceInput_Msk (0x1FUL /*<< TPI_DEVID_NrTraceInput_Pos*/) /*!< TPI DEVID: NrTraceInput Mask */ - -/* TPI DEVTYPE Register Definitions */ -#define TPI_DEVTYPE_SubType_Pos 4U /*!< TPI DEVTYPE: SubType Position */ -#define TPI_DEVTYPE_SubType_Msk (0xFUL /*<< TPI_DEVTYPE_SubType_Pos*/) /*!< TPI DEVTYPE: SubType Mask */ - -#define TPI_DEVTYPE_MajorType_Pos 0U /*!< TPI DEVTYPE: MajorType Position */ -#define TPI_DEVTYPE_MajorType_Msk (0xFUL << TPI_DEVTYPE_MajorType_Pos) /*!< TPI DEVTYPE: MajorType Mask */ - -/*@}*/ /* end of group CMSIS_TPI */ - - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_MPU Memory Protection Unit (MPU) - \brief Type definitions for the Memory Protection Unit (MPU) - @{ - */ - -/** - \brief Structure type to access the Memory Protection Unit (MPU). - */ -typedef struct -{ - __IM uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */ - __IOM uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */ - __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region RNRber Register */ - __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */ - __IOM uint32_t RASR; /*!< Offset: 0x010 (R/W) MPU Region Attribute and Size Register */ - __IOM uint32_t RBAR_A1; /*!< Offset: 0x014 (R/W) MPU Alias 1 Region Base Address Register */ - __IOM uint32_t RASR_A1; /*!< Offset: 0x018 (R/W) MPU Alias 1 Region Attribute and Size Register */ - __IOM uint32_t RBAR_A2; /*!< Offset: 0x01C (R/W) MPU Alias 2 Region Base Address Register */ - __IOM uint32_t RASR_A2; /*!< Offset: 0x020 (R/W) MPU Alias 2 Region Attribute and Size Register */ - __IOM uint32_t RBAR_A3; /*!< Offset: 0x024 (R/W) MPU Alias 3 Region Base Address Register */ - __IOM uint32_t RASR_A3; /*!< Offset: 0x028 (R/W) MPU Alias 3 Region Attribute and Size Register */ -} MPU_Type; - -#define MPU_TYPE_RALIASES 4U - -/* MPU Type Register Definitions */ -#define MPU_TYPE_IREGION_Pos 16U /*!< MPU TYPE: IREGION Position */ -#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */ - -#define MPU_TYPE_DREGION_Pos 8U /*!< MPU TYPE: DREGION Position */ -#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ - -#define MPU_TYPE_SEPARATE_Pos 0U /*!< MPU TYPE: SEPARATE Position */ -#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */ - -/* MPU Control Register Definitions */ -#define MPU_CTRL_PRIVDEFENA_Pos 2U /*!< MPU CTRL: PRIVDEFENA Position */ -#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */ - -#define MPU_CTRL_HFNMIENA_Pos 1U /*!< MPU CTRL: HFNMIENA Position */ -#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ - -#define MPU_CTRL_ENABLE_Pos 0U /*!< MPU CTRL: ENABLE Position */ -#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */ - -/* MPU Region Number Register Definitions */ -#define MPU_RNR_REGION_Pos 0U /*!< MPU RNR: REGION Position */ -#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */ - -/* MPU Region Base Address Register Definitions */ -#define MPU_RBAR_ADDR_Pos 5U /*!< MPU RBAR: ADDR Position */ -#define MPU_RBAR_ADDR_Msk (0x7FFFFFFUL << MPU_RBAR_ADDR_Pos) /*!< MPU RBAR: ADDR Mask */ - -#define MPU_RBAR_VALID_Pos 4U /*!< MPU RBAR: VALID Position */ -#define MPU_RBAR_VALID_Msk (1UL << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */ - -#define MPU_RBAR_REGION_Pos 0U /*!< MPU RBAR: REGION Position */ -#define MPU_RBAR_REGION_Msk (0xFUL /*<< MPU_RBAR_REGION_Pos*/) /*!< MPU RBAR: REGION Mask */ - -/* MPU Region Attribute and Size Register Definitions */ -#define MPU_RASR_ATTRS_Pos 16U /*!< MPU RASR: MPU Region Attribute field Position */ -#define MPU_RASR_ATTRS_Msk (0xFFFFUL << MPU_RASR_ATTRS_Pos) /*!< MPU RASR: MPU Region Attribute field Mask */ - -#define MPU_RASR_XN_Pos 28U /*!< MPU RASR: ATTRS.XN Position */ -#define MPU_RASR_XN_Msk (1UL << MPU_RASR_XN_Pos) /*!< MPU RASR: ATTRS.XN Mask */ - -#define MPU_RASR_AP_Pos 24U /*!< MPU RASR: ATTRS.AP Position */ -#define MPU_RASR_AP_Msk (0x7UL << MPU_RASR_AP_Pos) /*!< MPU RASR: ATTRS.AP Mask */ - -#define MPU_RASR_TEX_Pos 19U /*!< MPU RASR: ATTRS.TEX Position */ -#define MPU_RASR_TEX_Msk (0x7UL << MPU_RASR_TEX_Pos) /*!< MPU RASR: ATTRS.TEX Mask */ - -#define MPU_RASR_S_Pos 18U /*!< MPU RASR: ATTRS.S Position */ -#define MPU_RASR_S_Msk (1UL << MPU_RASR_S_Pos) /*!< MPU RASR: ATTRS.S Mask */ - -#define MPU_RASR_C_Pos 17U /*!< MPU RASR: ATTRS.C Position */ -#define MPU_RASR_C_Msk (1UL << MPU_RASR_C_Pos) /*!< MPU RASR: ATTRS.C Mask */ - -#define MPU_RASR_B_Pos 16U /*!< MPU RASR: ATTRS.B Position */ -#define MPU_RASR_B_Msk (1UL << MPU_RASR_B_Pos) /*!< MPU RASR: ATTRS.B Mask */ - -#define MPU_RASR_SRD_Pos 8U /*!< MPU RASR: Sub-Region Disable Position */ -#define MPU_RASR_SRD_Msk (0xFFUL << MPU_RASR_SRD_Pos) /*!< MPU RASR: Sub-Region Disable Mask */ - -#define MPU_RASR_SIZE_Pos 1U /*!< MPU RASR: Region Size Field Position */ -#define MPU_RASR_SIZE_Msk (0x1FUL << MPU_RASR_SIZE_Pos) /*!< MPU RASR: Region Size Field Mask */ - -#define MPU_RASR_ENABLE_Pos 0U /*!< MPU RASR: Region enable bit Position */ -#define MPU_RASR_ENABLE_Msk (1UL /*<< MPU_RASR_ENABLE_Pos*/) /*!< MPU RASR: Region enable bit Disable Mask */ - -/*@} end of group CMSIS_MPU */ -#endif /* defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_FPU Floating Point Unit (FPU) - \brief Type definitions for the Floating Point Unit (FPU) - @{ - */ - -/** - \brief Structure type to access the Floating Point Unit (FPU). - */ -typedef struct -{ - uint32_t RESERVED0[1U]; - __IOM uint32_t FPCCR; /*!< Offset: 0x004 (R/W) Floating-Point Context Control Register */ - __IOM uint32_t FPCAR; /*!< Offset: 0x008 (R/W) Floating-Point Context Address Register */ - __IOM uint32_t FPDSCR; /*!< Offset: 0x00C (R/W) Floating-Point Default Status Control Register */ - __IM uint32_t MVFR0; /*!< Offset: 0x010 (R/ ) Media and FP Feature Register 0 */ - __IM uint32_t MVFR1; /*!< Offset: 0x014 (R/ ) Media and FP Feature Register 1 */ - __IM uint32_t MVFR2; /*!< Offset: 0x018 (R/ ) Media and FP Feature Register 2 */ -} FPU_Type; - -/* Floating-Point Context Control Register Definitions */ -#define FPU_FPCCR_ASPEN_Pos 31U /*!< FPCCR: ASPEN bit Position */ -#define FPU_FPCCR_ASPEN_Msk (1UL << FPU_FPCCR_ASPEN_Pos) /*!< FPCCR: ASPEN bit Mask */ - -#define FPU_FPCCR_LSPEN_Pos 30U /*!< FPCCR: LSPEN Position */ -#define FPU_FPCCR_LSPEN_Msk (1UL << FPU_FPCCR_LSPEN_Pos) /*!< FPCCR: LSPEN bit Mask */ - -#define FPU_FPCCR_MONRDY_Pos 8U /*!< FPCCR: MONRDY Position */ -#define FPU_FPCCR_MONRDY_Msk (1UL << FPU_FPCCR_MONRDY_Pos) /*!< FPCCR: MONRDY bit Mask */ - -#define FPU_FPCCR_BFRDY_Pos 6U /*!< FPCCR: BFRDY Position */ -#define FPU_FPCCR_BFRDY_Msk (1UL << FPU_FPCCR_BFRDY_Pos) /*!< FPCCR: BFRDY bit Mask */ - -#define FPU_FPCCR_MMRDY_Pos 5U /*!< FPCCR: MMRDY Position */ -#define FPU_FPCCR_MMRDY_Msk (1UL << FPU_FPCCR_MMRDY_Pos) /*!< FPCCR: MMRDY bit Mask */ - -#define FPU_FPCCR_HFRDY_Pos 4U /*!< FPCCR: HFRDY Position */ -#define FPU_FPCCR_HFRDY_Msk (1UL << FPU_FPCCR_HFRDY_Pos) /*!< FPCCR: HFRDY bit Mask */ - -#define FPU_FPCCR_THREAD_Pos 3U /*!< FPCCR: processor mode bit Position */ -#define FPU_FPCCR_THREAD_Msk (1UL << FPU_FPCCR_THREAD_Pos) /*!< FPCCR: processor mode active bit Mask */ - -#define FPU_FPCCR_USER_Pos 1U /*!< FPCCR: privilege level bit Position */ -#define FPU_FPCCR_USER_Msk (1UL << FPU_FPCCR_USER_Pos) /*!< FPCCR: privilege level bit Mask */ - -#define FPU_FPCCR_LSPACT_Pos 0U /*!< FPCCR: Lazy state preservation active bit Position */ -#define FPU_FPCCR_LSPACT_Msk (1UL /*<< FPU_FPCCR_LSPACT_Pos*/) /*!< FPCCR: Lazy state preservation active bit Mask */ - -/* Floating-Point Context Address Register Definitions */ -#define FPU_FPCAR_ADDRESS_Pos 3U /*!< FPCAR: ADDRESS bit Position */ -#define FPU_FPCAR_ADDRESS_Msk (0x1FFFFFFFUL << FPU_FPCAR_ADDRESS_Pos) /*!< FPCAR: ADDRESS bit Mask */ - -/* Floating-Point Default Status Control Register Definitions */ -#define FPU_FPDSCR_AHP_Pos 26U /*!< FPDSCR: AHP bit Position */ -#define FPU_FPDSCR_AHP_Msk (1UL << FPU_FPDSCR_AHP_Pos) /*!< FPDSCR: AHP bit Mask */ - -#define FPU_FPDSCR_DN_Pos 25U /*!< FPDSCR: DN bit Position */ -#define FPU_FPDSCR_DN_Msk (1UL << FPU_FPDSCR_DN_Pos) /*!< FPDSCR: DN bit Mask */ - -#define FPU_FPDSCR_FZ_Pos 24U /*!< FPDSCR: FZ bit Position */ -#define FPU_FPDSCR_FZ_Msk (1UL << FPU_FPDSCR_FZ_Pos) /*!< FPDSCR: FZ bit Mask */ - -#define FPU_FPDSCR_RMode_Pos 22U /*!< FPDSCR: RMode bit Position */ -#define FPU_FPDSCR_RMode_Msk (3UL << FPU_FPDSCR_RMode_Pos) /*!< FPDSCR: RMode bit Mask */ - -/* Media and FP Feature Register 0 Definitions */ -#define FPU_MVFR0_FP_rounding_modes_Pos 28U /*!< MVFR0: FP rounding modes bits Position */ -#define FPU_MVFR0_FP_rounding_modes_Msk (0xFUL << FPU_MVFR0_FP_rounding_modes_Pos) /*!< MVFR0: FP rounding modes bits Mask */ - -#define FPU_MVFR0_Short_vectors_Pos 24U /*!< MVFR0: Short vectors bits Position */ -#define FPU_MVFR0_Short_vectors_Msk (0xFUL << FPU_MVFR0_Short_vectors_Pos) /*!< MVFR0: Short vectors bits Mask */ - -#define FPU_MVFR0_Square_root_Pos 20U /*!< MVFR0: Square root bits Position */ -#define FPU_MVFR0_Square_root_Msk (0xFUL << FPU_MVFR0_Square_root_Pos) /*!< MVFR0: Square root bits Mask */ - -#define FPU_MVFR0_Divide_Pos 16U /*!< MVFR0: Divide bits Position */ -#define FPU_MVFR0_Divide_Msk (0xFUL << FPU_MVFR0_Divide_Pos) /*!< MVFR0: Divide bits Mask */ - -#define FPU_MVFR0_FP_excep_trapping_Pos 12U /*!< MVFR0: FP exception trapping bits Position */ -#define FPU_MVFR0_FP_excep_trapping_Msk (0xFUL << FPU_MVFR0_FP_excep_trapping_Pos) /*!< MVFR0: FP exception trapping bits Mask */ - -#define FPU_MVFR0_Double_precision_Pos 8U /*!< MVFR0: Double-precision bits Position */ -#define FPU_MVFR0_Double_precision_Msk (0xFUL << FPU_MVFR0_Double_precision_Pos) /*!< MVFR0: Double-precision bits Mask */ - -#define FPU_MVFR0_Single_precision_Pos 4U /*!< MVFR0: Single-precision bits Position */ -#define FPU_MVFR0_Single_precision_Msk (0xFUL << FPU_MVFR0_Single_precision_Pos) /*!< MVFR0: Single-precision bits Mask */ - -#define FPU_MVFR0_A_SIMD_registers_Pos 0U /*!< MVFR0: A_SIMD registers bits Position */ -#define FPU_MVFR0_A_SIMD_registers_Msk (0xFUL /*<< FPU_MVFR0_A_SIMD_registers_Pos*/) /*!< MVFR0: A_SIMD registers bits Mask */ - -/* Media and FP Feature Register 1 Definitions */ -#define FPU_MVFR1_FP_fused_MAC_Pos 28U /*!< MVFR1: FP fused MAC bits Position */ -#define FPU_MVFR1_FP_fused_MAC_Msk (0xFUL << FPU_MVFR1_FP_fused_MAC_Pos) /*!< MVFR1: FP fused MAC bits Mask */ - -#define FPU_MVFR1_FP_HPFP_Pos 24U /*!< MVFR1: FP HPFP bits Position */ -#define FPU_MVFR1_FP_HPFP_Msk (0xFUL << FPU_MVFR1_FP_HPFP_Pos) /*!< MVFR1: FP HPFP bits Mask */ - -#define FPU_MVFR1_D_NaN_mode_Pos 4U /*!< MVFR1: D_NaN mode bits Position */ -#define FPU_MVFR1_D_NaN_mode_Msk (0xFUL << FPU_MVFR1_D_NaN_mode_Pos) /*!< MVFR1: D_NaN mode bits Mask */ - -#define FPU_MVFR1_FtZ_mode_Pos 0U /*!< MVFR1: FtZ mode bits Position */ -#define FPU_MVFR1_FtZ_mode_Msk (0xFUL /*<< FPU_MVFR1_FtZ_mode_Pos*/) /*!< MVFR1: FtZ mode bits Mask */ - -/* Media and FP Feature Register 2 Definitions */ - -#define FPU_MVFR2_VFP_Misc_Pos 4U /*!< MVFR2: VFP Misc bits Position */ -#define FPU_MVFR2_VFP_Misc_Msk (0xFUL << FPU_MVFR2_VFP_Misc_Pos) /*!< MVFR2: VFP Misc bits Mask */ - -/*@} end of group CMSIS_FPU */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug) - \brief Type definitions for the Core Debug Registers - @{ - */ - -/** - \brief Structure type to access the Core Debug Register (CoreDebug). - */ -typedef struct -{ - __IOM uint32_t DHCSR; /*!< Offset: 0x000 (R/W) Debug Halting Control and Status Register */ - __OM uint32_t DCRSR; /*!< Offset: 0x004 ( /W) Debug Core Register Selector Register */ - __IOM uint32_t DCRDR; /*!< Offset: 0x008 (R/W) Debug Core Register Data Register */ - __IOM uint32_t DEMCR; /*!< Offset: 0x00C (R/W) Debug Exception and Monitor Control Register */ -} CoreDebug_Type; - -/* Debug Halting Control and Status Register Definitions */ -#define CoreDebug_DHCSR_DBGKEY_Pos 16U /*!< CoreDebug DHCSR: DBGKEY Position */ -#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFUL << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */ - -#define CoreDebug_DHCSR_S_RESET_ST_Pos 25U /*!< CoreDebug DHCSR: S_RESET_ST Position */ -#define CoreDebug_DHCSR_S_RESET_ST_Msk (1UL << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */ - -#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24U /*!< CoreDebug DHCSR: S_RETIRE_ST Position */ -#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1UL << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */ - -#define CoreDebug_DHCSR_S_LOCKUP_Pos 19U /*!< CoreDebug DHCSR: S_LOCKUP Position */ -#define CoreDebug_DHCSR_S_LOCKUP_Msk (1UL << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */ - -#define CoreDebug_DHCSR_S_SLEEP_Pos 18U /*!< CoreDebug DHCSR: S_SLEEP Position */ -#define CoreDebug_DHCSR_S_SLEEP_Msk (1UL << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */ - -#define CoreDebug_DHCSR_S_HALT_Pos 17U /*!< CoreDebug DHCSR: S_HALT Position */ -#define CoreDebug_DHCSR_S_HALT_Msk (1UL << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */ - -#define CoreDebug_DHCSR_S_REGRDY_Pos 16U /*!< CoreDebug DHCSR: S_REGRDY Position */ -#define CoreDebug_DHCSR_S_REGRDY_Msk (1UL << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */ - -#define CoreDebug_DHCSR_C_SNAPSTALL_Pos 5U /*!< CoreDebug DHCSR: C_SNAPSTALL Position */ -#define CoreDebug_DHCSR_C_SNAPSTALL_Msk (1UL << CoreDebug_DHCSR_C_SNAPSTALL_Pos) /*!< CoreDebug DHCSR: C_SNAPSTALL Mask */ - -#define CoreDebug_DHCSR_C_MASKINTS_Pos 3U /*!< CoreDebug DHCSR: C_MASKINTS Position */ -#define CoreDebug_DHCSR_C_MASKINTS_Msk (1UL << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */ - -#define CoreDebug_DHCSR_C_STEP_Pos 2U /*!< CoreDebug DHCSR: C_STEP Position */ -#define CoreDebug_DHCSR_C_STEP_Msk (1UL << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */ - -#define CoreDebug_DHCSR_C_HALT_Pos 1U /*!< CoreDebug DHCSR: C_HALT Position */ -#define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */ - -#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0U /*!< CoreDebug DHCSR: C_DEBUGEN Position */ -#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL /*<< CoreDebug_DHCSR_C_DEBUGEN_Pos*/) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ - -/* Debug Core Register Selector Register Definitions */ -#define CoreDebug_DCRSR_REGWnR_Pos 16U /*!< CoreDebug DCRSR: REGWnR Position */ -#define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */ - -#define CoreDebug_DCRSR_REGSEL_Pos 0U /*!< CoreDebug DCRSR: REGSEL Position */ -#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL /*<< CoreDebug_DCRSR_REGSEL_Pos*/) /*!< CoreDebug DCRSR: REGSEL Mask */ - -/* Debug Exception and Monitor Control Register Definitions */ -#define CoreDebug_DEMCR_TRCENA_Pos 24U /*!< CoreDebug DEMCR: TRCENA Position */ -#define CoreDebug_DEMCR_TRCENA_Msk (1UL << CoreDebug_DEMCR_TRCENA_Pos) /*!< CoreDebug DEMCR: TRCENA Mask */ - -#define CoreDebug_DEMCR_MON_REQ_Pos 19U /*!< CoreDebug DEMCR: MON_REQ Position */ -#define CoreDebug_DEMCR_MON_REQ_Msk (1UL << CoreDebug_DEMCR_MON_REQ_Pos) /*!< CoreDebug DEMCR: MON_REQ Mask */ - -#define CoreDebug_DEMCR_MON_STEP_Pos 18U /*!< CoreDebug DEMCR: MON_STEP Position */ -#define CoreDebug_DEMCR_MON_STEP_Msk (1UL << CoreDebug_DEMCR_MON_STEP_Pos) /*!< CoreDebug DEMCR: MON_STEP Mask */ - -#define CoreDebug_DEMCR_MON_PEND_Pos 17U /*!< CoreDebug DEMCR: MON_PEND Position */ -#define CoreDebug_DEMCR_MON_PEND_Msk (1UL << CoreDebug_DEMCR_MON_PEND_Pos) /*!< CoreDebug DEMCR: MON_PEND Mask */ - -#define CoreDebug_DEMCR_MON_EN_Pos 16U /*!< CoreDebug DEMCR: MON_EN Position */ -#define CoreDebug_DEMCR_MON_EN_Msk (1UL << CoreDebug_DEMCR_MON_EN_Pos) /*!< CoreDebug DEMCR: MON_EN Mask */ - -#define CoreDebug_DEMCR_VC_HARDERR_Pos 10U /*!< CoreDebug DEMCR: VC_HARDERR Position */ -#define CoreDebug_DEMCR_VC_HARDERR_Msk (1UL << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */ - -#define CoreDebug_DEMCR_VC_INTERR_Pos 9U /*!< CoreDebug DEMCR: VC_INTERR Position */ -#define CoreDebug_DEMCR_VC_INTERR_Msk (1UL << CoreDebug_DEMCR_VC_INTERR_Pos) /*!< CoreDebug DEMCR: VC_INTERR Mask */ - -#define CoreDebug_DEMCR_VC_BUSERR_Pos 8U /*!< CoreDebug DEMCR: VC_BUSERR Position */ -#define CoreDebug_DEMCR_VC_BUSERR_Msk (1UL << CoreDebug_DEMCR_VC_BUSERR_Pos) /*!< CoreDebug DEMCR: VC_BUSERR Mask */ - -#define CoreDebug_DEMCR_VC_STATERR_Pos 7U /*!< CoreDebug DEMCR: VC_STATERR Position */ -#define CoreDebug_DEMCR_VC_STATERR_Msk (1UL << CoreDebug_DEMCR_VC_STATERR_Pos) /*!< CoreDebug DEMCR: VC_STATERR Mask */ - -#define CoreDebug_DEMCR_VC_CHKERR_Pos 6U /*!< CoreDebug DEMCR: VC_CHKERR Position */ -#define CoreDebug_DEMCR_VC_CHKERR_Msk (1UL << CoreDebug_DEMCR_VC_CHKERR_Pos) /*!< CoreDebug DEMCR: VC_CHKERR Mask */ - -#define CoreDebug_DEMCR_VC_NOCPERR_Pos 5U /*!< CoreDebug DEMCR: VC_NOCPERR Position */ -#define CoreDebug_DEMCR_VC_NOCPERR_Msk (1UL << CoreDebug_DEMCR_VC_NOCPERR_Pos) /*!< CoreDebug DEMCR: VC_NOCPERR Mask */ - -#define CoreDebug_DEMCR_VC_MMERR_Pos 4U /*!< CoreDebug DEMCR: VC_MMERR Position */ -#define CoreDebug_DEMCR_VC_MMERR_Msk (1UL << CoreDebug_DEMCR_VC_MMERR_Pos) /*!< CoreDebug DEMCR: VC_MMERR Mask */ - -#define CoreDebug_DEMCR_VC_CORERESET_Pos 0U /*!< CoreDebug DEMCR: VC_CORERESET Position */ -#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL /*<< CoreDebug_DEMCR_VC_CORERESET_Pos*/) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ - -/*@} end of group CMSIS_CoreDebug */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_bitfield Core register bit field macros - \brief Macros for use with bit field definitions (xxx_Pos, xxx_Msk). - @{ - */ - -/** - \brief Mask and shift a bit field value for use in a register bit range. - \param[in] field Name of the register bit field. - \param[in] value Value of the bit field. This parameter is interpreted as an uint32_t type. - \return Masked and shifted value. -*/ -#define _VAL2FLD(field, value) (((uint32_t)(value) << field ## _Pos) & field ## _Msk) - -/** - \brief Mask and shift a register value to extract a bit filed value. - \param[in] field Name of the register bit field. - \param[in] value Value of register. This parameter is interpreted as an uint32_t type. - \return Masked and shifted bit field value. -*/ -#define _FLD2VAL(field, value) (((uint32_t)(value) & field ## _Msk) >> field ## _Pos) - -/*@} end of group CMSIS_core_bitfield */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_base Core Definitions - \brief Definitions for base addresses, unions, and structures. - @{ - */ - -/* Memory mapping of Core Hardware */ -#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ -#define ITM_BASE (0xE0000000UL) /*!< ITM Base Address */ -#define DWT_BASE (0xE0001000UL) /*!< DWT Base Address */ -#define TPI_BASE (0xE0040000UL) /*!< TPI Base Address */ -#define CoreDebug_BASE (0xE000EDF0UL) /*!< Core Debug Base Address */ -#define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ -#define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ -#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ - -#define SCnSCB ((SCnSCB_Type *) SCS_BASE ) /*!< System control Register not in SCB */ -#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ -#define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ -#define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ -#define ITM ((ITM_Type *) ITM_BASE ) /*!< ITM configuration struct */ -#define DWT ((DWT_Type *) DWT_BASE ) /*!< DWT configuration struct */ -#define TPI ((TPI_Type *) TPI_BASE ) /*!< TPI configuration struct */ -#define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE) /*!< Core Debug configuration struct */ - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */ - #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */ -#endif - -#define FPU_BASE (SCS_BASE + 0x0F30UL) /*!< Floating Point Unit */ -#define FPU ((FPU_Type *) FPU_BASE ) /*!< Floating Point Unit */ - -/*@} */ - - - -/******************************************************************************* - * Hardware Abstraction Layer - Core Function Interface contains: - - Core NVIC Functions - - Core SysTick Functions - - Core Debug Functions - - Core Register Access Functions - ******************************************************************************/ -/** - \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference -*/ - - - -/* ########################## NVIC functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_NVICFunctions NVIC Functions - \brief Functions that manage interrupts and exceptions via the NVIC. - @{ - */ - -#ifdef CMSIS_NVIC_VIRTUAL - #ifndef CMSIS_NVIC_VIRTUAL_HEADER_FILE - #define CMSIS_NVIC_VIRTUAL_HEADER_FILE "cmsis_nvic_virtual.h" - #endif - #include CMSIS_NVIC_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetPriorityGrouping __NVIC_SetPriorityGrouping - #define NVIC_GetPriorityGrouping __NVIC_GetPriorityGrouping - #define NVIC_EnableIRQ __NVIC_EnableIRQ - #define NVIC_GetEnableIRQ __NVIC_GetEnableIRQ - #define NVIC_DisableIRQ __NVIC_DisableIRQ - #define NVIC_GetPendingIRQ __NVIC_GetPendingIRQ - #define NVIC_SetPendingIRQ __NVIC_SetPendingIRQ - #define NVIC_ClearPendingIRQ __NVIC_ClearPendingIRQ - #define NVIC_GetActive __NVIC_GetActive - #define NVIC_SetPriority __NVIC_SetPriority - #define NVIC_GetPriority __NVIC_GetPriority - #define NVIC_SystemReset __NVIC_SystemReset -#endif /* CMSIS_NVIC_VIRTUAL */ - -#ifdef CMSIS_VECTAB_VIRTUAL - #ifndef CMSIS_VECTAB_VIRTUAL_HEADER_FILE - #define CMSIS_VECTAB_VIRTUAL_HEADER_FILE "cmsis_vectab_virtual.h" - #endif - #include CMSIS_VECTAB_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetVector __NVIC_SetVector - #define NVIC_GetVector __NVIC_GetVector -#endif /* (CMSIS_VECTAB_VIRTUAL) */ - -#define NVIC_USER_IRQ_OFFSET 16 - - -/* The following EXC_RETURN values are saved the LR on exception entry */ -#define EXC_RETURN_HANDLER (0xFFFFFFF1UL) /* return to Handler mode, uses MSP after return */ -#define EXC_RETURN_THREAD_MSP (0xFFFFFFF9UL) /* return to Thread mode, uses MSP after return */ -#define EXC_RETURN_THREAD_PSP (0xFFFFFFFDUL) /* return to Thread mode, uses PSP after return */ -#define EXC_RETURN_HANDLER_FPU (0xFFFFFFE1UL) /* return to Handler mode, uses MSP after return, restore floating-point state */ -#define EXC_RETURN_THREAD_MSP_FPU (0xFFFFFFE9UL) /* return to Thread mode, uses MSP after return, restore floating-point state */ -#define EXC_RETURN_THREAD_PSP_FPU (0xFFFFFFEDUL) /* return to Thread mode, uses PSP after return, restore floating-point state */ - - -/** - \brief Set Priority Grouping - \details Sets the priority grouping field using the required unlock sequence. - The parameter PriorityGroup is assigned to the field SCB->AIRCR [10:8] PRIGROUP field. - Only values from 0..7 are used. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. - \param [in] PriorityGroup Priority grouping field. - */ -__STATIC_INLINE void __NVIC_SetPriorityGrouping(uint32_t PriorityGroup) -{ - uint32_t reg_value; - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - - reg_value = SCB->AIRCR; /* read old register configuration */ - reg_value &= ~((uint32_t)(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk)); /* clear bits to change */ - reg_value = (reg_value | - ((uint32_t)0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - (PriorityGroupTmp << SCB_AIRCR_PRIGROUP_Pos) ); /* Insert write key and priority group */ - SCB->AIRCR = reg_value; -} - - -/** - \brief Get Priority Grouping - \details Reads the priority grouping field from the NVIC Interrupt Controller. - \return Priority grouping field (SCB->AIRCR [10:8] PRIGROUP field). - */ -__STATIC_INLINE uint32_t __NVIC_GetPriorityGrouping(void) -{ - return ((uint32_t)((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos)); -} - - -/** - \brief Enable Interrupt - \details Enables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_EnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - __COMPILER_BARRIER(); - NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - __COMPILER_BARRIER(); - } -} - - -/** - \brief Get Interrupt Enable status - \details Returns a device specific interrupt enable status from the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt is not enabled. - \return 1 Interrupt is enabled. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetEnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Disable Interrupt - \details Disables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_DisableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - __DSB(); - __ISB(); - } -} - - -/** - \brief Get Pending Interrupt - \details Reads the NVIC pending register and returns the pending bit for the specified device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not pending. - \return 1 Interrupt status is pending. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Pending Interrupt - \details Sets the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_SetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Clear Pending Interrupt - \details Clears the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_ClearPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Active Interrupt - \details Reads the active register in the NVIC and returns the active bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not active. - \return 1 Interrupt status is active. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetActive(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Interrupt Priority - \details Sets the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \param [in] priority Priority to set. - \note The priority cannot be set for every processor exception. - */ -__STATIC_INLINE void __NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->IP[((uint32_t)IRQn)] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); - } - else - { - SCB->SHP[(((uint32_t)IRQn) & 0xFUL)-4UL] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); - } -} - - -/** - \brief Get Interrupt Priority - \details Reads the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Interrupt Priority. - Value is aligned automatically to the implemented priority bits of the microcontroller. - */ -__STATIC_INLINE uint32_t __NVIC_GetPriority(IRQn_Type IRQn) -{ - - if ((int32_t)(IRQn) >= 0) - { - return(((uint32_t)NVIC->IP[((uint32_t)IRQn)] >> (8U - __NVIC_PRIO_BITS))); - } - else - { - return(((uint32_t)SCB->SHP[(((uint32_t)IRQn) & 0xFUL)-4UL] >> (8U - __NVIC_PRIO_BITS))); - } -} - - -/** - \brief Encode Priority - \details Encodes the priority for an interrupt with the given priority group, - preemptive priority value, and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. - \param [in] PriorityGroup Used priority group. - \param [in] PreemptPriority Preemptive priority value (starting from 0). - \param [in] SubPriority Subpriority value (starting from 0). - \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority(). - */ -__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - return ( - ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | - ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) - ); -} - - -/** - \brief Decode Priority - \details Decodes an interrupt priority value with a given priority group to - preemptive priority value and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set. - \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority(). - \param [in] PriorityGroup Used priority group. - \param [out] pPreemptPriority Preemptive priority value (starting from 0). - \param [out] pSubPriority Subpriority value (starting from 0). - */ -__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* const pPreemptPriority, uint32_t* const pSubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - *pPreemptPriority = (Priority >> SubPriorityBits) & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL); - *pSubPriority = (Priority ) & (uint32_t)((1UL << (SubPriorityBits )) - 1UL); -} - - -/** - \brief Set Interrupt Vector - \details Sets an interrupt vector in SRAM based interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - VTOR must been relocated to SRAM before. - \param [in] IRQn Interrupt number - \param [in] vector Address of interrupt handler function - */ -__STATIC_INLINE void __NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) -{ - uint32_t vectors = (uint32_t )SCB->VTOR; - (* (int *) (vectors + ((int32_t)IRQn + NVIC_USER_IRQ_OFFSET) * 4)) = vector; - /* ARM Application Note 321 states that the M4 does not require the architectural barrier */ -} - - -/** - \brief Get Interrupt Vector - \details Reads an interrupt vector from interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Address of interrupt handler function - */ -__STATIC_INLINE uint32_t __NVIC_GetVector(IRQn_Type IRQn) -{ - uint32_t vectors = (uint32_t )SCB->VTOR; - return (uint32_t)(* (int *) (vectors + ((int32_t)IRQn + NVIC_USER_IRQ_OFFSET) * 4)); -} - - -/** - \brief System Reset - \details Initiates a system reset request to reset the MCU. - */ -__NO_RETURN __STATIC_INLINE void __NVIC_SystemReset(void) -{ - __DSB(); /* Ensure all outstanding memory accesses included - buffered write are completed before reset */ - SCB->AIRCR = (uint32_t)((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) | - SCB_AIRCR_SYSRESETREQ_Msk ); /* Keep priority group unchanged */ - __DSB(); /* Ensure completion of memory access */ - - for(;;) /* wait until reset */ - { - __NOP(); - } -} - -/*@} end of CMSIS_Core_NVICFunctions */ - - -/* ########################## MPU functions #################################### */ - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - -#include "mpu_armv7.h" - -#endif - - -/* ########################## FPU functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_FpuFunctions FPU Functions - \brief Function that provides FPU type. - @{ - */ - -/** - \brief get FPU type - \details returns the FPU type - \returns - - \b 0: No FPU - - \b 1: Single precision FPU - - \b 2: Double + Single precision FPU - */ -__STATIC_INLINE uint32_t SCB_GetFPUType(void) -{ - uint32_t mvfr0; - - mvfr0 = FPU->MVFR0; - if ((mvfr0 & (FPU_MVFR0_Single_precision_Msk | FPU_MVFR0_Double_precision_Msk)) == 0x020U) - { - return 1U; /* Single precision FPU */ - } - else - { - return 0U; /* No FPU */ - } -} - - -/*@} end of CMSIS_Core_FpuFunctions */ - - - -/* ################################## SysTick function ############################################ */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_SysTickFunctions SysTick Functions - \brief Functions that configure the System. - @{ - */ - -#if defined (__Vendor_SysTickConfig) && (__Vendor_SysTickConfig == 0U) - -/** - \brief System Tick Configuration - \details Initializes the System Timer and its interrupt, and starts the System Tick Timer. - Counter is in free running mode to generate periodic interrupts. - \param [in] ticks Number of ticks between two interrupts. - \return 0 Function succeeded. - \return 1 Function failed. - \note When the variable __Vendor_SysTickConfig is set to 1, then the - function SysTick_Config is not included. In this case, the file device.h - must contain a vendor-specific implementation of this function. - */ -__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) -{ - if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) - { - return (1UL); /* Reload value impossible */ - } - - SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ - NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ - SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ - SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | - SysTick_CTRL_TICKINT_Msk | - SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ - return (0UL); /* Function successful */ -} - -#endif - -/*@} end of CMSIS_Core_SysTickFunctions */ - - - -/* ##################################### Debug In/Output function ########################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_core_DebugFunctions ITM Functions - \brief Functions that access the ITM debug interface. - @{ - */ - -extern volatile int32_t ITM_RxBuffer; /*!< External variable to receive characters. */ -#define ITM_RXBUFFER_EMPTY ((int32_t)0x5AA55AA5U) /*!< Value identifying \ref ITM_RxBuffer is ready for next character. */ - - -/** - \brief ITM Send Character - \details Transmits a character via the ITM channel 0, and - \li Just returns when no debugger is connected that has booked the output. - \li Is blocking when a debugger is connected, but the previous character sent has not been transmitted. - \param [in] ch Character to transmit. - \returns Character to transmit. - */ -__STATIC_INLINE uint32_t ITM_SendChar (uint32_t ch) -{ - if (((ITM->TCR & ITM_TCR_ITMENA_Msk) != 0UL) && /* ITM enabled */ - ((ITM->TER & 1UL ) != 0UL) ) /* ITM Port #0 enabled */ - { - while (ITM->PORT[0U].u32 == 0UL) - { - __NOP(); - } - ITM->PORT[0U].u8 = (uint8_t)ch; - } - return (ch); -} - - -/** - \brief ITM Receive Character - \details Inputs a character via the external variable \ref ITM_RxBuffer. - \return Received character. - \return -1 No character pending. - */ -__STATIC_INLINE int32_t ITM_ReceiveChar (void) -{ - int32_t ch = -1; /* no character available */ - - if (ITM_RxBuffer != ITM_RXBUFFER_EMPTY) - { - ch = ITM_RxBuffer; - ITM_RxBuffer = ITM_RXBUFFER_EMPTY; /* ready for next character */ - } - - return (ch); -} - - -/** - \brief ITM Check Character - \details Checks whether a character is pending for reading in the variable \ref ITM_RxBuffer. - \return 0 No character available. - \return 1 Character available. - */ -__STATIC_INLINE int32_t ITM_CheckChar (void) -{ - - if (ITM_RxBuffer == ITM_RXBUFFER_EMPTY) - { - return (0); /* no character available */ - } - else - { - return (1); /* character available */ - } -} - -/*@} end of CMSIS_core_DebugFunctions */ - - - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_CM4_H_DEPENDANT */ - -#endif /* __CMSIS_GENERIC */ - diff --git a/panda/board/stm32fx/inc/mpu_armv7.h b/panda/board/stm32fx/inc/mpu_armv7.h deleted file mode 100644 index e72cc4623..000000000 --- a/panda/board/stm32fx/inc/mpu_armv7.h +++ /dev/null @@ -1,273 +0,0 @@ -/****************************************************************************** - * @file mpu_armv7.h - * @brief CMSIS MPU API for Armv7-M MPU - * @version V5.1.0 - * @date 08. March 2019 - ******************************************************************************/ -/* - * Copyright (c) 2017-2019 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed under the Apache License, Version 2.0 (the License); you may - * not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an AS IS BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined (__clang__) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef ARM_MPU_ARMV7_H -#define ARM_MPU_ARMV7_H - -#define ARM_MPU_REGION_SIZE_32B ((uint8_t)0x04U) ///!< MPU Region Size 32 Bytes -#define ARM_MPU_REGION_SIZE_64B ((uint8_t)0x05U) ///!< MPU Region Size 64 Bytes -#define ARM_MPU_REGION_SIZE_128B ((uint8_t)0x06U) ///!< MPU Region Size 128 Bytes -#define ARM_MPU_REGION_SIZE_256B ((uint8_t)0x07U) ///!< MPU Region Size 256 Bytes -#define ARM_MPU_REGION_SIZE_512B ((uint8_t)0x08U) ///!< MPU Region Size 512 Bytes -#define ARM_MPU_REGION_SIZE_1KB ((uint8_t)0x09U) ///!< MPU Region Size 1 KByte -#define ARM_MPU_REGION_SIZE_2KB ((uint8_t)0x0AU) ///!< MPU Region Size 2 KBytes -#define ARM_MPU_REGION_SIZE_4KB ((uint8_t)0x0BU) ///!< MPU Region Size 4 KBytes -#define ARM_MPU_REGION_SIZE_8KB ((uint8_t)0x0CU) ///!< MPU Region Size 8 KBytes -#define ARM_MPU_REGION_SIZE_16KB ((uint8_t)0x0DU) ///!< MPU Region Size 16 KBytes -#define ARM_MPU_REGION_SIZE_32KB ((uint8_t)0x0EU) ///!< MPU Region Size 32 KBytes -#define ARM_MPU_REGION_SIZE_64KB ((uint8_t)0x0FU) ///!< MPU Region Size 64 KBytes -#define ARM_MPU_REGION_SIZE_128KB ((uint8_t)0x10U) ///!< MPU Region Size 128 KBytes -#define ARM_MPU_REGION_SIZE_256KB ((uint8_t)0x11U) ///!< MPU Region Size 256 KBytes -#define ARM_MPU_REGION_SIZE_512KB ((uint8_t)0x12U) ///!< MPU Region Size 512 KBytes -#define ARM_MPU_REGION_SIZE_1MB ((uint8_t)0x13U) ///!< MPU Region Size 1 MByte -#define ARM_MPU_REGION_SIZE_2MB ((uint8_t)0x14U) ///!< MPU Region Size 2 MBytes -#define ARM_MPU_REGION_SIZE_4MB ((uint8_t)0x15U) ///!< MPU Region Size 4 MBytes -#define ARM_MPU_REGION_SIZE_8MB ((uint8_t)0x16U) ///!< MPU Region Size 8 MBytes -#define ARM_MPU_REGION_SIZE_16MB ((uint8_t)0x17U) ///!< MPU Region Size 16 MBytes -#define ARM_MPU_REGION_SIZE_32MB ((uint8_t)0x18U) ///!< MPU Region Size 32 MBytes -#define ARM_MPU_REGION_SIZE_64MB ((uint8_t)0x19U) ///!< MPU Region Size 64 MBytes -#define ARM_MPU_REGION_SIZE_128MB ((uint8_t)0x1AU) ///!< MPU Region Size 128 MBytes -#define ARM_MPU_REGION_SIZE_256MB ((uint8_t)0x1BU) ///!< MPU Region Size 256 MBytes -#define ARM_MPU_REGION_SIZE_512MB ((uint8_t)0x1CU) ///!< MPU Region Size 512 MBytes -#define ARM_MPU_REGION_SIZE_1GB ((uint8_t)0x1DU) ///!< MPU Region Size 1 GByte -#define ARM_MPU_REGION_SIZE_2GB ((uint8_t)0x1EU) ///!< MPU Region Size 2 GBytes -#define ARM_MPU_REGION_SIZE_4GB ((uint8_t)0x1FU) ///!< MPU Region Size 4 GBytes - -#define ARM_MPU_AP_NONE 0U ///!< MPU Access Permission no access -#define ARM_MPU_AP_PRIV 1U ///!< MPU Access Permission privileged access only -#define ARM_MPU_AP_URO 2U ///!< MPU Access Permission unprivileged access read-only -#define ARM_MPU_AP_FULL 3U ///!< MPU Access Permission full access -#define ARM_MPU_AP_PRO 5U ///!< MPU Access Permission privileged access read-only -#define ARM_MPU_AP_RO 6U ///!< MPU Access Permission read-only access - -/** MPU Region Base Address Register Value -* -* \param Region The region to be configured, number 0 to 15. -* \param BaseAddress The base address for the region. -*/ -#define ARM_MPU_RBAR(Region, BaseAddress) \ - (((BaseAddress) & MPU_RBAR_ADDR_Msk) | \ - ((Region) & MPU_RBAR_REGION_Msk) | \ - (MPU_RBAR_VALID_Msk)) - -/** -* MPU Memory Access Attributes -* -* \param TypeExtField Type extension field, allows you to configure memory access type, for example strongly ordered, peripheral. -* \param IsShareable Region is shareable between multiple bus masters. -* \param IsCacheable Region is cacheable, i.e. its value may be kept in cache. -* \param IsBufferable Region is bufferable, i.e. using write-back caching. Cacheable but non-bufferable regions use write-through policy. -*/ -#define ARM_MPU_ACCESS_(TypeExtField, IsShareable, IsCacheable, IsBufferable) \ - ((((TypeExtField) << MPU_RASR_TEX_Pos) & MPU_RASR_TEX_Msk) | \ - (((IsShareable) << MPU_RASR_S_Pos) & MPU_RASR_S_Msk) | \ - (((IsCacheable) << MPU_RASR_C_Pos) & MPU_RASR_C_Msk) | \ - (((IsBufferable) << MPU_RASR_B_Pos) & MPU_RASR_B_Msk)) - -/** -* MPU Region Attribute and Size Register Value -* -* \param DisableExec Instruction access disable bit, 1= disable instruction fetches. -* \param AccessPermission Data access permissions, allows you to configure read/write access for User and Privileged mode. -* \param AccessAttributes Memory access attribution, see \ref ARM_MPU_ACCESS_. -* \param SubRegionDisable Sub-region disable field. -* \param Size Region size of the region to be configured, for example 4K, 8K. -*/ -#define ARM_MPU_RASR_EX(DisableExec, AccessPermission, AccessAttributes, SubRegionDisable, Size) \ - ((((DisableExec) << MPU_RASR_XN_Pos) & MPU_RASR_XN_Msk) | \ - (((AccessPermission) << MPU_RASR_AP_Pos) & MPU_RASR_AP_Msk) | \ - (((AccessAttributes) & (MPU_RASR_TEX_Msk | MPU_RASR_S_Msk | MPU_RASR_C_Msk | MPU_RASR_B_Msk))) | \ - (((SubRegionDisable) << MPU_RASR_SRD_Pos) & MPU_RASR_SRD_Msk) | \ - (((Size) << MPU_RASR_SIZE_Pos) & MPU_RASR_SIZE_Msk) | \ - (((MPU_RASR_ENABLE_Msk)))) - -/** -* MPU Region Attribute and Size Register Value -* -* \param DisableExec Instruction access disable bit, 1= disable instruction fetches. -* \param AccessPermission Data access permissions, allows you to configure read/write access for User and Privileged mode. -* \param TypeExtField Type extension field, allows you to configure memory access type, for example strongly ordered, peripheral. -* \param IsShareable Region is shareable between multiple bus masters. -* \param IsCacheable Region is cacheable, i.e. its value may be kept in cache. -* \param IsBufferable Region is bufferable, i.e. using write-back caching. Cacheable but non-bufferable regions use write-through policy. -* \param SubRegionDisable Sub-region disable field. -* \param Size Region size of the region to be configured, for example 4K, 8K. -*/ -#define ARM_MPU_RASR(DisableExec, AccessPermission, TypeExtField, IsShareable, IsCacheable, IsBufferable, SubRegionDisable, Size) \ - ARM_MPU_RASR_EX(DisableExec, AccessPermission, ARM_MPU_ACCESS_(TypeExtField, IsShareable, IsCacheable, IsBufferable), SubRegionDisable, Size) - -/** -* MPU Memory Access Attribute for strongly ordered memory. -* - TEX: 000b -* - Shareable -* - Non-cacheable -* - Non-bufferable -*/ -#define ARM_MPU_ACCESS_ORDERED ARM_MPU_ACCESS_(0U, 1U, 0U, 0U) - -/** -* MPU Memory Access Attribute for device memory. -* - TEX: 000b (if shareable) or 010b (if non-shareable) -* - Shareable or non-shareable -* - Non-cacheable -* - Bufferable (if shareable) or non-bufferable (if non-shareable) -* -* \param IsShareable Configures the device memory as shareable or non-shareable. -*/ -#define ARM_MPU_ACCESS_DEVICE(IsShareable) ((IsShareable) ? ARM_MPU_ACCESS_(0U, 1U, 0U, 1U) : ARM_MPU_ACCESS_(2U, 0U, 0U, 0U)) - -/** -* MPU Memory Access Attribute for normal memory. -* - TEX: 1BBb (reflecting outer cacheability rules) -* - Shareable or non-shareable -* - Cacheable or non-cacheable (reflecting inner cacheability rules) -* - Bufferable or non-bufferable (reflecting inner cacheability rules) -* -* \param OuterCp Configures the outer cache policy. -* \param InnerCp Configures the inner cache policy. -* \param IsShareable Configures the memory as shareable or non-shareable. -*/ -#define ARM_MPU_ACCESS_NORMAL(OuterCp, InnerCp, IsShareable) ARM_MPU_ACCESS_((4U | (OuterCp)), IsShareable, ((InnerCp) & 2U), ((InnerCp) & 1U)) - -/** -* MPU Memory Access Attribute non-cacheable policy. -*/ -#define ARM_MPU_CACHEP_NOCACHE 0U - -/** -* MPU Memory Access Attribute write-back, write and read allocate policy. -*/ -#define ARM_MPU_CACHEP_WB_WRA 1U - -/** -* MPU Memory Access Attribute write-through, no write allocate policy. -*/ -#define ARM_MPU_CACHEP_WT_NWA 2U - -/** -* MPU Memory Access Attribute write-back, no write allocate policy. -*/ -#define ARM_MPU_CACHEP_WB_NWA 3U - - -/** -* Struct for a single MPU Region -*/ -typedef struct { - uint32_t RBAR; //!< The region base address register value (RBAR) - uint32_t RASR; //!< The region attribute and size register value (RASR) \ref MPU_RASR -} ARM_MPU_Region_t; - -/** Enable the MPU. -* \param MPU_Control Default access permissions for unconfigured regions. -*/ -__STATIC_INLINE void ARM_MPU_Enable(uint32_t MPU_Control) -{ - MPU->CTRL = MPU_Control | MPU_CTRL_ENABLE_Msk; -#ifdef SCB_SHCSR_MEMFAULTENA_Msk - SCB->SHCSR |= SCB_SHCSR_MEMFAULTENA_Msk; -#endif - __DSB(); - __ISB(); -} - -/** Disable the MPU. -*/ -__STATIC_INLINE void ARM_MPU_Disable(void) -{ - __DMB(); -#ifdef SCB_SHCSR_MEMFAULTENA_Msk - SCB->SHCSR &= ~SCB_SHCSR_MEMFAULTENA_Msk; -#endif - MPU->CTRL &= ~MPU_CTRL_ENABLE_Msk; -} - -/** Clear and disable the given MPU region. -* \param rnr Region number to be cleared. -*/ -__STATIC_INLINE void ARM_MPU_ClrRegion(uint32_t rnr) -{ - MPU->RNR = rnr; - MPU->RASR = 0U; -} - -/** Configure an MPU region. -* \param rbar Value for RBAR register. -* \param rsar Value for RSAR register. -*/ -__STATIC_INLINE void ARM_MPU_SetRegion(uint32_t rbar, uint32_t rasr) -{ - MPU->RBAR = rbar; - MPU->RASR = rasr; -} - -/** Configure the given MPU region. -* \param rnr Region number to be configured. -* \param rbar Value for RBAR register. -* \param rsar Value for RSAR register. -*/ -__STATIC_INLINE void ARM_MPU_SetRegionEx(uint32_t rnr, uint32_t rbar, uint32_t rasr) -{ - MPU->RNR = rnr; - MPU->RBAR = rbar; - MPU->RASR = rasr; -} - -/** Memcopy with strictly ordered memory access, e.g. for register targets. -* \param dst Destination data is copied to. -* \param src Source data is copied from. -* \param len Amount of data words to be copied. -*/ -__STATIC_INLINE void ARM_MPU_OrderedMemcpy(volatile uint32_t* dst, const uint32_t* __RESTRICT src, uint32_t len) -{ - uint32_t i; - for (i = 0U; i < len; ++i) - { - dst[i] = src[i]; - } -} - -/** Load the given number of MPU regions from a table. -* \param table Pointer to the MPU configuration table. -* \param cnt Amount of regions to be configured. -*/ -__STATIC_INLINE void ARM_MPU_Load(ARM_MPU_Region_t const* table, uint32_t cnt) -{ - const uint32_t rowWordSize = sizeof(ARM_MPU_Region_t)/4U; - while (cnt > MPU_TYPE_RALIASES) { - ARM_MPU_OrderedMemcpy(&(MPU->RBAR), &(table->RBAR), MPU_TYPE_RALIASES*rowWordSize); - table += MPU_TYPE_RALIASES; - cnt -= MPU_TYPE_RALIASES; - } - ARM_MPU_OrderedMemcpy(&(MPU->RBAR), &(table->RBAR), cnt*rowWordSize); -} - -#endif - diff --git a/panda/board/stm32fx/inc/stm32f205xx.h b/panda/board/stm32fx/inc/stm32f205xx.h deleted file mode 100644 index 368bcf39e..000000000 --- a/panda/board/stm32fx/inc/stm32f205xx.h +++ /dev/null @@ -1,7668 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f205xx.h - * @author MCD Application Team - * @version V2.1.2 - * @date 29-June-2016 - * @brief CMSIS STM32F205xx Device Peripheral Access Layer Header File. - * This file contains : - * - Data structures and the address mapping for all peripherals - * - Peripherals registers declarations and bits definition - * - Macros to access peripheral's registers hardware - * - ****************************************************************************** - * @attention - * - *

© COPYRIGHT(c) 2016 STMicroelectronics

- * - * 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. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * 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 HOLDER 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. - * - ****************************************************************************** - */ - -/** @addtogroup CMSIS - * @{ - */ - -/** @addtogroup stm32f205xx - * @{ - */ - -#ifndef __STM32F205xx_H -#define __STM32F205xx_H - -#ifdef __cplusplus - extern "C" { -#endif /* __cplusplus */ - - -/** @addtogroup Configuration_section_for_CMSIS - * @{ - */ - -/** - * @brief Configuration of the Cortex-M3 Processor and Core Peripherals - */ -#define __CM3_REV 0x0200U /*!< Core revision r0p1 */ -#define __MPU_PRESENT 1U /*!< STM32F2XX provides an MPU */ -#define __NVIC_PRIO_BITS 4U /*!< STM32F2XX uses 4 Bits for the Priority Levels */ -#define __Vendor_SysTickConfig 0U /*!< Set to 1 if different SysTick Config is used */ - -/** - * @} - */ - -/** @addtogroup Peripheral_interrupt_number_definition - * @{ - */ - -/** - * @brief STM32F2XX Interrupt Number Definition, according to the selected device - * in @ref Library_configuration_section - */ -typedef enum -{ -/****** Cortex-M3 Processor Exceptions Numbers ****************************************************************/ - NonMaskableInt_IRQn = -14, /*!< 2 Non Maskable Interrupt */ - MemoryManagement_IRQn = -12, /*!< 4 Cortex-M3 Memory Management Interrupt */ - BusFault_IRQn = -11, /*!< 5 Cortex-M3 Bus Fault Interrupt */ - UsageFault_IRQn = -10, /*!< 6 Cortex-M3 Usage Fault Interrupt */ - SVCall_IRQn = -5, /*!< 11 Cortex-M3 SV Call Interrupt */ - DebugMonitor_IRQn = -4, /*!< 12 Cortex-M3 Debug Monitor Interrupt */ - PendSV_IRQn = -2, /*!< 14 Cortex-M3 Pend SV Interrupt */ - SysTick_IRQn = -1, /*!< 15 Cortex-M3 System Tick Interrupt */ -/****** STM32 specific Interrupt Numbers **********************************************************************/ - WWDG_IRQn = 0, /*!< Window WatchDog Interrupt */ - PVD_IRQn = 1, /*!< PVD through EXTI Line detection Interrupt */ - TAMP_STAMP_IRQn = 2, /*!< Tamper and TimeStamp interrupts through the EXTI line */ - RTC_WKUP_IRQn = 3, /*!< RTC Wakeup interrupt through the EXTI line */ - FLASH_IRQn = 4, /*!< FLASH global Interrupt */ - RCC_IRQn = 5, /*!< RCC global Interrupt */ - EXTI0_IRQn = 6, /*!< EXTI Line0 Interrupt */ - EXTI1_IRQn = 7, /*!< EXTI Line1 Interrupt */ - EXTI2_IRQn = 8, /*!< EXTI Line2 Interrupt */ - EXTI3_IRQn = 9, /*!< EXTI Line3 Interrupt */ - EXTI4_IRQn = 10, /*!< EXTI Line4 Interrupt */ - DMA1_Stream0_IRQn = 11, /*!< DMA1 Stream 0 global Interrupt */ - DMA1_Stream1_IRQn = 12, /*!< DMA1 Stream 1 global Interrupt */ - DMA1_Stream2_IRQn = 13, /*!< DMA1 Stream 2 global Interrupt */ - DMA1_Stream3_IRQn = 14, /*!< DMA1 Stream 3 global Interrupt */ - DMA1_Stream4_IRQn = 15, /*!< DMA1 Stream 4 global Interrupt */ - DMA1_Stream5_IRQn = 16, /*!< DMA1 Stream 5 global Interrupt */ - DMA1_Stream6_IRQn = 17, /*!< DMA1 Stream 6 global Interrupt */ - ADC_IRQn = 18, /*!< ADC1, ADC2 and ADC3 global Interrupts */ - CAN1_TX_IRQn = 19, /*!< CAN1 TX Interrupt */ - CAN1_RX0_IRQn = 20, /*!< CAN1 RX0 Interrupt */ - CAN1_RX1_IRQn = 21, /*!< CAN1 RX1 Interrupt */ - CAN1_SCE_IRQn = 22, /*!< CAN1 SCE Interrupt */ - EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ - TIM1_BRK_TIM9_IRQn = 24, /*!< TIM1 Break interrupt and TIM9 global interrupt */ - TIM1_UP_TIM10_IRQn = 25, /*!< TIM1 Update Interrupt and TIM10 global interrupt */ - TIM1_TRG_COM_TIM11_IRQn = 26, /*!< TIM1 Trigger and Commutation Interrupt and TIM11 global interrupt */ - TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ - TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ - TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ - TIM4_IRQn = 30, /*!< TIM4 global Interrupt */ - I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ - I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ - I2C2_EV_IRQn = 33, /*!< I2C2 Event Interrupt */ - I2C2_ER_IRQn = 34, /*!< I2C2 Error Interrupt */ - SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ - SPI2_IRQn = 36, /*!< SPI2 global Interrupt */ - USART1_IRQn = 37, /*!< USART1 global Interrupt */ - USART2_IRQn = 38, /*!< USART2 global Interrupt */ - USART3_IRQn = 39, /*!< USART3 global Interrupt */ - EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ - RTC_Alarm_IRQn = 41, /*!< RTC Alarm (A and B) through EXTI Line Interrupt */ - OTG_FS_WKUP_IRQn = 42, /*!< USB OTG FS Wakeup through EXTI line interrupt */ - TIM8_BRK_TIM12_IRQn = 43, /*!< TIM8 Break Interrupt and TIM12 global interrupt */ - TIM8_UP_TIM13_IRQn = 44, /*!< TIM8 Update Interrupt and TIM13 global interrupt */ - TIM8_TRG_COM_TIM14_IRQn = 45, /*!< TIM8 Trigger and Commutation Interrupt and TIM14 global interrupt */ - TIM8_CC_IRQn = 46, /*!< TIM8 Capture Compare Interrupt */ - DMA1_Stream7_IRQn = 47, /*!< DMA1 Stream7 Interrupt */ - FSMC_IRQn = 48, /*!< FSMC global Interrupt */ - SDIO_IRQn = 49, /*!< SDIO global Interrupt */ - TIM5_IRQn = 50, /*!< TIM5 global Interrupt */ - SPI3_IRQn = 51, /*!< SPI3 global Interrupt */ - UART4_IRQn = 52, /*!< UART4 global Interrupt */ - UART5_IRQn = 53, /*!< UART5 global Interrupt */ - TIM6_DAC_IRQn = 54, /*!< TIM6 global and DAC1&2 underrun error interrupts */ - TIM7_IRQn = 55, /*!< TIM7 global interrupt */ - DMA2_Stream0_IRQn = 56, /*!< DMA2 Stream 0 global Interrupt */ - DMA2_Stream1_IRQn = 57, /*!< DMA2 Stream 1 global Interrupt */ - DMA2_Stream2_IRQn = 58, /*!< DMA2 Stream 2 global Interrupt */ - DMA2_Stream3_IRQn = 59, /*!< DMA2 Stream 3 global Interrupt */ - DMA2_Stream4_IRQn = 60, /*!< DMA2 Stream 4 global Interrupt */ - CAN2_TX_IRQn = 63, /*!< CAN2 TX Interrupt */ - CAN2_RX0_IRQn = 64, /*!< CAN2 RX0 Interrupt */ - CAN2_RX1_IRQn = 65, /*!< CAN2 RX1 Interrupt */ - CAN2_SCE_IRQn = 66, /*!< CAN2 SCE Interrupt */ - OTG_FS_IRQn = 67, /*!< USB OTG FS global Interrupt */ - DMA2_Stream5_IRQn = 68, /*!< DMA2 Stream 5 global interrupt */ - DMA2_Stream6_IRQn = 69, /*!< DMA2 Stream 6 global interrupt */ - DMA2_Stream7_IRQn = 70, /*!< DMA2 Stream 7 global interrupt */ - USART6_IRQn = 71, /*!< USART6 global interrupt */ - I2C3_EV_IRQn = 72, /*!< I2C3 event interrupt */ - I2C3_ER_IRQn = 73, /*!< I2C3 error interrupt */ - OTG_HS_EP1_OUT_IRQn = 74, /*!< USB OTG HS End Point 1 Out global interrupt */ - OTG_HS_EP1_IN_IRQn = 75, /*!< USB OTG HS End Point 1 In global interrupt */ - OTG_HS_WKUP_IRQn = 76, /*!< USB OTG HS Wakeup through EXTI interrupt */ - OTG_HS_IRQn = 77, /*!< USB OTG HS global interrupt */ - HASH_RNG_IRQn = 80 /*!< Hash and RNG global interrupt */ -} IRQn_Type; - -/** - * @} - */ - -#include "core_cm3.h" -#include "system_stm32f2xx.h" -#include - -/** @addtogroup Peripheral_registers_structures - * @{ - */ - -/** - * @brief Analog to Digital Converter - */ - -typedef struct -{ - __IO uint32_t SR; /*!< ADC status register, Address offset: 0x00 */ - __IO uint32_t CR1; /*!< ADC control register 1, Address offset: 0x04 */ - __IO uint32_t CR2; /*!< ADC control register 2, Address offset: 0x08 */ - __IO uint32_t SMPR1; /*!< ADC sample time register 1, Address offset: 0x0C */ - __IO uint32_t SMPR2; /*!< ADC sample time register 2, Address offset: 0x10 */ - __IO uint32_t JOFR1; /*!< ADC injected channel data offset register 1, Address offset: 0x14 */ - __IO uint32_t JOFR2; /*!< ADC injected channel data offset register 2, Address offset: 0x18 */ - __IO uint32_t JOFR3; /*!< ADC injected channel data offset register 3, Address offset: 0x1C */ - __IO uint32_t JOFR4; /*!< ADC injected channel data offset register 4, Address offset: 0x20 */ - __IO uint32_t HTR; /*!< ADC watchdog higher threshold register, Address offset: 0x24 */ - __IO uint32_t LTR; /*!< ADC watchdog lower threshold register, Address offset: 0x28 */ - __IO uint32_t SQR1; /*!< ADC regular sequence register 1, Address offset: 0x2C */ - __IO uint32_t SQR2; /*!< ADC regular sequence register 2, Address offset: 0x30 */ - __IO uint32_t SQR3; /*!< ADC regular sequence register 3, Address offset: 0x34 */ - __IO uint32_t JSQR; /*!< ADC injected sequence register, Address offset: 0x38*/ - __IO uint32_t JDR1; /*!< ADC injected data register 1, Address offset: 0x3C */ - __IO uint32_t JDR2; /*!< ADC injected data register 2, Address offset: 0x40 */ - __IO uint32_t JDR3; /*!< ADC injected data register 3, Address offset: 0x44 */ - __IO uint32_t JDR4; /*!< ADC injected data register 4, Address offset: 0x48 */ - __IO uint32_t DR; /*!< ADC regular data register, Address offset: 0x4C */ -} ADC_TypeDef; - -typedef struct -{ - __IO uint32_t CSR; /*!< ADC Common status register, Address offset: ADC1 base address + 0x300 */ - __IO uint32_t CCR; /*!< ADC common control register, Address offset: ADC1 base address + 0x304 */ - __IO uint32_t CDR; /*!< ADC common regular data register for dual - AND triple modes, Address offset: ADC1 base address + 0x308 */ -} ADC_Common_TypeDef; - - -/** - * @brief Controller Area Network TxMailBox - */ - -typedef struct -{ - __IO uint32_t TIR; /*!< CAN TX mailbox identifier register */ - __IO uint32_t TDTR; /*!< CAN mailbox data length control and time stamp register */ - __IO uint32_t TDLR; /*!< CAN mailbox data low register */ - __IO uint32_t TDHR; /*!< CAN mailbox data high register */ -} CAN_TxMailBox_TypeDef; - -/** - * @brief Controller Area Network FIFOMailBox - */ - -typedef struct -{ - __IO uint32_t RIR; /*!< CAN receive FIFO mailbox identifier register */ - __IO uint32_t RDTR; /*!< CAN receive FIFO mailbox data length control and time stamp register */ - __IO uint32_t RDLR; /*!< CAN receive FIFO mailbox data low register */ - __IO uint32_t RDHR; /*!< CAN receive FIFO mailbox data high register */ -} CAN_FIFOMailBox_TypeDef; - -/** - * @brief Controller Area Network FilterRegister - */ - -typedef struct -{ - __IO uint32_t FR1; /*!< CAN Filter bank register 1 */ - __IO uint32_t FR2; /*!< CAN Filter bank register 1 */ -} CAN_FilterRegister_TypeDef; - -/** - * @brief Controller Area Network - */ - -typedef struct -{ - __IO uint32_t MCR; /*!< CAN master control register, Address offset: 0x00 */ - __IO uint32_t MSR; /*!< CAN master status register, Address offset: 0x04 */ - __IO uint32_t TSR; /*!< CAN transmit status register, Address offset: 0x08 */ - __IO uint32_t RF0R; /*!< CAN receive FIFO 0 register, Address offset: 0x0C */ - __IO uint32_t RF1R; /*!< CAN receive FIFO 1 register, Address offset: 0x10 */ - __IO uint32_t IER; /*!< CAN interrupt enable register, Address offset: 0x14 */ - __IO uint32_t ESR; /*!< CAN error status register, Address offset: 0x18 */ - __IO uint32_t BTR; /*!< CAN bit timing register, Address offset: 0x1C */ - uint32_t RESERVED0[88]; /*!< Reserved, 0x020 - 0x17F */ - CAN_TxMailBox_TypeDef sTxMailBox[3]; /*!< CAN Tx MailBox, Address offset: 0x180 - 0x1AC */ - CAN_FIFOMailBox_TypeDef sFIFOMailBox[2]; /*!< CAN FIFO MailBox, Address offset: 0x1B0 - 0x1CC */ - uint32_t RESERVED1[12]; /*!< Reserved, 0x1D0 - 0x1FF */ - __IO uint32_t FMR; /*!< CAN filter master register, Address offset: 0x200 */ - __IO uint32_t FM1R; /*!< CAN filter mode register, Address offset: 0x204 */ - uint32_t RESERVED2; /*!< Reserved, 0x208 */ - __IO uint32_t FS1R; /*!< CAN filter scale register, Address offset: 0x20C */ - uint32_t RESERVED3; /*!< Reserved, 0x210 */ - __IO uint32_t FFA1R; /*!< CAN filter FIFO assignment register, Address offset: 0x214 */ - uint32_t RESERVED4; /*!< Reserved, 0x218 */ - __IO uint32_t FA1R; /*!< CAN filter activation register, Address offset: 0x21C */ - uint32_t RESERVED5[8]; /*!< Reserved, 0x220-0x23F */ - CAN_FilterRegister_TypeDef sFilterRegister[28]; /*!< CAN Filter Register, Address offset: 0x240-0x31C */ -} CAN_TypeDef; - -/** - * @brief CRC calculation unit - */ - -typedef struct -{ - __IO uint32_t DR; /*!< CRC Data register, Address offset: 0x00 */ - __IO uint8_t IDR; /*!< CRC Independent data register, Address offset: 0x04 */ - uint8_t RESERVED0; /*!< Reserved, 0x05 */ - uint16_t RESERVED1; /*!< Reserved, 0x06 */ - __IO uint32_t CR; /*!< CRC Control register, Address offset: 0x08 */ -} CRC_TypeDef; - -/** - * @brief Digital to Analog Converter - */ - -typedef struct -{ - __IO uint32_t CR; /*!< DAC control register, Address offset: 0x00 */ - __IO uint32_t SWTRIGR; /*!< DAC software trigger register, Address offset: 0x04 */ - __IO uint32_t DHR12R1; /*!< DAC channel1 12-bit right-aligned data holding register, Address offset: 0x08 */ - __IO uint32_t DHR12L1; /*!< DAC channel1 12-bit left aligned data holding register, Address offset: 0x0C */ - __IO uint32_t DHR8R1; /*!< DAC channel1 8-bit right aligned data holding register, Address offset: 0x10 */ - __IO uint32_t DHR12R2; /*!< DAC channel2 12-bit right aligned data holding register, Address offset: 0x14 */ - __IO uint32_t DHR12L2; /*!< DAC channel2 12-bit left aligned data holding register, Address offset: 0x18 */ - __IO uint32_t DHR8R2; /*!< DAC channel2 8-bit right-aligned data holding register, Address offset: 0x1C */ - __IO uint32_t DHR12RD; /*!< Dual DAC 12-bit right-aligned data holding register, Address offset: 0x20 */ - __IO uint32_t DHR12LD; /*!< DUAL DAC 12-bit left aligned data holding register, Address offset: 0x24 */ - __IO uint32_t DHR8RD; /*!< DUAL DAC 8-bit right aligned data holding register, Address offset: 0x28 */ - __IO uint32_t DOR1; /*!< DAC channel1 data output register, Address offset: 0x2C */ - __IO uint32_t DOR2; /*!< DAC channel2 data output register, Address offset: 0x30 */ - __IO uint32_t SR; /*!< DAC status register, Address offset: 0x34 */ -} DAC_TypeDef; - -/** - * @brief Debug MCU - */ - -typedef struct -{ - __IO uint32_t IDCODE; /*!< MCU device ID code, Address offset: 0x00 */ - __IO uint32_t CR; /*!< Debug MCU configuration register, Address offset: 0x04 */ - __IO uint32_t APB1FZ; /*!< Debug MCU APB1 freeze register, Address offset: 0x08 */ - __IO uint32_t APB2FZ; /*!< Debug MCU APB2 freeze register, Address offset: 0x0C */ -}DBGMCU_TypeDef; - - -/** - * @brief DMA Controller - */ - -typedef struct -{ - __IO uint32_t CR; /*!< DMA stream x configuration register */ - __IO uint32_t NDTR; /*!< DMA stream x number of data register */ - __IO uint32_t PAR; /*!< DMA stream x peripheral address register */ - __IO uint32_t M0AR; /*!< DMA stream x memory 0 address register */ - __IO uint32_t M1AR; /*!< DMA stream x memory 1 address register */ - __IO uint32_t FCR; /*!< DMA stream x FIFO control register */ -} DMA_Stream_TypeDef; - -typedef struct -{ - __IO uint32_t LISR; /*!< DMA low interrupt status register, Address offset: 0x00 */ - __IO uint32_t HISR; /*!< DMA high interrupt status register, Address offset: 0x04 */ - __IO uint32_t LIFCR; /*!< DMA low interrupt flag clear register, Address offset: 0x08 */ - __IO uint32_t HIFCR; /*!< DMA high interrupt flag clear register, Address offset: 0x0C */ -} DMA_TypeDef; - - -/** - * @brief External Interrupt/Event Controller - */ - -typedef struct -{ - __IO uint32_t IMR; /*!< EXTI Interrupt mask register, Address offset: 0x00 */ - __IO uint32_t EMR; /*!< EXTI Event mask register, Address offset: 0x04 */ - __IO uint32_t RTSR; /*!< EXTI Rising trigger selection register, Address offset: 0x08 */ - __IO uint32_t FTSR; /*!< EXTI Falling trigger selection register, Address offset: 0x0C */ - __IO uint32_t SWIER; /*!< EXTI Software interrupt event register, Address offset: 0x10 */ - __IO uint32_t PR; /*!< EXTI Pending register, Address offset: 0x14 */ -} EXTI_TypeDef; - -/** - * @brief FLASH Registers - */ - -typedef struct -{ - __IO uint32_t ACR; /*!< FLASH access control register, Address offset: 0x00 */ - __IO uint32_t KEYR; /*!< FLASH key register, Address offset: 0x04 */ - __IO uint32_t OPTKEYR; /*!< FLASH option key register, Address offset: 0x08 */ - __IO uint32_t SR; /*!< FLASH status register, Address offset: 0x0C */ - __IO uint32_t CR; /*!< FLASH control register, Address offset: 0x10 */ - __IO uint32_t OPTCR; /*!< FLASH option control register, Address offset: 0x14 */ -} FLASH_TypeDef; - - -/** - * @brief Flexible Static Memory Controller - */ - -typedef struct -{ - __IO uint32_t BTCR[8]; /*!< NOR/PSRAM chip-select control register(BCR) and chip-select timing register(BTR), Address offset: 0x00-1C */ -} FSMC_Bank1_TypeDef; - -/** - * @brief Flexible Static Memory Controller Bank1E - */ - -typedef struct -{ - __IO uint32_t BWTR[7]; /*!< NOR/PSRAM write timing registers, Address offset: 0x104-0x11C */ -} FSMC_Bank1E_TypeDef; - -/** - * @brief Flexible Static Memory Controller Bank2 - */ - -typedef struct -{ - __IO uint32_t PCR2; /*!< NAND Flash control register 2, Address offset: 0x60 */ - __IO uint32_t SR2; /*!< NAND Flash FIFO status and interrupt register 2, Address offset: 0x64 */ - __IO uint32_t PMEM2; /*!< NAND Flash Common memory space timing register 2, Address offset: 0x68 */ - __IO uint32_t PATT2; /*!< NAND Flash Attribute memory space timing register 2, Address offset: 0x6C */ - uint32_t RESERVED0; /*!< Reserved, 0x70 */ - __IO uint32_t ECCR2; /*!< NAND Flash ECC result registers 2, Address offset: 0x74 */ - uint32_t RESERVED1; /*!< Reserved, 0x78 */ - uint32_t RESERVED2; /*!< Reserved, 0x7C */ - __IO uint32_t PCR3; /*!< NAND Flash control register 3, Address offset: 0x80 */ - __IO uint32_t SR3; /*!< NAND Flash FIFO status and interrupt register 3, Address offset: 0x84 */ - __IO uint32_t PMEM3; /*!< NAND Flash Common memory space timing register 3, Address offset: 0x88 */ - __IO uint32_t PATT3; /*!< NAND Flash Attribute memory space timing register 3, Address offset: 0x8C */ - uint32_t RESERVED3; /*!< Reserved, 0x90 */ - __IO uint32_t ECCR3; /*!< NAND Flash ECC result registers 3, Address offset: 0x94 */ -} FSMC_Bank2_3_TypeDef; - -/** - * @brief Flexible Static Memory Controller Bank4 - */ - -typedef struct -{ - __IO uint32_t PCR4; /*!< PC Card control register 4, Address offset: 0xA0 */ - __IO uint32_t SR4; /*!< PC Card FIFO status and interrupt register 4, Address offset: 0xA4 */ - __IO uint32_t PMEM4; /*!< PC Card Common memory space timing register 4, Address offset: 0xA8 */ - __IO uint32_t PATT4; /*!< PC Card Attribute memory space timing register 4, Address offset: 0xAC */ - __IO uint32_t PIO4; /*!< PC Card I/O space timing register 4, Address offset: 0xB0 */ -} FSMC_Bank4_TypeDef; - - -/** - * @brief General Purpose I/O - */ - -typedef struct -{ - __IO uint32_t MODER; /*!< GPIO port mode register, Address offset: 0x00 */ - __IO uint32_t OTYPER; /*!< GPIO port output type register, Address offset: 0x04 */ - __IO uint32_t OSPEEDR; /*!< GPIO port output speed register, Address offset: 0x08 */ - __IO uint32_t PUPDR; /*!< GPIO port pull-up/pull-down register, Address offset: 0x0C */ - __IO uint32_t IDR; /*!< GPIO port input data register, Address offset: 0x10 */ - __IO uint32_t ODR; /*!< GPIO port output data register, Address offset: 0x14 */ - __IO uint32_t BSRR; /*!< GPIO port bit set/reset register, Address offset: 0x18 */ - __IO uint32_t LCKR; /*!< GPIO port configuration lock register, Address offset: 0x1C */ - __IO uint32_t AFR[2]; /*!< GPIO alternate function registers, Address offset: 0x20-0x24 */ -} GPIO_TypeDef; - -/** - * @brief System configuration controller - */ - -typedef struct -{ - __IO uint32_t MEMRMP; /*!< SYSCFG memory remap register, Address offset: 0x00 */ - __IO uint32_t PMC; /*!< SYSCFG peripheral mode configuration register, Address offset: 0x04 */ - __IO uint32_t EXTICR[4]; /*!< SYSCFG external interrupt configuration registers, Address offset: 0x08-0x14 */ - uint32_t RESERVED[2]; /*!< Reserved, 0x18-0x1C */ - __IO uint32_t CMPCR; /*!< SYSCFG Compensation cell control register, Address offset: 0x20 */ -} SYSCFG_TypeDef; - -/** - * @brief Inter-integrated Circuit Interface - */ - -typedef struct -{ - __IO uint32_t CR1; /*!< I2C Control register 1, Address offset: 0x00 */ - __IO uint32_t CR2; /*!< I2C Control register 2, Address offset: 0x04 */ - __IO uint32_t OAR1; /*!< I2C Own address register 1, Address offset: 0x08 */ - __IO uint32_t OAR2; /*!< I2C Own address register 2, Address offset: 0x0C */ - __IO uint32_t DR; /*!< I2C Data register, Address offset: 0x10 */ - __IO uint32_t SR1; /*!< I2C Status register 1, Address offset: 0x14 */ - __IO uint32_t SR2; /*!< I2C Status register 2, Address offset: 0x18 */ - __IO uint32_t CCR; /*!< I2C Clock control register, Address offset: 0x1C */ - __IO uint32_t TRISE; /*!< I2C TRISE register, Address offset: 0x20 */ -} I2C_TypeDef; - -/** - * @brief Independent WATCHDOG - */ - -typedef struct -{ - __IO uint32_t KR; /*!< IWDG Key register, Address offset: 0x00 */ - __IO uint32_t PR; /*!< IWDG Prescaler register, Address offset: 0x04 */ - __IO uint32_t RLR; /*!< IWDG Reload register, Address offset: 0x08 */ - __IO uint32_t SR; /*!< IWDG Status register, Address offset: 0x0C */ -} IWDG_TypeDef; - -/** - * @brief Power Control - */ - -typedef struct -{ - __IO uint32_t CR; /*!< PWR power control register, Address offset: 0x00 */ - __IO uint32_t CSR; /*!< PWR power control/status register, Address offset: 0x04 */ -} PWR_TypeDef; - -/** - * @brief Reset and Clock Control - */ - -typedef struct -{ - __IO uint32_t CR; /*!< RCC clock control register, Address offset: 0x00 */ - __IO uint32_t PLLCFGR; /*!< RCC PLL configuration register, Address offset: 0x04 */ - __IO uint32_t CFGR; /*!< RCC clock configuration register, Address offset: 0x08 */ - __IO uint32_t CIR; /*!< RCC clock interrupt register, Address offset: 0x0C */ - __IO uint32_t AHB1RSTR; /*!< RCC AHB1 peripheral reset register, Address offset: 0x10 */ - __IO uint32_t AHB2RSTR; /*!< RCC AHB2 peripheral reset register, Address offset: 0x14 */ - __IO uint32_t AHB3RSTR; /*!< RCC AHB3 peripheral reset register, Address offset: 0x18 */ - uint32_t RESERVED0; /*!< Reserved, 0x1C */ - __IO uint32_t APB1RSTR; /*!< RCC APB1 peripheral reset register, Address offset: 0x20 */ - __IO uint32_t APB2RSTR; /*!< RCC APB2 peripheral reset register, Address offset: 0x24 */ - uint32_t RESERVED1[2]; /*!< Reserved, 0x28-0x2C */ - __IO uint32_t AHB1ENR; /*!< RCC AHB1 peripheral clock register, Address offset: 0x30 */ - __IO uint32_t AHB2ENR; /*!< RCC AHB2 peripheral clock register, Address offset: 0x34 */ - __IO uint32_t AHB3ENR; /*!< RCC AHB3 peripheral clock register, Address offset: 0x38 */ - uint32_t RESERVED2; /*!< Reserved, 0x3C */ - __IO uint32_t APB1ENR; /*!< RCC APB1 peripheral clock enable register, Address offset: 0x40 */ - __IO uint32_t APB2ENR; /*!< RCC APB2 peripheral clock enable register, Address offset: 0x44 */ - uint32_t RESERVED3[2]; /*!< Reserved, 0x48-0x4C */ - __IO uint32_t AHB1LPENR; /*!< RCC AHB1 peripheral clock enable in low power mode register, Address offset: 0x50 */ - __IO uint32_t AHB2LPENR; /*!< RCC AHB2 peripheral clock enable in low power mode register, Address offset: 0x54 */ - __IO uint32_t AHB3LPENR; /*!< RCC AHB3 peripheral clock enable in low power mode register, Address offset: 0x58 */ - uint32_t RESERVED4; /*!< Reserved, 0x5C */ - __IO uint32_t APB1LPENR; /*!< RCC APB1 peripheral clock enable in low power mode register, Address offset: 0x60 */ - __IO uint32_t APB2LPENR; /*!< RCC APB2 peripheral clock enable in low power mode register, Address offset: 0x64 */ - uint32_t RESERVED5[2]; /*!< Reserved, 0x68-0x6C */ - __IO uint32_t BDCR; /*!< RCC Backup domain control register, Address offset: 0x70 */ - __IO uint32_t CSR; /*!< RCC clock control & status register, Address offset: 0x74 */ - uint32_t RESERVED6[2]; /*!< Reserved, 0x78-0x7C */ - __IO uint32_t SSCGR; /*!< RCC spread spectrum clock generation register, Address offset: 0x80 */ - __IO uint32_t PLLI2SCFGR; /*!< RCC PLLI2S configuration register, Address offset: 0x84 */ - -} RCC_TypeDef; - -/** - * @brief Real-Time Clock - */ - -typedef struct -{ - __IO uint32_t TR; /*!< RTC time register, Address offset: 0x00 */ - __IO uint32_t DR; /*!< RTC date register, Address offset: 0x04 */ - __IO uint32_t CR; /*!< RTC control register, Address offset: 0x08 */ - __IO uint32_t ISR; /*!< RTC initialization and status register, Address offset: 0x0C */ - __IO uint32_t PRER; /*!< RTC prescaler register, Address offset: 0x10 */ - __IO uint32_t WUTR; /*!< RTC wakeup timer register, Address offset: 0x14 */ - __IO uint32_t CALIBR; /*!< RTC calibration register, Address offset: 0x18 */ - __IO uint32_t ALRMAR; /*!< RTC alarm A register, Address offset: 0x1C */ - __IO uint32_t ALRMBR; /*!< RTC alarm B register, Address offset: 0x20 */ - __IO uint32_t WPR; /*!< RTC write protection register, Address offset: 0x24 */ - uint32_t RESERVED1; /*!< Reserved, 0x28 */ - uint32_t RESERVED2; /*!< Reserved, 0x2C */ - __IO uint32_t TSTR; /*!< RTC time stamp time register, Address offset: 0x30 */ - __IO uint32_t TSDR; /*!< RTC time stamp date register, Address offset: 0x34 */ - uint32_t RESERVED3; /*!< Reserved, 0x38 */ - uint32_t RESERVED4; /*!< Reserved, 0x3C */ - __IO uint32_t TAFCR; /*!< RTC tamper and alternate function configuration register, Address offset: 0x40 */ - uint32_t RESERVED5; /*!< Reserved, 0x44 */ - uint32_t RESERVED6; /*!< Reserved, 0x48 */ - uint32_t RESERVED7; /*!< Reserved, 0x4C */ - __IO uint32_t BKP0R; /*!< RTC backup register 1, Address offset: 0x50 */ - __IO uint32_t BKP1R; /*!< RTC backup register 1, Address offset: 0x54 */ - __IO uint32_t BKP2R; /*!< RTC backup register 2, Address offset: 0x58 */ - __IO uint32_t BKP3R; /*!< RTC backup register 3, Address offset: 0x5C */ - __IO uint32_t BKP4R; /*!< RTC backup register 4, Address offset: 0x60 */ - __IO uint32_t BKP5R; /*!< RTC backup register 5, Address offset: 0x64 */ - __IO uint32_t BKP6R; /*!< RTC backup register 6, Address offset: 0x68 */ - __IO uint32_t BKP7R; /*!< RTC backup register 7, Address offset: 0x6C */ - __IO uint32_t BKP8R; /*!< RTC backup register 8, Address offset: 0x70 */ - __IO uint32_t BKP9R; /*!< RTC backup register 9, Address offset: 0x74 */ - __IO uint32_t BKP10R; /*!< RTC backup register 10, Address offset: 0x78 */ - __IO uint32_t BKP11R; /*!< RTC backup register 11, Address offset: 0x7C */ - __IO uint32_t BKP12R; /*!< RTC backup register 12, Address offset: 0x80 */ - __IO uint32_t BKP13R; /*!< RTC backup register 13, Address offset: 0x84 */ - __IO uint32_t BKP14R; /*!< RTC backup register 14, Address offset: 0x88 */ - __IO uint32_t BKP15R; /*!< RTC backup register 15, Address offset: 0x8C */ - __IO uint32_t BKP16R; /*!< RTC backup register 16, Address offset: 0x90 */ - __IO uint32_t BKP17R; /*!< RTC backup register 17, Address offset: 0x94 */ - __IO uint32_t BKP18R; /*!< RTC backup register 18, Address offset: 0x98 */ - __IO uint32_t BKP19R; /*!< RTC backup register 19, Address offset: 0x9C */ -} RTC_TypeDef; - - -/** - * @brief SD host Interface - */ - -typedef struct -{ - __IO uint32_t POWER; /*!< SDIO power control register, Address offset: 0x00 */ - __IO uint32_t CLKCR; /*!< SDI clock control register, Address offset: 0x04 */ - __IO uint32_t ARG; /*!< SDIO argument register, Address offset: 0x08 */ - __IO uint32_t CMD; /*!< SDIO command register, Address offset: 0x0C */ - __IO const uint32_t RESPCMD; /*!< SDIO command response register, Address offset: 0x10 */ - __IO const uint32_t RESP1; /*!< SDIO response 1 register, Address offset: 0x14 */ - __IO const uint32_t RESP2; /*!< SDIO response 2 register, Address offset: 0x18 */ - __IO const uint32_t RESP3; /*!< SDIO response 3 register, Address offset: 0x1C */ - __IO const uint32_t RESP4; /*!< SDIO response 4 register, Address offset: 0x20 */ - __IO uint32_t DTIMER; /*!< SDIO data timer register, Address offset: 0x24 */ - __IO uint32_t DLEN; /*!< SDIO data length register, Address offset: 0x28 */ - __IO uint32_t DCTRL; /*!< SDIO data control register, Address offset: 0x2C */ - __IO const uint32_t DCOUNT; /*!< SDIO data counter register, Address offset: 0x30 */ - __IO const uint32_t STA; /*!< SDIO status register, Address offset: 0x34 */ - __IO uint32_t ICR; /*!< SDIO interrupt clear register, Address offset: 0x38 */ - __IO uint32_t MASK; /*!< SDIO mask register, Address offset: 0x3C */ - uint32_t RESERVED0[2]; /*!< Reserved, 0x40-0x44 */ - __IO const uint32_t FIFOCNT; /*!< SDIO FIFO counter register, Address offset: 0x48 */ - uint32_t RESERVED1[13]; /*!< Reserved, 0x4C-0x7C */ - __IO uint32_t FIFO; /*!< SDIO data FIFO register, Address offset: 0x80 */ -} SDIO_TypeDef; - -/** - * @brief Serial Peripheral Interface - */ - -typedef struct -{ - __IO uint32_t CR1; /*!< SPI control register 1 (not used in I2S mode), Address offset: 0x00 */ - __IO uint32_t CR2; /*!< SPI control register 2, Address offset: 0x04 */ - __IO uint32_t SR; /*!< SPI status register, Address offset: 0x08 */ - __IO uint32_t DR; /*!< SPI data register, Address offset: 0x0C */ - __IO uint32_t CRCPR; /*!< SPI CRC polynomial register (not used in I2S mode), Address offset: 0x10 */ - __IO uint32_t RXCRCR; /*!< SPI RX CRC register (not used in I2S mode), Address offset: 0x14 */ - __IO uint32_t TXCRCR; /*!< SPI TX CRC register (not used in I2S mode), Address offset: 0x18 */ - __IO uint32_t I2SCFGR; /*!< SPI_I2S configuration register, Address offset: 0x1C */ - __IO uint32_t I2SPR; /*!< SPI_I2S prescaler register, Address offset: 0x20 */ -} SPI_TypeDef; - -/** - * @brief TIM - */ - -typedef struct -{ - __IO uint32_t CR1; /*!< TIM control register 1, Address offset: 0x00 */ - __IO uint32_t CR2; /*!< TIM control register 2, Address offset: 0x04 */ - __IO uint32_t SMCR; /*!< TIM slave mode control register, Address offset: 0x08 */ - __IO uint32_t DIER; /*!< TIM DMA/interrupt enable register, Address offset: 0x0C */ - __IO uint32_t SR; /*!< TIM status register, Address offset: 0x10 */ - __IO uint32_t EGR; /*!< TIM event generation register, Address offset: 0x14 */ - __IO uint32_t CCMR1; /*!< TIM capture/compare mode register 1, Address offset: 0x18 */ - __IO uint32_t CCMR2; /*!< TIM capture/compare mode register 2, Address offset: 0x1C */ - __IO uint32_t CCER; /*!< TIM capture/compare enable register, Address offset: 0x20 */ - __IO uint32_t CNT; /*!< TIM counter register, Address offset: 0x24 */ - __IO uint32_t PSC; /*!< TIM prescaler, Address offset: 0x28 */ - __IO uint32_t ARR; /*!< TIM auto-reload register, Address offset: 0x2C */ - __IO uint32_t RCR; /*!< TIM repetition counter register, Address offset: 0x30 */ - __IO uint32_t CCR1; /*!< TIM capture/compare register 1, Address offset: 0x34 */ - __IO uint32_t CCR2; /*!< TIM capture/compare register 2, Address offset: 0x38 */ - __IO uint32_t CCR3; /*!< TIM capture/compare register 3, Address offset: 0x3C */ - __IO uint32_t CCR4; /*!< TIM capture/compare register 4, Address offset: 0x40 */ - __IO uint32_t BDTR; /*!< TIM break and dead-time register, Address offset: 0x44 */ - __IO uint32_t DCR; /*!< TIM DMA control register, Address offset: 0x48 */ - __IO uint32_t DMAR; /*!< TIM DMA address for full transfer, Address offset: 0x4C */ - __IO uint32_t OR; /*!< TIM option register, Address offset: 0x50 */ -} TIM_TypeDef; - -/** - * @brief Universal Synchronous Asynchronous Receiver Transmitter - */ - -typedef struct -{ - __IO uint32_t SR; /*!< USART Status register, Address offset: 0x00 */ - __IO uint32_t DR; /*!< USART Data register, Address offset: 0x04 */ - __IO uint32_t BRR; /*!< USART Baud rate register, Address offset: 0x08 */ - __IO uint32_t CR1; /*!< USART Control register 1, Address offset: 0x0C */ - __IO uint32_t CR2; /*!< USART Control register 2, Address offset: 0x10 */ - __IO uint32_t CR3; /*!< USART Control register 3, Address offset: 0x14 */ - __IO uint32_t GTPR; /*!< USART Guard time and prescaler register, Address offset: 0x18 */ -} USART_TypeDef; - -/** - * @brief Window WATCHDOG - */ - -typedef struct -{ - __IO uint32_t CR; /*!< WWDG Control register, Address offset: 0x00 */ - __IO uint32_t CFR; /*!< WWDG Configuration register, Address offset: 0x04 */ - __IO uint32_t SR; /*!< WWDG Status register, Address offset: 0x08 */ -} WWDG_TypeDef; - - -/** - * @brief RNG - */ - -typedef struct -{ - __IO uint32_t CR; /*!< RNG control register, Address offset: 0x00 */ - __IO uint32_t SR; /*!< RNG status register, Address offset: 0x04 */ - __IO uint32_t DR; /*!< RNG data register, Address offset: 0x08 */ -} RNG_TypeDef; - - - -/** - * @brief __USB_OTG_Core_register - */ -typedef struct -{ - __IO uint32_t GOTGCTL; /*!< USB_OTG Control and Status Register Address offset : 0x00 */ - __IO uint32_t GOTGINT; /*!< USB_OTG Interrupt Register Address offset : 0x04 */ - __IO uint32_t GAHBCFG; /*!< Core AHB Configuration Register Address offset : 0x08 */ - __IO uint32_t GUSBCFG; /*!< Core USB Configuration Register Address offset : 0x0C */ - __IO uint32_t GRSTCTL; /*!< Core Reset Register Address offset : 0x10 */ - __IO uint32_t GINTSTS; /*!< Core Interrupt Register Address offset : 0x14 */ - __IO uint32_t GINTMSK; /*!< Core Interrupt Mask Register Address offset : 0x18 */ - __IO uint32_t GRXSTSR; /*!< Receive Sts Q Read Register Address offset : 0x1C */ - __IO uint32_t GRXSTSP; /*!< Receive Sts Q Read & POP Register Address offset : 0x20 */ - __IO uint32_t GRXFSIZ; /* Receive FIFO Size Register Address offset : 0x24 */ - __IO uint32_t DIEPTXF0_HNPTXFSIZ; /*!< EP0 / Non Periodic Tx FIFO Size Register Address offset : 0x28 */ - __IO uint32_t HNPTXSTS; /*!< Non Periodic Tx FIFO/Queue Sts reg Address offset : 0x2C */ - uint32_t Reserved30[2]; /* Reserved Address offset : 0x30 */ - __IO uint32_t GCCFG; /*!< General Purpose IO Register Address offset : 0x38 */ - __IO uint32_t CID; /*!< User ID Register Address offset : 0x3C */ - uint32_t Reserved40[48]; /*!< Reserved Address offset : 0x40-0xFF */ - __IO uint32_t HPTXFSIZ; /*!< Host Periodic Tx FIFO Size Reg Address offset : 0x100 */ - __IO uint32_t DIEPTXF[0x0F]; /*!< dev Periodic Transmit FIFO */ -} -USB_OTG_GlobalTypeDef; - - - -/** - * @brief __device_Registers - */ -typedef struct -{ - __IO uint32_t DCFG; /*!< dev Configuration Register Address offset : 0x800 */ - __IO uint32_t DCTL; /*!< dev Control Register Address offset : 0x804 */ - __IO uint32_t DSTS; /*!< dev Status Register (RO) Address offset : 0x808 */ - uint32_t Reserved0C; /*!< Reserved Address offset : 0x80C */ - __IO uint32_t DIEPMSK; /* !< dev IN Endpoint Mask Address offset : 0x810 */ - __IO uint32_t DOEPMSK; /*!< dev OUT Endpoint Mask Address offset : 0x814 */ - __IO uint32_t DAINT; /*!< dev All Endpoints Itr Reg Address offset : 0x818 */ - __IO uint32_t DAINTMSK; /*!< dev All Endpoints Itr Mask Address offset : 0x81C */ - uint32_t Reserved20; /*!< Reserved Address offset : 0x820 */ - uint32_t Reserved9; /*!< Reserved Address offset : 0x824 */ - __IO uint32_t DVBUSDIS; /*!< dev VBUS discharge Register Address offset : 0x828 */ - __IO uint32_t DVBUSPULSE; /*!< dev VBUS Pulse Register Address offset : 0x82C */ - __IO uint32_t DTHRCTL; /*!< dev thr Address offset : 0x830 */ - __IO uint32_t DIEPEMPMSK; /*!< dev empty msk Address offset : 0x834 */ - __IO uint32_t DEACHINT; /*!< dedicated EP interrupt Address offset : 0x838 */ - __IO uint32_t DEACHMSK; /*!< dedicated EP msk Address offset : 0x83C */ - uint32_t Reserved40; /*!< dedicated EP mask Address offset : 0x840 */ - __IO uint32_t DINEP1MSK; /*!< dedicated EP mask Address offset : 0x844 */ - uint32_t Reserved44[15]; /*!< Reserved Address offset : 0x844-0x87C */ - __IO uint32_t DOUTEP1MSK; /*!< dedicated EP msk Address offset : 0x884 */ -} -USB_OTG_DeviceTypeDef; - - -/** - * @brief __IN_Endpoint-Specific_Register - */ -typedef struct -{ - __IO uint32_t DIEPCTL; /* dev IN Endpoint Control Reg 900h + (ep_num * 20h) + 00h */ - uint32_t Reserved04; /* Reserved 900h + (ep_num * 20h) + 04h */ - __IO uint32_t DIEPINT; /* dev IN Endpoint Itr Reg 900h + (ep_num * 20h) + 08h */ - uint32_t Reserved0C; /* Reserved 900h + (ep_num * 20h) + 0Ch */ - __IO uint32_t DIEPTSIZ; /* IN Endpoint Txfer Size 900h + (ep_num * 20h) + 10h */ - __IO uint32_t DIEPDMA; /* IN Endpoint DMA Address Reg 900h + (ep_num * 20h) + 14h */ - __IO uint32_t DTXFSTS; /*IN Endpoint Tx FIFO Status Reg 900h + (ep_num * 20h) + 18h */ - uint32_t Reserved18; /* Reserved 900h+(ep_num*20h)+1Ch-900h+ (ep_num * 20h) + 1Ch */ -} -USB_OTG_INEndpointTypeDef; - - -/** - * @brief __OUT_Endpoint-Specific_Registers - */ -typedef struct -{ - __IO uint32_t DOEPCTL; /* dev OUT Endpoint Control Reg B00h + (ep_num * 20h) + 00h*/ - uint32_t Reserved04; /* Reserved B00h + (ep_num * 20h) + 04h*/ - __IO uint32_t DOEPINT; /* dev OUT Endpoint Itr Reg B00h + (ep_num * 20h) + 08h*/ - uint32_t Reserved0C; /* Reserved B00h + (ep_num * 20h) + 0Ch*/ - __IO uint32_t DOEPTSIZ; /* dev OUT Endpoint Txfer Size B00h + (ep_num * 20h) + 10h*/ - __IO uint32_t DOEPDMA; /* dev OUT Endpoint DMA Address B00h + (ep_num * 20h) + 14h*/ - uint32_t Reserved18[2]; /* Reserved B00h + (ep_num * 20h) + 18h - B00h + (ep_num * 20h) + 1Ch*/ -} -USB_OTG_OUTEndpointTypeDef; - - -/** - * @brief __Host_Mode_Register_Structures - */ -typedef struct -{ - __IO uint32_t HCFG; /* Host Configuration Register 400h*/ - __IO uint32_t HFIR; /* Host Frame Interval Register 404h*/ - __IO uint32_t HFNUM; /* Host Frame Nbr/Frame Remaining 408h*/ - uint32_t Reserved40C; /* Reserved 40Ch*/ - __IO uint32_t HPTXSTS; /* Host Periodic Tx FIFO/ Queue Status 410h*/ - __IO uint32_t HAINT; /* Host All Channels Interrupt Register 414h*/ - __IO uint32_t HAINTMSK; /* Host All Channels Interrupt Mask 418h*/ -} -USB_OTG_HostTypeDef; - - -/** - * @brief __Host_Channel_Specific_Registers - */ -typedef struct -{ - __IO uint32_t HCCHAR; - __IO uint32_t HCSPLT; - __IO uint32_t HCINT; - __IO uint32_t HCINTMSK; - __IO uint32_t HCTSIZ; - __IO uint32_t HCDMA; - uint32_t Reserved[2]; -} -USB_OTG_HostChannelTypeDef; - - -/** - * @brief Peripheral_memory_map - */ -#define FLASH_BASE 0x08000000U /*!< FLASH(up to 1 MB) base address in the alias region */ -#define SRAM1_BASE 0x20000000U /*!< SRAM1(112 KB) base address in the alias region */ -#define SRAM2_BASE 0x2001C000U /*!< SRAM2(16 KB) base address in the alias region */ -#define PERIPH_BASE 0x40000000U /*!< Peripheral base address in the alias region */ -#define BKPSRAM_BASE 0x40024000U /*!< Backup SRAM(4 KB) base address in the alias region */ -#define FSMC_R_BASE 0xA0000000U /*!< FSMC registers base address */ -#define SRAM1_BB_BASE 0x22000000U /*!< SRAM1(112 KB) base address in the bit-band region */ -#define SRAM2_BB_BASE 0x22380000U /*!< SRAM2(16 KB) base address in the bit-band region */ -#define PERIPH_BB_BASE 0x42000000U /*!< Peripheral base address in the bit-band region */ -#define BKPSRAM_BB_BASE 0x42480000U /*!< Backup SRAM(4 KB) base address in the bit-band region */ -#define FLASH_END 0x080FFFFFU /*!< FLASH end address */ - -/* Legacy defines */ -#define SRAM_BASE SRAM1_BASE -#define SRAM_BB_BASE SRAM1_BB_BASE - - -/*!< Peripheral memory map */ -#define APB1PERIPH_BASE PERIPH_BASE -#define APB2PERIPH_BASE (PERIPH_BASE + 0x00010000U) -#define AHB1PERIPH_BASE (PERIPH_BASE + 0x00020000U) -#define AHB2PERIPH_BASE (PERIPH_BASE + 0x10000000U) - -/*!< APB1 peripherals */ -#define TIM2_BASE (APB1PERIPH_BASE + 0x0000U) -#define TIM3_BASE (APB1PERIPH_BASE + 0x0400U) -#define TIM4_BASE (APB1PERIPH_BASE + 0x0800U) -#define TIM5_BASE (APB1PERIPH_BASE + 0x0C00U) -#define TIM6_BASE (APB1PERIPH_BASE + 0x1000U) -#define TIM7_BASE (APB1PERIPH_BASE + 0x1400U) -#define TIM12_BASE (APB1PERIPH_BASE + 0x1800U) -#define TIM13_BASE (APB1PERIPH_BASE + 0x1C00U) -#define TIM14_BASE (APB1PERIPH_BASE + 0x2000U) -#define RTC_BASE (APB1PERIPH_BASE + 0x2800U) -#define WWDG_BASE (APB1PERIPH_BASE + 0x2C00U) -#define IWDG_BASE (APB1PERIPH_BASE + 0x3000U) -#define SPI2_BASE (APB1PERIPH_BASE + 0x3800U) -#define SPI3_BASE (APB1PERIPH_BASE + 0x3C00U) -#define USART2_BASE (APB1PERIPH_BASE + 0x4400U) -#define USART3_BASE (APB1PERIPH_BASE + 0x4800U) -#define UART4_BASE (APB1PERIPH_BASE + 0x4C00U) -#define UART5_BASE (APB1PERIPH_BASE + 0x5000U) -#define I2C1_BASE (APB1PERIPH_BASE + 0x5400U) -#define I2C2_BASE (APB1PERIPH_BASE + 0x5800U) -#define I2C3_BASE (APB1PERIPH_BASE + 0x5C00U) -#define CAN1_BASE (APB1PERIPH_BASE + 0x6400U) -#define CAN2_BASE (APB1PERIPH_BASE + 0x6800U) -#define PWR_BASE (APB1PERIPH_BASE + 0x7000U) -#define DAC_BASE (APB1PERIPH_BASE + 0x7400U) - -/*!< APB2 peripherals */ -#define TIM1_BASE (APB2PERIPH_BASE + 0x0000U) -#define TIM8_BASE (APB2PERIPH_BASE + 0x0400U) -#define USART1_BASE (APB2PERIPH_BASE + 0x1000U) -#define USART6_BASE (APB2PERIPH_BASE + 0x1400U) -#define ADC1_BASE (APB2PERIPH_BASE + 0x2000U) -#define ADC2_BASE (APB2PERIPH_BASE + 0x2100U) -#define ADC3_BASE (APB2PERIPH_BASE + 0x2200U) -#define ADC_BASE (APB2PERIPH_BASE + 0x2300U) -#define SDIO_BASE (APB2PERIPH_BASE + 0x2C00U) -#define SPI1_BASE (APB2PERIPH_BASE + 0x3000U) -#define SYSCFG_BASE (APB2PERIPH_BASE + 0x3800U) -#define EXTI_BASE (APB2PERIPH_BASE + 0x3C00U) -#define TIM9_BASE (APB2PERIPH_BASE + 0x4000U) -#define TIM10_BASE (APB2PERIPH_BASE + 0x4400U) -#define TIM11_BASE (APB2PERIPH_BASE + 0x4800U) - -/*!< AHB1 peripherals */ -#define GPIOA_BASE (AHB1PERIPH_BASE + 0x0000U) -#define GPIOB_BASE (AHB1PERIPH_BASE + 0x0400U) -#define GPIOC_BASE (AHB1PERIPH_BASE + 0x0800U) -#define GPIOD_BASE (AHB1PERIPH_BASE + 0x0C00U) -#define GPIOE_BASE (AHB1PERIPH_BASE + 0x1000U) -#define GPIOF_BASE (AHB1PERIPH_BASE + 0x1400U) -#define GPIOG_BASE (AHB1PERIPH_BASE + 0x1800U) -#define GPIOH_BASE (AHB1PERIPH_BASE + 0x1C00U) -#define GPIOI_BASE (AHB1PERIPH_BASE + 0x2000U) -#define CRC_BASE (AHB1PERIPH_BASE + 0x3000U) -#define RCC_BASE (AHB1PERIPH_BASE + 0x3800U) -#define FLASH_R_BASE (AHB1PERIPH_BASE + 0x3C00U) -#define DMA1_BASE (AHB1PERIPH_BASE + 0x6000U) -#define DMA1_Stream0_BASE (DMA1_BASE + 0x010U) -#define DMA1_Stream1_BASE (DMA1_BASE + 0x028U) -#define DMA1_Stream2_BASE (DMA1_BASE + 0x040U) -#define DMA1_Stream3_BASE (DMA1_BASE + 0x058U) -#define DMA1_Stream4_BASE (DMA1_BASE + 0x070U) -#define DMA1_Stream5_BASE (DMA1_BASE + 0x088U) -#define DMA1_Stream6_BASE (DMA1_BASE + 0x0A0U) -#define DMA1_Stream7_BASE (DMA1_BASE + 0x0B8U) -#define DMA2_BASE (AHB1PERIPH_BASE + 0x6400U) -#define DMA2_Stream0_BASE (DMA2_BASE + 0x010U) -#define DMA2_Stream1_BASE (DMA2_BASE + 0x028U) -#define DMA2_Stream2_BASE (DMA2_BASE + 0x040U) -#define DMA2_Stream3_BASE (DMA2_BASE + 0x058U) -#define DMA2_Stream4_BASE (DMA2_BASE + 0x070U) -#define DMA2_Stream5_BASE (DMA2_BASE + 0x088U) -#define DMA2_Stream6_BASE (DMA2_BASE + 0x0A0U) -#define DMA2_Stream7_BASE (DMA2_BASE + 0x0B8U) - -/*!< AHB2 peripherals */ -#define RNG_BASE (AHB2PERIPH_BASE + 0x60800U) - -/*!< FSMC Bankx registers base address */ -#define FSMC_Bank1_R_BASE (FSMC_R_BASE + 0x0000U) -#define FSMC_Bank1E_R_BASE (FSMC_R_BASE + 0x0104U) -#define FSMC_Bank2_3_R_BASE (FSMC_R_BASE + 0x0060U) -#define FSMC_Bank4_R_BASE (FSMC_R_BASE + 0x00A0U) - -/* Debug MCU registers base address */ -#define DBGMCU_BASE 0xE0042000U - -/*!< USB registers base address */ -#define USB_OTG_HS_PERIPH_BASE 0x40040000U -#define USB_OTG_FS_PERIPH_BASE 0x50000000U - -#define USB_OTG_GLOBAL_BASE 0x000U -#define USB_OTG_DEVICE_BASE 0x800U -#define USB_OTG_IN_ENDPOINT_BASE 0x900U -#define USB_OTG_OUT_ENDPOINT_BASE 0xB00U -#define USB_OTG_EP_REG_SIZE 0x20U -#define USB_OTG_HOST_BASE 0x400U -#define USB_OTG_HOST_PORT_BASE 0x440U -#define USB_OTG_HOST_CHANNEL_BASE 0x500U -#define USB_OTG_HOST_CHANNEL_SIZE 0x20U -#define USB_OTG_PCGCCTL_BASE 0xE00U -#define USB_OTG_FIFO_BASE 0x1000U -#define USB_OTG_FIFO_SIZE 0x1000U - -/** - * @} - */ - -/** @addtogroup Peripheral_declaration - * @{ - */ -#define TIM2 ((TIM_TypeDef *) TIM2_BASE) -#define TIM3 ((TIM_TypeDef *) TIM3_BASE) -#define TIM4 ((TIM_TypeDef *) TIM4_BASE) -#define TIM5 ((TIM_TypeDef *) TIM5_BASE) -#define TIM6 ((TIM_TypeDef *) TIM6_BASE) -#define TIM7 ((TIM_TypeDef *) TIM7_BASE) -#define TIM12 ((TIM_TypeDef *) TIM12_BASE) -#define TIM13 ((TIM_TypeDef *) TIM13_BASE) -#define TIM14 ((TIM_TypeDef *) TIM14_BASE) -#define RTC ((RTC_TypeDef *) RTC_BASE) -#define WWDG ((WWDG_TypeDef *) WWDG_BASE) -#define IWDG ((IWDG_TypeDef *) IWDG_BASE) -#define SPI2 ((SPI_TypeDef *) SPI2_BASE) -#define SPI3 ((SPI_TypeDef *) SPI3_BASE) -#define USART2 ((USART_TypeDef *) USART2_BASE) -#define USART3 ((USART_TypeDef *) USART3_BASE) -#define UART4 ((USART_TypeDef *) UART4_BASE) -#define UART5 ((USART_TypeDef *) UART5_BASE) -#define I2C1 ((I2C_TypeDef *) I2C1_BASE) -#define I2C2 ((I2C_TypeDef *) I2C2_BASE) -#define I2C3 ((I2C_TypeDef *) I2C3_BASE) -#define CAN1 ((CAN_TypeDef *) CAN1_BASE) -#define CAN2 ((CAN_TypeDef *) CAN2_BASE) -#define PWR ((PWR_TypeDef *) PWR_BASE) -#define DAC ((DAC_TypeDef *) DAC_BASE) -#define TIM1 ((TIM_TypeDef *) TIM1_BASE) -#define TIM8 ((TIM_TypeDef *) TIM8_BASE) -#define USART1 ((USART_TypeDef *) USART1_BASE) -#define USART6 ((USART_TypeDef *) USART6_BASE) -#define ADC ((ADC_Common_TypeDef *) ADC_BASE) -#define ADC1 ((ADC_TypeDef *) ADC1_BASE) -#define ADC2 ((ADC_TypeDef *) ADC2_BASE) -#define ADC3 ((ADC_TypeDef *) ADC3_BASE) -#define SDIO ((SDIO_TypeDef *) SDIO_BASE) -#define SPI1 ((SPI_TypeDef *) SPI1_BASE) -#define SYSCFG ((SYSCFG_TypeDef *) SYSCFG_BASE) -#define EXTI ((EXTI_TypeDef *) EXTI_BASE) -#define TIM9 ((TIM_TypeDef *) TIM9_BASE) -#define TIM10 ((TIM_TypeDef *) TIM10_BASE) -#define TIM11 ((TIM_TypeDef *) TIM11_BASE) -#define GPIOA ((GPIO_TypeDef *) GPIOA_BASE) -#define GPIOB ((GPIO_TypeDef *) GPIOB_BASE) -#define GPIOC ((GPIO_TypeDef *) GPIOC_BASE) -#define GPIOD ((GPIO_TypeDef *) GPIOD_BASE) -#define GPIOE ((GPIO_TypeDef *) GPIOE_BASE) -#define GPIOF ((GPIO_TypeDef *) GPIOF_BASE) -#define GPIOG ((GPIO_TypeDef *) GPIOG_BASE) -#define GPIOH ((GPIO_TypeDef *) GPIOH_BASE) -#define GPIOI ((GPIO_TypeDef *) GPIOI_BASE) -#define CRC ((CRC_TypeDef *) CRC_BASE) -#define RCC ((RCC_TypeDef *) RCC_BASE) -#define FLASH ((FLASH_TypeDef *) FLASH_R_BASE) -#define DMA1 ((DMA_TypeDef *) DMA1_BASE) -#define DMA1_Stream0 ((DMA_Stream_TypeDef *) DMA1_Stream0_BASE) -#define DMA1_Stream1 ((DMA_Stream_TypeDef *) DMA1_Stream1_BASE) -#define DMA1_Stream2 ((DMA_Stream_TypeDef *) DMA1_Stream2_BASE) -#define DMA1_Stream3 ((DMA_Stream_TypeDef *) DMA1_Stream3_BASE) -#define DMA1_Stream4 ((DMA_Stream_TypeDef *) DMA1_Stream4_BASE) -#define DMA1_Stream5 ((DMA_Stream_TypeDef *) DMA1_Stream5_BASE) -#define DMA1_Stream6 ((DMA_Stream_TypeDef *) DMA1_Stream6_BASE) -#define DMA1_Stream7 ((DMA_Stream_TypeDef *) DMA1_Stream7_BASE) -#define DMA2 ((DMA_TypeDef *) DMA2_BASE) -#define DMA2_Stream0 ((DMA_Stream_TypeDef *) DMA2_Stream0_BASE) -#define DMA2_Stream1 ((DMA_Stream_TypeDef *) DMA2_Stream1_BASE) -#define DMA2_Stream2 ((DMA_Stream_TypeDef *) DMA2_Stream2_BASE) -#define DMA2_Stream3 ((DMA_Stream_TypeDef *) DMA2_Stream3_BASE) -#define DMA2_Stream4 ((DMA_Stream_TypeDef *) DMA2_Stream4_BASE) -#define DMA2_Stream5 ((DMA_Stream_TypeDef *) DMA2_Stream5_BASE) -#define DMA2_Stream6 ((DMA_Stream_TypeDef *) DMA2_Stream6_BASE) -#define DMA2_Stream7 ((DMA_Stream_TypeDef *) DMA2_Stream7_BASE) -#define RNG ((RNG_TypeDef *) RNG_BASE) -#define FSMC_Bank1 ((FSMC_Bank1_TypeDef *) FSMC_Bank1_R_BASE) -#define FSMC_Bank1E ((FSMC_Bank1E_TypeDef *) FSMC_Bank1E_R_BASE) -#define FSMC_Bank2_3 ((FSMC_Bank2_3_TypeDef *) FSMC_Bank2_3_R_BASE) -#define FSMC_Bank4 ((FSMC_Bank4_TypeDef *) FSMC_Bank4_R_BASE) - -#define DBGMCU ((DBGMCU_TypeDef *) DBGMCU_BASE) - -#define USB_OTG_FS ((USB_OTG_GlobalTypeDef *) USB_OTG_FS_PERIPH_BASE) -#define USB_OTG_HS ((USB_OTG_GlobalTypeDef *) USB_OTG_HS_PERIPH_BASE) - -/** - * @} - */ - -/** @addtogroup Exported_constants - * @{ - */ - - /** @addtogroup Peripheral_Registers_Bits_Definition - * @{ - */ - -/******************************************************************************/ -/* Peripheral Registers_Bits_Definition */ -/******************************************************************************/ - -/******************************************************************************/ -/* */ -/* Analog to Digital Converter */ -/* */ -/******************************************************************************/ -/******************** Bit definition for ADC_SR register ********************/ -#define ADC_SR_AWD 0x00000001U /*!
© COPYRIGHT(c) 2016 STMicroelectronics
- * - * 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. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * 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 HOLDER 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. - * - ****************************************************************************** - */ - -/** @addtogroup CMSIS - * @{ - */ - -/** @addtogroup stm32f2xx - * @{ - */ - -#ifndef __STM32F2xx_H -#define __STM32F2xx_H - -#ifdef __cplusplus - extern "C" { -#endif /* __cplusplus */ - -/** @addtogroup Library_configuration_section - * @{ - */ - -/** - * @brief STM32 Family - */ -#if !defined (STM32F2) -#define STM32F2 -#endif /* STM32F2 */ - -/* Uncomment the line below according to the target STM32 device used in your - application - */ -/* #if !defined (STM32F205xx) && !defined (STM32F215xx) && !defined (STM32F207xx) && !defined (STM32F217xx) */ - - /* #define STM32F205xx */ /*!< STM32F205RG, STM32F205VG, STM32F205ZG, STM32F205RF, STM32F205VF, STM32F205ZF, - STM32F205RE, STM32F205VE, STM32F205ZE, STM32F205RC, STM32F205VC, STM32F205ZC, - STM32F205RB and STM32F205VB Devices */ - /* #define STM32F215xx */ /*!< STM32F215RG, STM32F215VG, STM32F215ZG, STM32F215RE, STM32F215VE and STM32F215ZE Devices */ - /* #define STM32F207xx */ /*!< STM32F207VG, STM32F207ZG, STM32F207IG, STM32F207VF, STM32F207ZF, STM32F207IF, - STM32F207VE, STM32F207ZE, STM32F207IE, STM32F207VC, STM32F207ZC and STM32F207IC Devices */ - /* #define STM32F217xx */ /*!< STM32F217VG, STM32F217ZG, STM32F217IG, STM32F217VE, STM32F217ZE and STM32F217IE Devices */ - -//#endif - -/* Tip: To avoid modifying this file each time you need to switch between these - devices, you can define the device in your toolchain compiler preprocessor. - */ -#if !defined (USE_HAL_DRIVER) -/** - * @brief Comment the line below if you will not use the peripherals drivers. - In this case, these drivers will not be included and the application code will - be based on direct access to peripherals registers - */ - /*#define USE_HAL_DRIVER */ -#endif /* USE_HAL_DRIVER */ - -/** - * @brief CMSIS Device version number V2.1.2 - */ -#define __STM32F2xx_CMSIS_VERSION_MAIN (0x02U) /*!< [31:24] main version */ -#define __STM32F2xx_CMSIS_VERSION_SUB1 (0x01U) /*!< [23:16] sub1 version */ -#define __STM32F2xx_CMSIS_VERSION_SUB2 (0x02U) /*!< [15:8] sub2 version */ -#define __STM32F2xx_CMSIS_VERSION_RC (0x00U) /*!< [7:0] release candidate */ -#define __STM32F2xx_CMSIS_VERSION ((__STM32F2xx_CMSIS_VERSION_MAIN << 24)\ - |(__STM32F2xx_CMSIS_VERSION_SUB1 << 16)\ - |(__STM32F2xx_CMSIS_VERSION_SUB2 << 8 )\ - |(__STM32F2xx_CMSIS_VERSION)) - -/** - * @} - */ - -/** @addtogroup Device_Included - * @{ - */ - -#if defined(STM32F215xx) - #include "stm32f215xx.h" -#elif defined(STM32F205xx) - #include "stm32f205xx.h" -// #elif defined(STM32F207xx) -// #include "stm32f207xx.h" -// #elif defined(STM32F217xx) -// #include "stm32f217xx.h" -#else - #error "Please select first the target STM32F2xx device used in your application (in stm32f2xx.h file)" -#endif - -/** - * @} - */ - -/** @addtogroup Exported_types - * @{ - */ -typedef enum -{ - RESET = 0, - SET = !RESET -} FlagStatus, ITStatus; - -typedef enum -{ - DISABLE = 0, - ENABLE = !DISABLE -} FunctionalState; -#define IS_FUNCTIONAL_STATE(STATE) (((STATE) == DISABLE) || ((STATE) == ENABLE)) - -typedef enum -{ - ERROR = 0, - SUCCESS = !ERROR -} ErrorStatus; - -/** - * @} - */ - - -/** @addtogroup Exported_macro - * @{ - */ -#define SET_BIT(REG, BIT) ((REG) |= (BIT)) - -#define CLEAR_BIT(REG, BIT) ((REG) &= ~(BIT)) - -#define READ_BIT(REG, BIT) ((REG) & (BIT)) - -#define CLEAR_REG(REG) ((REG) = (0x0)) - -#define WRITE_REG(REG, VAL) ((REG) = (VAL)) - -#define READ_REG(REG) ((REG)) - -#define MODIFY_REG(REG, CLEARMASK, SETMASK) WRITE_REG((REG), (((READ_REG(REG)) & (~(CLEARMASK))) | (SETMASK))) - -#define POSITION_VAL(VAL) (__CLZ(__RBIT(VAL))) - - -/** - * @} - */ - -#if defined (USE_HAL_DRIVER) - #include "stm32f2xx_hal.h" -#endif /* USE_HAL_DRIVER */ - -#ifdef __cplusplus -} -#endif /* __cplusplus */ - -#endif /* __STM32F2xx_H */ - -/** - * @} - */ - -/** - * @} - */ - - - - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/panda/board/stm32fx/inc/stm32f2xx_hal_def.h b/panda/board/stm32fx/inc/stm32f2xx_hal_def.h deleted file mode 100644 index dfef07939..000000000 --- a/panda/board/stm32fx/inc/stm32f2xx_hal_def.h +++ /dev/null @@ -1,181 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f2xx_hal_def.h - * @author MCD Application Team - * @version V1.1.3 - * @date 29-June-2016 - * @brief This file contains HAL common defines, enumeration, macros and - * structures definitions. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT(c) 2016 STMicroelectronics

- * - * 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. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * 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 HOLDER 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. - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F2xx_HAL_DEF -#define __STM32F2xx_HAL_DEF - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f2xx.h" -//#include "Legacy/stm32_hal_legacy.h" -//#include - -/* Exported types ------------------------------------------------------------*/ - -/** - * @brief HAL Status structures definition - */ -typedef enum -{ - HAL_OK = 0x00U, - HAL_ERROR = 0x01U, - HAL_BUSY = 0x02U, - HAL_TIMEOUT = 0x03U -} HAL_StatusTypeDef; - -/** - * @brief HAL Lock structures definition - */ -typedef enum -{ - HAL_UNLOCKED = 0x00U, - HAL_LOCKED = 0x01U -} HAL_LockTypeDef; - -/* Exported macro ------------------------------------------------------------*/ -#define HAL_MAX_DELAY 0xFFFFFFFFU - -#define HAL_IS_BIT_SET(REG, BIT) (((REG) & (BIT)) != RESET) -#define HAL_IS_BIT_CLR(REG, BIT) (((REG) & (BIT)) == RESET) - -#define __HAL_LINKDMA(__HANDLE__, __PPP_DMA_FIELD_, __DMA_HANDLE_) \ - do{ \ - (__HANDLE__)->__PPP_DMA_FIELD_ = &(__DMA_HANDLE_); \ - (__DMA_HANDLE_).Parent = (__HANDLE__); \ - } while(0) - -#define UNUSED(x) ((void)(x)) - -/** @brief Reset the Handle's State field. - * @param __HANDLE__: specifies the Peripheral Handle. - * @note This macro can be used for the following purpose: - * - When the Handle is declared as local variable; before passing it as parameter - * to HAL_PPP_Init() for the first time, it is mandatory to use this macro - * to set to 0 the Handle's "State" field. - * Otherwise, "State" field may have any random value and the first time the function - * HAL_PPP_Init() is called, the low level hardware initialization will be missed - * (i.e. HAL_PPP_MspInit() will not be executed). - * - When there is a need to reconfigure the low level hardware: instead of calling - * HAL_PPP_DeInit() then HAL_PPP_Init(), user can make a call to this macro then HAL_PPP_Init(). - * In this later function, when the Handle's "State" field is set to 0, it will execute the function - * HAL_PPP_MspInit() which will reconfigure the low level hardware. - * @retval None - */ -#define __HAL_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = 0U) - -#if (USE_RTOS == 1) - /* Reserved for future use */ - #error " USE_RTOS should be 0 in the current HAL release " -#else - #define __HAL_LOCK(__HANDLE__) \ - do{ \ - if((__HANDLE__)->Lock == HAL_LOCKED) \ - { \ - return HAL_BUSY; \ - } \ - else \ - { \ - (__HANDLE__)->Lock = HAL_LOCKED; \ - } \ - }while (0) - - #define __HAL_UNLOCK(__HANDLE__) \ - do{ \ - (__HANDLE__)->Lock = HAL_UNLOCKED; \ - }while (0) -#endif /* USE_RTOS */ - -#if defined ( __GNUC__ ) - #ifndef __weak - #define __weak __attribute__((weak)) - #endif /* __weak */ - #ifndef __packed - #define __packed __attribute__((__packed__)) - #endif /* __packed */ -#endif /* __GNUC__ */ - - -/* Macro to get variable aligned on 4-bytes, for __ICCARM__ the directive "#pragma data_alignment=4" must be used instead */ -#if defined (__GNUC__) /* GNU Compiler */ - #ifndef __ALIGN_END - #define __ALIGN_END __attribute__ ((aligned (4))) - #endif /* __ALIGN_END */ - #ifndef __ALIGN_BEGIN - #define __ALIGN_BEGIN - #endif /* __ALIGN_BEGIN */ -#else - #ifndef __ALIGN_END - #define __ALIGN_END - #endif /* __ALIGN_END */ - #ifndef __ALIGN_BEGIN - #if defined (__CC_ARM) /* ARM Compiler */ - #define __ALIGN_BEGIN __align(4) - #elif defined (__ICCARM__) /* IAR Compiler */ - #define __ALIGN_BEGIN - #endif /* __CC_ARM */ - #endif /* __ALIGN_BEGIN */ -#endif /* __GNUC__ */ - -/** - * @brief __NOINLINE definition - */ -#if defined ( __CC_ARM ) || defined ( __GNUC__ ) -/* ARM & GNUCompiler - ---------------- -*/ -#define __NOINLINE __attribute__ ( (noinline) ) - -#elif defined ( __ICCARM__ ) -/* ICCARM Compiler - --------------- -*/ -#define __NOINLINE _Pragma("optimize = no_inline") - -#endif - -#ifdef __cplusplus -} -#endif - -#endif /* ___STM32F2xx_HAL_DEF */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/panda/board/stm32fx/inc/stm32f2xx_hal_gpio_ex.h b/panda/board/stm32fx/inc/stm32f2xx_hal_gpio_ex.h deleted file mode 100644 index 7cef9a648..000000000 --- a/panda/board/stm32fx/inc/stm32f2xx_hal_gpio_ex.h +++ /dev/null @@ -1,299 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f2xx_hal_gpio_ex.h - * @author MCD Application Team - * @version V1.1.3 - * @date 29-June-2016 - * @brief Header file of GPIO HAL Extension module. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT(c) 2016 STMicroelectronics

- * - * 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. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * 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 HOLDER 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. - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F2xx_HAL_GPIO_EX_H -#define __STM32F2xx_HAL_GPIO_EX_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f2xx_hal_def.h" - -/** @addtogroup STM32F2xx_HAL_Driver - * @{ - */ - -/** @defgroup GPIOEx GPIOEx - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ - -/** @defgroup GPIOEx_Exported_Constants GPIO Exported Constants - * @{ - */ - -/** @defgroup GPIO_Alternate_function_selection GPIO Alternate function selection - * @{ - */ - -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00U) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00U) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00U) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00U) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00U) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01U) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01U) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02U) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02U) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02U) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM8 ((uint8_t)0x03U) /* TIM8 Alternate Function mapping */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03U) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03U) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03U) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04U) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04U) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04U) /* I2C3 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05U) /* SPI1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05U) /* SPI2/I2S2 Alternate Function mapping */ -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06U) /* SPI3/I2S3 Alternate Function mapping */ - -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_USART1 ((uint8_t)0x07U) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07U) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_USART3 ((uint8_t)0x07U) /* USART3 Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_UART4 ((uint8_t)0x08U) /* UART4 Alternate Function mapping */ -#define GPIO_AF8_UART5 ((uint8_t)0x08U) /* UART5 Alternate Function mapping */ -#define GPIO_AF8_USART6 ((uint8_t)0x08U) /* USART6 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_CAN1 ((uint8_t)0x09U) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_CAN2 ((uint8_t)0x09U) /* CAN2 Alternate Function mapping */ -#define GPIO_AF9_TIM12 ((uint8_t)0x09U) /* TIM12 Alternate Function mapping */ -#define GPIO_AF9_TIM13 ((uint8_t)0x09U) /* TIM13 Alternate Function mapping */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09U) /* TIM14 Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0xAU) /* OTG_FS Alternate Function mapping */ -#define GPIO_AF10_OTG_HS ((uint8_t)0xAU) /* OTG_HS Alternate Function mapping */ - -/** - * @brief AF 11 selection - */ -#if defined(STM32F207xx) || defined(STM32F217xx) -#define GPIO_AF11_ETH ((uint8_t)0x0BU) /* ETHERNET Alternate Function mapping */ -#endif /* STM32F207xx || STM32F217xx */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_FSMC ((uint8_t)0xCU) /* FSMC Alternate Function mapping */ -#define GPIO_AF12_OTG_HS_FS ((uint8_t)0xCU) /* OTG HS configured in FS, Alternate Function mapping */ -#define GPIO_AF12_SDIO ((uint8_t)0xCU) /* SDIO Alternate Function mapping */ - -/** - * @brief AF 13 selection - */ -#if defined(STM32F207xx) || defined(STM32F217xx) -#define GPIO_AF13_DCMI ((uint8_t)0x0DU) /* DCMI Alternate Function mapping */ -#endif /* STM32F207xx || STM32F217xx */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0FU) /* EVENTOUT Alternate Function mapping */ - -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup GPIOEx_Exported_Macros GPIO Exported Macros - * @{ - */ -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup GPIOEx_Exported_Functions GPIO Exported Functions - * @{ - */ -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup GPIOEx_Private_Constants GPIO Private Constants - * @{ - */ -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup GPIOEx_Private_Macros GPIO Private Macros - * @{ - */ -/** @defgroup GPIOEx_Get_Port_Index GPIO Get Port Index - * @{ - */ -#define GPIO_GET_INDEX(__GPIOx__) (uint8_t)(((__GPIOx__) == (GPIOA))? 0U :\ - ((__GPIOx__) == (GPIOB))? 1U :\ - ((__GPIOx__) == (GPIOC))? 2U :\ - ((__GPIOx__) == (GPIOD))? 3U :\ - ((__GPIOx__) == (GPIOE))? 4U :\ - ((__GPIOx__) == (GPIOF))? 5U :\ - ((__GPIOx__) == (GPIOG))? 6U :\ - ((__GPIOx__) == (GPIOH))? 7U :\ - ((__GPIOx__) == (GPIOI))? 8U : 9U) -/** - * @} - */ - -/** @defgroup GPIOEx_IS_Alternat_function_selection GPIO Check Alternate Function - * @{ - */ -#if defined(STM32F207xx) || defined(STM32F217xx) - -#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ - ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ - ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ - ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ - ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ - ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF3_TIM8) || \ - ((AF) == GPIO_AF4_I2C1) || ((AF) == GPIO_AF4_I2C2) || \ - ((AF) == GPIO_AF4_I2C3) || ((AF) == GPIO_AF5_SPI1) || \ - ((AF) == GPIO_AF5_SPI2) || ((AF) == GPIO_AF9_TIM13) || \ - ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF9_TIM12) || \ - ((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \ - ((AF) == GPIO_AF7_USART3) || ((AF) == GPIO_AF8_UART4) || \ - ((AF) == GPIO_AF8_UART5) || ((AF) == GPIO_AF8_USART6) || \ - ((AF) == GPIO_AF9_CAN1) || ((AF) == GPIO_AF9_CAN2) || \ - ((AF) == GPIO_AF10_OTG_FS) || ((AF) == GPIO_AF10_OTG_HS) || \ - ((AF) == GPIO_AF11_ETH) || ((AF) == GPIO_AF12_OTG_HS_FS) || \ - ((AF) == GPIO_AF12_SDIO) || ((AF) == GPIO_AF13_DCMI) || \ - ((AF) == GPIO_AF12_FSMC) || ((AF) == GPIO_AF15_EVENTOUT)) -#else /* STM32F207xx || STM32F217xx */ -#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ - ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ - ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ - ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ - ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ - ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF3_TIM8) || \ - ((AF) == GPIO_AF4_I2C1) || ((AF) == GPIO_AF4_I2C2) || \ - ((AF) == GPIO_AF4_I2C3) || ((AF) == GPIO_AF5_SPI1) || \ - ((AF) == GPIO_AF5_SPI2) || ((AF) == GPIO_AF9_TIM13) || \ - ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF9_TIM12) || \ - ((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \ - ((AF) == GPIO_AF7_USART3) || ((AF) == GPIO_AF8_UART4) || \ - ((AF) == GPIO_AF8_UART5) || ((AF) == GPIO_AF8_USART6) || \ - ((AF) == GPIO_AF9_CAN1) || ((AF) == GPIO_AF9_CAN2) || \ - ((AF) == GPIO_AF10_OTG_FS) || ((AF) == GPIO_AF10_OTG_HS) || \ - ((AF) == GPIO_AF12_OTG_HS_FS) || ((AF) == GPIO_AF12_SDIO) || \ - ((AF) == GPIO_AF12_FSMC) || ((AF) == GPIO_AF15_EVENTOUT)) -#endif /* STM32F207xx || STM32F217xx */ - -/** - * @} - */ - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup GPIOEx_Private_Functions GPIO Private Functions - * @{ - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F2xx_HAL_GPIO_EX_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/panda/board/stm32fx/inc/stm32f413xx.h b/panda/board/stm32fx/inc/stm32f413xx.h deleted file mode 100644 index 0962a8def..000000000 --- a/panda/board/stm32fx/inc/stm32f413xx.h +++ /dev/null @@ -1,14995 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f413xx.h - * @author MCD Application Team - * @version V2.6.0 - * @date 04-November-2016 - * @brief CMSIS STM32F413xx Device Peripheral Access Layer Header File. - * - * This file contains: - * - Data structures and the address mapping for all peripherals - * - peripherals registers declarations and bits definition - * - Macros to access peripheral’s registers hardware - * - ****************************************************************************** - * @attention - * - *

© COPYRIGHT(c) 2016 STMicroelectronics

- * - * 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. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * 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 HOLDER 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. - * - ****************************************************************************** - */ - -/** @addtogroup CMSIS_Device - * @{ - */ - -/** @addtogroup stm32f413xx - * @{ - */ - -#ifndef __STM32F413xx_H -#define __STM32F413xx_H - -#ifdef __cplusplus - extern "C" { -#endif /* __cplusplus */ - -/** @addtogroup Configuration_section_for_CMSIS - * @{ - */ - -/** - * @brief Configuration of the Cortex-M4 Processor and Core Peripherals - */ -#define __CM4_REV 0x0001U /*!< Core revision r0p1 */ -#define __MPU_PRESENT 1U /*!< STM32F4XX provides an MPU */ -#define __NVIC_PRIO_BITS 4U /*!< STM32F4XX uses 4 Bits for the Priority Levels */ -#define __Vendor_SysTickConfig 0U /*!< Set to 1 if different SysTick Config is used */ -#define __FPU_PRESENT 1U /*!< FPU present */ - -/** - * @} - */ - -/** @addtogroup Peripheral_interrupt_number_definition - * @{ - */ - -/** - * @brief STM32F4XX Interrupt Number Definition, according to the selected device - * in @ref Library_configuration_section - */ -typedef enum -{ -/****** Cortex-M4 Processor Exceptions Numbers ****************************************************************/ - NonMaskableInt_IRQn = -14, /*!< 2 Non Maskable Interrupt */ - MemoryManagement_IRQn = -12, /*!< 4 Cortex-M4 Memory Management Interrupt */ - BusFault_IRQn = -11, /*!< 5 Cortex-M4 Bus Fault Interrupt */ - UsageFault_IRQn = -10, /*!< 6 Cortex-M4 Usage Fault Interrupt */ - SVCall_IRQn = -5, /*!< 11 Cortex-M4 SV Call Interrupt */ - DebugMonitor_IRQn = -4, /*!< 12 Cortex-M4 Debug Monitor Interrupt */ - PendSV_IRQn = -2, /*!< 14 Cortex-M4 Pend SV Interrupt */ - SysTick_IRQn = -1, /*!< 15 Cortex-M4 System Tick Interrupt */ -/****** STM32 specific Interrupt Numbers **********************************************************************/ - WWDG_IRQn = 0, /*!< Window WatchDog Interrupt */ - PVD_IRQn = 1, /*!< PVD through EXTI Line detection Interrupt */ - TAMP_STAMP_IRQn = 2, /*!< Tamper and TimeStamp interrupts through the EXTI line */ - RTC_WKUP_IRQn = 3, /*!< RTC Wakeup interrupt through the EXTI line */ - FLASH_IRQn = 4, /*!< FLASH global Interrupt */ - RCC_IRQn = 5, /*!< RCC global Interrupt */ - EXTI0_IRQn = 6, /*!< EXTI Line0 Interrupt */ - EXTI1_IRQn = 7, /*!< EXTI Line1 Interrupt */ - EXTI2_IRQn = 8, /*!< EXTI Line2 Interrupt */ - EXTI3_IRQn = 9, /*!< EXTI Line3 Interrupt */ - EXTI4_IRQn = 10, /*!< EXTI Line4 Interrupt */ - DMA1_Stream0_IRQn = 11, /*!< DMA1 Stream 0 global Interrupt */ - DMA1_Stream1_IRQn = 12, /*!< DMA1 Stream 1 global Interrupt */ - DMA1_Stream2_IRQn = 13, /*!< DMA1 Stream 2 global Interrupt */ - DMA1_Stream3_IRQn = 14, /*!< DMA1 Stream 3 global Interrupt */ - DMA1_Stream4_IRQn = 15, /*!< DMA1 Stream 4 global Interrupt */ - DMA1_Stream5_IRQn = 16, /*!< DMA1 Stream 5 global Interrupt */ - DMA1_Stream6_IRQn = 17, /*!< DMA1 Stream 6 global Interrupt */ - ADC_IRQn = 18, /*!< ADC1, ADC2 and ADC3 global Interrupts */ - CAN1_TX_IRQn = 19, /*!< CAN1 TX Interrupt */ - CAN1_RX0_IRQn = 20, /*!< CAN1 RX0 Interrupt */ - CAN1_RX1_IRQn = 21, /*!< CAN1 RX1 Interrupt */ - CAN1_SCE_IRQn = 22, /*!< CAN1 SCE Interrupt */ - EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ - TIM1_BRK_TIM9_IRQn = 24, /*!< TIM1 Break interrupt and TIM9 global interrupt */ - TIM1_UP_TIM10_IRQn = 25, /*!< TIM1 Update Interrupt and TIM10 global interrupt */ - TIM1_TRG_COM_TIM11_IRQn = 26, /*!< TIM1 Trigger and Commutation Interrupt and TIM11 global interrupt */ - TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ - TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ - TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ - TIM4_IRQn = 30, /*!< TIM4 global Interrupt */ - I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ - I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ - I2C2_EV_IRQn = 33, /*!< I2C2 Event Interrupt */ - I2C2_ER_IRQn = 34, /*!< I2C2 Error Interrupt */ - SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ - SPI2_IRQn = 36, /*!< SPI2 global Interrupt */ - USART1_IRQn = 37, /*!< USART1 global Interrupt */ - USART2_IRQn = 38, /*!< USART2 global Interrupt */ - USART3_IRQn = 39, /*!< USART3 global Interrupt */ - EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ - RTC_Alarm_IRQn = 41, /*!< RTC Alarm (A and B) through EXTI Line Interrupt */ - OTG_FS_WKUP_IRQn = 42, /*!< USB OTG FS Wakeup through EXTI line interrupt */ - TIM8_BRK_TIM12_IRQn = 43, /*!< TIM8 Break Interrupt and TIM12 global interrupt */ - TIM8_UP_TIM13_IRQn = 44, /*!< TIM8 Update Interrupt and TIM13 global interrupt */ - TIM8_TRG_COM_TIM14_IRQn = 45, /*!< TIM8 Trigger and Commutation Interrupt and TIM14 global interrupt */ - TIM8_CC_IRQn = 46, /*!< TIM8 Capture Compare global interrupt */ - DMA1_Stream7_IRQn = 47, /*!< DMA1 Stream7 Interrupt */ - FSMC_IRQn = 48, /*!< FSMC global Interrupt */ - SDIO_IRQn = 49, /*!< SDIO global Interrupt */ - TIM5_IRQn = 50, /*!< TIM5 global Interrupt */ - SPI3_IRQn = 51, /*!< SPI3 global Interrupt */ - UART4_IRQn = 52, /*!< UART4 global Interrupt */ - UART5_IRQn = 53, /*!< UART5 global Interrupt */ - TIM6_DAC_IRQn = 54, /*!< TIM6 global and DAC1&2 underrun error interrupts */ - TIM7_IRQn = 55, /*!< TIM7 global interrupt */ - DMA2_Stream0_IRQn = 56, /*!< DMA2 Stream 0 global Interrupt */ - DMA2_Stream1_IRQn = 57, /*!< DMA2 Stream 1 global Interrupt */ - DMA2_Stream2_IRQn = 58, /*!< DMA2 Stream 2 global Interrupt */ - DMA2_Stream3_IRQn = 59, /*!< DMA2 Stream 3 global Interrupt */ - DMA2_Stream4_IRQn = 60, /*!< DMA2 Stream 4 global Interrupt */ - DFSDM1_FLT0_IRQn = 61, /*!< DFSDM1 Filter 0 global Interrupt */ - DFSDM1_FLT1_IRQn = 62, /*!< DFSDM1 Filter 1 global Interrupt */ - CAN2_TX_IRQn = 63, /*!< CAN2 TX Interrupt */ - CAN2_RX0_IRQn = 64, /*!< CAN2 RX0 Interrupt */ - CAN2_RX1_IRQn = 65, /*!< CAN2 RX1 Interrupt */ - CAN2_SCE_IRQn = 66, /*!< CAN2 SCE Interrupt */ - OTG_FS_IRQn = 67, /*!< USB OTG FS global Interrupt */ - DMA2_Stream5_IRQn = 68, /*!< DMA2 Stream 5 global interrupt */ - DMA2_Stream6_IRQn = 69, /*!< DMA2 Stream 6 global interrupt */ - DMA2_Stream7_IRQn = 70, /*!< DMA2 Stream 7 global interrupt */ - USART6_IRQn = 71, /*!< USART6 global interrupt */ - I2C3_EV_IRQn = 72, /*!< I2C3 event interrupt */ - I2C3_ER_IRQn = 73, /*!< I2C3 error interrupt */ - CAN3_TX_IRQn = 74, /*!< CAN3 TX Interrupt */ - CAN3_RX0_IRQn = 75, /*!< CAN3 RX0 Interrupt */ - CAN3_RX1_IRQn = 76, /*!< CAN3 RX1 Interrupt */ - CAN3_SCE_IRQn = 77, /*!< CAN3 SCE Interrupt */ - RNG_IRQn = 80, /*!< RNG global Interrupt */ - FPU_IRQn = 81, /*!< FPU global interrupt */ - UART7_IRQn = 82, /*!< UART7 global interrupt */ - UART8_IRQn = 83, /*!< UART8 global interrupt */ - SPI4_IRQn = 84, /*!< SPI4 global Interrupt */ - SPI5_IRQn = 85, /*!< SPI5 global Interrupt */ - SAI1_IRQn = 87, /*!< SAI1 global Interrupt */ - UART9_IRQn = 88, /*!< UART9 global Interrupt */ - UART10_IRQn = 89, /*!< UART10 global Interrupt */ - QUADSPI_IRQn = 92, /*!< QuadSPI global Interrupt */ - FMPI2C1_EV_IRQn = 95, /*!< FMPI2C1 Event Interrupt */ - FMPI2C1_ER_IRQn = 96, /*!< FMPI2C1 Error Interrupt */ - LPTIM1_IRQn = 97, /*!< LP TIM1 interrupt */ - DFSDM2_FLT0_IRQn = 98, /*!< DFSDM2 Filter 0 global Interrupt */ - DFSDM2_FLT1_IRQn = 99, /*!< DFSDM2 Filter 1 global Interrupt */ - DFSDM2_FLT2_IRQn = 100, /*!< DFSDM2 Filter 2 global Interrupt */ - DFSDM2_FLT3_IRQn = 101 /*!< DFSDM2 Filter 3 global Interrupt */ -} IRQn_Type; - -/** - * @} - */ - -#include "core_cm4.h" /* Cortex-M4 processor and core peripherals */ -#include "system_stm32f4xx.h" -#include - -/** @addtogroup Peripheral_registers_structures - * @{ - */ - -/** - * @brief Analog to Digital Converter - */ - -typedef struct -{ - __IO uint32_t SR; /*!< ADC status register, Address offset: 0x00 */ - __IO uint32_t CR1; /*!< ADC control register 1, Address offset: 0x04 */ - __IO uint32_t CR2; /*!< ADC control register 2, Address offset: 0x08 */ - __IO uint32_t SMPR1; /*!< ADC sample time register 1, Address offset: 0x0C */ - __IO uint32_t SMPR2; /*!< ADC sample time register 2, Address offset: 0x10 */ - __IO uint32_t JOFR1; /*!< ADC injected channel data offset register 1, Address offset: 0x14 */ - __IO uint32_t JOFR2; /*!< ADC injected channel data offset register 2, Address offset: 0x18 */ - __IO uint32_t JOFR3; /*!< ADC injected channel data offset register 3, Address offset: 0x1C */ - __IO uint32_t JOFR4; /*!< ADC injected channel data offset register 4, Address offset: 0x20 */ - __IO uint32_t HTR; /*!< ADC watchdog higher threshold register, Address offset: 0x24 */ - __IO uint32_t LTR; /*!< ADC watchdog lower threshold register, Address offset: 0x28 */ - __IO uint32_t SQR1; /*!< ADC regular sequence register 1, Address offset: 0x2C */ - __IO uint32_t SQR2; /*!< ADC regular sequence register 2, Address offset: 0x30 */ - __IO uint32_t SQR3; /*!< ADC regular sequence register 3, Address offset: 0x34 */ - __IO uint32_t JSQR; /*!< ADC injected sequence register, Address offset: 0x38*/ - __IO uint32_t JDR1; /*!< ADC injected data register 1, Address offset: 0x3C */ - __IO uint32_t JDR2; /*!< ADC injected data register 2, Address offset: 0x40 */ - __IO uint32_t JDR3; /*!< ADC injected data register 3, Address offset: 0x44 */ - __IO uint32_t JDR4; /*!< ADC injected data register 4, Address offset: 0x48 */ - __IO uint32_t DR; /*!< ADC regular data register, Address offset: 0x4C */ -} ADC_TypeDef; - -typedef struct -{ - __IO uint32_t CSR; /*!< ADC Common status register, Address offset: ADC1 base address + 0x300 */ - __IO uint32_t CCR; /*!< ADC common control register, Address offset: ADC1 base address + 0x304 */ - __IO uint32_t CDR; /*!< ADC common regular data register for dual - AND triple modes, Address offset: ADC1 base address + 0x308 */ -} ADC_Common_TypeDef; - - -/** - * @brief Controller Area Network TxMailBox - */ - -typedef struct -{ - __IO uint32_t TIR; /*!< CAN TX mailbox identifier register */ - __IO uint32_t TDTR; /*!< CAN mailbox data length control and time stamp register */ - __IO uint32_t TDLR; /*!< CAN mailbox data low register */ - __IO uint32_t TDHR; /*!< CAN mailbox data high register */ -} CAN_TxMailBox_TypeDef; - -/** - * @brief Controller Area Network FIFOMailBox - */ - -typedef struct -{ - __IO uint32_t RIR; /*!< CAN receive FIFO mailbox identifier register */ - __IO uint32_t RDTR; /*!< CAN receive FIFO mailbox data length control and time stamp register */ - __IO uint32_t RDLR; /*!< CAN receive FIFO mailbox data low register */ - __IO uint32_t RDHR; /*!< CAN receive FIFO mailbox data high register */ -} CAN_FIFOMailBox_TypeDef; - -/** - * @brief Controller Area Network FilterRegister - */ - -typedef struct -{ - __IO uint32_t FR1; /*!< CAN Filter bank register 1 */ - __IO uint32_t FR2; /*!< CAN Filter bank register 1 */ -} CAN_FilterRegister_TypeDef; - -/** - * @brief Controller Area Network - */ - -typedef struct -{ - __IO uint32_t MCR; /*!< CAN master control register, Address offset: 0x00 */ - __IO uint32_t MSR; /*!< CAN master status register, Address offset: 0x04 */ - __IO uint32_t TSR; /*!< CAN transmit status register, Address offset: 0x08 */ - __IO uint32_t RF0R; /*!< CAN receive FIFO 0 register, Address offset: 0x0C */ - __IO uint32_t RF1R; /*!< CAN receive FIFO 1 register, Address offset: 0x10 */ - __IO uint32_t IER; /*!< CAN interrupt enable register, Address offset: 0x14 */ - __IO uint32_t ESR; /*!< CAN error status register, Address offset: 0x18 */ - __IO uint32_t BTR; /*!< CAN bit timing register, Address offset: 0x1C */ - uint32_t RESERVED0[88]; /*!< Reserved, 0x020 - 0x17F */ - CAN_TxMailBox_TypeDef sTxMailBox[3]; /*!< CAN Tx MailBox, Address offset: 0x180 - 0x1AC */ - CAN_FIFOMailBox_TypeDef sFIFOMailBox[2]; /*!< CAN FIFO MailBox, Address offset: 0x1B0 - 0x1CC */ - uint32_t RESERVED1[12]; /*!< Reserved, 0x1D0 - 0x1FF */ - __IO uint32_t FMR; /*!< CAN filter master register, Address offset: 0x200 */ - __IO uint32_t FM1R; /*!< CAN filter mode register, Address offset: 0x204 */ - uint32_t RESERVED2; /*!< Reserved, 0x208 */ - __IO uint32_t FS1R; /*!< CAN filter scale register, Address offset: 0x20C */ - uint32_t RESERVED3; /*!< Reserved, 0x210 */ - __IO uint32_t FFA1R; /*!< CAN filter FIFO assignment register, Address offset: 0x214 */ - uint32_t RESERVED4; /*!< Reserved, 0x218 */ - __IO uint32_t FA1R; /*!< CAN filter activation register, Address offset: 0x21C */ - uint32_t RESERVED5[8]; /*!< Reserved, 0x220-0x23F */ - CAN_FilterRegister_TypeDef sFilterRegister[28]; /*!< CAN Filter Register, Address offset: 0x240-0x31C */ -} CAN_TypeDef; - -/** - * @brief CRC calculation unit - */ - -typedef struct -{ - __IO uint32_t DR; /*!< CRC Data register, Address offset: 0x00 */ - __IO uint8_t IDR; /*!< CRC Independent data register, Address offset: 0x04 */ - uint8_t RESERVED0; /*!< Reserved, 0x05 */ - uint16_t RESERVED1; /*!< Reserved, 0x06 */ - __IO uint32_t CR; /*!< CRC Control register, Address offset: 0x08 */ -} CRC_TypeDef; - -/** - * @brief DFSDM module registers - */ -typedef struct -{ - __IO uint32_t FLTCR1; /*!< DFSDM control register1, Address offset: 0x100 */ - __IO uint32_t FLTCR2; /*!< DFSDM control register2, Address offset: 0x104 */ - __IO uint32_t FLTISR; /*!< DFSDM interrupt and status register, Address offset: 0x108 */ - __IO uint32_t FLTICR; /*!< DFSDM interrupt flag clear register, Address offset: 0x10C */ - __IO uint32_t FLTJCHGR; /*!< DFSDM injected channel group selection register, Address offset: 0x110 */ - __IO uint32_t FLTFCR; /*!< DFSDM filter control register, Address offset: 0x114 */ - __IO uint32_t FLTJDATAR; /*!< DFSDM data register for injected group, Address offset: 0x118 */ - __IO uint32_t FLTRDATAR; /*!< DFSDM data register for regular group, Address offset: 0x11C */ - __IO uint32_t FLTAWHTR; /*!< DFSDM analog watchdog high threshold register, Address offset: 0x120 */ - __IO uint32_t FLTAWLTR; /*!< DFSDM analog watchdog low threshold register, Address offset: 0x124 */ - __IO uint32_t FLTAWSR; /*!< DFSDM analog watchdog status register Address offset: 0x128 */ - __IO uint32_t FLTAWCFR; /*!< DFSDM analog watchdog clear flag register Address offset: 0x12C */ - __IO uint32_t FLTEXMAX; /*!< DFSDM extreme detector maximum register, Address offset: 0x130 */ - __IO uint32_t FLTEXMIN; /*!< DFSDM extreme detector minimum register Address offset: 0x134 */ - __IO uint32_t FLTCNVTIMR; /*!< DFSDM conversion timer, Address offset: 0x138 */ -} DFSDM_Filter_TypeDef; - -/** - * @brief DFSDM channel configuration registers - */ -typedef struct -{ - __IO uint32_t CHCFGR1; /*!< DFSDM channel configuration register1, Address offset: 0x00 */ - __IO uint32_t CHCFGR2; /*!< DFSDM channel configuration register2, Address offset: 0x04 */ - __IO uint32_t CHAWSCDR; /*!< DFSDM channel analog watchdog and - short circuit detector register, Address offset: 0x08 */ - __IO uint32_t CHWDATAR; /*!< DFSDM channel watchdog filter data register, Address offset: 0x0C */ - __IO uint32_t CHDATINR; /*!< DFSDM channel data input register, Address offset: 0x10 */ -} DFSDM_Channel_TypeDef; - -/** - * @brief Digital to Analog Converter - */ - -typedef struct -{ - __IO uint32_t CR; /*!< DAC control register, Address offset: 0x00 */ - __IO uint32_t SWTRIGR; /*!< DAC software trigger register, Address offset: 0x04 */ - __IO uint32_t DHR12R1; /*!< DAC channel1 12-bit right-aligned data holding register, Address offset: 0x08 */ - __IO uint32_t DHR12L1; /*!< DAC channel1 12-bit left aligned data holding register, Address offset: 0x0C */ - __IO uint32_t DHR8R1; /*!< DAC channel1 8-bit right aligned data holding register, Address offset: 0x10 */ - __IO uint32_t DHR12R2; /*!< DAC channel2 12-bit right aligned data holding register, Address offset: 0x14 */ - __IO uint32_t DHR12L2; /*!< DAC channel2 12-bit left aligned data holding register, Address offset: 0x18 */ - __IO uint32_t DHR8R2; /*!< DAC channel2 8-bit right-aligned data holding register, Address offset: 0x1C */ - __IO uint32_t DHR12RD; /*!< Dual DAC 12-bit right-aligned data holding register, Address offset: 0x20 */ - __IO uint32_t DHR12LD; /*!< DUAL DAC 12-bit left aligned data holding register, Address offset: 0x24 */ - __IO uint32_t DHR8RD; /*!< DUAL DAC 8-bit right aligned data holding register, Address offset: 0x28 */ - __IO uint32_t DOR1; /*!< DAC channel1 data output register, Address offset: 0x2C */ - __IO uint32_t DOR2; /*!< DAC channel2 data output register, Address offset: 0x30 */ - __IO uint32_t SR; /*!< DAC status register, Address offset: 0x34 */ -} DAC_TypeDef; - -/** - * @brief Debug MCU - */ - -typedef struct -{ - __IO uint32_t IDCODE; /*!< MCU device ID code, Address offset: 0x00 */ - __IO uint32_t CR; /*!< Debug MCU configuration register, Address offset: 0x04 */ - __IO uint32_t APB1FZ; /*!< Debug MCU APB1 freeze register, Address offset: 0x08 */ - __IO uint32_t APB2FZ; /*!< Debug MCU APB2 freeze register, Address offset: 0x0C */ -}DBGMCU_TypeDef; - - -/** - * @brief DMA Controller - */ - -typedef struct -{ - __IO uint32_t CR; /*!< DMA stream x configuration register */ - __IO uint32_t NDTR; /*!< DMA stream x number of data register */ - __IO uint32_t PAR; /*!< DMA stream x peripheral address register */ - __IO uint32_t M0AR; /*!< DMA stream x memory 0 address register */ - __IO uint32_t M1AR; /*!< DMA stream x memory 1 address register */ - __IO uint32_t FCR; /*!< DMA stream x FIFO control register */ -} DMA_Stream_TypeDef; - -typedef struct -{ - __IO uint32_t LISR; /*!< DMA low interrupt status register, Address offset: 0x00 */ - __IO uint32_t HISR; /*!< DMA high interrupt status register, Address offset: 0x04 */ - __IO uint32_t LIFCR; /*!< DMA low interrupt flag clear register, Address offset: 0x08 */ - __IO uint32_t HIFCR; /*!< DMA high interrupt flag clear register, Address offset: 0x0C */ -} DMA_TypeDef; - -/** - * @brief External Interrupt/Event Controller - */ - -typedef struct -{ - __IO uint32_t IMR; /*!< EXTI Interrupt mask register, Address offset: 0x00 */ - __IO uint32_t EMR; /*!< EXTI Event mask register, Address offset: 0x04 */ - __IO uint32_t RTSR; /*!< EXTI Rising trigger selection register, Address offset: 0x08 */ - __IO uint32_t FTSR; /*!< EXTI Falling trigger selection register, Address offset: 0x0C */ - __IO uint32_t SWIER; /*!< EXTI Software interrupt event register, Address offset: 0x10 */ - __IO uint32_t PR; /*!< EXTI Pending register, Address offset: 0x14 */ -} EXTI_TypeDef; - -/** - * @brief FLASH Registers - */ - -typedef struct -{ - __IO uint32_t ACR; /*!< FLASH access control register, Address offset: 0x00 */ - __IO uint32_t KEYR; /*!< FLASH key register, Address offset: 0x04 */ - __IO uint32_t OPTKEYR; /*!< FLASH option key register, Address offset: 0x08 */ - __IO uint32_t SR; /*!< FLASH status register, Address offset: 0x0C */ - __IO uint32_t CR; /*!< FLASH control register, Address offset: 0x10 */ - __IO uint32_t OPTCR; /*!< FLASH option control register , Address offset: 0x14 */ - __IO uint32_t OPTCR1; /*!< FLASH option control register 1, Address offset: 0x18 */ -} FLASH_TypeDef; - - - -/** - * @brief Flexible Static Memory Controller - */ - -typedef struct -{ - __IO uint32_t BTCR[8]; /*!< NOR/PSRAM chip-select control register(BCR) and chip-select timing register(BTR), Address offset: 0x00-1C */ -} FSMC_Bank1_TypeDef; - -/** - * @brief Flexible Static Memory Controller Bank1E - */ - -typedef struct -{ - __IO uint32_t BWTR[7]; /*!< NOR/PSRAM write timing registers, Address offset: 0x104-0x11C */ -} FSMC_Bank1E_TypeDef; -/** - * @brief General Purpose I/O - */ - -typedef struct -{ - __IO uint32_t MODER; /*!< GPIO port mode register, Address offset: 0x00 */ - __IO uint32_t OTYPER; /*!< GPIO port output type register, Address offset: 0x04 */ - __IO uint32_t OSPEEDR; /*!< GPIO port output speed register, Address offset: 0x08 */ - __IO uint32_t PUPDR; /*!< GPIO port pull-up/pull-down register, Address offset: 0x0C */ - __IO uint32_t IDR; /*!< GPIO port input data register, Address offset: 0x10 */ - __IO uint32_t ODR; /*!< GPIO port output data register, Address offset: 0x14 */ - __IO uint32_t BSRR; /*!< GPIO port bit set/reset register, Address offset: 0x18 */ - __IO uint32_t LCKR; /*!< GPIO port configuration lock register, Address offset: 0x1C */ - __IO uint32_t AFR[2]; /*!< GPIO alternate function registers, Address offset: 0x20-0x24 */ -} GPIO_TypeDef; - -/** - * @brief System configuration controller - */ - -typedef struct -{ - __IO uint32_t MEMRMP; /*!< SYSCFG memory remap register, Address offset: 0x00 */ - __IO uint32_t PMC; /*!< SYSCFG peripheral mode configuration register, Address offset: 0x04 */ - __IO uint32_t EXTICR[4]; /*!< SYSCFG external interrupt configuration registers, Address offset: 0x08-0x14 */ - uint32_t RESERVED; /*!< Reserved, 0x18 */ - __IO uint32_t CFGR2; /*!< SYSCFG Configuration register2, Address offset: 0x1C */ - __IO uint32_t CMPCR; /*!< SYSCFG Compensation cell control register, Address offset: 0x20 */ - uint32_t RESERVED1[2]; /*!< Reserved, 0x24-0x28 */ - __IO uint32_t CFGR; /*!< SYSCFG Configuration register, Address offset: 0x2C */ - __IO uint32_t MCHDLYCR; /*!< SYSCFG multi-channel delay register, Address offset: 0x30 */ -} SYSCFG_TypeDef; - -/** - * @brief Inter-integrated Circuit Interface - */ - -typedef struct -{ - __IO uint32_t CR1; /*!< I2C Control register 1, Address offset: 0x00 */ - __IO uint32_t CR2; /*!< I2C Control register 2, Address offset: 0x04 */ - __IO uint32_t OAR1; /*!< I2C Own address register 1, Address offset: 0x08 */ - __IO uint32_t OAR2; /*!< I2C Own address register 2, Address offset: 0x0C */ - __IO uint32_t DR; /*!< I2C Data register, Address offset: 0x10 */ - __IO uint32_t SR1; /*!< I2C Status register 1, Address offset: 0x14 */ - __IO uint32_t SR2; /*!< I2C Status register 2, Address offset: 0x18 */ - __IO uint32_t CCR; /*!< I2C Clock control register, Address offset: 0x1C */ - __IO uint32_t TRISE; /*!< I2C TRISE register, Address offset: 0x20 */ - __IO uint32_t FLTR; /*!< I2C FLTR register, Address offset: 0x24 */ -} I2C_TypeDef; - -/** - * @brief Inter-integrated Circuit Interface - */ - -typedef struct -{ - __IO uint32_t CR1; /*!< FMPI2C Control register 1, Address offset: 0x00 */ - __IO uint32_t CR2; /*!< FMPI2C Control register 2, Address offset: 0x04 */ - __IO uint32_t OAR1; /*!< FMPI2C Own address 1 register, Address offset: 0x08 */ - __IO uint32_t OAR2; /*!< FMPI2C Own address 2 register, Address offset: 0x0C */ - __IO uint32_t TIMINGR; /*!< FMPI2C Timing register, Address offset: 0x10 */ - __IO uint32_t TIMEOUTR; /*!< FMPI2C Timeout register, Address offset: 0x14 */ - __IO uint32_t ISR; /*!< FMPI2C Interrupt and status register, Address offset: 0x18 */ - __IO uint32_t ICR; /*!< FMPI2C Interrupt clear register, Address offset: 0x1C */ - __IO uint32_t PECR; /*!< FMPI2C PEC register, Address offset: 0x20 */ - __IO uint32_t RXDR; /*!< FMPI2C Receive data register, Address offset: 0x24 */ - __IO uint32_t TXDR; /*!< FMPI2C Transmit data register, Address offset: 0x28 */ -} FMPI2C_TypeDef; - -/** - * @brief Independent WATCHDOG - */ - -typedef struct -{ - __IO uint32_t KR; /*!< IWDG Key register, Address offset: 0x00 */ - __IO uint32_t PR; /*!< IWDG Prescaler register, Address offset: 0x04 */ - __IO uint32_t RLR; /*!< IWDG Reload register, Address offset: 0x08 */ - __IO uint32_t SR; /*!< IWDG Status register, Address offset: 0x0C */ -} IWDG_TypeDef; - - -/** - * @brief Power Control - */ - -typedef struct -{ - __IO uint32_t CR; /*!< PWR power control register, Address offset: 0x00 */ - __IO uint32_t CSR; /*!< PWR power control/status register, Address offset: 0x04 */ -} PWR_TypeDef; - -/** - * @brief Reset and Clock Control - */ - -typedef struct -{ - __IO uint32_t CR; /*!< RCC clock control register, Address offset: 0x00 */ - __IO uint32_t PLLCFGR; /*!< RCC PLL configuration register, Address offset: 0x04 */ - __IO uint32_t CFGR; /*!< RCC clock configuration register, Address offset: 0x08 */ - __IO uint32_t CIR; /*!< RCC clock interrupt register, Address offset: 0x0C */ - __IO uint32_t AHB1RSTR; /*!< RCC AHB1 peripheral reset register, Address offset: 0x10 */ - __IO uint32_t AHB2RSTR; /*!< RCC AHB2 peripheral reset register, Address offset: 0x14 */ - __IO uint32_t AHB3RSTR; /*!< RCC AHB3 peripheral reset register, Address offset: 0x18 */ - uint32_t RESERVED0; /*!< Reserved, 0x1C */ - __IO uint32_t APB1RSTR; /*!< RCC APB1 peripheral reset register, Address offset: 0x20 */ - __IO uint32_t APB2RSTR; /*!< RCC APB2 peripheral reset register, Address offset: 0x24 */ - uint32_t RESERVED1[2]; /*!< Reserved, 0x28-0x2C */ - __IO uint32_t AHB1ENR; /*!< RCC AHB1 peripheral clock register, Address offset: 0x30 */ - __IO uint32_t AHB2ENR; /*!< RCC AHB2 peripheral clock register, Address offset: 0x34 */ - __IO uint32_t AHB3ENR; /*!< RCC AHB3 peripheral clock register, Address offset: 0x38 */ - uint32_t RESERVED2; /*!< Reserved, 0x3C */ - __IO uint32_t APB1ENR; /*!< RCC APB1 peripheral clock enable register, Address offset: 0x40 */ - __IO uint32_t APB2ENR; /*!< RCC APB2 peripheral clock enable register, Address offset: 0x44 */ - uint32_t RESERVED3[2]; /*!< Reserved, 0x48-0x4C */ - __IO uint32_t AHB1LPENR; /*!< RCC AHB1 peripheral clock enable in low power mode register, Address offset: 0x50 */ - __IO uint32_t AHB2LPENR; /*!< RCC AHB2 peripheral clock enable in low power mode register, Address offset: 0x54 */ - __IO uint32_t AHB3LPENR; /*!< RCC AHB3 peripheral clock enable in low power mode register, Address offset: 0x58 */ - uint32_t RESERVED4; /*!< Reserved, 0x5C */ - __IO uint32_t APB1LPENR; /*!< RCC APB1 peripheral clock enable in low power mode register, Address offset: 0x60 */ - __IO uint32_t APB2LPENR; /*!< RCC APB2 peripheral clock enable in low power mode register, Address offset: 0x64 */ - uint32_t RESERVED5[2]; /*!< Reserved, 0x68-0x6C */ - __IO uint32_t BDCR; /*!< RCC Backup domain control register, Address offset: 0x70 */ - __IO uint32_t CSR; /*!< RCC clock control & status register, Address offset: 0x74 */ - uint32_t RESERVED6[2]; /*!< Reserved, 0x78-0x7C */ - __IO uint32_t SSCGR; /*!< RCC spread spectrum clock generation register, Address offset: 0x80 */ - __IO uint32_t PLLI2SCFGR; /*!< RCC PLLI2S configuration register, Address offset: 0x84 */ - uint32_t RESERVED7; /*!< Reserved, 0x84 */ - __IO uint32_t DCKCFGR; /*!< RCC Dedicated Clocks configuration register, Address offset: 0x8C */ - __IO uint32_t CKGATENR; /*!< RCC Clocks Gated ENable Register, Address offset: 0x90 */ - __IO uint32_t DCKCFGR2; /*!< RCC Dedicated Clocks configuration register 2, Address offset: 0x94 */ -} RCC_TypeDef; - -/** - * @brief Real-Time Clock - */ - -typedef struct -{ - __IO uint32_t TR; /*!< RTC time register, Address offset: 0x00 */ - __IO uint32_t DR; /*!< RTC date register, Address offset: 0x04 */ - __IO uint32_t CR; /*!< RTC control register, Address offset: 0x08 */ - __IO uint32_t ISR; /*!< RTC initialization and status register, Address offset: 0x0C */ - __IO uint32_t PRER; /*!< RTC prescaler register, Address offset: 0x10 */ - __IO uint32_t WUTR; /*!< RTC wakeup timer register, Address offset: 0x14 */ - __IO uint32_t CALIBR; /*!< RTC calibration register, Address offset: 0x18 */ - __IO uint32_t ALRMAR; /*!< RTC alarm A register, Address offset: 0x1C */ - __IO uint32_t ALRMBR; /*!< RTC alarm B register, Address offset: 0x20 */ - __IO uint32_t WPR; /*!< RTC write protection register, Address offset: 0x24 */ - __IO uint32_t SSR; /*!< RTC sub second register, Address offset: 0x28 */ - __IO uint32_t SHIFTR; /*!< RTC shift control register, Address offset: 0x2C */ - __IO uint32_t TSTR; /*!< RTC time stamp time register, Address offset: 0x30 */ - __IO uint32_t TSDR; /*!< RTC time stamp date register, Address offset: 0x34 */ - __IO uint32_t TSSSR; /*!< RTC time-stamp sub second register, Address offset: 0x38 */ - __IO uint32_t CALR; /*!< RTC calibration register, Address offset: 0x3C */ - __IO uint32_t TAFCR; /*!< RTC tamper and alternate function configuration register, Address offset: 0x40 */ - __IO uint32_t ALRMASSR;/*!< RTC alarm A sub second register, Address offset: 0x44 */ - __IO uint32_t ALRMBSSR;/*!< RTC alarm B sub second register, Address offset: 0x48 */ - uint32_t RESERVED7; /*!< Reserved, 0x4C */ - __IO uint32_t BKP0R; /*!< RTC backup register 1, Address offset: 0x50 */ - __IO uint32_t BKP1R; /*!< RTC backup register 1, Address offset: 0x54 */ - __IO uint32_t BKP2R; /*!< RTC backup register 2, Address offset: 0x58 */ - __IO uint32_t BKP3R; /*!< RTC backup register 3, Address offset: 0x5C */ - __IO uint32_t BKP4R; /*!< RTC backup register 4, Address offset: 0x60 */ - __IO uint32_t BKP5R; /*!< RTC backup register 5, Address offset: 0x64 */ - __IO uint32_t BKP6R; /*!< RTC backup register 6, Address offset: 0x68 */ - __IO uint32_t BKP7R; /*!< RTC backup register 7, Address offset: 0x6C */ - __IO uint32_t BKP8R; /*!< RTC backup register 8, Address offset: 0x70 */ - __IO uint32_t BKP9R; /*!< RTC backup register 9, Address offset: 0x74 */ - __IO uint32_t BKP10R; /*!< RTC backup register 10, Address offset: 0x78 */ - __IO uint32_t BKP11R; /*!< RTC backup register 11, Address offset: 0x7C */ - __IO uint32_t BKP12R; /*!< RTC backup register 12, Address offset: 0x80 */ - __IO uint32_t BKP13R; /*!< RTC backup register 13, Address offset: 0x84 */ - __IO uint32_t BKP14R; /*!< RTC backup register 14, Address offset: 0x88 */ - __IO uint32_t BKP15R; /*!< RTC backup register 15, Address offset: 0x8C */ - __IO uint32_t BKP16R; /*!< RTC backup register 16, Address offset: 0x90 */ - __IO uint32_t BKP17R; /*!< RTC backup register 17, Address offset: 0x94 */ - __IO uint32_t BKP18R; /*!< RTC backup register 18, Address offset: 0x98 */ - __IO uint32_t BKP19R; /*!< RTC backup register 19, Address offset: 0x9C */ -} RTC_TypeDef; - -/** - * @brief Serial Audio Interface - */ - -typedef struct -{ - __IO uint32_t GCR; /*!< SAI global configuration register, Address offset: 0x00 */ -} SAI_TypeDef; - -typedef struct -{ - __IO uint32_t CR1; /*!< SAI block x configuration register 1, Address offset: 0x04 */ - __IO uint32_t CR2; /*!< SAI block x configuration register 2, Address offset: 0x08 */ - __IO uint32_t FRCR; /*!< SAI block x frame configuration register, Address offset: 0x0C */ - __IO uint32_t SLOTR; /*!< SAI block x slot register, Address offset: 0x10 */ - __IO uint32_t IMR; /*!< SAI block x interrupt mask register, Address offset: 0x14 */ - __IO uint32_t SR; /*!< SAI block x status register, Address offset: 0x18 */ - __IO uint32_t CLRFR; /*!< SAI block x clear flag register, Address offset: 0x1C */ - __IO uint32_t DR; /*!< SAI block x data register, Address offset: 0x20 */ -} SAI_Block_TypeDef; - -/** - * @brief SD host Interface - */ - -typedef struct -{ - __IO uint32_t POWER; /*!< SDIO power control register, Address offset: 0x00 */ - __IO uint32_t CLKCR; /*!< SDI clock control register, Address offset: 0x04 */ - __IO uint32_t ARG; /*!< SDIO argument register, Address offset: 0x08 */ - __IO uint32_t CMD; /*!< SDIO command register, Address offset: 0x0C */ - __IO const uint32_t RESPCMD; /*!< SDIO command response register, Address offset: 0x10 */ - __IO const uint32_t RESP1; /*!< SDIO response 1 register, Address offset: 0x14 */ - __IO const uint32_t RESP2; /*!< SDIO response 2 register, Address offset: 0x18 */ - __IO const uint32_t RESP3; /*!< SDIO response 3 register, Address offset: 0x1C */ - __IO const uint32_t RESP4; /*!< SDIO response 4 register, Address offset: 0x20 */ - __IO uint32_t DTIMER; /*!< SDIO data timer register, Address offset: 0x24 */ - __IO uint32_t DLEN; /*!< SDIO data length register, Address offset: 0x28 */ - __IO uint32_t DCTRL; /*!< SDIO data control register, Address offset: 0x2C */ - __IO const uint32_t DCOUNT; /*!< SDIO data counter register, Address offset: 0x30 */ - __IO const uint32_t STA; /*!< SDIO status register, Address offset: 0x34 */ - __IO uint32_t ICR; /*!< SDIO interrupt clear register, Address offset: 0x38 */ - __IO uint32_t MASK; /*!< SDIO mask register, Address offset: 0x3C */ - uint32_t RESERVED0[2]; /*!< Reserved, 0x40-0x44 */ - __IO const uint32_t FIFOCNT; /*!< SDIO FIFO counter register, Address offset: 0x48 */ - uint32_t RESERVED1[13]; /*!< Reserved, 0x4C-0x7C */ - __IO uint32_t FIFO; /*!< SDIO data FIFO register, Address offset: 0x80 */ -} SDIO_TypeDef; - -/** - * @brief Serial Peripheral Interface - */ - -typedef struct -{ - __IO uint32_t CR1; /*!< SPI control register 1 (not used in I2S mode), Address offset: 0x00 */ - __IO uint32_t CR2; /*!< SPI control register 2, Address offset: 0x04 */ - __IO uint32_t SR; /*!< SPI status register, Address offset: 0x08 */ - __IO uint32_t DR; /*!< SPI data register, Address offset: 0x0C */ - __IO uint32_t CRCPR; /*!< SPI CRC polynomial register (not used in I2S mode), Address offset: 0x10 */ - __IO uint32_t RXCRCR; /*!< SPI RX CRC register (not used in I2S mode), Address offset: 0x14 */ - __IO uint32_t TXCRCR; /*!< SPI TX CRC register (not used in I2S mode), Address offset: 0x18 */ - __IO uint32_t I2SCFGR; /*!< SPI_I2S configuration register, Address offset: 0x1C */ - __IO uint32_t I2SPR; /*!< SPI_I2S prescaler register, Address offset: 0x20 */ -} SPI_TypeDef; - -/** - * @brief QUAD Serial Peripheral Interface - */ - -typedef struct -{ - __IO uint32_t CR; /*!< QUADSPI Control register, Address offset: 0x00 */ - __IO uint32_t DCR; /*!< QUADSPI Device Configuration register, Address offset: 0x04 */ - __IO uint32_t SR; /*!< QUADSPI Status register, Address offset: 0x08 */ - __IO uint32_t FCR; /*!< QUADSPI Flag Clear register, Address offset: 0x0C */ - __IO uint32_t DLR; /*!< QUADSPI Data Length register, Address offset: 0x10 */ - __IO uint32_t CCR; /*!< QUADSPI Communication Configuration register, Address offset: 0x14 */ - __IO uint32_t AR; /*!< QUADSPI Address register, Address offset: 0x18 */ - __IO uint32_t ABR; /*!< QUADSPI Alternate Bytes register, Address offset: 0x1C */ - __IO uint32_t DR; /*!< QUADSPI Data register, Address offset: 0x20 */ - __IO uint32_t PSMKR; /*!< QUADSPI Polling Status Mask register, Address offset: 0x24 */ - __IO uint32_t PSMAR; /*!< QUADSPI Polling Status Match register, Address offset: 0x28 */ - __IO uint32_t PIR; /*!< QUADSPI Polling Interval register, Address offset: 0x2C */ - __IO uint32_t LPTR; /*!< QUADSPI Low Power Timeout register, Address offset: 0x30 */ -} QUADSPI_TypeDef; - -/** - * @brief TIM - */ - -typedef struct -{ - __IO uint32_t CR1; /*!< TIM control register 1, Address offset: 0x00 */ - __IO uint32_t CR2; /*!< TIM control register 2, Address offset: 0x04 */ - __IO uint32_t SMCR; /*!< TIM slave mode control register, Address offset: 0x08 */ - __IO uint32_t DIER; /*!< TIM DMA/interrupt enable register, Address offset: 0x0C */ - __IO uint32_t SR; /*!< TIM status register, Address offset: 0x10 */ - __IO uint32_t EGR; /*!< TIM event generation register, Address offset: 0x14 */ - __IO uint32_t CCMR1; /*!< TIM capture/compare mode register 1, Address offset: 0x18 */ - __IO uint32_t CCMR2; /*!< TIM capture/compare mode register 2, Address offset: 0x1C */ - __IO uint32_t CCER; /*!< TIM capture/compare enable register, Address offset: 0x20 */ - __IO uint32_t CNT; /*!< TIM counter register, Address offset: 0x24 */ - __IO uint32_t PSC; /*!< TIM prescaler, Address offset: 0x28 */ - __IO uint32_t ARR; /*!< TIM auto-reload register, Address offset: 0x2C */ - __IO uint32_t RCR; /*!< TIM repetition counter register, Address offset: 0x30 */ - __IO uint32_t CCR1; /*!< TIM capture/compare register 1, Address offset: 0x34 */ - __IO uint32_t CCR2; /*!< TIM capture/compare register 2, Address offset: 0x38 */ - __IO uint32_t CCR3; /*!< TIM capture/compare register 3, Address offset: 0x3C */ - __IO uint32_t CCR4; /*!< TIM capture/compare register 4, Address offset: 0x40 */ - __IO uint32_t BDTR; /*!< TIM break and dead-time register, Address offset: 0x44 */ - __IO uint32_t DCR; /*!< TIM DMA control register, Address offset: 0x48 */ - __IO uint32_t DMAR; /*!< TIM DMA address for full transfer, Address offset: 0x4C */ - __IO uint32_t OR; /*!< TIM option register, Address offset: 0x50 */ -} TIM_TypeDef; - -/** - * @brief Universal Synchronous Asynchronous Receiver Transmitter - */ - -typedef struct -{ - __IO uint32_t SR; /*!< USART Status register, Address offset: 0x00 */ - __IO uint32_t DR; /*!< USART Data register, Address offset: 0x04 */ - __IO uint32_t BRR; /*!< USART Baud rate register, Address offset: 0x08 */ - __IO uint32_t CR1; /*!< USART Control register 1, Address offset: 0x0C */ - __IO uint32_t CR2; /*!< USART Control register 2, Address offset: 0x10 */ - __IO uint32_t CR3; /*!< USART Control register 3, Address offset: 0x14 */ - __IO uint32_t GTPR; /*!< USART Guard time and prescaler register, Address offset: 0x18 */ -} USART_TypeDef; - -/** - * @brief Window WATCHDOG - */ - -typedef struct -{ - __IO uint32_t CR; /*!< WWDG Control register, Address offset: 0x00 */ - __IO uint32_t CFR; /*!< WWDG Configuration register, Address offset: 0x04 */ - __IO uint32_t SR; /*!< WWDG Status register, Address offset: 0x08 */ -} WWDG_TypeDef; - -/** - * @brief RNG - */ - -typedef struct -{ - __IO uint32_t CR; /*!< RNG control register, Address offset: 0x00 */ - __IO uint32_t SR; /*!< RNG status register, Address offset: 0x04 */ - __IO uint32_t DR; /*!< RNG data register, Address offset: 0x08 */ -} RNG_TypeDef; - -/** - * @brief USB_OTG_Core_Registers - */ -typedef struct -{ - __IO uint32_t GOTGCTL; /*!< USB_OTG Control and Status Register 000h */ - __IO uint32_t GOTGINT; /*!< USB_OTG Interrupt Register 004h */ - __IO uint32_t GAHBCFG; /*!< Core AHB Configuration Register 008h */ - __IO uint32_t GUSBCFG; /*!< Core USB Configuration Register 00Ch */ - __IO uint32_t GRSTCTL; /*!< Core Reset Register 010h */ - __IO uint32_t GINTSTS; /*!< Core Interrupt Register 014h */ - __IO uint32_t GINTMSK; /*!< Core Interrupt Mask Register 018h */ - __IO uint32_t GRXSTSR; /*!< Receive Sts Q Read Register 01Ch */ - __IO uint32_t GRXSTSP; /*!< Receive Sts Q Read & POP Register 020h */ - __IO uint32_t GRXFSIZ; /*!< Receive FIFO Size Register 024h */ - __IO uint32_t DIEPTXF0_HNPTXFSIZ; /*!< EP0 / Non Periodic Tx FIFO Size Register 028h */ - __IO uint32_t HNPTXSTS; /*!< Non Periodic Tx FIFO/Queue Sts reg 02Ch */ - uint32_t Reserved30[2]; /*!< Reserved 030h */ - __IO uint32_t GCCFG; /*!< General Purpose IO Register 038h */ - __IO uint32_t CID; /*!< User ID Register 03Ch */ - uint32_t Reserved5[3]; /*!< Reserved 040h-048h */ - __IO uint32_t GHWCFG3; /*!< User HW config3 04Ch */ - uint32_t Reserved6; /*!< Reserved 050h */ - __IO uint32_t GLPMCFG; /*!< LPM Register 054h */ - uint32_t Reserved; /*!< Reserved 058h */ - __IO uint32_t GDFIFOCFG; /*!< DFIFO Software Config Register 05Ch */ - uint32_t Reserved43[40]; /*!< Reserved 058h-0FFh */ - __IO uint32_t HPTXFSIZ; /*!< Host Periodic Tx FIFO Size Reg 100h */ - __IO uint32_t DIEPTXF[0x0F]; /*!< dev Periodic Transmit FIFO */ -} USB_OTG_GlobalTypeDef; - -/** - * @brief USB_OTG_device_Registers - */ -typedef struct -{ - __IO uint32_t DCFG; /*!< dev Configuration Register 800h */ - __IO uint32_t DCTL; /*!< dev Control Register 804h */ - __IO uint32_t DSTS; /*!< dev Status Register (RO) 808h */ - uint32_t Reserved0C; /*!< Reserved 80Ch */ - __IO uint32_t DIEPMSK; /*!< dev IN Endpoint Mask 810h */ - __IO uint32_t DOEPMSK; /*!< dev OUT Endpoint Mask 814h */ - __IO uint32_t DAINT; /*!< dev All Endpoints Itr Reg 818h */ - __IO uint32_t DAINTMSK; /*!< dev All Endpoints Itr Mask 81Ch */ - uint32_t Reserved20; /*!< Reserved 820h */ - uint32_t Reserved9; /*!< Reserved 824h */ - __IO uint32_t DVBUSDIS; /*!< dev VBUS discharge Register 828h */ - __IO uint32_t DVBUSPULSE; /*!< dev VBUS Pulse Register 82Ch */ - __IO uint32_t DTHRCTL; /*!< dev threshold 830h */ - __IO uint32_t DIEPEMPMSK; /*!< dev empty msk 834h */ - __IO uint32_t DEACHINT; /*!< dedicated EP interrupt 838h */ - __IO uint32_t DEACHMSK; /*!< dedicated EP msk 83Ch */ - uint32_t Reserved40; /*!< dedicated EP mask 840h */ - __IO uint32_t DINEP1MSK; /*!< dedicated EP mask 844h */ - uint32_t Reserved44[15]; /*!< Reserved 844-87Ch */ - __IO uint32_t DOUTEP1MSK; /*!< dedicated EP msk 884h */ -} USB_OTG_DeviceTypeDef; - -/** - * @brief USB_OTG_IN_Endpoint-Specific_Register - */ -typedef struct -{ - __IO uint32_t DIEPCTL; /*!< dev IN Endpoint Control Reg 900h + (ep_num * 20h) + 00h */ - uint32_t Reserved04; /*!< Reserved 900h + (ep_num * 20h) + 04h */ - __IO uint32_t DIEPINT; /*!< dev IN Endpoint Itr Reg 900h + (ep_num * 20h) + 08h */ - uint32_t Reserved0C; /*!< Reserved 900h + (ep_num * 20h) + 0Ch */ - __IO uint32_t DIEPTSIZ; /*!< IN Endpoint Txfer Size 900h + (ep_num * 20h) + 10h */ - __IO uint32_t DIEPDMA; /*!< IN Endpoint DMA Address Reg 900h + (ep_num * 20h) + 14h */ - __IO uint32_t DTXFSTS; /*!< IN Endpoint Tx FIFO Status Reg 900h + (ep_num * 20h) + 18h */ - uint32_t Reserved18; /*!< Reserved 900h+(ep_num*20h)+1Ch-900h+ (ep_num * 20h) + 1Ch */ -} USB_OTG_INEndpointTypeDef; - -/** - * @brief USB_OTG_OUT_Endpoint-Specific_Registers - */ -typedef struct -{ - __IO uint32_t DOEPCTL; /*!< dev OUT Endpoint Control Reg B00h + (ep_num * 20h) + 00h */ - uint32_t Reserved04; /*!< Reserved B00h + (ep_num * 20h) + 04h */ - __IO uint32_t DOEPINT; /*!< dev OUT Endpoint Itr Reg B00h + (ep_num * 20h) + 08h */ - uint32_t Reserved0C; /*!< Reserved B00h + (ep_num * 20h) + 0Ch */ - __IO uint32_t DOEPTSIZ; /*!< dev OUT Endpoint Txfer Size B00h + (ep_num * 20h) + 10h */ - __IO uint32_t DOEPDMA; /*!< dev OUT Endpoint DMA Address B00h + (ep_num * 20h) + 14h */ - uint32_t Reserved18[2]; /*!< Reserved B00h + (ep_num * 20h) + 18h - B00h + (ep_num * 20h) + 1Ch */ -} USB_OTG_OUTEndpointTypeDef; - -/** - * @brief USB_OTG_Host_Mode_Register_Structures - */ -typedef struct -{ - __IO uint32_t HCFG; /*!< Host Configuration Register 400h */ - __IO uint32_t HFIR; /*!< Host Frame Interval Register 404h */ - __IO uint32_t HFNUM; /*!< Host Frame Nbr/Frame Remaining 408h */ - uint32_t Reserved40C; /*!< Reserved 40Ch */ - __IO uint32_t HPTXSTS; /*!< Host Periodic Tx FIFO/ Queue Status 410h */ - __IO uint32_t HAINT; /*!< Host All Channels Interrupt Register 414h */ - __IO uint32_t HAINTMSK; /*!< Host All Channels Interrupt Mask 418h */ -} USB_OTG_HostTypeDef; - -/** - * @brief USB_OTG_Host_Channel_Specific_Registers - */ -typedef struct -{ - __IO uint32_t HCCHAR; /*!< Host Channel Characteristics Register 500h */ - __IO uint32_t HCSPLT; /*!< Host Channel Split Control Register 504h */ - __IO uint32_t HCINT; /*!< Host Channel Interrupt Register 508h */ - __IO uint32_t HCINTMSK; /*!< Host Channel Interrupt Mask Register 50Ch */ - __IO uint32_t HCTSIZ; /*!< Host Channel Transfer Size Register 510h */ - __IO uint32_t HCDMA; /*!< Host Channel DMA Address Register 514h */ - uint32_t Reserved[2]; /*!< Reserved */ -} USB_OTG_HostChannelTypeDef; - -/** - * @brief LPTIMER - */ -typedef struct -{ - __IO uint32_t ISR; /*!< LPTIM Interrupt and Status register, Address offset: 0x00 */ - __IO uint32_t ICR; /*!< LPTIM Interrupt Clear register, Address offset: 0x04 */ - __IO uint32_t IER; /*!< LPTIM Interrupt Enable register, Address offset: 0x08 */ - __IO uint32_t CFGR; /*!< LPTIM Configuration register, Address offset: 0x0C */ - __IO uint32_t CR; /*!< LPTIM Control register, Address offset: 0x10 */ - __IO uint32_t CMP; /*!< LPTIM Compare register, Address offset: 0x14 */ - __IO uint32_t ARR; /*!< LPTIM Autoreload register, Address offset: 0x18 */ - __IO uint32_t CNT; /*!< LPTIM Counter register, Address offset: 0x1C */ - __IO uint32_t OR; /*!< LPTIM Option register, Address offset: 0x20 */ -} LPTIM_TypeDef; - -/** - * @} - */ - -/** @addtogroup Peripheral_memory_map - * @{ - */ -#define FLASH_BASE 0x08000000U /*!< FLASH (up to 1.5 MB) base address in the alias region */ -#define SRAM1_BASE 0x20000000U /*!< SRAM1(256 KB) base address in the alias region */ -#define SRAM2_BASE 0x20040000U /*!< SRAM2(64 KB) base address in the alias region */ -#define PERIPH_BASE 0x40000000U /*!< Peripheral base address in the alias region */ -#define FSMC_R_BASE 0xA0000000U /*!< FSMC registers base address */ -#define QSPI_R_BASE 0xA0001000U /*!< QuadSPI registers base address */ -#define SRAM1_BB_BASE 0x22000000U /*!< SRAM1(256 KB) base address in the bit-band region */ -#define SRAM2_BB_BASE 0x22800000U /*!< SRAM2(64 KB) base address in the bit-band region */ -#define PERIPH_BB_BASE 0x42000000U /*!< Peripheral base address in the bit-band region */ -#define FLASH_END 0x0817FFFFU /*!< FLASH end address */ - -/* Legacy defines */ -#define SRAM_BASE SRAM1_BASE -#define SRAM_BB_BASE SRAM1_BB_BASE - - -/*!< Peripheral memory map */ -#define APB1PERIPH_BASE PERIPH_BASE -#define APB2PERIPH_BASE (PERIPH_BASE + 0x00010000U) -#define AHB1PERIPH_BASE (PERIPH_BASE + 0x00020000U) -#define AHB2PERIPH_BASE (PERIPH_BASE + 0x10000000U) - -/*!< APB1 peripherals */ -#define TIM2_BASE (APB1PERIPH_BASE + 0x0000U) -#define TIM3_BASE (APB1PERIPH_BASE + 0x0400U) -#define TIM4_BASE (APB1PERIPH_BASE + 0x0800U) -#define TIM5_BASE (APB1PERIPH_BASE + 0x0C00U) -#define TIM6_BASE (APB1PERIPH_BASE + 0x1000U) -#define TIM7_BASE (APB1PERIPH_BASE + 0x1400U) -#define TIM12_BASE (APB1PERIPH_BASE + 0x1800U) -#define TIM13_BASE (APB1PERIPH_BASE + 0x1C00U) -#define TIM14_BASE (APB1PERIPH_BASE + 0x2000U) -#define LPTIM1_BASE (APB1PERIPH_BASE + 0x2400U) -#define RTC_BASE (APB1PERIPH_BASE + 0x2800U) -#define WWDG_BASE (APB1PERIPH_BASE + 0x2C00U) -#define IWDG_BASE (APB1PERIPH_BASE + 0x3000U) -#define I2S2ext_BASE (APB1PERIPH_BASE + 0x3400U) -#define SPI2_BASE (APB1PERIPH_BASE + 0x3800U) -#define SPI3_BASE (APB1PERIPH_BASE + 0x3C00U) -#define I2S3ext_BASE (APB1PERIPH_BASE + 0x4000U) -#define USART2_BASE (APB1PERIPH_BASE + 0x4400U) -#define USART3_BASE (APB1PERIPH_BASE + 0x4800U) -#define UART4_BASE (APB1PERIPH_BASE + 0x4C00U) -#define UART5_BASE (APB1PERIPH_BASE + 0x5000U) -#define I2C1_BASE (APB1PERIPH_BASE + 0x5400U) -#define I2C2_BASE (APB1PERIPH_BASE + 0x5800U) -#define I2C3_BASE (APB1PERIPH_BASE + 0x5C00U) -#define FMPI2C1_BASE (APB1PERIPH_BASE + 0x6000U) -#define CAN1_BASE (APB1PERIPH_BASE + 0x6400U) -#define CAN2_BASE (APB1PERIPH_BASE + 0x6800U) -#define CAN3_BASE (APB1PERIPH_BASE + 0x6C00U) -#define PWR_BASE (APB1PERIPH_BASE + 0x7000U) -#define DAC_BASE (APB1PERIPH_BASE + 0x7400U) -#define UART7_BASE (APB1PERIPH_BASE + 0x7800U) -#define UART8_BASE (APB1PERIPH_BASE + 0x7C00U) - -/*!< APB2 peripherals */ -#define TIM1_BASE (APB2PERIPH_BASE + 0x0000U) -#define TIM8_BASE (APB2PERIPH_BASE + 0x0400U) -#define USART1_BASE (APB2PERIPH_BASE + 0x1000U) -#define USART6_BASE (APB2PERIPH_BASE + 0x1400U) -#define UART9_BASE (APB2PERIPH_BASE + 0x1800U) -#define UART10_BASE (APB2PERIPH_BASE + 0x1C00U) -#define ADC1_BASE (APB2PERIPH_BASE + 0x2000U) -#define ADC_BASE (APB2PERIPH_BASE + 0x2300U) -#define SDIO_BASE (APB2PERIPH_BASE + 0x2C00U) -#define SPI1_BASE (APB2PERIPH_BASE + 0x3000U) -#define SPI4_BASE (APB2PERIPH_BASE + 0x3400U) -#define SYSCFG_BASE (APB2PERIPH_BASE + 0x3800U) -#define EXTI_BASE (APB2PERIPH_BASE + 0x3C00U) -#define TIM9_BASE (APB2PERIPH_BASE + 0x4000U) -#define TIM10_BASE (APB2PERIPH_BASE + 0x4400U) -#define TIM11_BASE (APB2PERIPH_BASE + 0x4800U) -#define SPI5_BASE (APB2PERIPH_BASE + 0x5000U) -#define DFSDM1_BASE (APB2PERIPH_BASE + 0x6000U) -#define DFSDM2_BASE (APB2PERIPH_BASE + 0x6400U) -#define DFSDM1_Channel0_BASE (DFSDM1_BASE + 0x00U) -#define DFSDM1_Channel1_BASE (DFSDM1_BASE + 0x20U) -#define DFSDM1_Channel2_BASE (DFSDM1_BASE + 0x40U) -#define DFSDM1_Channel3_BASE (DFSDM1_BASE + 0x60U) -#define DFSDM1_Filter0_BASE (DFSDM1_BASE + 0x100U) -#define DFSDM1_Filter1_BASE (DFSDM1_BASE + 0x180U) -#define DFSDM2_Channel0_BASE (DFSDM2_BASE + 0x00U) -#define DFSDM2_Channel1_BASE (DFSDM2_BASE + 0x20U) -#define DFSDM2_Channel2_BASE (DFSDM2_BASE + 0x40U) -#define DFSDM2_Channel3_BASE (DFSDM2_BASE + 0x60U) -#define DFSDM2_Channel4_BASE (DFSDM2_BASE + 0x80U) -#define DFSDM2_Channel5_BASE (DFSDM2_BASE + 0xA0U) -#define DFSDM2_Channel6_BASE (DFSDM2_BASE + 0xC0U) -#define DFSDM2_Channel7_BASE (DFSDM2_BASE + 0xE0U) -#define DFSDM2_Filter0_BASE (DFSDM2_BASE + 0x100U) -#define DFSDM2_Filter1_BASE (DFSDM2_BASE + 0x180U) -#define DFSDM2_Filter2_BASE (DFSDM2_BASE + 0x200U) -#define DFSDM2_Filter3_BASE (DFSDM2_BASE + 0x280U) -#define SAI1_BASE (APB2PERIPH_BASE + 0x5800U) -#define SAI1_Block_A_BASE (SAI1_BASE + 0x004U) -#define SAI1_Block_B_BASE (SAI1_BASE + 0x024U) - -/*!< AHB1 peripherals */ -#define GPIOA_BASE (AHB1PERIPH_BASE + 0x0000U) -#define GPIOB_BASE (AHB1PERIPH_BASE + 0x0400U) -#define GPIOC_BASE (AHB1PERIPH_BASE + 0x0800U) -#define GPIOD_BASE (AHB1PERIPH_BASE + 0x0C00U) -#define GPIOE_BASE (AHB1PERIPH_BASE + 0x1000U) -#define GPIOF_BASE (AHB1PERIPH_BASE + 0x1400U) -#define GPIOG_BASE (AHB1PERIPH_BASE + 0x1800U) -#define GPIOH_BASE (AHB1PERIPH_BASE + 0x1C00U) -#define CRC_BASE (AHB1PERIPH_BASE + 0x3000U) -#define RCC_BASE (AHB1PERIPH_BASE + 0x3800U) -#define FLASH_R_BASE (AHB1PERIPH_BASE + 0x3C00U) -#define DMA1_BASE (AHB1PERIPH_BASE + 0x6000U) -#define DMA1_Stream0_BASE (DMA1_BASE + 0x010U) -#define DMA1_Stream1_BASE (DMA1_BASE + 0x028U) -#define DMA1_Stream2_BASE (DMA1_BASE + 0x040U) -#define DMA1_Stream3_BASE (DMA1_BASE + 0x058U) -#define DMA1_Stream4_BASE (DMA1_BASE + 0x070U) -#define DMA1_Stream5_BASE (DMA1_BASE + 0x088U) -#define DMA1_Stream6_BASE (DMA1_BASE + 0x0A0U) -#define DMA1_Stream7_BASE (DMA1_BASE + 0x0B8U) -#define DMA2_BASE (AHB1PERIPH_BASE + 0x6400U) -#define DMA2_Stream0_BASE (DMA2_BASE + 0x010U) -#define DMA2_Stream1_BASE (DMA2_BASE + 0x028U) -#define DMA2_Stream2_BASE (DMA2_BASE + 0x040U) -#define DMA2_Stream3_BASE (DMA2_BASE + 0x058U) -#define DMA2_Stream4_BASE (DMA2_BASE + 0x070U) -#define DMA2_Stream5_BASE (DMA2_BASE + 0x088U) -#define DMA2_Stream6_BASE (DMA2_BASE + 0x0A0U) -#define DMA2_Stream7_BASE (DMA2_BASE + 0x0B8U) - -/*!< AHB2 peripherals */ -#define RNG_BASE (AHB2PERIPH_BASE + 0x60800U) - - -/*!< FSMC Bankx registers base address */ -#define FSMC_Bank1_R_BASE (FSMC_R_BASE + 0x0000U) -#define FSMC_Bank1E_R_BASE (FSMC_R_BASE + 0x0104U) - -/*!< Debug MCU registers base address */ -#define DBGMCU_BASE 0xE0042000U -/*!< USB registers base address */ -#define USB_OTG_FS_PERIPH_BASE 0x50000000U - -#define USB_OTG_GLOBAL_BASE 0x000U -#define USB_OTG_DEVICE_BASE 0x800U -#define USB_OTG_IN_ENDPOINT_BASE 0x900U -#define USB_OTG_OUT_ENDPOINT_BASE 0xB00U -#define USB_OTG_EP_REG_SIZE 0x20U -#define USB_OTG_HOST_BASE 0x400U -#define USB_OTG_HOST_PORT_BASE 0x440U -#define USB_OTG_HOST_CHANNEL_BASE 0x500U -#define USB_OTG_HOST_CHANNEL_SIZE 0x20U -#define USB_OTG_PCGCCTL_BASE 0xE00U -#define USB_OTG_FIFO_BASE 0x1000U -#define USB_OTG_FIFO_SIZE 0x1000U - -#define UID_BASE 0x1FFF7A10U /*!< Unique device ID register base address */ -#define FLASHSIZE_BASE 0x1FFF7A22U /*!< FLASH Size register base address */ -#define PACKAGE_BASE 0x1FFF7BF0U /*!< Package size register base address */ -/** - * @} - */ - -/** @addtogroup Peripheral_declaration - * @{ - */ -#define TIM2 ((TIM_TypeDef *) TIM2_BASE) -#define TIM3 ((TIM_TypeDef *) TIM3_BASE) -#define TIM4 ((TIM_TypeDef *) TIM4_BASE) -#define TIM5 ((TIM_TypeDef *) TIM5_BASE) -#define TIM6 ((TIM_TypeDef *) TIM6_BASE) -#define TIM7 ((TIM_TypeDef *) TIM7_BASE) -#define TIM12 ((TIM_TypeDef *) TIM12_BASE) -#define TIM13 ((TIM_TypeDef *) TIM13_BASE) -#define TIM14 ((TIM_TypeDef *) TIM14_BASE) -#define LPTIM1 ((LPTIM_TypeDef *) LPTIM1_BASE) -#define RTC ((RTC_TypeDef *) RTC_BASE) -#define WWDG ((WWDG_TypeDef *) WWDG_BASE) -#define IWDG ((IWDG_TypeDef *) IWDG_BASE) -#define I2S2ext ((SPI_TypeDef *) I2S2ext_BASE) -#define SPI2 ((SPI_TypeDef *) SPI2_BASE) -#define SPI3 ((SPI_TypeDef *) SPI3_BASE) -#define I2S3ext ((SPI_TypeDef *) I2S3ext_BASE) -#define USART2 ((USART_TypeDef *) USART2_BASE) -#define USART3 ((USART_TypeDef *) USART3_BASE) -#define UART4 ((USART_TypeDef *) UART4_BASE) -#define UART5 ((USART_TypeDef *) UART5_BASE) -#define I2C1 ((I2C_TypeDef *) I2C1_BASE) -#define I2C2 ((I2C_TypeDef *) I2C2_BASE) -#define I2C3 ((I2C_TypeDef *) I2C3_BASE) -#define FMPI2C1 ((FMPI2C_TypeDef *) FMPI2C1_BASE) -#define CAN1 ((CAN_TypeDef *) CAN1_BASE) -#define CAN2 ((CAN_TypeDef *) CAN2_BASE) -#define CAN3 ((CAN_TypeDef *) CAN3_BASE) -#define PWR ((PWR_TypeDef *) PWR_BASE) -#define DAC1 ((DAC_TypeDef *) DAC_BASE) -#define DAC ((DAC_TypeDef *) DAC_BASE) /* Kept for legacy purpose */ -#define UART7 ((USART_TypeDef *) UART7_BASE) -#define UART8 ((USART_TypeDef *) UART8_BASE) -#define TIM1 ((TIM_TypeDef *) TIM1_BASE) -#define TIM8 ((TIM_TypeDef *) TIM8_BASE) -#define USART1 ((USART_TypeDef *) USART1_BASE) -#define USART6 ((USART_TypeDef *) USART6_BASE) -#define UART9 ((USART_TypeDef *) UART9_BASE) -#define UART10 ((USART_TypeDef *) UART10_BASE) -#define ADC ((ADC_Common_TypeDef *) ADC_BASE) -#define ADC1 ((ADC_TypeDef *) ADC1_BASE) -#define SDIO ((SDIO_TypeDef *) SDIO_BASE) -#define SPI1 ((SPI_TypeDef *) SPI1_BASE) -#define SPI4 ((SPI_TypeDef *) SPI4_BASE) -#define SYSCFG ((SYSCFG_TypeDef *) SYSCFG_BASE) -#define EXTI ((EXTI_TypeDef *) EXTI_BASE) -#define TIM9 ((TIM_TypeDef *) TIM9_BASE) -#define TIM10 ((TIM_TypeDef *) TIM10_BASE) -#define TIM11 ((TIM_TypeDef *) TIM11_BASE) -#define SPI5 ((SPI_TypeDef *) SPI5_BASE) -#define DFSDM1_Channel0 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel0_BASE) -#define DFSDM1_Channel1 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel1_BASE) -#define DFSDM1_Channel2 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel2_BASE) -#define DFSDM1_Channel3 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel3_BASE) -#define DFSDM1_Filter0 ((DFSDM_Filter_TypeDef *) DFSDM1_Filter0_BASE) -#define DFSDM1_Filter1 ((DFSDM_Filter_TypeDef *) DFSDM1_Filter1_BASE) -#define DFSDM2_Channel0 ((DFSDM_Channel_TypeDef *) DFSDM2_Channel0_BASE) -#define DFSDM2_Channel1 ((DFSDM_Channel_TypeDef *) DFSDM2_Channel1_BASE) -#define DFSDM2_Channel2 ((DFSDM_Channel_TypeDef *) DFSDM2_Channel2_BASE) -#define DFSDM2_Channel3 ((DFSDM_Channel_TypeDef *) DFSDM2_Channel3_BASE) -#define DFSDM2_Channel4 ((DFSDM_Channel_TypeDef *) DFSDM2_Channel4_BASE) -#define DFSDM2_Channel5 ((DFSDM_Channel_TypeDef *) DFSDM2_Channel5_BASE) -#define DFSDM2_Channel6 ((DFSDM_Channel_TypeDef *) DFSDM2_Channel6_BASE) -#define DFSDM2_Channel7 ((DFSDM_Channel_TypeDef *) DFSDM2_Channel7_BASE) -#define DFSDM2_Filter0 ((DFSDM_Filter_TypeDef *) DFSDM2_Filter0_BASE) -#define DFSDM2_Filter1 ((DFSDM_Filter_TypeDef *) DFSDM2_Filter1_BASE) -#define DFSDM2_Filter2 ((DFSDM_Filter_TypeDef *) DFSDM2_Filter2_BASE) -#define DFSDM2_Filter3 ((DFSDM_Filter_TypeDef *) DFSDM2_Filter3_BASE) -#define SAI1 ((SAI_TypeDef *) SAI1_BASE) -#define SAI1_Block_A ((SAI_Block_TypeDef *)SAI1_Block_A_BASE) -#define SAI1_Block_B ((SAI_Block_TypeDef *)SAI1_Block_B_BASE) -#define GPIOA ((GPIO_TypeDef *) GPIOA_BASE) -#define GPIOB ((GPIO_TypeDef *) GPIOB_BASE) -#define GPIOC ((GPIO_TypeDef *) GPIOC_BASE) -#define GPIOD ((GPIO_TypeDef *) GPIOD_BASE) -#define GPIOE ((GPIO_TypeDef *) GPIOE_BASE) -#define GPIOF ((GPIO_TypeDef *) GPIOF_BASE) -#define GPIOG ((GPIO_TypeDef *) GPIOG_BASE) -#define GPIOH ((GPIO_TypeDef *) GPIOH_BASE) -#define CRC ((CRC_TypeDef *) CRC_BASE) -#define RCC ((RCC_TypeDef *) RCC_BASE) -#define FLASH ((FLASH_TypeDef *) FLASH_R_BASE) -#define DMA1 ((DMA_TypeDef *) DMA1_BASE) -#define DMA1_Stream0 ((DMA_Stream_TypeDef *) DMA1_Stream0_BASE) -#define DMA1_Stream1 ((DMA_Stream_TypeDef *) DMA1_Stream1_BASE) -#define DMA1_Stream2 ((DMA_Stream_TypeDef *) DMA1_Stream2_BASE) -#define DMA1_Stream3 ((DMA_Stream_TypeDef *) DMA1_Stream3_BASE) -#define DMA1_Stream4 ((DMA_Stream_TypeDef *) DMA1_Stream4_BASE) -#define DMA1_Stream5 ((DMA_Stream_TypeDef *) DMA1_Stream5_BASE) -#define DMA1_Stream6 ((DMA_Stream_TypeDef *) DMA1_Stream6_BASE) -#define DMA1_Stream7 ((DMA_Stream_TypeDef *) DMA1_Stream7_BASE) -#define DMA2 ((DMA_TypeDef *) DMA2_BASE) -#define DMA2_Stream0 ((DMA_Stream_TypeDef *) DMA2_Stream0_BASE) -#define DMA2_Stream1 ((DMA_Stream_TypeDef *) DMA2_Stream1_BASE) -#define DMA2_Stream2 ((DMA_Stream_TypeDef *) DMA2_Stream2_BASE) -#define DMA2_Stream3 ((DMA_Stream_TypeDef *) DMA2_Stream3_BASE) -#define DMA2_Stream4 ((DMA_Stream_TypeDef *) DMA2_Stream4_BASE) -#define DMA2_Stream5 ((DMA_Stream_TypeDef *) DMA2_Stream5_BASE) -#define DMA2_Stream6 ((DMA_Stream_TypeDef *) DMA2_Stream6_BASE) -#define DMA2_Stream7 ((DMA_Stream_TypeDef *) DMA2_Stream7_BASE) -#define RNG ((RNG_TypeDef *) RNG_BASE) -#define FSMC_Bank1 ((FSMC_Bank1_TypeDef *) FSMC_Bank1_R_BASE) -#define FSMC_Bank1E ((FSMC_Bank1E_TypeDef *) FSMC_Bank1E_R_BASE) -#define QUADSPI ((QUADSPI_TypeDef *) QSPI_R_BASE) -#define DBGMCU ((DBGMCU_TypeDef *) DBGMCU_BASE) -#define USB_OTG_FS ((USB_OTG_GlobalTypeDef *) USB_OTG_FS_PERIPH_BASE) - -/** - * @} - */ - -/** @addtogroup Exported_constants - * @{ - */ - - /** @addtogroup Peripheral_Registers_Bits_Definition - * @{ - */ - -/******************************************************************************/ -/* Peripheral Registers_Bits_Definition */ -/******************************************************************************/ - -/******************************************************************************/ -/* */ -/* Analog to Digital Converter */ -/* */ -/******************************************************************************/ -/******************** Bit definition for ADC_SR register ********************/ -#define ADC_SR_AWD_Pos (0U) -#define ADC_SR_AWD_Msk (0x1U << ADC_SR_AWD_Pos) /*!< 0x00000001 */ -#define ADC_SR_AWD ADC_SR_AWD_Msk /*!
© COPYRIGHT(c) 2016 STMicroelectronics
- * - * 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. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * 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 HOLDER 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. - * - ****************************************************************************** - */ - -/** @addtogroup CMSIS - * @{ - */ - -/** @addtogroup stm32f4xx - * @{ - */ - -#ifndef __STM32F4xx_H -#define __STM32F4xx_H - -#ifdef __cplusplus - extern "C" { -#endif /* __cplusplus */ - -/** @addtogroup Library_configuration_section - * @{ - */ - -/** - * @brief STM32 Family - */ -#if !defined (STM32F4) -#define STM32F4 -#endif /* STM32F4 */ - -/* Uncomment the line below according to the target STM32 device used in your - application - */ -/* #if !defined (STM32F405xx) && !defined (STM32F415xx) && !defined (STM32F407xx) && !defined (STM32F417xx) && \ - !defined (STM32F427xx) && !defined (STM32F437xx) && !defined (STM32F429xx) && !defined (STM32F439xx) && \ - !defined (STM32F401xC) && !defined (STM32F401xE) && !defined (STM32F410Tx) && !defined (STM32F410Cx) && \ - !defined (STM32F410Rx) && !defined (STM32F411xE) && !defined (STM32F446xx) && !defined (STM32F469xx) && \ - !defined (STM32F479xx) && !defined (STM32F412Cx) && !defined (STM32F412Rx) && !defined (STM32F412Vx) && \ - !defined (STM32F412Zx) && !defined (STM32F413xx) && !defined (STM32F423xx) */ - /* #define STM32F405xx */ /*!< STM32F405RG, STM32F405VG and STM32F405ZG Devices */ - /* #define STM32F415xx */ /*!< STM32F415RG, STM32F415VG and STM32F415ZG Devices */ - /* #define STM32F407xx */ /*!< STM32F407VG, STM32F407VE, STM32F407ZG, STM32F407ZE, STM32F407IG and STM32F407IE Devices */ - /* #define STM32F417xx */ /*!< STM32F417VG, STM32F417VE, STM32F417ZG, STM32F417ZE, STM32F417IG and STM32F417IE Devices */ - /* #define STM32F427xx */ /*!< STM32F427VG, STM32F427VI, STM32F427ZG, STM32F427ZI, STM32F427IG and STM32F427II Devices */ - /* #define STM32F437xx */ /*!< STM32F437VG, STM32F437VI, STM32F437ZG, STM32F437ZI, STM32F437IG and STM32F437II Devices */ - /* #define STM32F429xx */ /*!< STM32F429VG, STM32F429VI, STM32F429ZG, STM32F429ZI, STM32F429BG, STM32F429BI, STM32F429NG, - STM32F439NI, STM32F429IG and STM32F429II Devices */ - /* #define STM32F439xx */ /*!< STM32F439VG, STM32F439VI, STM32F439ZG, STM32F439ZI, STM32F439BG, STM32F439BI, STM32F439NG, - STM32F439NI, STM32F439IG and STM32F439II Devices */ - /* #define STM32F401xC */ /*!< STM32F401CB, STM32F401CC, STM32F401RB, STM32F401RC, STM32F401VB and STM32F401VC Devices */ - /* #define STM32F401xE */ /*!< STM32F401CD, STM32F401RD, STM32F401VD, STM32F401CE, STM32F401RE and STM32F401VE Devices */ - /* #define STM32F410Tx */ /*!< STM32F410T8 and STM32F410TB Devices */ - /* #define STM32F410Cx */ /*!< STM32F410C8 and STM32F410CB Devices */ - /* #define STM32F410Rx */ /*!< STM32F410R8 and STM32F410RB Devices */ - /* #define STM32F411xE */ /*!< STM32F411CC, STM32F411RC, STM32F411VC, STM32F411CE, STM32F411RE and STM32F411VE Devices */ - /* #define STM32F446xx */ /*!< STM32F446MC, STM32F446ME, STM32F446RC, STM32F446RE, STM32F446VC, STM32F446VE, STM32F446ZC, - and STM32F446ZE Devices */ - /* #define STM32F469xx */ /*!< STM32F469AI, STM32F469II, STM32F469BI, STM32F469NI, STM32F469AG, STM32F469IG, STM32F469BG, - STM32F469NG, STM32F469AE, STM32F469IE, STM32F469BE and STM32F469NE Devices */ - /* #define STM32F479xx */ /*!< STM32F479AI, STM32F479II, STM32F479BI, STM32F479NI, STM32F479AG, STM32F479IG, STM32F479BG - and STM32F479NG Devices */ - /* #define STM32F412Cx */ /*!< STM32F412CEU and STM32F412CGU Devices */ - /* #define STM32F412Zx */ /*!< STM32F412ZET, STM32F412ZGT, STM32F412ZEJ and STM32F412ZGJ Devices */ - /* #define STM32F412Vx */ /*!< STM32F412VET, STM32F412VGT, STM32F412VEH and STM32F412VGH Devices */ - /* #define STM32F412Rx */ /*!< STM32F412RET, STM32F412RGT, STM32F412REY and STM32F412RGY Devices */ - /* #define STM32F413xx */ /*!< STM32F413CH, STM32F413MH, STM32F413RH, STM32F413VH, STM32F413ZH, STM32F413CG, STM32F413MG, - STM32F413RG, STM32F413VG and STM32F413ZG Devices */ - /* #define STM32F423xx */ /*!< STM32F423CH, STM32F423RH, STM32F423VH and STM32F423ZH Devices */ -//#endif - -/* Tip: To avoid modifying this file each time you need to switch between these - devices, you can define the device in your toolchain compiler preprocessor. - */ -#if !defined (USE_HAL_DRIVER) -/** - * @brief Comment the line below if you will not use the peripherals drivers. - In this case, these drivers will not be included and the application code will - be based on direct access to peripherals registers - */ - /*#define USE_HAL_DRIVER */ -#endif /* USE_HAL_DRIVER */ - -/** - * @brief CMSIS version number V2.6.0 - */ -#define __STM32F4xx_CMSIS_VERSION_MAIN (0x02U) /*!< [31:24] main version */ -#define __STM32F4xx_CMSIS_VERSION_SUB1 (0x06U) /*!< [23:16] sub1 version */ -#define __STM32F4xx_CMSIS_VERSION_SUB2 (0x00U) /*!< [15:8] sub2 version */ -#define __STM32F4xx_CMSIS_VERSION_RC (0x00U) /*!< [7:0] release candidate */ -#define __STM32F4xx_CMSIS_VERSION ((__STM32F4xx_CMSIS_VERSION_MAIN << 24)\ - |(__STM32F4xx_CMSIS_VERSION_SUB1 << 16)\ - |(__STM32F4xx_CMSIS_VERSION_SUB2 << 8 )\ - |(__STM32F4xx_CMSIS_VERSION)) - -/** - * @} - */ - -/** @addtogroup Device_Included - * @{ - */ - -// #if defined(STM32F405xx) -// #include "stm32f405xx.h" -// #elif defined(STM32F415xx) -// #include "stm32f415xx.h" -// #elif defined(STM32F407xx) -// #include "stm32f407xx.h" -// #elif defined(STM32F417xx) -// #include "stm32f417xx.h" -// #elif defined(STM32F427xx) -// #include "stm32f427xx.h" -// #elif defined(STM32F437xx) -// #include "stm32f437xx.h" -// #elif defined(STM32F429xx) -// #include "stm32f429xx.h" -// #elif defined(STM32F439xx) -// #include "stm32f439xx.h" -// #elif defined(STM32F401xC) -// #include "stm32f401xc.h" -// #elif defined(STM32F401xE) -// #include "stm32f401xe.h" -// #elif defined(STM32F410Tx) -// #include "stm32f410tx.h" -// #elif defined(STM32F410Cx) -// #include "stm32f410cx.h" -// #elif defined(STM32F410Rx) -// #include "stm32f410rx.h" -// #elif defined(STM32F411xE) -// #include "stm32f411xe.h" -// #elif defined(STM32F446xx) -// #include "stm32f446xx.h" -// #elif defined(STM32F469xx) -// #include "stm32f469xx.h" -// #elif defined(STM32F479xx) -// #include "stm32f479xx.h" -// #elif defined(STM32F412Cx) -// #include "stm32f412cx.h" -// #elif defined(STM32F412Zx) -// #include "stm32f412zx.h" -// #elif defined(STM32F412Rx) -// #include "stm32f412rx.h" -// #elif defined(STM32F412Vx) -// #include "stm32f412vx.h" -#if defined(STM32F413xx) - #include "stm32f413xx.h" - #elif defined(STM32F423xx) - #include "stm32f423xx.h" -#else - #error "Please select first the target STM32F4xx device used in your application (in stm32f4xx.h file)" -#endif - -/** - * @} - */ - -/** @addtogroup Exported_types - * @{ - */ -typedef enum -{ - RESET = 0U, - SET = !RESET -} FlagStatus, ITStatus; - -typedef enum -{ - DISABLE = 0U, - ENABLE = !DISABLE -} FunctionalState; -#define IS_FUNCTIONAL_STATE(STATE) (((STATE) == DISABLE) || ((STATE) == ENABLE)) - -typedef enum -{ - ERROR = 0U, - SUCCESS = !ERROR -} ErrorStatus; - -/** - * @} - */ - - -/** @addtogroup Exported_macro - * @{ - */ -#define SET_BIT(REG, BIT) ((REG) |= (BIT)) - -#define CLEAR_BIT(REG, BIT) ((REG) &= ~(BIT)) - -#define READ_BIT(REG, BIT) ((REG) & (BIT)) - -#define CLEAR_REG(REG) ((REG) = (0x0)) - -#define WRITE_REG(REG, VAL) ((REG) = (VAL)) - -#define READ_REG(REG) ((REG)) - -#define MODIFY_REG(REG, CLEARMASK, SETMASK) WRITE_REG((REG), (((READ_REG(REG)) & (~(CLEARMASK))) | (SETMASK))) - -#define POSITION_VAL(VAL) (__CLZ(__RBIT(VAL))) - - -/** - * @} - */ - -#if defined (USE_HAL_DRIVER) - #include "stm32f4xx_hal.h" -#endif /* USE_HAL_DRIVER */ - -#ifdef __cplusplus -} -#endif /* __cplusplus */ - -#endif /* __STM32F4xx_H */ -/** - * @} - */ - -/** - * @} - */ - - - - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/panda/board/stm32fx/inc/stm32f4xx_hal_def.h b/panda/board/stm32fx/inc/stm32f4xx_hal_def.h deleted file mode 100644 index b77f179a0..000000000 --- a/panda/board/stm32fx/inc/stm32f4xx_hal_def.h +++ /dev/null @@ -1,214 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_def.h - * @author MCD Application Team - * @version V1.6.0 - * @date 04-November-2016 - * @brief This file contains HAL common defines, enumeration, macros and - * structures definitions. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT(c) 2016 STMicroelectronics

- * - * 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. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * 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 HOLDER 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. - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_DEF -#define __STM32F4xx_HAL_DEF - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" -//#include "Legacy/stm32_hal_legacy.h" -//#include - -/* Exported types ------------------------------------------------------------*/ - -/** - * @brief HAL Status structures definition - */ -typedef enum -{ - HAL_OK = 0x00U, - HAL_ERROR = 0x01U, - HAL_BUSY = 0x02U, - HAL_TIMEOUT = 0x03U -} HAL_StatusTypeDef; - -/** - * @brief HAL Lock structures definition - */ -typedef enum -{ - HAL_UNLOCKED = 0x00U, - HAL_LOCKED = 0x01U -} HAL_LockTypeDef; - -/* Exported macro ------------------------------------------------------------*/ -#define HAL_MAX_DELAY 0xFFFFFFFFU - -#define HAL_IS_BIT_SET(REG, BIT) (((REG) & (BIT)) != RESET) -#define HAL_IS_BIT_CLR(REG, BIT) (((REG) & (BIT)) == RESET) - -#define __HAL_LINKDMA(__HANDLE__, __PPP_DMA_FIELD__, __DMA_HANDLE__) \ - do{ \ - (__HANDLE__)->__PPP_DMA_FIELD__ = &(__DMA_HANDLE__); \ - (__DMA_HANDLE__).Parent = (__HANDLE__); \ - } while(0) - -#define UNUSED(x) ((void)(x)) - -/** @brief Reset the Handle's State field. - * @param __HANDLE__: specifies the Peripheral Handle. - * @note This macro can be used for the following purpose: - * - When the Handle is declared as local variable; before passing it as parameter - * to HAL_PPP_Init() for the first time, it is mandatory to use this macro - * to set to 0 the Handle's "State" field. - * Otherwise, "State" field may have any random value and the first time the function - * HAL_PPP_Init() is called, the low level hardware initialization will be missed - * (i.e. HAL_PPP_MspInit() will not be executed). - * - When there is a need to reconfigure the low level hardware: instead of calling - * HAL_PPP_DeInit() then HAL_PPP_Init(), user can make a call to this macro then HAL_PPP_Init(). - * In this later function, when the Handle's "State" field is set to 0, it will execute the function - * HAL_PPP_MspInit() which will reconfigure the low level hardware. - * @retval None - */ -#define __HAL_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = 0U) - -#if (USE_RTOS == 1) - /* Reserved for future use */ - #error "USE_RTOS should be 0 in the current HAL release" -#else - #define __HAL_LOCK(__HANDLE__) \ - do{ \ - if((__HANDLE__)->Lock == HAL_LOCKED) \ - { \ - return HAL_BUSY; \ - } \ - else \ - { \ - (__HANDLE__)->Lock = HAL_LOCKED; \ - } \ - }while (0) - - #define __HAL_UNLOCK(__HANDLE__) \ - do{ \ - (__HANDLE__)->Lock = HAL_UNLOCKED; \ - }while (0) -#endif /* USE_RTOS */ - -#if defined ( __GNUC__ ) - #ifndef __weak - #define __weak __attribute__((weak)) - #endif /* __weak */ - #ifndef __packed - #define __packed __attribute__((__packed__)) - #endif /* __packed */ -#endif /* __GNUC__ */ - - -/* Macro to get variable aligned on 4-bytes, for __ICCARM__ the directive "#pragma data_alignment=4" must be used instead */ -#if defined (__GNUC__) /* GNU Compiler */ - #ifndef __ALIGN_END - #define __ALIGN_END __attribute__ ((aligned (4))) - #endif /* __ALIGN_END */ - #ifndef __ALIGN_BEGIN - #define __ALIGN_BEGIN - #endif /* __ALIGN_BEGIN */ -#else - #ifndef __ALIGN_END - #define __ALIGN_END - #endif /* __ALIGN_END */ - #ifndef __ALIGN_BEGIN - #if defined (__CC_ARM) /* ARM Compiler */ - #define __ALIGN_BEGIN __align(4) - #elif defined (__ICCARM__) /* IAR Compiler */ - #define __ALIGN_BEGIN - #endif /* __CC_ARM */ - #endif /* __ALIGN_BEGIN */ -#endif /* __GNUC__ */ - - -/** - * @brief __RAM_FUNC definition - */ -#if defined ( __CC_ARM ) -/* ARM Compiler - ------------ - RAM functions are defined using the toolchain options. - Functions that are executed in RAM should reside in a separate source module. - Using the 'Options for File' dialog you can simply change the 'Code / Const' - area of a module to a memory space in physical RAM. - Available memory areas are declared in the 'Target' tab of the 'Options for Target' - dialog. -*/ -#define __RAM_FUNC HAL_StatusTypeDef - -#elif defined ( __ICCARM__ ) -/* ICCARM Compiler - --------------- - RAM functions are defined using a specific toolchain keyword "__ramfunc". -*/ -#define __RAM_FUNC __ramfunc HAL_StatusTypeDef - -#elif defined ( __GNUC__ ) -/* GNU Compiler - ------------ - RAM functions are defined using a specific toolchain attribute - "__attribute__((section(".RamFunc")))". -*/ -#define __RAM_FUNC HAL_StatusTypeDef __attribute__((section(".RamFunc"))) - -#endif - -/** - * @brief __NOINLINE definition - */ -#if defined ( __CC_ARM ) || defined ( __GNUC__ ) -/* ARM & GNUCompiler - ---------------- -*/ -#define __NOINLINE __attribute__ ( (noinline) ) - -#elif defined ( __ICCARM__ ) -/* ICCARM Compiler - --------------- -*/ -#define __NOINLINE _Pragma("optimize = no_inline") - -#endif - -#ifdef __cplusplus -} -#endif - -#endif /* ___STM32F4xx_HAL_DEF */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/panda/board/stm32fx/inc/stm32f4xx_hal_gpio_ex.h b/panda/board/stm32fx/inc/stm32f4xx_hal_gpio_ex.h deleted file mode 100644 index 6c5f34dcb..000000000 --- a/panda/board/stm32fx/inc/stm32f4xx_hal_gpio_ex.h +++ /dev/null @@ -1,1591 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_gpio_ex.h - * @author MCD Application Team - * @version V1.6.0 - * @date 04-November-2016 - * @brief Header file of GPIO HAL Extension module. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT(c) 2016 STMicroelectronics

- * - * 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. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * 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 HOLDER 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. - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_GPIO_EX_H -#define __STM32F4xx_HAL_GPIO_EX_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup GPIOEx GPIOEx - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/** @defgroup GPIOEx_Exported_Constants GPIO Exported Constants - * @{ - */ - -/** @defgroup GPIO_Alternate_function_selection GPIO Alternate Function Selection - * @{ - */ - -/*------------------------------------------ STM32F429xx/STM32F439xx ---------*/ -#if defined(STM32F429xx) || defined(STM32F439xx) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00U) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00U) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00U) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00U) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00U) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01U) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01U) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02U) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02U) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02U) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM8 ((uint8_t)0x03U) /* TIM8 Alternate Function mapping */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03U) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03U) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03U) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04U) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04U) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04U) /* I2C3 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05U) /* SPI1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05U) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_SPI3 ((uint8_t)0x05U) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF5_SPI4 ((uint8_t)0x05U) /* SPI4 Alternate Function mapping */ -#define GPIO_AF5_SPI5 ((uint8_t)0x05U) /* SPI5 Alternate Function mapping */ -#define GPIO_AF5_SPI6 ((uint8_t)0x05U) /* SPI6 Alternate Function mapping */ -#define GPIO_AF5_I2S3ext ((uint8_t)0x05U) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06U) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_I2S2ext ((uint8_t)0x06U) /* I2S2ext_SD Alternate Function mapping */ -#define GPIO_AF6_SAI1 ((uint8_t)0x06U) /* SAI1 Alternate Function mapping */ - -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_USART1 ((uint8_t)0x07U) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07U) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_USART3 ((uint8_t)0x07U) /* USART3 Alternate Function mapping */ -#define GPIO_AF7_I2S3ext ((uint8_t)0x07U) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_UART4 ((uint8_t)0x08U) /* UART4 Alternate Function mapping */ -#define GPIO_AF8_UART5 ((uint8_t)0x08U) /* UART5 Alternate Function mapping */ -#define GPIO_AF8_USART6 ((uint8_t)0x08U) /* USART6 Alternate Function mapping */ -#define GPIO_AF8_UART7 ((uint8_t)0x08U) /* UART7 Alternate Function mapping */ -#define GPIO_AF8_UART8 ((uint8_t)0x08U) /* UART8 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_CAN1 ((uint8_t)0x09U) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_CAN2 ((uint8_t)0x09U) /* CAN2 Alternate Function mapping */ -#define GPIO_AF9_TIM12 ((uint8_t)0x09U) /* TIM12 Alternate Function mapping */ -#define GPIO_AF9_TIM13 ((uint8_t)0x09U) /* TIM13 Alternate Function mapping */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09U) /* TIM14 Alternate Function mapping */ -#define GPIO_AF9_LTDC ((uint8_t)0x09U) /* LCD-TFT Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0AU) /* OTG_FS Alternate Function mapping */ -#define GPIO_AF10_OTG_HS ((uint8_t)0x0AU) /* OTG_HS Alternate Function mapping */ - -/** - * @brief AF 11 selection - */ -#define GPIO_AF11_ETH ((uint8_t)0x0BU) /* ETHERNET Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_FMC ((uint8_t)0x0CU) /* FMC Alternate Function mapping */ -#define GPIO_AF12_OTG_HS_FS ((uint8_t)0x0CU) /* OTG HS configured in FS, Alternate Function mapping */ -#define GPIO_AF12_SDIO ((uint8_t)0x0CU) /* SDIO Alternate Function mapping */ - -/** - * @brief AF 13 selection - */ -#define GPIO_AF13_DCMI ((uint8_t)0x0DU) /* DCMI Alternate Function mapping */ - -/** - * @brief AF 14 selection - */ -#define GPIO_AF14_LTDC ((uint8_t)0x0EU) /* LCD-TFT Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0FU) /* EVENTOUT Alternate Function mapping */ -#endif /* STM32F429xx || STM32F439xx */ -/*----------------------------------------------------------------------------*/ - -/*---------------------------------- STM32F427xx/STM32F437xx------------------*/ -#if defined(STM32F427xx) || defined(STM32F437xx) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00U) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00U) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00U) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00U) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00U) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01U) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01U) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02U) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02U) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02U) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM8 ((uint8_t)0x03U) /* TIM8 Alternate Function mapping */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03U) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03U) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03U) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04U) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04U) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04U) /* I2C3 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05U) /* SPI1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05U) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_SPI3 ((uint8_t)0x05U) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF5_SPI4 ((uint8_t)0x05U) /* SPI4 Alternate Function mapping */ -#define GPIO_AF5_SPI5 ((uint8_t)0x05U) /* SPI5 Alternate Function mapping */ -#define GPIO_AF5_SPI6 ((uint8_t)0x05U) /* SPI6 Alternate Function mapping */ -/** @brief GPIO_Legacy - */ -#define GPIO_AF5_I2S3ext GPIO_AF5_SPI3 /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06U) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_I2S2ext ((uint8_t)0x06U) /* I2S2ext_SD Alternate Function mapping */ -#define GPIO_AF6_SAI1 ((uint8_t)0x06U) /* SAI1 Alternate Function mapping */ - -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_USART1 ((uint8_t)0x07U) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07U) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_USART3 ((uint8_t)0x07U) /* USART3 Alternate Function mapping */ -#define GPIO_AF7_I2S3ext ((uint8_t)0x07U) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_UART4 ((uint8_t)0x08U) /* UART4 Alternate Function mapping */ -#define GPIO_AF8_UART5 ((uint8_t)0x08U) /* UART5 Alternate Function mapping */ -#define GPIO_AF8_USART6 ((uint8_t)0x08U) /* USART6 Alternate Function mapping */ -#define GPIO_AF8_UART7 ((uint8_t)0x08U) /* UART7 Alternate Function mapping */ -#define GPIO_AF8_UART8 ((uint8_t)0x08U) /* UART8 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_CAN1 ((uint8_t)0x09U) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_CAN2 ((uint8_t)0x09U) /* CAN2 Alternate Function mapping */ -#define GPIO_AF9_TIM12 ((uint8_t)0x09U) /* TIM12 Alternate Function mapping */ -#define GPIO_AF9_TIM13 ((uint8_t)0x09U) /* TIM13 Alternate Function mapping */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09U) /* TIM14 Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0AU) /* OTG_FS Alternate Function mapping */ -#define GPIO_AF10_OTG_HS ((uint8_t)0x0AU) /* OTG_HS Alternate Function mapping */ - -/** - * @brief AF 11 selection - */ -#define GPIO_AF11_ETH ((uint8_t)0x0BU) /* ETHERNET Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_FMC ((uint8_t)0x0CU) /* FMC Alternate Function mapping */ -#define GPIO_AF12_OTG_HS_FS ((uint8_t)0x0CU) /* OTG HS configured in FS, Alternate Function mapping */ -#define GPIO_AF12_SDIO ((uint8_t)0x0CU) /* SDIO Alternate Function mapping */ - -/** - * @brief AF 13 selection - */ -#define GPIO_AF13_DCMI ((uint8_t)0x0DU) /* DCMI Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0FU) /* EVENTOUT Alternate Function mapping */ -#endif /* STM32F427xx || STM32F437xx */ -/*----------------------------------------------------------------------------*/ - -/*---------------------------------- STM32F407xx/STM32F417xx------------------*/ -#if defined(STM32F407xx) || defined(STM32F417xx) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00U) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00U) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00U) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00U) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00U) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01U) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01U) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02U) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02U) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02U) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM8 ((uint8_t)0x03U) /* TIM8 Alternate Function mapping */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03U) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03U) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03U) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04U) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04U) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04U) /* I2C3 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05U) /* SPI1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05U) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_I2S3ext ((uint8_t)0x05U) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06U) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_I2S2ext ((uint8_t)0x06U) /* I2S2ext_SD Alternate Function mapping */ - -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_USART1 ((uint8_t)0x07U) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07U) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_USART3 ((uint8_t)0x07U) /* USART3 Alternate Function mapping */ -#define GPIO_AF7_I2S3ext ((uint8_t)0x07U) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_UART4 ((uint8_t)0x08U) /* UART4 Alternate Function mapping */ -#define GPIO_AF8_UART5 ((uint8_t)0x08U) /* UART5 Alternate Function mapping */ -#define GPIO_AF8_USART6 ((uint8_t)0x08U) /* USART6 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_CAN1 ((uint8_t)0x09U) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_CAN2 ((uint8_t)0x09U) /* CAN2 Alternate Function mapping */ -#define GPIO_AF9_TIM12 ((uint8_t)0x09U) /* TIM12 Alternate Function mapping */ -#define GPIO_AF9_TIM13 ((uint8_t)0x09U) /* TIM13 Alternate Function mapping */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09U) /* TIM14 Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0AU) /* OTG_FS Alternate Function mapping */ -#define GPIO_AF10_OTG_HS ((uint8_t)0x0AU) /* OTG_HS Alternate Function mapping */ - -/** - * @brief AF 11 selection - */ -#define GPIO_AF11_ETH ((uint8_t)0x0BU) /* ETHERNET Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_FSMC ((uint8_t)0x0CU) /* FSMC Alternate Function mapping */ -#define GPIO_AF12_OTG_HS_FS ((uint8_t)0x0CU) /* OTG HS configured in FS, Alternate Function mapping */ -#define GPIO_AF12_SDIO ((uint8_t)0x0CU) /* SDIO Alternate Function mapping */ - -/** - * @brief AF 13 selection - */ -#define GPIO_AF13_DCMI ((uint8_t)0x0DU) /* DCMI Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0FU) /* EVENTOUT Alternate Function mapping */ -#endif /* STM32F407xx || STM32F417xx */ -/*----------------------------------------------------------------------------*/ - -/*---------------------------------- STM32F405xx/STM32F415xx------------------*/ -#if defined(STM32F405xx) || defined(STM32F415xx) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00U) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00U) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00U) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00U) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00U) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01U) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01U) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02U) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02U) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02U) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM8 ((uint8_t)0x03U) /* TIM8 Alternate Function mapping */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03U) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03U) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03U) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04U) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04U) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04U) /* I2C3 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05U) /* SPI1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05U) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_I2S3ext ((uint8_t)0x05U) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06U) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_I2S2ext ((uint8_t)0x06U) /* I2S2ext_SD Alternate Function mapping */ - -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_USART1 ((uint8_t)0x07U) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07U) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_USART3 ((uint8_t)0x07U) /* USART3 Alternate Function mapping */ -#define GPIO_AF7_I2S3ext ((uint8_t)0x07U) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_UART4 ((uint8_t)0x08U) /* UART4 Alternate Function mapping */ -#define GPIO_AF8_UART5 ((uint8_t)0x08U) /* UART5 Alternate Function mapping */ -#define GPIO_AF8_USART6 ((uint8_t)0x08U) /* USART6 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_CAN1 ((uint8_t)0x09U) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_CAN2 ((uint8_t)0x09U) /* CAN2 Alternate Function mapping */ -#define GPIO_AF9_TIM12 ((uint8_t)0x09U) /* TIM12 Alternate Function mapping */ -#define GPIO_AF9_TIM13 ((uint8_t)0x09U) /* TIM13 Alternate Function mapping */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09U) /* TIM14 Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0AU) /* OTG_FS Alternate Function mapping */ -#define GPIO_AF10_OTG_HS ((uint8_t)0x0AU) /* OTG_HS Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_FSMC ((uint8_t)0x0CU) /* FSMC Alternate Function mapping */ -#define GPIO_AF12_OTG_HS_FS ((uint8_t)0x0CU) /* OTG HS configured in FS, Alternate Function mapping */ -#define GPIO_AF12_SDIO ((uint8_t)0x0CU) /* SDIO Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0FU) /* EVENTOUT Alternate Function mapping */ -#endif /* STM32F405xx || STM32F415xx */ - -/*----------------------------------------------------------------------------*/ - -/*---------------------------------------- STM32F401xx------------------------*/ -#if defined(STM32F401xC) || defined(STM32F401xE) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00U) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00U) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00U) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00U) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00U) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01U) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01U) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02U) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02U) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02U) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03U) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03U) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03U) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04U) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04U) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04U) /* I2C3 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05U) /* SPI1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05U) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_SPI4 ((uint8_t)0x05U) /* SPI4 Alternate Function mapping */ -#define GPIO_AF5_I2S3ext ((uint8_t)0x05U) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06U) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_I2S2ext ((uint8_t)0x06U) /* I2S2ext_SD Alternate Function mapping */ - -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_USART1 ((uint8_t)0x07U) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07U) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_I2S3ext ((uint8_t)0x07U) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_USART6 ((uint8_t)0x08U) /* USART6 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09U) /* TIM14 Alternate Function mapping */ -#define GPIO_AF9_I2C2 ((uint8_t)0x09U) /* I2C2 Alternate Function mapping */ -#define GPIO_AF9_I2C3 ((uint8_t)0x09U) /* I2C3 Alternate Function mapping */ - - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0AU) /* OTG_FS Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_SDIO ((uint8_t)0x0CU) /* SDIO Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0FU) /* EVENTOUT Alternate Function mapping */ -#endif /* STM32F401xC || STM32F401xE */ -/*----------------------------------------------------------------------------*/ - -/*--------------- STM32F412Zx/STM32F412Vx/STM32F412Rx/STM32F412Cx-------------*/ -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00U) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00U) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00U) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00U) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00U) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01U) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01U) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02U) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02U) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02U) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM8 ((uint8_t)0x03U) /* TIM8 Alternate Function mapping */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03U) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03U) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03U) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04U) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04U) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04U) /* I2C3 Alternate Function mapping */ -#define GPIO_AF4_FMPI2C1 ((uint8_t)0x04U) /* FMPI2C1 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05U) /* SPI1/I2S1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05U) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_SPI3 ((uint8_t)0x05U) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF5_SPI4 ((uint8_t)0x05U) /* SPI4/I2S4 Alternate Function mapping */ -#define GPIO_AF5_I2S3ext ((uint8_t)0x05U) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI2 ((uint8_t)0x06U) /* I2S2 Alternate Function mapping */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06U) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_SPI4 ((uint8_t)0x06U) /* SPI4/I2S4 Alternate Function mapping */ -#define GPIO_AF6_SPI5 ((uint8_t)0x06U) /* SPI5/I2S5 Alternate Function mapping */ -#define GPIO_AF6_I2S2ext ((uint8_t)0x06U) /* I2S2ext_SD Alternate Function mapping */ -#define GPIO_AF6_DFSDM1 ((uint8_t)0x06U) /* DFSDM1 Alternate Function mapping */ -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_SPI3 ((uint8_t)0x07U) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF7_USART1 ((uint8_t)0x07U) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07U) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_USART3 ((uint8_t)0x07U) /* USART3 Alternate Function mapping */ -#define GPIO_AF7_I2S3ext ((uint8_t)0x07U) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_USART6 ((uint8_t)0x08U) /* USART6 Alternate Function mapping */ -#define GPIO_AF8_USART3 ((uint8_t)0x08U) /* USART3 Alternate Function mapping */ -#define GPIO_AF8_DFSDM1 ((uint8_t)0x08U) /* DFSDM1 Alternate Function mapping */ -#define GPIO_AF8_CAN1 ((uint8_t)0x08U) /* CAN1 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_TIM13 ((uint8_t)0x09U) /* TIM13 Alternate Function mapping */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09U) /* TIM14 Alternate Function mapping */ -#define GPIO_AF9_I2C2 ((uint8_t)0x09U) /* I2C2 Alternate Function mapping */ -#define GPIO_AF9_I2C3 ((uint8_t)0x09U) /* I2C3 Alternate Function mapping */ -#define GPIO_AF9_FMPI2C1 ((uint8_t)0x09U) /* FMPI2C1 Alternate Function mapping */ -#define GPIO_AF9_CAN1 ((uint8_t)0x09U) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_CAN2 ((uint8_t)0x09U) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_QSPI ((uint8_t)0x09U) /* QSPI Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0AU) /* OTG_FS Alternate Function mapping */ -#define GPIO_AF10_DFSDM1 ((uint8_t)0x0AU) /* DFSDM1 Alternate Function mapping */ -#define GPIO_AF10_QSPI ((uint8_t)0x0AU) /* QSPI Alternate Function mapping */ -#define GPIO_AF10_FMC ((uint8_t)0x0AU) /* FMC Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_SDIO ((uint8_t)0x0CU) /* SDIO Alternate Function mapping */ -#define GPIO_AF12_FSMC ((uint8_t)0x0CU) /* FMC Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0FU) /* EVENTOUT Alternate Function mapping */ -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ - -/*----------------------------------------------------------------------------*/ - -/*--------------- STM32F413xx/STM32F423xx-------------------------------------*/ -#if defined(STM32F413xx) || defined(STM32F423xx) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00U) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00U) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00U) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00U) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01U) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01U) /* TIM2 Alternate Function mapping */ -#define GPIO_AF1_LPTIM1 ((uint8_t)0x01U) /* LPTIM1 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02U) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02U) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02U) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM8 ((uint8_t)0x03U) /* TIM8 Alternate Function mapping */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03U) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03U) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03U) /* TIM11 Alternate Function mapping */ -#define GPIO_AF3_DFSDM2 ((uint8_t)0x03U) /* DFSDM2 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04U) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04U) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04U) /* I2C3 Alternate Function mapping */ -#define GPIO_AF4_FMPI2C1 ((uint8_t)0x04U) /* FMPI2C1 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05U) /* SPI1/I2S1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05U) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_SPI3 ((uint8_t)0x05U) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF5_SPI4 ((uint8_t)0x05U) /* SPI4/I2S4 Alternate Function mapping */ -#define GPIO_AF5_I2S3ext ((uint8_t)0x05U) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI2 ((uint8_t)0x06U) /* I2S2 Alternate Function mapping */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06U) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_SPI4 ((uint8_t)0x06U) /* SPI4/I2S4 Alternate Function mapping */ -#define GPIO_AF6_SPI5 ((uint8_t)0x06U) /* SPI5/I2S5 Alternate Function mapping */ -#define GPIO_AF6_I2S2ext ((uint8_t)0x06U) /* I2S2ext_SD Alternate Function mapping */ -#define GPIO_AF6_DFSDM1 ((uint8_t)0x06U) /* DFSDM1 Alternate Function mapping */ -#define GPIO_AF6_DFSDM2 ((uint8_t)0x06U) /* DFSDM2 Alternate Function mapping */ -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_SPI3 ((uint8_t)0x07U) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF7_SAI1 ((uint8_t)0x07U) /* SAI1 Alternate Function mapping */ -#define GPIO_AF7_USART1 ((uint8_t)0x07U) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07U) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_USART3 ((uint8_t)0x07U) /* USART3 Alternate Function mapping */ -#define GPIO_AF7_I2S3ext ((uint8_t)0x07U) /* I2S3ext_SD Alternate Function mapping */ -#define GPIO_AF7_DFSDM2 ((uint8_t)0x07U) /* DFSDM2 Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_USART6 ((uint8_t)0x08U) /* USART6 Alternate Function mapping */ -#define GPIO_AF8_USART3 ((uint8_t)0x08U) /* USART3 Alternate Function mapping */ -#define GPIO_AF8_UART4 ((uint8_t)0x08U) /* UART4 Alternate Function mapping */ -#define GPIO_AF8_UART5 ((uint8_t)0x08U) /* UART5 Alternate Function mapping */ -#define GPIO_AF8_UART7 ((uint8_t)0x08U) /* UART8 Alternate Function mapping */ -#define GPIO_AF8_UART8 ((uint8_t)0x08U) /* UART8 Alternate Function mapping */ -#define GPIO_AF8_DFSDM1 ((uint8_t)0x08U) /* DFSDM1 Alternate Function mapping */ -#define GPIO_AF8_CAN1 ((uint8_t)0x08U) /* CAN1 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_TIM12 ((uint8_t)0x09U) /* TIM12 Alternate Function mapping */ -#define GPIO_AF9_TIM13 ((uint8_t)0x09U) /* TIM13 Alternate Function mapping */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09U) /* TIM14 Alternate Function mapping */ -#define GPIO_AF9_I2C2 ((uint8_t)0x09U) /* I2C2 Alternate Function mapping */ -#define GPIO_AF9_I2C3 ((uint8_t)0x09U) /* I2C3 Alternate Function mapping */ -#define GPIO_AF9_FMPI2C1 ((uint8_t)0x09U) /* FMPI2C1 Alternate Function mapping */ -#define GPIO_AF9_CAN1 ((uint8_t)0x09U) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_CAN2 ((uint8_t)0x09U) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_QSPI ((uint8_t)0x09U) /* QSPI Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_SAI1 ((uint8_t)0x0AU) /* SAI1 Alternate Function mapping */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0AU) /* OTG_FS Alternate Function mapping */ -#define GPIO_AF10_DFSDM1 ((uint8_t)0x0AU) /* DFSDM1 Alternate Function mapping */ -#define GPIO_AF10_DFSDM2 ((uint8_t)0x0AU) /* DFSDM2 Alternate Function mapping */ -#define GPIO_AF10_QSPI ((uint8_t)0x0AU) /* QSPI Alternate Function mapping */ -#define GPIO_AF10_FSMC ((uint8_t)0x0AU) /* FSMC Alternate Function mapping */ - -/** - * @brief AF 11 selection - */ -#define GPIO_AF11_UART4 ((uint8_t)0x0BU) /* UART4 Alternate Function mapping */ -#define GPIO_AF11_UART5 ((uint8_t)0x0BU) /* UART5 Alternate Function mapping */ -#define GPIO_AF11_UART9 ((uint8_t)0x0BU) /* UART9 Alternate Function mapping */ -#define GPIO_AF11_UART10 ((uint8_t)0x0BU) /* UART10 Alternate Function mapping */ -#define GPIO_AF11_CAN3 ((uint8_t)0x0BU) /* CAN3 Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_SDIO ((uint8_t)0x0CU) /* SDIO Alternate Function mapping */ -#define GPIO_AF12_FSMC ((uint8_t)0x0CU) /* FMC Alternate Function mapping */ - -/** - * @brief AF 14 selection - */ -#define GPIO_AF14_RNG ((uint8_t)0x0EU) /* RNG Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0FU) /* EVENTOUT Alternate Function mapping */ -#endif /* STM32F413xx || STM32F423xx */ - -/*---------------------------------------- STM32F411xx------------------------*/ -#if defined(STM32F411xE) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00U) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00U) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00U) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00U) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00U) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01U) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01U) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02U) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02U) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02U) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03U) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03U) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03U) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04U) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04U) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04U) /* I2C3 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05U) /* SPI1/I2S1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05U) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_SPI3 ((uint8_t)0x05U) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF5_SPI4 ((uint8_t)0x05U) /* SPI4 Alternate Function mapping */ -#define GPIO_AF5_I2S3ext ((uint8_t)0x05U) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI2 ((uint8_t)0x06U) /* I2S2 Alternate Function mapping */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06U) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_SPI4 ((uint8_t)0x06U) /* SPI4/I2S4 Alternate Function mapping */ -#define GPIO_AF6_SPI5 ((uint8_t)0x06U) /* SPI5/I2S5 Alternate Function mapping */ -#define GPIO_AF6_I2S2ext ((uint8_t)0x06U) /* I2S2ext_SD Alternate Function mapping */ - -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_SPI3 ((uint8_t)0x07U) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF7_USART1 ((uint8_t)0x07U) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07U) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_I2S3ext ((uint8_t)0x07U) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_USART6 ((uint8_t)0x08U) /* USART6 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09U) /* TIM14 Alternate Function mapping */ -#define GPIO_AF9_I2C2 ((uint8_t)0x09U) /* I2C2 Alternate Function mapping */ -#define GPIO_AF9_I2C3 ((uint8_t)0x09U) /* I2C3 Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0AU) /* OTG_FS Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_SDIO ((uint8_t)0x0CU) /* SDIO Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0FU) /* EVENTOUT Alternate Function mapping */ -#endif /* STM32F411xE */ - -/*---------------------------------------- STM32F410xx------------------------*/ -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00U) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00U) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00U) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00U) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00U) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01U) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_LPTIM1 ((uint8_t)0x01U) /* LPTIM1 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02U) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03U) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03U) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04U) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04U) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_FMPI2C1 ((uint8_t)0x04U) /* FMPI2C1 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05U) /* SPI1/I2S1 Alternate Function mapping */ -#if defined(STM32F410Cx) || defined(STM32F410Rx) -#define GPIO_AF5_SPI2 ((uint8_t)0x05U) /* SPI2/I2S2 Alternate Function mapping */ -#endif /* STM32F410Cx || STM32F410Rx */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI1 ((uint8_t)0x06U) /* SPI1 Alternate Function mapping */ -#if defined(STM32F410Cx) || defined(STM32F410Rx) -#define GPIO_AF6_SPI2 ((uint8_t)0x06U) /* I2S2 Alternate Function mapping */ -#endif /* STM32F410Cx || STM32F410Rx */ -#define GPIO_AF6_SPI5 ((uint8_t)0x06U) /* SPI5/I2S5 Alternate Function mapping */ -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_USART1 ((uint8_t)0x07U) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07U) /* USART2 Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_USART6 ((uint8_t)0x08U) /* USART6 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_I2C2 ((uint8_t)0x09U) /* I2C2 Alternate Function mapping */ -#define GPIO_AF9_FMPI2C1 ((uint8_t)0x09U) /* FMPI2C1 Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0FU) /* EVENTOUT Alternate Function mapping */ -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -/*---------------------------------------- STM32F446xx -----------------------*/ -#if defined(STM32F446xx) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00U) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00U) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00U) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00U) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00U) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01U) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01U) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02U) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02U) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02U) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM8 ((uint8_t)0x03U) /* TIM8 Alternate Function mapping */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03U) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03U) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03U) /* TIM11 Alternate Function mapping */ -#define GPIO_AF3_CEC ((uint8_t)0x03U) /* CEC Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04U) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04U) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04U) /* I2C3 Alternate Function mapping */ -#define GPIO_AF4_FMPI2C1 ((uint8_t)0x04U) /* FMPI2C1 Alternate Function mapping */ -#define GPIO_AF4_CEC ((uint8_t)0x04U) /* CEC Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05U) /* SPI1/I2S1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05U) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_SPI3 ((uint8_t)0x05U) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF5_SPI4 ((uint8_t)0x05U) /* SPI4 Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI2 ((uint8_t)0x06U) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06U) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_SPI4 ((uint8_t)0x06U) /* SPI4 Alternate Function mapping */ -#define GPIO_AF6_SAI1 ((uint8_t)0x06U) /* SAI1 Alternate Function mapping */ - -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_USART1 ((uint8_t)0x07U) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07U) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_USART3 ((uint8_t)0x07U) /* USART3 Alternate Function mapping */ -#define GPIO_AF7_UART5 ((uint8_t)0x07U) /* UART5 Alternate Function mapping */ -#define GPIO_AF7_SPI2 ((uint8_t)0x07U) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF7_SPI3 ((uint8_t)0x07U) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF7_SPDIFRX ((uint8_t)0x07U) /* SPDIFRX Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_UART4 ((uint8_t)0x08U) /* UART4 Alternate Function mapping */ -#define GPIO_AF8_UART5 ((uint8_t)0x08U) /* UART5 Alternate Function mapping */ -#define GPIO_AF8_USART6 ((uint8_t)0x08U) /* USART6 Alternate Function mapping */ -#define GPIO_AF8_SPDIFRX ((uint8_t)0x08U) /* SPDIFRX Alternate Function mapping */ -#define GPIO_AF8_SAI2 ((uint8_t)0x08U) /* SAI2 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_CAN1 ((uint8_t)0x09U) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_CAN2 ((uint8_t)0x09U) /* CAN2 Alternate Function mapping */ -#define GPIO_AF9_TIM12 ((uint8_t)0x09U) /* TIM12 Alternate Function mapping */ -#define GPIO_AF9_TIM13 ((uint8_t)0x09U) /* TIM13 Alternate Function mapping */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09U) /* TIM14 Alternate Function mapping */ -#define GPIO_AF9_QSPI ((uint8_t)0x09U) /* QSPI Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0AU) /* OTG_FS Alternate Function mapping */ -#define GPIO_AF10_OTG_HS ((uint8_t)0x0AU) /* OTG_HS Alternate Function mapping */ -#define GPIO_AF10_SAI2 ((uint8_t)0x0AU) /* SAI2 Alternate Function mapping */ -#define GPIO_AF10_QSPI ((uint8_t)0x0AU) /* QSPI Alternate Function mapping */ - -/** - * @brief AF 11 selection - */ -#define GPIO_AF11_ETH ((uint8_t)0x0BU) /* ETHERNET Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_FMC ((uint8_t)0x0CU) /* FMC Alternate Function mapping */ -#define GPIO_AF12_OTG_HS_FS ((uint8_t)0x0CU) /* OTG HS configured in FS, Alternate Function mapping */ -#define GPIO_AF12_SDIO ((uint8_t)0x0CU) /* SDIO Alternate Function mapping */ - -/** - * @brief AF 13 selection - */ -#define GPIO_AF13_DCMI ((uint8_t)0x0DU) /* DCMI Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0FU) /* EVENTOUT Alternate Function mapping */ - -#endif /* STM32F446xx */ -/*----------------------------------------------------------------------------*/ - -/*-------------------------------- STM32F469xx/STM32F479xx--------------------*/ -#if defined(STM32F469xx) || defined(STM32F479xx) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00U) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00U) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00U) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00U) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00U) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01U) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01U) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02U) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02U) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02U) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM8 ((uint8_t)0x03U) /* TIM8 Alternate Function mapping */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03U) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03U) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03U) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04U) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04U) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04U) /* I2C3 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05U) /* SPI1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05U) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_SPI3 ((uint8_t)0x05U) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF5_SPI4 ((uint8_t)0x05U) /* SPI4 Alternate Function mapping */ -#define GPIO_AF5_SPI5 ((uint8_t)0x05U) /* SPI5 Alternate Function mapping */ -#define GPIO_AF5_SPI6 ((uint8_t)0x05U) /* SPI6 Alternate Function mapping */ -#define GPIO_AF5_I2S3ext ((uint8_t)0x05U) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06U) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_I2S2ext ((uint8_t)0x06U) /* I2S2ext_SD Alternate Function mapping */ -#define GPIO_AF6_SAI1 ((uint8_t)0x06U) /* SAI1 Alternate Function mapping */ - -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_USART1 ((uint8_t)0x07U) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07U) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_USART3 ((uint8_t)0x07U) /* USART3 Alternate Function mapping */ -#define GPIO_AF7_I2S3ext ((uint8_t)0x07U) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_UART4 ((uint8_t)0x08U) /* UART4 Alternate Function mapping */ -#define GPIO_AF8_UART5 ((uint8_t)0x08U) /* UART5 Alternate Function mapping */ -#define GPIO_AF8_USART6 ((uint8_t)0x08U) /* USART6 Alternate Function mapping */ -#define GPIO_AF8_UART7 ((uint8_t)0x08U) /* UART7 Alternate Function mapping */ -#define GPIO_AF8_UART8 ((uint8_t)0x08U) /* UART8 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_CAN1 ((uint8_t)0x09U) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_CAN2 ((uint8_t)0x09U) /* CAN2 Alternate Function mapping */ -#define GPIO_AF9_TIM12 ((uint8_t)0x09U) /* TIM12 Alternate Function mapping */ -#define GPIO_AF9_TIM13 ((uint8_t)0x09U) /* TIM13 Alternate Function mapping */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09U) /* TIM14 Alternate Function mapping */ -#define GPIO_AF9_LTDC ((uint8_t)0x09U) /* LCD-TFT Alternate Function mapping */ -#define GPIO_AF9_QSPI ((uint8_t)0x09U) /* QSPI Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0AU) /* OTG_FS Alternate Function mapping */ -#define GPIO_AF10_OTG_HS ((uint8_t)0x0AU) /* OTG_HS Alternate Function mapping */ -#define GPIO_AF10_QSPI ((uint8_t)0x0AU) /* QSPI Alternate Function mapping */ - -/** - * @brief AF 11 selection - */ -#define GPIO_AF11_ETH ((uint8_t)0x0BU) /* ETHERNET Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_FMC ((uint8_t)0x0CU) /* FMC Alternate Function mapping */ -#define GPIO_AF12_OTG_HS_FS ((uint8_t)0x0CU) /* OTG HS configured in FS, Alternate Function mapping */ -#define GPIO_AF12_SDIO ((uint8_t)0x0CU) /* SDIO Alternate Function mapping */ - -/** - * @brief AF 13 selection - */ -#define GPIO_AF13_DCMI ((uint8_t)0x0DU) /* DCMI Alternate Function mapping */ -#define GPIO_AF13_DSI ((uint8_t)0x0DU) /* DSI Alternate Function mapping */ - -/** - * @brief AF 14 selection - */ -#define GPIO_AF14_LTDC ((uint8_t)0x0EU) /* LCD-TFT Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0FU) /* EVENTOUT Alternate Function mapping */ - -#endif /* STM32F469xx || STM32F479xx */ -/*----------------------------------------------------------------------------*/ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup GPIOEx_Exported_Macros GPIO Exported Macros - * @{ - */ -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup GPIOEx_Exported_Functions GPIO Exported Functions - * @{ - */ -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup GPIOEx_Private_Constants GPIO Private Constants - * @{ - */ -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup GPIOEx_Private_Macros GPIO Private Macros - * @{ - */ -/** @defgroup GPIOEx_Get_Port_Index GPIO Get Port Index - * @{ - */ -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) -#define GPIO_GET_INDEX(__GPIOx__) (uint8_t)(((__GPIOx__) == (GPIOA))? 0U :\ - ((__GPIOx__) == (GPIOB))? 1U :\ - ((__GPIOx__) == (GPIOC))? 2U :\ - ((__GPIOx__) == (GPIOD))? 3U :\ - ((__GPIOx__) == (GPIOE))? 4U :\ - ((__GPIOx__) == (GPIOF))? 5U :\ - ((__GPIOx__) == (GPIOG))? 6U :\ - ((__GPIOx__) == (GPIOH))? 7U : 8U) -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F469xx) || defined(STM32F479xx) -#define GPIO_GET_INDEX(__GPIOx__) (uint8_t)(((__GPIOx__) == (GPIOA))? 0U :\ - ((__GPIOx__) == (GPIOB))? 1U :\ - ((__GPIOx__) == (GPIOC))? 2U :\ - ((__GPIOx__) == (GPIOD))? 3U :\ - ((__GPIOx__) == (GPIOE))? 4U :\ - ((__GPIOx__) == (GPIOF))? 5U :\ - ((__GPIOx__) == (GPIOG))? 6U :\ - ((__GPIOx__) == (GPIOH))? 7U :\ - ((__GPIOx__) == (GPIOI))? 8U :\ - ((__GPIOx__) == (GPIOJ))? 9U : 10U) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -#define GPIO_GET_INDEX(__GPIOx__) (uint8_t)(((__GPIOx__) == (GPIOA))? 0U :\ - ((__GPIOx__) == (GPIOB))? 1U :\ - ((__GPIOx__) == (GPIOC))? 2U : 7U) -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) -#define GPIO_GET_INDEX(__GPIOx__) (uint8_t)(((__GPIOx__) == (GPIOA))? 0U :\ - ((__GPIOx__) == (GPIOB))? 1U :\ - ((__GPIOx__) == (GPIOC))? 2U :\ - ((__GPIOx__) == (GPIOD))? 3U :\ - ((__GPIOx__) == (GPIOE))? 4U : 7U) -#endif /* STM32F401xC || STM32F401xE || STM32F411xE */ - -#if defined(STM32F446xx) || defined(STM32F412Zx) ||defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -#define GPIO_GET_INDEX(__GPIOx__) (uint8_t)(((__GPIOx__) == (GPIOA))? 0U :\ - ((__GPIOx__) == (GPIOB))? 1U :\ - ((__GPIOx__) == (GPIOC))? 2U :\ - ((__GPIOx__) == (GPIOD))? 3U :\ - ((__GPIOx__) == (GPIOE))? 4U :\ - ((__GPIOx__) == (GPIOF))? 5U :\ - ((__GPIOx__) == (GPIOG))? 6U : 7U) -#endif /* STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ - -/** - * @} - */ - -/** @defgroup GPIOEx_IS_Alternat_function_selection GPIO Check Alternate Function - * @{ - */ -/*------------------------- STM32F429xx/STM32F439xx---------------------------*/ -#if defined(STM32F429xx) || defined(STM32F439xx) -#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ - ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ - ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ - ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ - ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ - ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF3_TIM8) || \ - ((AF) == GPIO_AF4_I2C1) || ((AF) == GPIO_AF4_I2C2) || \ - ((AF) == GPIO_AF4_I2C3) || ((AF) == GPIO_AF5_SPI1) || \ - ((AF) == GPIO_AF5_SPI2) || ((AF) == GPIO_AF9_TIM13) || \ - ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF9_TIM12) || \ - ((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \ - ((AF) == GPIO_AF7_USART3) || ((AF) == GPIO_AF8_UART4) || \ - ((AF) == GPIO_AF8_UART5) || ((AF) == GPIO_AF8_USART6) || \ - ((AF) == GPIO_AF9_CAN1) || ((AF) == GPIO_AF9_CAN2) || \ - ((AF) == GPIO_AF10_OTG_FS) || ((AF) == GPIO_AF10_OTG_HS) || \ - ((AF) == GPIO_AF11_ETH) || ((AF) == GPIO_AF12_OTG_HS_FS) || \ - ((AF) == GPIO_AF12_SDIO) || ((AF) == GPIO_AF13_DCMI) || \ - ((AF) == GPIO_AF15_EVENTOUT) || ((AF) == GPIO_AF5_SPI4) || \ - ((AF) == GPIO_AF5_SPI5) || ((AF) == GPIO_AF5_SPI6) || \ - ((AF) == GPIO_AF8_UART7) || ((AF) == GPIO_AF8_UART8) || \ - ((AF) == GPIO_AF12_FMC) || ((AF) == GPIO_AF6_SAI1) || \ - ((AF) == GPIO_AF14_LTDC)) - -#endif /* STM32F429xx || STM32F439xx */ -/*----------------------------------------------------------------------------*/ - -/*---------------------------------- STM32F427xx/STM32F437xx------------------*/ -#if defined(STM32F427xx) || defined(STM32F437xx) -#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ - ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ - ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ - ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ - ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ - ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF3_TIM8) || \ - ((AF) == GPIO_AF4_I2C1) || ((AF) == GPIO_AF4_I2C2) || \ - ((AF) == GPIO_AF4_I2C3) || ((AF) == GPIO_AF5_SPI1) || \ - ((AF) == GPIO_AF5_SPI2) || ((AF) == GPIO_AF9_TIM13) || \ - ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF9_TIM12) || \ - ((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \ - ((AF) == GPIO_AF7_USART3) || ((AF) == GPIO_AF8_UART4) || \ - ((AF) == GPIO_AF8_UART5) || ((AF) == GPIO_AF8_USART6) || \ - ((AF) == GPIO_AF9_CAN1) || ((AF) == GPIO_AF9_CAN2) || \ - ((AF) == GPIO_AF10_OTG_FS) || ((AF) == GPIO_AF10_OTG_HS) || \ - ((AF) == GPIO_AF11_ETH) || ((AF) == GPIO_AF12_OTG_HS_FS) || \ - ((AF) == GPIO_AF12_SDIO) || ((AF) == GPIO_AF13_DCMI) || \ - ((AF) == GPIO_AF15_EVENTOUT) || ((AF) == GPIO_AF5_SPI4) || \ - ((AF) == GPIO_AF5_SPI5) || ((AF) == GPIO_AF5_SPI6) || \ - ((AF) == GPIO_AF8_UART7) || ((AF) == GPIO_AF8_UART8) || \ - ((AF) == GPIO_AF12_FMC) || ((AF) == GPIO_AF6_SAI1)) - -#endif /* STM32F427xx || STM32F437xx */ -/*----------------------------------------------------------------------------*/ - -/*---------------------------------- STM32F407xx/STM32F417xx------------------*/ -#if defined(STM32F407xx) || defined(STM32F417xx) -#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ - ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ - ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ - ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ - ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ - ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF3_TIM8) || \ - ((AF) == GPIO_AF4_I2C1) || ((AF) == GPIO_AF4_I2C2) || \ - ((AF) == GPIO_AF4_I2C3) || ((AF) == GPIO_AF5_SPI1) || \ - ((AF) == GPIO_AF5_SPI2) || ((AF) == GPIO_AF9_TIM13) || \ - ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF9_TIM12) || \ - ((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \ - ((AF) == GPIO_AF7_USART3) || ((AF) == GPIO_AF8_UART4) || \ - ((AF) == GPIO_AF8_UART5) || ((AF) == GPIO_AF8_USART6) || \ - ((AF) == GPIO_AF9_CAN1) || ((AF) == GPIO_AF9_CAN2) || \ - ((AF) == GPIO_AF10_OTG_FS) || ((AF) == GPIO_AF10_OTG_HS) || \ - ((AF) == GPIO_AF11_ETH) || ((AF) == GPIO_AF12_OTG_HS_FS) || \ - ((AF) == GPIO_AF12_SDIO) || ((AF) == GPIO_AF13_DCMI) || \ - ((AF) == GPIO_AF12_FSMC) || ((AF) == GPIO_AF15_EVENTOUT)) - -#endif /* STM32F407xx || STM32F417xx */ -/*----------------------------------------------------------------------------*/ - -/*---------------------------------- STM32F405xx/STM32F415xx------------------*/ -#if defined(STM32F405xx) || defined(STM32F415xx) -#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ - ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ - ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ - ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ - ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ - ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF3_TIM8) || \ - ((AF) == GPIO_AF4_I2C1) || ((AF) == GPIO_AF4_I2C2) || \ - ((AF) == GPIO_AF4_I2C3) || ((AF) == GPIO_AF5_SPI1) || \ - ((AF) == GPIO_AF5_SPI2) || ((AF) == GPIO_AF9_TIM13) || \ - ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF9_TIM12) || \ - ((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \ - ((AF) == GPIO_AF7_USART3) || ((AF) == GPIO_AF8_UART4) || \ - ((AF) == GPIO_AF8_UART5) || ((AF) == GPIO_AF8_USART6) || \ - ((AF) == GPIO_AF9_CAN1) || ((AF) == GPIO_AF9_CAN2) || \ - ((AF) == GPIO_AF10_OTG_FS) || ((AF) == GPIO_AF10_OTG_HS) || \ - ((AF) == GPIO_AF12_OTG_HS_FS) || ((AF) == GPIO_AF12_SDIO) || \ - ((AF) == GPIO_AF12_FSMC) || ((AF) == GPIO_AF15_EVENTOUT)) - -#endif /* STM32F405xx || STM32F415xx */ - -/*----------------------------------------------------------------------------*/ - -/*---------------------------------------- STM32F401xx------------------------*/ -#if defined(STM32F401xC) || defined(STM32F401xE) -#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ - ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ - ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ - ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ - ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ - ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF4_I2C1) || \ - ((AF) == GPIO_AF4_I2C2) || ((AF) == GPIO_AF4_I2C3) || \ - ((AF) == GPIO_AF5_SPI1) || ((AF) == GPIO_AF5_SPI2) || \ - ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF5_SPI4) || \ - ((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \ - ((AF) == GPIO_AF8_USART6) || ((AF) == GPIO_AF10_OTG_FS) || \ - ((AF) == GPIO_AF9_I2C2) || ((AF) == GPIO_AF9_I2C3) || \ - ((AF) == GPIO_AF12_SDIO) || ((AF) == GPIO_AF15_EVENTOUT)) - -#endif /* STM32F401xC || STM32F401xE */ -/*----------------------------------------------------------------------------*/ -/*---------------------------------------- STM32F410xx------------------------*/ -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -#define IS_GPIO_AF(AF) (((AF) < 10U) || ((AF) == 15U)) -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -/*---------------------------------------- STM32F411xx------------------------*/ -#if defined(STM32F411xE) -#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ - ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ - ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ - ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ - ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ - ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF4_I2C1) || \ - ((AF) == GPIO_AF4_I2C2) || ((AF) == GPIO_AF4_I2C3) || \ - ((AF) == GPIO_AF5_SPI1) || ((AF) == GPIO_AF5_SPI2) || \ - ((AF) == GPIO_AF5_SPI3) || ((AF) == GPIO_AF6_SPI4) || \ - ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF5_SPI4) || \ - ((AF) == GPIO_AF6_SPI5) || ((AF) == GPIO_AF7_SPI3) || \ - ((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \ - ((AF) == GPIO_AF8_USART6) || ((AF) == GPIO_AF10_OTG_FS) || \ - ((AF) == GPIO_AF9_I2C2) || ((AF) == GPIO_AF9_I2C3) || \ - ((AF) == GPIO_AF12_SDIO) || ((AF) == GPIO_AF15_EVENTOUT)) - -#endif /* STM32F411xE */ -/*----------------------------------------------------------------------------*/ - -/*----------------------------------------------- STM32F446xx ----------------*/ -#if defined(STM32F446xx) -#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ - ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ - ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ - ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ - ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ - ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF3_TIM8) || \ - ((AF) == GPIO_AF4_I2C1) || ((AF) == GPIO_AF4_I2C2) || \ - ((AF) == GPIO_AF4_I2C3) || ((AF) == GPIO_AF5_SPI1) || \ - ((AF) == GPIO_AF5_SPI2) || ((AF) == GPIO_AF9_TIM13) || \ - ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF9_TIM12) || \ - ((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \ - ((AF) == GPIO_AF7_USART3) || ((AF) == GPIO_AF8_UART4) || \ - ((AF) == GPIO_AF8_UART5) || ((AF) == GPIO_AF8_USART6) || \ - ((AF) == GPIO_AF9_CAN1) || ((AF) == GPIO_AF9_CAN2) || \ - ((AF) == GPIO_AF10_OTG_FS) || ((AF) == GPIO_AF10_OTG_HS) || \ - ((AF) == GPIO_AF11_ETH) || ((AF) == GPIO_AF12_OTG_HS_FS) || \ - ((AF) == GPIO_AF12_SDIO) || ((AF) == GPIO_AF13_DCMI) || \ - ((AF) == GPIO_AF15_EVENTOUT) || ((AF) == GPIO_AF5_SPI4) || \ - ((AF) == GPIO_AF12_FMC) || ((AF) == GPIO_AF6_SAI1) || \ - ((AF) == GPIO_AF3_CEC) || ((AF) == GPIO_AF4_CEC) || \ - ((AF) == GPIO_AF5_SPI3) || ((AF) == GPIO_AF6_SPI2) || \ - ((AF) == GPIO_AF6_SPI4) || ((AF) == GPIO_AF7_UART5) || \ - ((AF) == GPIO_AF7_SPI2) || ((AF) == GPIO_AF7_SPI3) || \ - ((AF) == GPIO_AF7_SPDIFRX) || ((AF) == GPIO_AF8_SPDIFRX) || \ - ((AF) == GPIO_AF8_SAI2) || ((AF) == GPIO_AF9_QSPI) || \ - ((AF) == GPIO_AF10_SAI2) || ((AF) == GPIO_AF10_QSPI)) - -#endif /* STM32F446xx */ -/*----------------------------------------------------------------------------*/ - -/*------------------------------------------- STM32F469xx/STM32F479xx --------*/ -#if defined(STM32F469xx) || defined(STM32F479xx) -#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ - ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ - ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ - ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ - ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ - ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF3_TIM8) || \ - ((AF) == GPIO_AF4_I2C1) || ((AF) == GPIO_AF4_I2C2) || \ - ((AF) == GPIO_AF4_I2C3) || ((AF) == GPIO_AF5_SPI1) || \ - ((AF) == GPIO_AF5_SPI2) || ((AF) == GPIO_AF9_TIM13) || \ - ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF9_TIM12) || \ - ((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \ - ((AF) == GPIO_AF7_USART3) || ((AF) == GPIO_AF8_UART4) || \ - ((AF) == GPIO_AF8_UART5) || ((AF) == GPIO_AF8_USART6) || \ - ((AF) == GPIO_AF9_CAN1) || ((AF) == GPIO_AF9_CAN2) || \ - ((AF) == GPIO_AF10_OTG_FS) || ((AF) == GPIO_AF10_OTG_HS) || \ - ((AF) == GPIO_AF11_ETH) || ((AF) == GPIO_AF12_OTG_HS_FS) || \ - ((AF) == GPIO_AF12_SDIO) || ((AF) == GPIO_AF13_DCMI) || \ - ((AF) == GPIO_AF15_EVENTOUT) || ((AF) == GPIO_AF5_SPI4) || \ - ((AF) == GPIO_AF5_SPI5) || ((AF) == GPIO_AF5_SPI6) || \ - ((AF) == GPIO_AF8_UART7) || ((AF) == GPIO_AF8_UART8) || \ - ((AF) == GPIO_AF12_FMC) || ((AF) == GPIO_AF6_SAI1) || \ - ((AF) == GPIO_AF14_LTDC) || ((AF) == GPIO_AF13_DSI) || \ - ((AF) == GPIO_AF9_QSPI) || ((AF) == GPIO_AF10_QSPI)) - -#endif /* STM32F469xx || STM32F479xx */ -/*----------------------------------------------------------------------------*/ - -/*------------------STM32F412Zx/STM32F412Vx/STM32F412Rx/STM32F412Cx-----------*/ -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) -#define IS_GPIO_AF(AF) (((AF) < 16U) && ((AF) != 11U) && ((AF) != 14U) && ((AF) != 13U)) -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ -/*----------------------------------------------------------------------------*/ - -/*------------------STM32F413xx/STM32F423xx-----------------------------------*/ -#if defined(STM32F413xx) || defined(STM32F423xx) -#define IS_GPIO_AF(AF) (((AF) < 16U) && ((AF) != 13U)) -#endif /* STM32F413xx || STM32F423xx */ -/*----------------------------------------------------------------------------*/ - -/** - * @} - */ - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup GPIOEx_Private_Functions GPIO Private Functions - * @{ - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_GPIO_EX_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/panda/board/stm32fx/inc/system_stm32f2xx.h b/panda/board/stm32fx/inc/system_stm32f2xx.h deleted file mode 100644 index cd4b83c57..000000000 --- a/panda/board/stm32fx/inc/system_stm32f2xx.h +++ /dev/null @@ -1,122 +0,0 @@ -/** - ****************************************************************************** - * @file system_stm32f2xx.h - * @author MCD Application Team - * @version V2.1.2 - * @date 29-June-2016 - * @brief CMSIS Cortex-M3 Device System Source File for STM32F2xx devices. -****************************************************************************** - * @attention - * - *

© COPYRIGHT(c) 2016 STMicroelectronics

- * - * 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. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * 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 HOLDER 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. - * - ****************************************************************************** - */ - -/** @addtogroup CMSIS - * @{ - */ - -/** @addtogroup stm32f2xx_system - * @{ - */ - -/** - * @brief Define to prevent recursive inclusion - */ -#ifndef __SYSTEM_STM32F2XX_H -#define __SYSTEM_STM32F2XX_H - -#ifdef __cplusplus - extern "C" { -#endif - -/** @addtogroup STM32F2xx_System_Includes - * @{ - */ - -/** - * @} - */ - - -/** @addtogroup STM32F2xx_System_Exported_types - * @{ - */ - /* This variable is updated in three ways: - 1) by calling CMSIS function SystemCoreClockUpdate() - 2) by calling HAL API function HAL_RCC_GetSysClockFreq() - 3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency - Note: If you use this function to configure the system clock; then there - is no need to call the 2 first functions listed above, since SystemCoreClock - variable is updated automatically. - */ -extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */ - - -/** - * @} - */ - -/** @addtogroup STM32F2xx_System_Exported_Constants - * @{ - */ - -/** - * @} - */ - -/** @addtogroup STM32F2xx_System_Exported_Macros - * @{ - */ - -/** - * @} - */ - -/** @addtogroup STM32F2xx_System_Exported_Functions - * @{ - */ - -extern void SystemInit(void); -extern void SystemCoreClockUpdate(void); -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /*__SYSTEM_STM32F2XX_H */ - -/** - * @} - */ - -/** - * @} - */ -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/panda/board/stm32fx/inc/system_stm32f4xx.h b/panda/board/stm32fx/inc/system_stm32f4xx.h deleted file mode 100644 index 7978dab45..000000000 --- a/panda/board/stm32fx/inc/system_stm32f4xx.h +++ /dev/null @@ -1,124 +0,0 @@ -/** - ****************************************************************************** - * @file system_stm32f4xx.h - * @author MCD Application Team - * @version V2.6.0 - * @date 04-November-2016 - * @brief CMSIS Cortex-M4 Device System Source File for STM32F4xx devices. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT(c) 2016 STMicroelectronics

- * - * 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. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * 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 HOLDER 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. - * - ****************************************************************************** - */ - -/** @addtogroup CMSIS - * @{ - */ - -/** @addtogroup stm32f4xx_system - * @{ - */ - -/** - * @brief Define to prevent recursive inclusion - */ -#ifndef __SYSTEM_STM32F4XX_H -#define __SYSTEM_STM32F4XX_H - -#ifdef __cplusplus - extern "C" { -#endif - -/** @addtogroup STM32F4xx_System_Includes - * @{ - */ - -/** - * @} - */ - - -/** @addtogroup STM32F4xx_System_Exported_types - * @{ - */ - /* This variable is updated in three ways: - 1) by calling CMSIS function SystemCoreClockUpdate() - 2) by calling HAL API function HAL_RCC_GetSysClockFreq() - 3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency - Note: If you use this function to configure the system clock; then there - is no need to call the 2 first functions listed above, since SystemCoreClock - variable is updated automatically. - */ -extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */ - -extern const uint8_t AHBPrescTable[16]; /*!< AHB prescalers table values */ -extern const uint8_t APBPrescTable[8]; /*!< APB prescalers table values */ - -/** - * @} - */ - -/** @addtogroup STM32F4xx_System_Exported_Constants - * @{ - */ - -/** - * @} - */ - -/** @addtogroup STM32F4xx_System_Exported_Macros - * @{ - */ - -/** - * @} - */ - -/** @addtogroup STM32F4xx_System_Exported_Functions - * @{ - */ - -extern void SystemInit(void); -extern void SystemCoreClockUpdate(void); -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /*__SYSTEM_STM32F4XX_H */ - -/** - * @} - */ - -/** - * @} - */ -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/panda/board/stm32fx/interrupt_handlers.h b/panda/board/stm32fx/interrupt_handlers.h deleted file mode 100644 index 3b40f4ee5..000000000 --- a/panda/board/stm32fx/interrupt_handlers.h +++ /dev/null @@ -1,100 +0,0 @@ -// ********************* Bare interrupt handlers ********************* -// Only implemented the STM32F413 interrupts for now, the STM32F203 specific ones do not fall into the scope of SIL2 - -void WWDG_IRQHandler(void) {handle_interrupt(WWDG_IRQn);} -void PVD_IRQHandler(void) {handle_interrupt(PVD_IRQn);} -void TAMP_STAMP_IRQHandler(void) {handle_interrupt(TAMP_STAMP_IRQn);} -void RTC_WKUP_IRQHandler(void) {handle_interrupt(RTC_WKUP_IRQn);} -void FLASH_IRQHandler(void) {handle_interrupt(FLASH_IRQn);} -void RCC_IRQHandler(void) {handle_interrupt(RCC_IRQn);} -void EXTI0_IRQHandler(void) {handle_interrupt(EXTI0_IRQn);} -void EXTI1_IRQHandler(void) {handle_interrupt(EXTI1_IRQn);} -void EXTI2_IRQHandler(void) {handle_interrupt(EXTI2_IRQn);} -void EXTI3_IRQHandler(void) {handle_interrupt(EXTI3_IRQn);} -void EXTI4_IRQHandler(void) {handle_interrupt(EXTI4_IRQn);} -void DMA1_Stream0_IRQHandler(void) {handle_interrupt(DMA1_Stream0_IRQn);} -void DMA1_Stream1_IRQHandler(void) {handle_interrupt(DMA1_Stream1_IRQn);} -void DMA1_Stream2_IRQHandler(void) {handle_interrupt(DMA1_Stream2_IRQn);} -void DMA1_Stream3_IRQHandler(void) {handle_interrupt(DMA1_Stream3_IRQn);} -void DMA1_Stream4_IRQHandler(void) {handle_interrupt(DMA1_Stream4_IRQn);} -void DMA1_Stream5_IRQHandler(void) {handle_interrupt(DMA1_Stream5_IRQn);} -void DMA1_Stream6_IRQHandler(void) {handle_interrupt(DMA1_Stream6_IRQn);} -void ADC_IRQHandler(void) {handle_interrupt(ADC_IRQn);} -void CAN1_TX_IRQHandler(void) {handle_interrupt(CAN1_TX_IRQn);} -void CAN1_RX0_IRQHandler(void) {handle_interrupt(CAN1_RX0_IRQn);} -void CAN1_RX1_IRQHandler(void) {handle_interrupt(CAN1_RX1_IRQn);} -void CAN1_SCE_IRQHandler(void) {handle_interrupt(CAN1_SCE_IRQn);} -void EXTI9_5_IRQHandler(void) {handle_interrupt(EXTI9_5_IRQn);} -void TIM1_BRK_TIM9_IRQHandler(void) {handle_interrupt(TIM1_BRK_TIM9_IRQn);} -void TIM1_UP_TIM10_IRQHandler(void) {handle_interrupt(TIM1_UP_TIM10_IRQn);} -void TIM1_TRG_COM_TIM11_IRQHandler(void) {handle_interrupt(TIM1_TRG_COM_TIM11_IRQn);} -void TIM1_CC_IRQHandler(void) {handle_interrupt(TIM1_CC_IRQn);} -void TIM2_IRQHandler(void) {handle_interrupt(TIM2_IRQn);} -void TIM3_IRQHandler(void) {handle_interrupt(TIM3_IRQn);} -void TIM4_IRQHandler(void) {handle_interrupt(TIM4_IRQn);} -void I2C1_EV_IRQHandler(void) {handle_interrupt(I2C1_EV_IRQn);} -void I2C1_ER_IRQHandler(void) {handle_interrupt(I2C1_ER_IRQn);} -void I2C2_EV_IRQHandler(void) {handle_interrupt(I2C2_EV_IRQn);} -void I2C2_ER_IRQHandler(void) {handle_interrupt(I2C2_ER_IRQn);} -void SPI1_IRQHandler(void) {handle_interrupt(SPI1_IRQn);} -void SPI2_IRQHandler(void) {handle_interrupt(SPI2_IRQn);} -void USART1_IRQHandler(void) {handle_interrupt(USART1_IRQn);} -void USART2_IRQHandler(void) {handle_interrupt(USART2_IRQn);} -void USART3_IRQHandler(void) {handle_interrupt(USART3_IRQn);} -void EXTI15_10_IRQHandler(void) {handle_interrupt(EXTI15_10_IRQn);} -void RTC_Alarm_IRQHandler(void) {handle_interrupt(RTC_Alarm_IRQn);} -void OTG_FS_WKUP_IRQHandler(void) {handle_interrupt(OTG_FS_WKUP_IRQn);} -void TIM8_BRK_TIM12_IRQHandler(void) {handle_interrupt(TIM8_BRK_TIM12_IRQn);} -void TIM8_UP_TIM13_IRQHandler(void) {handle_interrupt(TIM8_UP_TIM13_IRQn);} -void TIM8_TRG_COM_TIM14_IRQHandler(void) {handle_interrupt(TIM8_TRG_COM_TIM14_IRQn);} -void TIM8_CC_IRQHandler(void) {handle_interrupt(TIM8_CC_IRQn);} -void DMA1_Stream7_IRQHandler(void) {handle_interrupt(DMA1_Stream7_IRQn);} -void FSMC_IRQHandler(void) {handle_interrupt(FSMC_IRQn);} -void SDIO_IRQHandler(void) {handle_interrupt(SDIO_IRQn);} -void TIM5_IRQHandler(void) {handle_interrupt(TIM5_IRQn);} -void SPI3_IRQHandler(void) {handle_interrupt(SPI3_IRQn);} -void UART4_IRQHandler(void) {handle_interrupt(UART4_IRQn);} -void UART5_IRQHandler(void) {handle_interrupt(UART5_IRQn);} -void TIM6_DAC_IRQHandler(void) {handle_interrupt(TIM6_DAC_IRQn);} -void TIM7_IRQHandler(void) {handle_interrupt(TIM7_IRQn);} -void DMA2_Stream0_IRQHandler(void) {handle_interrupt(DMA2_Stream0_IRQn);} -void DMA2_Stream1_IRQHandler(void) {handle_interrupt(DMA2_Stream1_IRQn);} -void DMA2_Stream2_IRQHandler(void) {handle_interrupt(DMA2_Stream2_IRQn);} -void DMA2_Stream3_IRQHandler(void) {handle_interrupt(DMA2_Stream3_IRQn);} -void DMA2_Stream4_IRQHandler(void) {handle_interrupt(DMA2_Stream4_IRQn);} -void CAN2_TX_IRQHandler(void) {handle_interrupt(CAN2_TX_IRQn);} -void CAN2_RX0_IRQHandler(void) {handle_interrupt(CAN2_RX0_IRQn);} -void CAN2_RX1_IRQHandler(void) {handle_interrupt(CAN2_RX1_IRQn);} -void CAN2_SCE_IRQHandler(void) {handle_interrupt(CAN2_SCE_IRQn);} -void OTG_FS_IRQHandler(void) {handle_interrupt(OTG_FS_IRQn);} -void DMA2_Stream5_IRQHandler(void) {handle_interrupt(DMA2_Stream5_IRQn);} -void DMA2_Stream6_IRQHandler(void) {handle_interrupt(DMA2_Stream6_IRQn);} -void DMA2_Stream7_IRQHandler(void) {handle_interrupt(DMA2_Stream7_IRQn);} -void USART6_IRQHandler(void) {handle_interrupt(USART6_IRQn);} -void I2C3_EV_IRQHandler(void) {handle_interrupt(I2C3_EV_IRQn);} -void I2C3_ER_IRQHandler(void) {handle_interrupt(I2C3_ER_IRQn);} -#ifdef STM32F4 - void DFSDM1_FLT0_IRQHandler(void) {handle_interrupt(DFSDM1_FLT0_IRQn);} - void DFSDM1_FLT1_IRQHandler(void) {handle_interrupt(DFSDM1_FLT1_IRQn);} - void CAN3_TX_IRQHandler(void) {handle_interrupt(CAN3_TX_IRQn);} - void CAN3_RX0_IRQHandler(void) {handle_interrupt(CAN3_RX0_IRQn);} - void CAN3_RX1_IRQHandler(void) {handle_interrupt(CAN3_RX1_IRQn);} - void CAN3_SCE_IRQHandler(void) {handle_interrupt(CAN3_SCE_IRQn);} - void RNG_IRQHandler(void) {handle_interrupt(RNG_IRQn);} - void FPU_IRQHandler(void) {handle_interrupt(FPU_IRQn);} - void UART7_IRQHandler(void) {handle_interrupt(UART7_IRQn);} - void UART8_IRQHandler(void) {handle_interrupt(UART8_IRQn);} - void SPI4_IRQHandler(void) {handle_interrupt(SPI4_IRQn);} - void SPI5_IRQHandler(void) {handle_interrupt(SPI5_IRQn);} - void SAI1_IRQHandler(void) {handle_interrupt(SAI1_IRQn);} - void UART9_IRQHandler(void) {handle_interrupt(UART9_IRQn);} - void UART10_IRQHandler(void) {handle_interrupt(UART10_IRQn);} - void QUADSPI_IRQHandler(void) {handle_interrupt(QUADSPI_IRQn);} - void FMPI2C1_EV_IRQHandler(void) {handle_interrupt(FMPI2C1_EV_IRQn);} - void FMPI2C1_ER_IRQHandler(void) {handle_interrupt(FMPI2C1_ER_IRQn);} - void LPTIM1_IRQHandler(void) {handle_interrupt(LPTIM1_IRQn);} - void DFSDM2_FLT0_IRQHandler(void) {handle_interrupt(DFSDM2_FLT0_IRQn);} - void DFSDM2_FLT1_IRQHandler(void) {handle_interrupt(DFSDM2_FLT1_IRQn);} - void DFSDM2_FLT2_IRQHandler(void) {handle_interrupt(DFSDM2_FLT2_IRQn);} - void DFSDM2_FLT3_IRQHandler(void) {handle_interrupt(DFSDM2_FLT3_IRQn);} -#endif diff --git a/panda/board/stm32fx/lladc.h b/panda/board/stm32fx/lladc.h deleted file mode 100644 index 31c17f4b2..000000000 --- a/panda/board/stm32fx/lladc.h +++ /dev/null @@ -1,33 +0,0 @@ -// ACCEL1 = ADC10 -// ACCEL2 = ADC11 -// VOLT_S = ADC12 -// CURR_S = ADC13 - -#define ADCCHAN_ACCEL0 10 -#define ADCCHAN_ACCEL1 11 -#define ADCCHAN_VIN 12 -#define ADCCHAN_CURRENT 13 - -void register_set(volatile uint32_t *addr, uint32_t val, uint32_t mask); - -void adc_init(void) { - register_set(&(ADC->CCR), ADC_CCR_TSVREFE | ADC_CCR_VBATE, 0xC30000U); - register_set(&(ADC1->CR2), ADC_CR2_ADON, 0xFF7F0F03U); - register_set(&(ADC1->SMPR1), ADC_SMPR1_SMP12 | ADC_SMPR1_SMP13, 0x7FFFFFFU); -} - -uint16_t adc_get_raw(uint8_t channel) { - // Select channel - register_set(&(ADC1->JSQR), ((uint32_t) channel << 15U), 0x3FFFFFU); - - // Start conversion - ADC1->SR &= ~(ADC_SR_JEOC); - ADC1->CR2 |= ADC_CR2_JSWSTART; - while (!(ADC1->SR & ADC_SR_JEOC)); - - return ADC1->JDR1; -} - -uint16_t adc_get_mV(uint8_t channel) { - return (adc_get_raw(channel) * current_board->avdd_mV) / 4095U; -} diff --git a/panda/board/stm32fx/llbxcan.h b/panda/board/stm32fx/llbxcan.h deleted file mode 100644 index 64f990514..000000000 --- a/panda/board/stm32fx/llbxcan.h +++ /dev/null @@ -1,162 +0,0 @@ -// Flasher and pedal use raw mailbox access -#define GET_MAILBOX_BYTE(msg, b) (((int)(b) > 3) ? (((msg)->RDHR >> (8U * ((unsigned int)(b) % 4U))) & 0xFFU) : (((msg)->RDLR >> (8U * (unsigned int)(b))) & 0xFFU)) -#define GET_MAILBOX_BYTES_04(msg) ((msg)->RDLR) -#define GET_MAILBOX_BYTES_48(msg) ((msg)->RDHR) - -// SAE 2284-3 : minimum 16 tq, SJW 3, sample point at 81.3% -#define CAN_QUANTA 16U -#define CAN_SEQ1 12U -#define CAN_SEQ2 3U -#define CAN_SJW 3U - -#define CAN_PCLK 48000U -// 333 = 33.3 kbps -// 5000 = 500 kbps -#define can_speed_to_prescaler(x) (CAN_PCLK / CAN_QUANTA * 10U / (x)) - -#define CAN_NAME_FROM_CANIF(CAN_DEV) (((CAN_DEV)==CAN1) ? "CAN1" : (((CAN_DEV) == CAN2) ? "CAN2" : "CAN3")) - -void print(const char *a); - -// kbps multiplied by 10 -const uint32_t speeds[] = {100U, 200U, 500U, 1000U, 1250U, 2500U, 5000U, 10000U}; -const uint32_t data_speeds[] = {0U}; // No separate data speed, dummy - -bool llcan_set_speed(CAN_TypeDef *CAN_obj, uint32_t speed, bool loopback, bool silent) { - bool ret = true; - - // initialization mode - register_set(&(CAN_obj->MCR), CAN_MCR_TTCM | CAN_MCR_INRQ, 0x180FFU); - uint32_t timeout_counter = 0U; - while((CAN_obj->MSR & CAN_MSR_INAK) != CAN_MSR_INAK){ - // Delay for about 1ms - delay(10000); - timeout_counter++; - - if(timeout_counter >= CAN_INIT_TIMEOUT_MS){ - print(CAN_NAME_FROM_CANIF(CAN_obj)); print(" set_speed timed out (1)!\n"); - ret = false; - break; - } - } - - if(ret){ - // set time quanta from defines - register_set(&(CAN_obj->BTR), ((CAN_BTR_TS1_0 * (CAN_SEQ1-1U)) | - (CAN_BTR_TS2_0 * (CAN_SEQ2-1U)) | - (CAN_BTR_SJW_0 * (CAN_SJW-1U)) | - (can_speed_to_prescaler(speed) - 1U)), 0xC37F03FFU); - - // silent loopback mode for debugging - if (loopback) { - register_set_bits(&(CAN_obj->BTR), CAN_BTR_SILM | CAN_BTR_LBKM); - } - if (silent) { - register_set_bits(&(CAN_obj->BTR), CAN_BTR_SILM); - } - - // reset - register_set(&(CAN_obj->MCR), CAN_MCR_TTCM | CAN_MCR_ABOM, 0x180FFU); - - timeout_counter = 0U; - while(((CAN_obj->MSR & CAN_MSR_INAK) == CAN_MSR_INAK)) { - // Delay for about 1ms - delay(10000); - timeout_counter++; - - if(timeout_counter >= CAN_INIT_TIMEOUT_MS){ - print(CAN_NAME_FROM_CANIF(CAN_obj)); print(" set_speed timed out (2)!\n"); - ret = false; - break; - } - } - } - - return ret; -} - -void llcan_irq_disable(CAN_TypeDef *CAN_obj) { - if (CAN_obj == CAN1) { - NVIC_DisableIRQ(CAN1_TX_IRQn); - NVIC_DisableIRQ(CAN1_RX0_IRQn); - NVIC_DisableIRQ(CAN1_SCE_IRQn); - } else if (CAN_obj == CAN2) { - NVIC_DisableIRQ(CAN2_TX_IRQn); - NVIC_DisableIRQ(CAN2_RX0_IRQn); - NVIC_DisableIRQ(CAN2_SCE_IRQn); - #ifdef CAN3 - } else if (CAN_obj == CAN3) { - NVIC_DisableIRQ(CAN3_TX_IRQn); - NVIC_DisableIRQ(CAN3_RX0_IRQn); - NVIC_DisableIRQ(CAN3_SCE_IRQn); - #endif - } else { - } -} - -void llcan_irq_enable(CAN_TypeDef *CAN_obj) { - if (CAN_obj == CAN1) { - NVIC_EnableIRQ(CAN1_TX_IRQn); - NVIC_EnableIRQ(CAN1_RX0_IRQn); - NVIC_EnableIRQ(CAN1_SCE_IRQn); - } else if (CAN_obj == CAN2) { - NVIC_EnableIRQ(CAN2_TX_IRQn); - NVIC_EnableIRQ(CAN2_RX0_IRQn); - NVIC_EnableIRQ(CAN2_SCE_IRQn); - #ifdef CAN3 - } else if (CAN_obj == CAN3) { - NVIC_EnableIRQ(CAN3_TX_IRQn); - NVIC_EnableIRQ(CAN3_RX0_IRQn); - NVIC_EnableIRQ(CAN3_SCE_IRQn); - #endif - } else { - } -} - -bool llcan_init(CAN_TypeDef *CAN_obj) { - bool ret = true; - - // Enter init mode - register_set_bits(&(CAN_obj->FMR), CAN_FMR_FINIT); - - // Wait for INAK bit to be set - uint32_t timeout_counter = 0U; - while(((CAN_obj->MSR & CAN_MSR_INAK) == CAN_MSR_INAK)) { - // Delay for about 1ms - delay(10000); - timeout_counter++; - - if(timeout_counter >= CAN_INIT_TIMEOUT_MS){ - print(CAN_NAME_FROM_CANIF(CAN_obj)); print(" initialization timed out!\n"); - ret = false; - break; - } - } - - if(ret){ - // no mask - // For some weird reason some of these registers do not want to set properly on CAN2 and CAN3. Probably something to do with the single/dual mode and their different filters. - CAN_obj->sFilterRegister[0].FR1 = 0U; - CAN_obj->sFilterRegister[0].FR2 = 0U; - CAN_obj->sFilterRegister[14].FR1 = 0U; - CAN_obj->sFilterRegister[14].FR2 = 0U; - CAN_obj->FA1R |= 1U | (1U << 14); - - // Exit init mode, do not wait - register_clear_bits(&(CAN_obj->FMR), CAN_FMR_FINIT); - - // enable certain CAN interrupts - register_set_bits(&(CAN_obj->IER), CAN_IER_TMEIE | CAN_IER_FMPIE0 | CAN_IER_ERRIE | CAN_IER_LECIE | CAN_IER_BOFIE | CAN_IER_EPVIE | CAN_IER_EWGIE | CAN_IER_FOVIE0 | CAN_IER_FFIE0); - - // clear overrun flag on init - CAN_obj->RF0R &= ~(CAN_RF0R_FOVR0); - - llcan_irq_enable(CAN_obj); - } - return ret; -} - -void llcan_clear_send(CAN_TypeDef *CAN_obj) { - CAN_obj->TSR |= CAN_TSR_ABRQ0; // Abort message transmission on error interrupt - CAN_obj->MSR |= CAN_MSR_ERRI; // Clear error interrupt -} diff --git a/panda/board/stm32fx/lldac.h b/panda/board/stm32fx/lldac.h deleted file mode 100644 index 6cd2f8ca2..000000000 --- a/panda/board/stm32fx/lldac.h +++ /dev/null @@ -1,16 +0,0 @@ -void dac_init(void) { - // No buffers required since we have an opamp - register_set(&(DAC->DHR12R1), 0U, 0xFFFU); - register_set(&(DAC->DHR12R2), 0U, 0xFFFU); - register_set(&(DAC->CR), DAC_CR_EN1 | DAC_CR_EN2, 0x3FFF3FFFU); -} - -void dac_set(int channel, uint32_t value) { - if (channel == 0) { - register_set(&(DAC->DHR12R1), value, 0xFFFU); - } else if (channel == 1) { - register_set(&(DAC->DHR12R2), value, 0xFFFU); - } else { - print("Failed to set DAC: invalid channel value: 0x"); puth(value); print("\n"); - } -} diff --git a/panda/board/stm32fx/llexti.h b/panda/board/stm32fx/llexti.h deleted file mode 100644 index 6de13ab7f..000000000 --- a/panda/board/stm32fx/llexti.h +++ /dev/null @@ -1,56 +0,0 @@ -void EXTI_IRQ_Handler(void); - -void exti_irq_init(void) { - SYSCFG->EXTICR[2] &= ~(SYSCFG_EXTICR3_EXTI8_Msk); - if (harness.status == HARNESS_STATUS_FLIPPED) { - // CAN2_RX - current_board->enable_can_transceiver(3U, false); - SYSCFG->EXTICR[2] |= (SYSCFG_EXTICR3_EXTI8_PA); - - // IRQ on falling edge for PC3 (SBU2, EXTI3) - SYSCFG->EXTICR[0] &= ~(SYSCFG_EXTICR1_EXTI3_Msk); - SYSCFG->EXTICR[0] |= (SYSCFG_EXTICR1_EXTI3_PC); - EXTI->IMR |= EXTI_IMR_MR3; - EXTI->RTSR &= ~EXTI_RTSR_TR3; // rising edge - EXTI->FTSR |= EXTI_FTSR_TR3; // falling edge - REGISTER_INTERRUPT(EXTI3_IRQn, EXTI_IRQ_Handler, 100U, FAULT_INTERRUPT_RATE_EXTI) - NVIC_EnableIRQ(EXTI3_IRQn); - } else { - // CAN0_RX - current_board->enable_can_transceiver(1U, false); - SYSCFG->EXTICR[2] |= (SYSCFG_EXTICR3_EXTI8_PB); - - // IRQ on falling edge for PC0 (SBU1, EXTI0) - SYSCFG->EXTICR[0] &= ~(SYSCFG_EXTICR1_EXTI0_Msk); - SYSCFG->EXTICR[0] |= (SYSCFG_EXTICR1_EXTI0_PC); - EXTI->IMR |= EXTI_IMR_MR0; - EXTI->RTSR &= ~EXTI_RTSR_TR0; // rising edge - EXTI->FTSR |= EXTI_FTSR_TR0; // falling edge - REGISTER_INTERRUPT(EXTI0_IRQn, EXTI_IRQ_Handler, 100U, FAULT_INTERRUPT_RATE_EXTI) - NVIC_EnableIRQ(EXTI0_IRQn); - } - // CAN0 or CAN2 IRQ on falling edge (EXTI8) - EXTI->IMR |= EXTI_IMR_MR8; - EXTI->RTSR &= ~EXTI_RTSR_TR8; // rising edge - EXTI->FTSR |= EXTI_FTSR_TR8; // falling edge - REGISTER_INTERRUPT(EXTI9_5_IRQn, EXTI_IRQ_Handler, 100U, FAULT_INTERRUPT_RATE_EXTI) - NVIC_EnableIRQ(EXTI9_5_IRQn); -} - -bool check_exti_irq(void) { - return ((EXTI->PR & EXTI_PR_PR8) || (EXTI->PR & EXTI_PR_PR3) || (EXTI->PR & EXTI_PR_PR0)); -} - -void exti_irq_clear(void) { - // Clear pending bits - EXTI->PR |= EXTI_PR_PR8; - EXTI->PR |= EXTI_PR_PR0; - EXTI->PR |= EXTI_PR_PR3; - EXTI->PR |= EXTI_PR_PR22; - - // Disable all active EXTI IRQs - EXTI->IMR &= ~EXTI_IMR_MR8; - EXTI->IMR &= ~EXTI_IMR_MR0; - EXTI->IMR &= ~EXTI_IMR_MR3; - EXTI->IMR &= ~EXTI_IMR_MR22; -} diff --git a/panda/board/stm32fx/llfan.h b/panda/board/stm32fx/llfan.h deleted file mode 100644 index 9e3f0c654..000000000 --- a/panda/board/stm32fx/llfan.h +++ /dev/null @@ -1,23 +0,0 @@ -// TACH interrupt handler -void EXTI2_IRQ_Handler(void) { - volatile unsigned int pr = EXTI->PR & (1U << 2); - if ((pr & (1U << 2)) != 0U) { - fan_state.tach_counter++; - } - EXTI->PR = (1U << 2); -} - -void llfan_init(void) { - // 5000RPM * 4 tach edges / 60 seconds - REGISTER_INTERRUPT(EXTI2_IRQn, EXTI2_IRQ_Handler, 700U, FAULT_INTERRUPT_RATE_TACH) - - // Init PWM speed control - pwm_init(TIM3, 3); - - // Init TACH interrupt - register_set(&(SYSCFG->EXTICR[0]), SYSCFG_EXTICR1_EXTI2_PD, 0xF00U); - register_set_bits(&(EXTI->IMR), (1U << 2)); - register_set_bits(&(EXTI->RTSR), (1U << 2)); - register_set_bits(&(EXTI->FTSR), (1U << 2)); - NVIC_EnableIRQ(EXTI2_IRQn); -} diff --git a/panda/board/stm32fx/llflash.h b/panda/board/stm32fx/llflash.h deleted file mode 100644 index 52f628487..000000000 --- a/panda/board/stm32fx/llflash.h +++ /dev/null @@ -1,50 +0,0 @@ -bool flash_is_locked(void) { - return (FLASH->CR & FLASH_CR_LOCK); -} - -void flash_unlock(void) { - FLASH->KEYR = 0x45670123; - FLASH->KEYR = 0xCDEF89AB; -} - -void flash_lock(void) { - FLASH->CR |= FLASH_CR_LOCK; -} - -bool flash_erase_sector(uint16_t sector) { -#ifdef BOOTSTUB - // don't erase the bootloader(sector 0) - uint16_t min_sector = 1U; - uint16_t max_sector = 11U; -#else - uint16_t min_sector = LOGGING_FLASH_SECTOR_A; - uint16_t max_sector = LOGGING_FLASH_SECTOR_B; -#endif - - bool ret = false; - if ((sector >= min_sector) && (sector <= max_sector) && (!flash_is_locked())) { - FLASH->CR = (sector << 3) | FLASH_CR_SER; - FLASH->CR |= FLASH_CR_STRT; - while ((FLASH->SR & FLASH_SR_BSY) != 0U); - ret = true; - } - return ret; -} - -void flash_write_word(uint32_t *prog_ptr, uint32_t data) { - #ifndef BOOTSTUB - // don't write to any region besides the logging region - if ((prog_ptr >= (uint32_t *)LOGGING_FLASH_BASE_A) && (prog_ptr < (uint32_t *)(LOGGING_FLASH_BASE_B + LOGGING_FLASH_SECTOR_SIZE))) { - #endif - - uint32_t *pp = prog_ptr; - FLASH->CR = FLASH_CR_PSIZE_1 | FLASH_CR_PG; - *pp = data; - while ((FLASH->SR & FLASH_SR_BSY) != 0U); - - #ifndef BOOTSTUB - } - #endif -} - -void flush_write_buffer(void) { } diff --git a/panda/board/stm32fx/llrtc.h b/panda/board/stm32fx/llrtc.h deleted file mode 100644 index a9b61917e..000000000 --- a/panda/board/stm32fx/llrtc.h +++ /dev/null @@ -1,69 +0,0 @@ -void enable_bdomain_protection(void) { - register_clear_bits(&(PWR->CR), PWR_CR_DBP); -} - -void disable_bdomain_protection(void) { - register_set_bits(&(PWR->CR), PWR_CR_DBP); -} - -void rtc_init(void){ - uint32_t bdcr_opts = RCC_BDCR_RTCEN; - uint32_t bdcr_mask = (RCC_BDCR_RTCEN | RCC_BDCR_RTCSEL); - if (current_board->has_rtc_battery) { - bdcr_opts |= (RCC_BDCR_RTCSEL_0 | RCC_BDCR_LSEON); - bdcr_mask |= (RCC_BDCR_LSEMOD | RCC_BDCR_LSEBYP | RCC_BDCR_LSEON); - } else { - bdcr_opts |= RCC_BDCR_RTCSEL_1; - RCC->CSR |= RCC_CSR_LSION; - while((RCC->CSR & RCC_CSR_LSIRDY) == 0){} - } - - // Initialize RTC module and clock if not done already. - if((RCC->BDCR & bdcr_mask) != bdcr_opts){ - print("Initializing RTC\n"); - // Reset backup domain - register_set_bits(&(RCC->BDCR), RCC_BDCR_BDRST); - - // Disable write protection - disable_bdomain_protection(); - - // Clear backup domain reset - register_clear_bits(&(RCC->BDCR), RCC_BDCR_BDRST); - - // Set RTC options - register_set(&(RCC->BDCR), bdcr_opts, bdcr_mask); - - // Enable write protection - enable_bdomain_protection(); - } -} - -void rtc_wakeup_init(void) { - EXTI->IMR |= EXTI_IMR_MR22; - EXTI->RTSR |= EXTI_RTSR_TR22; // rising edge - EXTI->FTSR &= ~EXTI_FTSR_TR22; // falling edge - - NVIC_DisableIRQ(RTC_WKUP_IRQn); - - // Disable write protection - disable_bdomain_protection(); - RTC->WPR = 0xCA; - RTC->WPR = 0x53; - - RTC->CR &= ~RTC_CR_WUTE; - while((RTC->ISR & RTC_ISR_WUTWF) == 0){} - - RTC->CR &= ~RTC_CR_WUTIE; - RTC->ISR &= ~RTC_ISR_WUTF; - //PWR->CR |= PWR_CR_CWUF; - - RTC->WUTR = DEEPSLEEP_WAKEUP_DELAY; - // Wakeup timer interrupt enable, wakeup timer enable, select 1Hz rate - RTC->CR |= RTC_CR_WUTE | RTC_CR_WUTIE | RTC_CR_WUCKSEL_2; - - // Re-enable write protection - RTC->WPR = 0x00; - enable_bdomain_protection(); - - NVIC_EnableIRQ(RTC_WKUP_IRQn); -} diff --git a/panda/board/stm32fx/llspi.h b/panda/board/stm32fx/llspi.h deleted file mode 100644 index 31e419b6f..000000000 --- a/panda/board/stm32fx/llspi.h +++ /dev/null @@ -1,90 +0,0 @@ -void llspi_miso_dma(uint8_t *addr, int len) { - // disable DMA - DMA2_Stream3->CR &= ~DMA_SxCR_EN; - register_clear_bits(&(SPI1->CR2), SPI_CR2_TXDMAEN); - - // setup source and length - register_set(&(DMA2_Stream3->M0AR), (uint32_t)addr, 0xFFFFFFFFU); - DMA2_Stream3->NDTR = len; - - // enable DMA - register_set_bits(&(SPI1->CR2), SPI_CR2_TXDMAEN); - DMA2_Stream3->CR |= DMA_SxCR_EN; -} - -void llspi_mosi_dma(uint8_t *addr, int len) { - // disable DMA - register_clear_bits(&(SPI1->CR2), SPI_CR2_RXDMAEN); - DMA2_Stream2->CR &= ~DMA_SxCR_EN; - - // drain the bus - volatile uint8_t dat = SPI1->DR; - (void)dat; - - // setup destination and length - register_set(&(DMA2_Stream2->M0AR), (uint32_t)addr, 0xFFFFFFFFU); - DMA2_Stream2->NDTR = len; - - // enable DMA - DMA2_Stream2->CR |= DMA_SxCR_EN; - register_set_bits(&(SPI1->CR2), SPI_CR2_RXDMAEN); -} - -// SPI MOSI DMA FINISHED -void DMA2_Stream2_IRQ_Handler(void) { - // Clear interrupt flag - ENTER_CRITICAL(); - DMA2->LIFCR = DMA_LIFCR_CTCIF2; - - spi_rx_done(); - - EXIT_CRITICAL(); -} - -// SPI MISO DMA FINISHED -void DMA2_Stream3_IRQ_Handler(void) { - // Clear interrupt flag - DMA2->LIFCR = DMA_LIFCR_CTCIF3; - - // Wait until the transaction is actually finished and clear the DR - // Timeout to prevent hang when the master clock stops. - bool timed_out = false; - uint32_t start_time = microsecond_timer_get(); - while (!(SPI1->SR & SPI_SR_TXE)) { - if (get_ts_elapsed(microsecond_timer_get(), start_time) > SPI_TIMEOUT_US) { - timed_out = true; - break; - } - } - volatile uint8_t dat = SPI1->DR; - (void)dat; - SPI1->DR = 0U; - - if (timed_out) { - print("SPI: TX timeout\n"); - } - - spi_tx_done(timed_out); -} - -// ***************************** SPI init ***************************** -void llspi_init(void) { - REGISTER_INTERRUPT(DMA2_Stream2_IRQn, DMA2_Stream2_IRQ_Handler, SPI_IRQ_RATE, FAULT_INTERRUPT_RATE_SPI_DMA) - REGISTER_INTERRUPT(DMA2_Stream3_IRQn, DMA2_Stream3_IRQ_Handler, SPI_IRQ_RATE, FAULT_INTERRUPT_RATE_SPI_DMA) - - // Setup MOSI DMA - register_set(&(DMA2_Stream2->CR), (DMA_SxCR_CHSEL_1 | DMA_SxCR_CHSEL_0 | DMA_SxCR_MINC | DMA_SxCR_TCIE), 0x1E077EFEU); - register_set(&(DMA2_Stream2->PAR), (uint32_t)&(SPI1->DR), 0xFFFFFFFFU); - - // Setup MISO DMA - register_set(&(DMA2_Stream3->CR), (DMA_SxCR_CHSEL_1 | DMA_SxCR_CHSEL_0 | DMA_SxCR_MINC | DMA_SxCR_DIR_0 | DMA_SxCR_TCIE), 0x1E077EFEU); - register_set(&(DMA2_Stream3->PAR), (uint32_t)&(SPI1->DR), 0xFFFFFFFFU); - - // Enable SPI and the error interrupts - // TODO: verify clock phase and polarity - register_set(&(SPI1->CR1), SPI_CR1_SPE, 0xFFFFU); - register_set(&(SPI1->CR2), 0U, 0xF7U); - - NVIC_EnableIRQ(DMA2_Stream2_IRQn); - NVIC_EnableIRQ(DMA2_Stream3_IRQn); -} diff --git a/panda/board/stm32fx/lluart.h b/panda/board/stm32fx/lluart.h deleted file mode 100644 index aed99a77f..000000000 --- a/panda/board/stm32fx/lluart.h +++ /dev/null @@ -1,127 +0,0 @@ -// ***************************** Interrupt handlers ***************************** - -void uart_tx_ring(uart_ring *q){ - ENTER_CRITICAL(); - // Send out next byte of TX buffer - if (q->w_ptr_tx != q->r_ptr_tx) { - // Only send if transmit register is empty (aka last byte has been sent) - if ((q->uart->SR & USART_SR_TXE) != 0) { - q->uart->DR = q->elems_tx[q->r_ptr_tx]; // This clears TXE - q->r_ptr_tx = (q->r_ptr_tx + 1U) % q->tx_fifo_size; - } - - // Enable TXE interrupt if there is still data to be sent - if(q->r_ptr_tx != q->w_ptr_tx){ - q->uart->CR1 |= USART_CR1_TXEIE; - } else { - q->uart->CR1 &= ~USART_CR1_TXEIE; - } - } - EXIT_CRITICAL(); -} - -void uart_rx_ring(uart_ring *q){ - ENTER_CRITICAL(); - - // Read out RX buffer - uint8_t c = q->uart->DR; // This read after reading SR clears a bunch of interrupts - - uint16_t next_w_ptr = (q->w_ptr_rx + 1U) % q->rx_fifo_size; - - if ((next_w_ptr == q->r_ptr_rx) && q->overwrite) { - // overwrite mode: drop oldest byte - q->r_ptr_rx = (q->r_ptr_rx + 1U) % q->rx_fifo_size; - } - - // Do not overwrite buffer data - if (next_w_ptr != q->r_ptr_rx) { - q->elems_rx[q->w_ptr_rx] = c; - q->w_ptr_rx = next_w_ptr; - if (q->callback != NULL) { - q->callback(q); - } - } - - EXIT_CRITICAL(); -} - -void uart_send_break(uart_ring *u) { - while ((u->uart->CR1 & USART_CR1_SBK) != 0); - u->uart->CR1 |= USART_CR1_SBK; -} - -// This read after reading SR clears all error interrupts. We don't want compiler warnings, nor optimizations -#define UART_READ_DR(uart) volatile uint8_t t = (uart)->DR; UNUSED(t); - -void uart_interrupt_handler(uart_ring *q) { - ENTER_CRITICAL(); - - // Read UART status. This is also the first step necessary in clearing most interrupts - uint32_t status = q->uart->SR; - - // If RXNE is set, perform a read. This clears RXNE, ORE, IDLE, NF and FE - if((status & USART_SR_RXNE) != 0U){ - uart_rx_ring(q); - } - - // Detect errors and clear them - uint32_t err = (status & USART_SR_ORE) | (status & USART_SR_NE) | (status & USART_SR_FE) | (status & USART_SR_PE); - if(err != 0U){ - #ifdef DEBUG_UART - print("Encountered UART error: "); puth(err); print("\n"); - #endif - UART_READ_DR(q->uart) - } - // Send if necessary - uart_tx_ring(q); - - EXIT_CRITICAL(); -} - -void USART2_IRQ_Handler(void) { uart_interrupt_handler(&uart_ring_debug); } -void USART3_IRQ_Handler(void) { uart_interrupt_handler(&uart_ring_lin2); } -void UART5_IRQ_Handler(void) { uart_interrupt_handler(&uart_ring_lin1); } - -// ***************************** Hardware setup ***************************** - -#define __DIV(_PCLK_, _BAUD_) (((_PCLK_) * 25U) / (4U * (_BAUD_))) -#define __DIVMANT(_PCLK_, _BAUD_) (__DIV((_PCLK_), (_BAUD_)) / 100U) -#define __DIVFRAQ(_PCLK_, _BAUD_) ((((__DIV((_PCLK_), (_BAUD_)) - (__DIVMANT((_PCLK_), (_BAUD_)) * 100U)) * 16U) + 50U) / 100U) -#define __USART_BRR(_PCLK_, _BAUD_) ((__DIVMANT((_PCLK_), (_BAUD_)) << 4) | (__DIVFRAQ((_PCLK_), (_BAUD_)) & 0x0FU)) - -void uart_set_baud(USART_TypeDef *u, unsigned int baud) { - u->BRR = __USART_BRR(24000000U, baud); -} - -void uart_init(uart_ring *q, int baud) { - if(q->uart != NULL){ - // Register interrupts (max data rate: 115200 baud) - if (q->uart == USART2){ - REGISTER_INTERRUPT(USART2_IRQn, USART2_IRQ_Handler, 150000U, FAULT_INTERRUPT_RATE_UART_2) - } else if (q->uart == USART3){ - REGISTER_INTERRUPT(USART3_IRQn, USART3_IRQ_Handler, 150000U, FAULT_INTERRUPT_RATE_UART_3) - } else if (q->uart == UART5){ - REGISTER_INTERRUPT(UART5_IRQn, UART5_IRQ_Handler, 150000U, FAULT_INTERRUPT_RATE_UART_5) - } else { - // UART not used. Skip registering interrupts - } - - // Set baud and enable peripheral with TX and RX mode - uart_set_baud(q->uart, baud); - q->uart->CR1 = USART_CR1_UE | USART_CR1_TE | USART_CR1_RE; - if ((q->uart == USART2) || (q->uart == USART3) || (q->uart == UART5)) { - q->uart->CR1 |= USART_CR1_RXNEIE; - } - - // Enable UART interrupts - if (q->uart == USART2){ - NVIC_EnableIRQ(USART2_IRQn); - } else if (q->uart == USART3){ - NVIC_EnableIRQ(USART3_IRQn); - } else if (q->uart == UART5){ - NVIC_EnableIRQ(UART5_IRQn); - } else { - // UART not used. Skip enabling interrupts - } - } -} diff --git a/panda/board/stm32fx/llusb.h b/panda/board/stm32fx/llusb.h deleted file mode 100644 index ab34672aa..000000000 --- a/panda/board/stm32fx/llusb.h +++ /dev/null @@ -1,102 +0,0 @@ -typedef struct -{ - __IO uint32_t HPRT; -} -USB_OTG_HostPortTypeDef; - -USB_OTG_GlobalTypeDef *USBx = USB_OTG_FS; - -#define USBx_HOST ((USB_OTG_HostTypeDef *)((uint32_t)USBx + USB_OTG_HOST_BASE)) -#define USBx_HOST_PORT ((USB_OTG_HostPortTypeDef *)((uint32_t)USBx + USB_OTG_HOST_PORT_BASE)) -#define USBx_DEVICE ((USB_OTG_DeviceTypeDef *)((uint32_t)USBx + USB_OTG_DEVICE_BASE)) -#define USBx_INEP(i) ((USB_OTG_INEndpointTypeDef *)((uint32_t)USBx + USB_OTG_IN_ENDPOINT_BASE + ((i) * USB_OTG_EP_REG_SIZE))) -#define USBx_OUTEP(i) ((USB_OTG_OUTEndpointTypeDef *)((uint32_t)USBx + USB_OTG_OUT_ENDPOINT_BASE + ((i) * USB_OTG_EP_REG_SIZE))) -#define USBx_DFIFO(i) *(__IO uint32_t *)((uint32_t)USBx + USB_OTG_FIFO_BASE + ((i) * USB_OTG_FIFO_SIZE)) -#define USBx_PCGCCTL *(__IO uint32_t *)((uint32_t)USBx + USB_OTG_PCGCCTL_BASE) - -#define USBD_FS_TRDT_VALUE 5U -#define USB_OTG_SPEED_FULL 3 - - -void usb_irqhandler(void); - -void OTG_FS_IRQ_Handler(void) { - NVIC_DisableIRQ(OTG_FS_IRQn); - //__disable_irq(); - usb_irqhandler(); - //__enable_irq(); - NVIC_EnableIRQ(OTG_FS_IRQn); -} - -void usb_init(void) { - REGISTER_INTERRUPT(OTG_FS_IRQn, OTG_FS_IRQ_Handler, 1500000U, FAULT_INTERRUPT_RATE_USB) //TODO: Find out a better rate limit for USB. Now it's the 1.5MB/s rate - - // full speed PHY, do reset and remove power down - /*puth(USBx->GRSTCTL); - print(" resetting PHY\n");*/ - while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_AHBIDL) == 0); - //print("AHB idle\n"); - - // reset PHY here - USBx->GRSTCTL |= USB_OTG_GRSTCTL_CSRST; - while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_CSRST) == USB_OTG_GRSTCTL_CSRST); - //print("reset done\n"); - - // internal PHY, force device mode - USBx->GUSBCFG = USB_OTG_GUSBCFG_PHYSEL | USB_OTG_GUSBCFG_FDMOD; - - // slowest timings - USBx->GUSBCFG |= ((USBD_FS_TRDT_VALUE << 10) & USB_OTG_GUSBCFG_TRDT); - - // power up the PHY -#ifdef STM32F4 - USBx->GCCFG = USB_OTG_GCCFG_PWRDWN; - - //USBx->GCCFG |= USB_OTG_GCCFG_VBDEN | USB_OTG_GCCFG_SDEN |USB_OTG_GCCFG_PDEN | USB_OTG_GCCFG_DCDEN; - - /* B-peripheral session valid override enable*/ - USBx->GOTGCTL |= USB_OTG_GOTGCTL_BVALOVAL; - USBx->GOTGCTL |= USB_OTG_GOTGCTL_BVALOEN; -#else - USBx->GCCFG = USB_OTG_GCCFG_PWRDWN | USB_OTG_GCCFG_NOVBUSSENS; -#endif - - // be a device, slowest timings - //USBx->GUSBCFG = USB_OTG_GUSBCFG_FDMOD | USB_OTG_GUSBCFG_PHYSEL | USB_OTG_GUSBCFG_TRDT | USB_OTG_GUSBCFG_TOCAL; - //USBx->GUSBCFG |= (uint32_t)((USBD_FS_TRDT_VALUE << 10) & USB_OTG_GUSBCFG_TRDT); - //USBx->GUSBCFG = USB_OTG_GUSBCFG_PHYSEL | USB_OTG_GUSBCFG_TRDT | USB_OTG_GUSBCFG_TOCAL; - - // **** for debugging, doesn't seem to work **** - //USBx->GUSBCFG |= USB_OTG_GUSBCFG_CTXPKT; - - // reset PHY clock - USBx_PCGCCTL = 0; - - // enable the fancy OTG things - // DCFG_FRAME_INTERVAL_80 is 0 - //USBx->GUSBCFG |= USB_OTG_GUSBCFG_HNPCAP | USB_OTG_GUSBCFG_SRPCAP; - USBx_DEVICE->DCFG |= USB_OTG_SPEED_FULL | USB_OTG_DCFG_NZLSOHSK; - - //USBx_DEVICE->DCFG = USB_OTG_DCFG_NZLSOHSK | USB_OTG_DCFG_DSPD; - //USBx_DEVICE->DCFG = USB_OTG_DCFG_DSPD; - - // clear pending interrupts - USBx->GINTSTS = 0xBFFFFFFFU; - - // setup USB interrupts - // all interrupts except TXFIFO EMPTY - //USBx->GINTMSK = 0xFFFFFFFF & ~(USB_OTG_GINTMSK_NPTXFEM | USB_OTG_GINTMSK_PTXFEM | USB_OTG_GINTSTS_SOF | USB_OTG_GINTSTS_EOPF); - //USBx->GINTMSK = 0xFFFFFFFF & ~(USB_OTG_GINTMSK_NPTXFEM | USB_OTG_GINTMSK_PTXFEM); - USBx->GINTMSK = USB_OTG_GINTMSK_USBRST | USB_OTG_GINTMSK_ENUMDNEM | USB_OTG_GINTMSK_OTGINT | - USB_OTG_GINTMSK_RXFLVLM | USB_OTG_GINTMSK_GONAKEFFM | USB_OTG_GINTMSK_GINAKEFFM | - USB_OTG_GINTMSK_OEPINT | USB_OTG_GINTMSK_IEPINT | USB_OTG_GINTMSK_USBSUSPM | - USB_OTG_GINTMSK_CIDSCHGM | USB_OTG_GINTMSK_SRQIM | USB_OTG_GINTMSK_MMISM | USB_OTG_GINTMSK_EOPFM; - - USBx->GAHBCFG = USB_OTG_GAHBCFG_GINT; - - // DCTL startup value is 2 on new chip, 0 on old chip - USBx_DEVICE->DCTL = 0; - - // enable the IRQ - NVIC_EnableIRQ(OTG_FS_IRQn); -} diff --git a/panda/board/stm32fx/peripherals.h b/panda/board/stm32fx/peripherals.h deleted file mode 100644 index 33a1f6ffe..000000000 --- a/panda/board/stm32fx/peripherals.h +++ /dev/null @@ -1,93 +0,0 @@ -void gpio_usb_init(void) { - // A11,A12: USB - set_gpio_alternate(GPIOA, 11, GPIO_AF10_OTG_FS); - set_gpio_alternate(GPIOA, 12, GPIO_AF10_OTG_FS); - GPIOA->OSPEEDR = GPIO_OSPEEDER_OSPEEDR11 | GPIO_OSPEEDER_OSPEEDR12; -} - -void gpio_spi_init(void) { - // A4-A7: SPI - set_gpio_alternate(GPIOA, 4, GPIO_AF5_SPI1); - set_gpio_alternate(GPIOA, 5, GPIO_AF5_SPI1); - set_gpio_alternate(GPIOA, 6, GPIO_AF5_SPI1); - set_gpio_alternate(GPIOA, 7, GPIO_AF5_SPI1); - register_set_bits(&(GPIOA->OSPEEDR), GPIO_OSPEEDER_OSPEEDR4 | GPIO_OSPEEDER_OSPEEDR5 | GPIO_OSPEEDER_OSPEEDR6 | GPIO_OSPEEDER_OSPEEDR7); -} - -void gpio_usart2_init(void) { - // A2,A3: USART 2 for debugging - set_gpio_alternate(GPIOA, 2, GPIO_AF7_USART2); - set_gpio_alternate(GPIOA, 3, GPIO_AF7_USART2); -} - -// Common GPIO initialization -void common_init_gpio(void) { - // TODO: Is this block actually doing something??? - // pull low to hold ESP in reset?? - // enable OTG out tied to ground - GPIOA->ODR = 0; - GPIOB->ODR = 0; - GPIOA->PUPDR = 0; - GPIOB->AFR[0] = 0; - GPIOB->AFR[1] = 0; - - // C2: Voltage sense line - set_gpio_mode(GPIOC, 2, MODE_ANALOG); - - gpio_usb_init(); - - // B8,B9: CAN 1 - #ifdef STM32F4 - set_gpio_alternate(GPIOB, 8, GPIO_AF8_CAN1); - set_gpio_alternate(GPIOB, 9, GPIO_AF8_CAN1); - #else - set_gpio_alternate(GPIOB, 8, GPIO_AF9_CAN1); - set_gpio_alternate(GPIOB, 9, GPIO_AF9_CAN1); - #endif -} - -void flasher_peripherals_init(void) { - RCC->AHB1ENR |= RCC_AHB1ENR_DMA2EN; - RCC->APB2ENR |= RCC_APB2ENR_SPI1EN; - RCC->AHB2ENR |= RCC_AHB2ENR_OTGFSEN; - RCC->APB1ENR |= RCC_APB1ENR_USART2EN; -} - -// Peripheral initialization -void peripherals_init(void) { - // enable GPIOB, UART2, CAN, USB clock - RCC->AHB1ENR |= RCC_AHB1ENR_GPIOAEN; - RCC->AHB1ENR |= RCC_AHB1ENR_GPIOBEN; - RCC->AHB1ENR |= RCC_AHB1ENR_GPIOCEN; - RCC->AHB1ENR |= RCC_AHB1ENR_GPIODEN; - - RCC->AHB1ENR |= RCC_AHB1ENR_DMA2EN; - RCC->APB1ENR |= RCC_APB1ENR_USART2EN; - RCC->APB1ENR |= RCC_APB1ENR_USART3EN; - #ifndef PEDAL - RCC->APB1ENR |= RCC_APB1ENR_UART5EN; - #endif - RCC->APB1ENR |= RCC_APB1ENR_CAN1EN; - RCC->APB1ENR |= RCC_APB1ENR_CAN2EN; - #ifdef CAN3 - RCC->APB1ENR |= RCC_APB1ENR_CAN3EN; - #endif - RCC->APB1ENR |= RCC_APB1ENR_DACEN; - RCC->APB1ENR |= RCC_APB1ENR_TIM2EN; // main counter - RCC->APB1ENR |= RCC_APB1ENR_TIM3EN; // pedal and fan PWM - RCC->APB1ENR |= RCC_APB1ENR_TIM4EN; // IR PWM - RCC->APB1ENR |= RCC_APB1ENR_TIM5EN; // k-line init - RCC->APB1ENR |= RCC_APB1ENR_TIM6EN; // interrupt timer - RCC->APB1ENR |= RCC_APB1ENR_TIM12EN; // gmlan_alt - RCC->APB1ENR |= RCC_APB1ENR_PWREN; // for RTC config - RCC->AHB2ENR |= RCC_AHB2ENR_OTGFSEN; - RCC->APB2ENR |= RCC_APB2ENR_TIM1EN; // clock source timer - RCC->APB2ENR |= RCC_APB2ENR_ADC1EN; - RCC->APB2ENR |= RCC_APB2ENR_SPI1EN; - RCC->APB2ENR |= RCC_APB2ENR_SYSCFGEN; - RCC->APB2ENR |= RCC_APB2ENR_TIM9EN; // slow loop -} - -void enable_interrupt_timer(void) { - register_set_bits(&(RCC->APB1ENR), RCC_APB1ENR_TIM6EN); // Enable interrupt timer peripheral -} diff --git a/panda/board/stm32fx/startup_stm32f205xx.s b/panda/board/stm32fx/startup_stm32f205xx.s deleted file mode 100644 index 7554efc4c..000000000 --- a/panda/board/stm32fx/startup_stm32f205xx.s +++ /dev/null @@ -1,511 +0,0 @@ -/** - ****************************************************************************** - * @file startup_stm32f205xx.s - * @author MCD Application Team - * @version V2.1.2 - * @date 29-June-2016 - * @brief STM32F205xx Devices vector table for Atollic TrueSTUDIO toolchain. - * This module performs: - * - Set the initial SP - * - Set the initial PC == Reset_Handler, - * - Set the vector table entries with the exceptions ISR address - * - Branches to main in the C library (which eventually - * calls main()). - * After Reset the Cortex-M3 processor is in Thread mode, - * priority is Privileged, and the Stack is set to Main. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT 2016 STMicroelectronics

- * - * 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. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * 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 HOLDER 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. - * - ****************************************************************************** - */ - - .syntax unified - .cpu cortex-m3 - .thumb - -.global g_pfnVectors -.global Default_Handler - -/* start address for the initialization values of the .data section. -defined in linker script */ -.word _sidata -/* start address for the .data section. defined in linker script */ -.word _sdata -/* end address for the .data section. defined in linker script */ -.word _edata -/* start address for the .bss section. defined in linker script */ -.word _sbss -/* end address for the .bss section. defined in linker script */ -.word _ebss -/* stack used for SystemInit_ExtMemCtl; always internal RAM used */ - -/** - * @brief This is the code that gets called when the processor first - * starts execution following a reset event. Only the absolutely - * necessary set is performed, after which the application - * supplied main() routine is called. - * @param None - * @retval : None -*/ - - .section .text.Reset_Handler - .weak Reset_Handler - .type Reset_Handler, %function -Reset_Handler: - ldr sp, =_estack /* set stack pointer */ - bl __initialize_hardware_early - -/* Copy the data segment initializers from flash to SRAM */ - movs r1, #0 - b LoopCopyDataInit - -CopyDataInit: - ldr r3, =_sidata - ldr r3, [r3, r1] - str r3, [r0, r1] - adds r1, r1, #4 - -LoopCopyDataInit: - ldr r0, =_sdata - ldr r3, =_edata - adds r2, r0, r1 - cmp r2, r3 - bcc CopyDataInit - ldr r2, =_sbss - b LoopFillZerobss -/* Zero fill the bss segment. */ -FillZerobss: - movs r3, #0 - str r3, [r2], #4 - -LoopFillZerobss: - ldr r3, = _ebss - cmp r2, r3 - bcc FillZerobss - -/* Call the clock system initialization function.*/ - /*bl SystemInit */ -/* Call static constructors */ - /*bl __libc_init_array*/ -/* Call the application's entry point.*/ - bl main - bx lr -.size Reset_Handler, .-Reset_Handler - -/** - * @brief This is the code that gets called when the processor receives an - * unexpected interrupt. This simply enters an infinite loop, preserving - * the system state for examination by a debugger. - * @param None - * @retval None -*/ - .section .text.Default_Handler,"ax",%progbits -Default_Handler: -Infinite_Loop: - b Infinite_Loop - .size Default_Handler, .-Default_Handler -/****************************************************************************** -* -* The minimal vector table for a Cortex M3. Note that the proper constructs -* must be placed on this to ensure that it ends up at physical address -* 0x0000.0000. -* -*******************************************************************************/ - .section .isr_vector,"a",%progbits - .type g_pfnVectors, %object - .size g_pfnVectors, .-g_pfnVectors - - - -g_pfnVectors: - .word _estack - .word Reset_Handler - - .word NMI_Handler - .word HardFault_Handler - .word MemManage_Handler - .word BusFault_Handler - .word UsageFault_Handler - .word 0 - .word 0 - .word 0 - .word 0 - .word SVC_Handler - .word DebugMon_Handler - .word 0 - .word PendSV_Handler - .word SysTick_Handler - - /* External Interrupts */ - .word WWDG_IRQHandler /* Window WatchDog */ - .word PVD_IRQHandler /* PVD through EXTI Line detection */ - .word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXTI line */ - .word RTC_WKUP_IRQHandler /* RTC Wakeup through the EXTI line */ - .word FLASH_IRQHandler /* FLASH */ - .word RCC_IRQHandler /* RCC */ - .word EXTI0_IRQHandler /* EXTI Line0 */ - .word EXTI1_IRQHandler /* EXTI Line1 */ - .word EXTI2_IRQHandler /* EXTI Line2 */ - .word EXTI3_IRQHandler /* EXTI Line3 */ - .word EXTI4_IRQHandler /* EXTI Line4 */ - .word DMA1_Stream0_IRQHandler /* DMA1 Stream 0 */ - .word DMA1_Stream1_IRQHandler /* DMA1 Stream 1 */ - .word DMA1_Stream2_IRQHandler /* DMA1 Stream 2 */ - .word DMA1_Stream3_IRQHandler /* DMA1 Stream 3 */ - .word DMA1_Stream4_IRQHandler /* DMA1 Stream 4 */ - .word DMA1_Stream5_IRQHandler /* DMA1 Stream 5 */ - .word DMA1_Stream6_IRQHandler /* DMA1 Stream 6 */ - .word ADC_IRQHandler /* ADC1, ADC2 and ADC3s */ - .word CAN1_TX_IRQHandler /* CAN1 TX */ - .word CAN1_RX0_IRQHandler /* CAN1 RX0 */ - .word CAN1_RX1_IRQHandler /* CAN1 RX1 */ - .word CAN1_SCE_IRQHandler /* CAN1 SCE */ - .word EXTI9_5_IRQHandler /* External Line[9:5]s */ - .word TIM1_BRK_TIM9_IRQHandler /* TIM1 Break and TIM9 */ - .word TIM1_UP_TIM10_IRQHandler /* TIM1 Update and TIM10 */ - .word TIM1_TRG_COM_TIM11_IRQHandler /* TIM1 Trigger and Commutation and TIM11 */ - .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */ - .word TIM2_IRQHandler /* TIM2 */ - .word TIM3_IRQHandler /* TIM3 */ - .word TIM4_IRQHandler /* TIM4 */ - .word I2C1_EV_IRQHandler /* I2C1 Event */ - .word I2C1_ER_IRQHandler /* I2C1 Error */ - .word I2C2_EV_IRQHandler /* I2C2 Event */ - .word I2C2_ER_IRQHandler /* I2C2 Error */ - .word SPI1_IRQHandler /* SPI1 */ - .word SPI2_IRQHandler /* SPI2 */ - .word USART1_IRQHandler /* USART1 */ - .word USART2_IRQHandler /* USART2 */ - .word USART3_IRQHandler /* USART3 */ - .word EXTI15_10_IRQHandler /* External Line[15:10]s */ - .word RTC_Alarm_IRQHandler /* RTC Alarm (A and B) through EXTI Line */ - .word OTG_FS_WKUP_IRQHandler /* USB OTG FS Wakeup through EXTI line */ - .word TIM8_BRK_TIM12_IRQHandler /* TIM8 Break and TIM12 */ - .word TIM8_UP_TIM13_IRQHandler /* TIM8 Update and TIM13 */ - .word TIM8_TRG_COM_TIM14_IRQHandler /* TIM8 Trigger and Commutation and TIM14 */ - .word TIM8_CC_IRQHandler /* TIM8 Capture Compare */ - .word DMA1_Stream7_IRQHandler /* DMA1 Stream7 */ - .word FSMC_IRQHandler /* FSMC */ - .word SDIO_IRQHandler /* SDIO */ - .word TIM5_IRQHandler /* TIM5 */ - .word SPI3_IRQHandler /* SPI3 */ - .word UART4_IRQHandler /* UART4 */ - .word UART5_IRQHandler /* UART5 */ - .word TIM6_DAC_IRQHandler /* TIM6 and DAC1&2 underrun errors */ - .word TIM7_IRQHandler /* TIM7 */ - .word DMA2_Stream0_IRQHandler /* DMA2 Stream 0 */ - .word DMA2_Stream1_IRQHandler /* DMA2 Stream 1 */ - .word DMA2_Stream2_IRQHandler /* DMA2 Stream 2 */ - .word DMA2_Stream3_IRQHandler /* DMA2 Stream 3 */ - .word DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word CAN2_TX_IRQHandler /* CAN2 TX */ - .word CAN2_RX0_IRQHandler /* CAN2 RX0 */ - .word CAN2_RX1_IRQHandler /* CAN2 RX1 */ - .word CAN2_SCE_IRQHandler /* CAN2 SCE */ - .word OTG_FS_IRQHandler /* USB OTG FS */ - .word DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */ - .word DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */ - .word DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */ - .word USART6_IRQHandler /* USART6 */ - .word I2C3_EV_IRQHandler /* I2C3 event */ - .word I2C3_ER_IRQHandler /* I2C3 error */ - .word OTG_HS_EP1_OUT_IRQHandler /* USB OTG HS End Point 1 Out */ - .word OTG_HS_EP1_IN_IRQHandler /* USB OTG HS End Point 1 In */ - .word OTG_HS_WKUP_IRQHandler /* USB OTG HS Wakeup through EXTI */ - .word OTG_HS_IRQHandler /* USB OTG HS */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word HASH_RNG_IRQHandler /* Hash and Rng */ - -/******************************************************************************* -* -* Provide weak aliases for each Exception handler to the Default_Handler. -* As they are weak aliases, any function with the same name will override -* this definition. -* -*******************************************************************************/ - .weak NMI_Handler - .thumb_set NMI_Handler,Default_Handler - - .weak HardFault_Handler - .thumb_set HardFault_Handler,Default_Handler - - .weak MemManage_Handler - .thumb_set MemManage_Handler,Default_Handler - - .weak BusFault_Handler - .thumb_set BusFault_Handler,Default_Handler - - .weak UsageFault_Handler - .thumb_set UsageFault_Handler,Default_Handler - - .weak SVC_Handler - .thumb_set SVC_Handler,Default_Handler - - .weak DebugMon_Handler - .thumb_set DebugMon_Handler,Default_Handler - - .weak PendSV_Handler - .thumb_set PendSV_Handler,Default_Handler - - .weak SysTick_Handler - .thumb_set SysTick_Handler,Default_Handler - - .weak WWDG_IRQHandler - .thumb_set WWDG_IRQHandler,Default_Handler - - .weak PVD_IRQHandler - .thumb_set PVD_IRQHandler,Default_Handler - - .weak TAMP_STAMP_IRQHandler - .thumb_set TAMP_STAMP_IRQHandler,Default_Handler - - .weak RTC_WKUP_IRQHandler - .thumb_set RTC_WKUP_IRQHandler,Default_Handler - - .weak FLASH_IRQHandler - .thumb_set FLASH_IRQHandler,Default_Handler - - .weak RCC_IRQHandler - .thumb_set RCC_IRQHandler,Default_Handler - - .weak EXTI0_IRQHandler - .thumb_set EXTI0_IRQHandler,Default_Handler - - .weak EXTI1_IRQHandler - .thumb_set EXTI1_IRQHandler,Default_Handler - - .weak EXTI2_IRQHandler - .thumb_set EXTI2_IRQHandler,Default_Handler - - .weak EXTI3_IRQHandler - .thumb_set EXTI3_IRQHandler,Default_Handler - - .weak EXTI4_IRQHandler - .thumb_set EXTI4_IRQHandler,Default_Handler - - .weak DMA1_Stream0_IRQHandler - .thumb_set DMA1_Stream0_IRQHandler,Default_Handler - - .weak DMA1_Stream1_IRQHandler - .thumb_set DMA1_Stream1_IRQHandler,Default_Handler - - .weak DMA1_Stream2_IRQHandler - .thumb_set DMA1_Stream2_IRQHandler,Default_Handler - - .weak DMA1_Stream3_IRQHandler - .thumb_set DMA1_Stream3_IRQHandler,Default_Handler - - .weak DMA1_Stream4_IRQHandler - .thumb_set DMA1_Stream4_IRQHandler,Default_Handler - - .weak DMA1_Stream5_IRQHandler - .thumb_set DMA1_Stream5_IRQHandler,Default_Handler - - .weak DMA1_Stream6_IRQHandler - .thumb_set DMA1_Stream6_IRQHandler,Default_Handler - - .weak ADC_IRQHandler - .thumb_set ADC_IRQHandler,Default_Handler - - .weak CAN1_TX_IRQHandler - .thumb_set CAN1_TX_IRQHandler,Default_Handler - - .weak CAN1_RX0_IRQHandler - .thumb_set CAN1_RX0_IRQHandler,Default_Handler - - .weak CAN1_RX1_IRQHandler - .thumb_set CAN1_RX1_IRQHandler,Default_Handler - - .weak CAN1_SCE_IRQHandler - .thumb_set CAN1_SCE_IRQHandler,Default_Handler - - .weak EXTI9_5_IRQHandler - .thumb_set EXTI9_5_IRQHandler,Default_Handler - - .weak TIM1_BRK_TIM9_IRQHandler - .thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler - - .weak TIM1_UP_TIM10_IRQHandler - .thumb_set TIM1_UP_TIM10_IRQHandler,Default_Handler - - .weak TIM1_TRG_COM_TIM11_IRQHandler - .thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler - - .weak TIM1_CC_IRQHandler - .thumb_set TIM1_CC_IRQHandler,Default_Handler - - .weak TIM2_IRQHandler - .thumb_set TIM2_IRQHandler,Default_Handler - - .weak TIM3_IRQHandler - .thumb_set TIM3_IRQHandler,Default_Handler - - .weak TIM4_IRQHandler - .thumb_set TIM4_IRQHandler,Default_Handler - - .weak I2C1_EV_IRQHandler - .thumb_set I2C1_EV_IRQHandler,Default_Handler - - .weak I2C1_ER_IRQHandler - .thumb_set I2C1_ER_IRQHandler,Default_Handler - - .weak I2C2_EV_IRQHandler - .thumb_set I2C2_EV_IRQHandler,Default_Handler - - .weak I2C2_ER_IRQHandler - .thumb_set I2C2_ER_IRQHandler,Default_Handler - - .weak SPI1_IRQHandler - .thumb_set SPI1_IRQHandler,Default_Handler - - .weak SPI2_IRQHandler - .thumb_set SPI2_IRQHandler,Default_Handler - - .weak USART1_IRQHandler - .thumb_set USART1_IRQHandler,Default_Handler - - .weak USART2_IRQHandler - .thumb_set USART2_IRQHandler,Default_Handler - - .weak USART3_IRQHandler - .thumb_set USART3_IRQHandler,Default_Handler - - .weak EXTI15_10_IRQHandler - .thumb_set EXTI15_10_IRQHandler,Default_Handler - - .weak RTC_Alarm_IRQHandler - .thumb_set RTC_Alarm_IRQHandler,Default_Handler - - .weak OTG_FS_WKUP_IRQHandler - .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler - - .weak TIM8_BRK_TIM12_IRQHandler - .thumb_set TIM8_BRK_TIM12_IRQHandler,Default_Handler - - .weak TIM8_UP_TIM13_IRQHandler - .thumb_set TIM8_UP_TIM13_IRQHandler,Default_Handler - - .weak TIM8_TRG_COM_TIM14_IRQHandler - .thumb_set TIM8_TRG_COM_TIM14_IRQHandler,Default_Handler - - .weak TIM8_CC_IRQHandler - .thumb_set TIM8_CC_IRQHandler,Default_Handler - - .weak DMA1_Stream7_IRQHandler - .thumb_set DMA1_Stream7_IRQHandler,Default_Handler - - .weak FSMC_IRQHandler - .thumb_set FSMC_IRQHandler,Default_Handler - - .weak SDIO_IRQHandler - .thumb_set SDIO_IRQHandler,Default_Handler - - .weak TIM5_IRQHandler - .thumb_set TIM5_IRQHandler,Default_Handler - - .weak SPI3_IRQHandler - .thumb_set SPI3_IRQHandler,Default_Handler - - .weak UART4_IRQHandler - .thumb_set UART4_IRQHandler,Default_Handler - - .weak UART5_IRQHandler - .thumb_set UART5_IRQHandler,Default_Handler - - .weak TIM6_DAC_IRQHandler - .thumb_set TIM6_DAC_IRQHandler,Default_Handler - - .weak TIM7_IRQHandler - .thumb_set TIM7_IRQHandler,Default_Handler - - .weak DMA2_Stream0_IRQHandler - .thumb_set DMA2_Stream0_IRQHandler,Default_Handler - - .weak DMA2_Stream1_IRQHandler - .thumb_set DMA2_Stream1_IRQHandler,Default_Handler - - .weak DMA2_Stream2_IRQHandler - .thumb_set DMA2_Stream2_IRQHandler,Default_Handler - - .weak DMA2_Stream3_IRQHandler - .thumb_set DMA2_Stream3_IRQHandler,Default_Handler - - .weak DMA2_Stream4_IRQHandler - .thumb_set DMA2_Stream4_IRQHandler,Default_Handler - - .weak CAN2_TX_IRQHandler - .thumb_set CAN2_TX_IRQHandler,Default_Handler - - .weak CAN2_RX0_IRQHandler - .thumb_set CAN2_RX0_IRQHandler,Default_Handler - - .weak CAN2_RX1_IRQHandler - .thumb_set CAN2_RX1_IRQHandler,Default_Handler - - .weak CAN2_SCE_IRQHandler - .thumb_set CAN2_SCE_IRQHandler,Default_Handler - - .weak OTG_FS_IRQHandler - .thumb_set OTG_FS_IRQHandler,Default_Handler - - .weak DMA2_Stream5_IRQHandler - .thumb_set DMA2_Stream5_IRQHandler,Default_Handler - - .weak DMA2_Stream6_IRQHandler - .thumb_set DMA2_Stream6_IRQHandler,Default_Handler - - .weak DMA2_Stream7_IRQHandler - .thumb_set DMA2_Stream7_IRQHandler,Default_Handler - - .weak USART6_IRQHandler - .thumb_set USART6_IRQHandler,Default_Handler - - .weak I2C3_EV_IRQHandler - .thumb_set I2C3_EV_IRQHandler,Default_Handler - - .weak I2C3_ER_IRQHandler - .thumb_set I2C3_ER_IRQHandler,Default_Handler - - .weak OTG_HS_EP1_OUT_IRQHandler - .thumb_set OTG_HS_EP1_OUT_IRQHandler,Default_Handler - - .weak OTG_HS_EP1_IN_IRQHandler - .thumb_set OTG_HS_EP1_IN_IRQHandler,Default_Handler - - .weak OTG_HS_WKUP_IRQHandler - .thumb_set OTG_HS_WKUP_IRQHandler,Default_Handler - - .weak OTG_HS_IRQHandler - .thumb_set OTG_HS_IRQHandler,Default_Handler - - .weak HASH_RNG_IRQHandler - .thumb_set HASH_RNG_IRQHandler,Default_Handler - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/panda/board/stm32fx/startup_stm32f413xx.s b/panda/board/stm32fx/startup_stm32f413xx.s deleted file mode 100644 index 6e6fb5ffa..000000000 --- a/panda/board/stm32fx/startup_stm32f413xx.s +++ /dev/null @@ -1,583 +0,0 @@ -/** - ****************************************************************************** - * @file startup_stm32f413xx.s - * @author MCD Application Team - * @version V2.6.0 - * @date 04-November-2016 - * @brief STM32F413xx Devices vector table for GCC based toolchains. - * This module performs: - * - Set the initial SP - * - Set the initial PC == Reset_Handler, - * - Set the vector table entries with the exceptions ISR address - * - Branches to main in the C library (which eventually - * calls main()). - * After Reset the Cortex-M4 processor is in Thread mode, - * priority is Privileged, and the Stack is set to Main. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT 2016 STMicroelectronics

- * - * 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. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * 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 HOLDER 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. - * - ****************************************************************************** - */ - - .syntax unified - .cpu cortex-m4 - .fpu softvfp - .thumb - -.global g_pfnVectors -.global Default_Handler - -/* start address for the initialization values of the .data section. -defined in linker script */ -.word _sidata -/* start address for the .data section. defined in linker script */ -.word _sdata -/* end address for the .data section. defined in linker script */ -.word _edata -/* start address for the .bss section. defined in linker script */ -.word _sbss -/* end address for the .bss section. defined in linker script */ -.word _ebss -/* stack used for SystemInit_ExtMemCtl; always internal RAM used */ - -/** - * @brief This is the code that gets called when the processor first - * starts execution following a reset event. Only the absolutely - * necessary set is performed, after which the application - * supplied main() routine is called. - * @param None - * @retval : None -*/ - - .section .text.Reset_Handler - .weak Reset_Handler - .type Reset_Handler, %function -Reset_Handler: - ldr sp, =_estack /* set stack pointer */ - bl __initialize_hardware_early - -/* Copy the data segment initializers from flash to SRAM */ - movs r1, #0 - b LoopCopyDataInit - -CopyDataInit: - ldr r3, =_sidata - ldr r3, [r3, r1] - str r3, [r0, r1] - adds r1, r1, #4 - -LoopCopyDataInit: - ldr r0, =_sdata - ldr r3, =_edata - adds r2, r0, r1 - cmp r2, r3 - bcc CopyDataInit - ldr r2, =_sbss - b LoopFillZerobss -/* Zero fill the bss segment. */ -FillZerobss: - movs r3, #0 - str r3, [r2], #4 - -LoopFillZerobss: - ldr r3, = _ebss - cmp r2, r3 - bcc FillZerobss - -/* Call the clock system intitialization function.*/ - /* bl SystemInit */ -/* Call static constructors */ - /* bl __libc_init_array */ -/* Call the application's entry point.*/ - bl main - bx lr -.size Reset_Handler, .-Reset_Handler - -/** - * @brief This is the code that gets called when the processor receives an - * unexpected interrupt. This simply enters an infinite loop, preserving - * the system state for examination by a debugger. - * @param None - * @retval None -*/ - .section .text.Default_Handler,"ax",%progbits -Default_Handler: -Infinite_Loop: - b Infinite_Loop - .size Default_Handler, .-Default_Handler -/****************************************************************************** -* -* The minimal vector table for a Cortex M3. Note that the proper constructs -* must be placed on this to ensure that it ends up at physical address -* 0x0000.0000. -* -*******************************************************************************/ - .section .isr_vector,"a",%progbits - .type g_pfnVectors, %object - .size g_pfnVectors, .-g_pfnVectors - -g_pfnVectors: - .word _estack - .word Reset_Handler - .word NMI_Handler - .word HardFault_Handler - .word MemManage_Handler - .word BusFault_Handler - .word UsageFault_Handler - .word 0 - .word 0 - .word 0 - .word 0 - .word SVC_Handler - .word DebugMon_Handler - .word 0 - .word PendSV_Handler - .word SysTick_Handler - - /* External Interrupts */ - .word WWDG_IRQHandler /* Window WatchDog */ - .word PVD_IRQHandler /* PVD through EXTI Line detection */ - .word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXTI line */ - .word RTC_WKUP_IRQHandler /* RTC Wakeup through the EXTI line */ - .word FLASH_IRQHandler /* FLASH */ - .word RCC_IRQHandler /* RCC */ - .word EXTI0_IRQHandler /* EXTI Line0 */ - .word EXTI1_IRQHandler /* EXTI Line1 */ - .word EXTI2_IRQHandler /* EXTI Line2 */ - .word EXTI3_IRQHandler /* EXTI Line3 */ - .word EXTI4_IRQHandler /* EXTI Line4 */ - .word DMA1_Stream0_IRQHandler /* DMA1 Stream 0 */ - .word DMA1_Stream1_IRQHandler /* DMA1 Stream 1 */ - .word DMA1_Stream2_IRQHandler /* DMA1 Stream 2 */ - .word DMA1_Stream3_IRQHandler /* DMA1 Stream 3 */ - .word DMA1_Stream4_IRQHandler /* DMA1 Stream 4 */ - .word DMA1_Stream5_IRQHandler /* DMA1 Stream 5 */ - .word DMA1_Stream6_IRQHandler /* DMA1 Stream 6 */ - .word ADC_IRQHandler /* ADC1, ADC2 and ADC3s */ - .word CAN1_TX_IRQHandler /* CAN1 TX */ - .word CAN1_RX0_IRQHandler /* CAN1 RX0 */ - .word CAN1_RX1_IRQHandler /* CAN1 RX1 */ - .word CAN1_SCE_IRQHandler /* CAN1 SCE */ - .word EXTI9_5_IRQHandler /* External Line[9:5]s */ - .word TIM1_BRK_TIM9_IRQHandler /* TIM1 Break and TIM9 */ - .word TIM1_UP_TIM10_IRQHandler /* TIM1 Update and TIM10 */ - .word TIM1_TRG_COM_TIM11_IRQHandler /* TIM1 Trigger and Commutation and TIM11 */ - .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */ - .word TIM2_IRQHandler /* TIM2 */ - .word TIM3_IRQHandler /* TIM3 */ - .word TIM4_IRQHandler /* TIM4 */ - .word I2C1_EV_IRQHandler /* I2C1 Event */ - .word I2C1_ER_IRQHandler /* I2C1 Error */ - .word I2C2_EV_IRQHandler /* I2C2 Event */ - .word I2C2_ER_IRQHandler /* I2C2 Error */ - .word SPI1_IRQHandler /* SPI1 */ - .word SPI2_IRQHandler /* SPI2 */ - .word USART1_IRQHandler /* USART1 */ - .word USART2_IRQHandler /* USART2 */ - .word USART3_IRQHandler /* USART3 */ - .word EXTI15_10_IRQHandler /* External Line[15:10]s */ - .word RTC_Alarm_IRQHandler /* RTC Alarm (A and B) through EXTI Line */ - .word OTG_FS_WKUP_IRQHandler /* USB OTG FS Wakeup through EXTI line */ - .word TIM8_BRK_TIM12_IRQHandler /* TIM8 Break and TIM12 */ - .word TIM8_UP_TIM13_IRQHandler /* TIM8 Update and TIM13 */ - .word TIM8_TRG_COM_TIM14_IRQHandler /* TIM8 Trigger and Commutation and TIM14 */ - .word TIM8_CC_IRQHandler /* TIM8 Capture Compare */ - .word DMA1_Stream7_IRQHandler /* DMA1 Stream7 */ - .word FSMC_IRQHandler /* FSMC */ - .word SDIO_IRQHandler /* SDIO */ - .word TIM5_IRQHandler /* TIM5 */ - .word SPI3_IRQHandler /* SPI3 */ - .word UART4_IRQHandler /* UART4 */ - .word UART5_IRQHandler /* UART5 */ - .word TIM6_DAC_IRQHandler /* TIM6, DAC1 and DAC2 */ - .word TIM7_IRQHandler /* TIM7 */ - .word DMA2_Stream0_IRQHandler /* DMA2 Stream 0 */ - .word DMA2_Stream1_IRQHandler /* DMA2 Stream 1 */ - .word DMA2_Stream2_IRQHandler /* DMA2 Stream 2 */ - .word DMA2_Stream3_IRQHandler /* DMA2 Stream 3 */ - .word DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */ - .word DFSDM1_FLT0_IRQHandler /* DFSDM1 Filter0 */ - .word DFSDM1_FLT1_IRQHandler /* DFSDM1 Filter1 */ - .word CAN2_TX_IRQHandler /* CAN2 TX */ - .word CAN2_RX0_IRQHandler /* CAN2 RX0 */ - .word CAN2_RX1_IRQHandler /* CAN2 RX1 */ - .word CAN2_SCE_IRQHandler /* CAN2 SCE */ - .word OTG_FS_IRQHandler /* USB OTG FS */ - .word DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */ - .word DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */ - .word DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */ - .word USART6_IRQHandler /* USART6 */ - .word I2C3_EV_IRQHandler /* I2C3 event */ - .word I2C3_ER_IRQHandler /* I2C3 error */ - .word CAN3_TX_IRQHandler /* CAN3 TX */ - .word CAN3_RX0_IRQHandler /* CAN3 RX0 */ - .word CAN3_RX1_IRQHandler /* CAN3 RX1 */ - .word CAN3_SCE_IRQHandler /* CAN3 SCE */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word RNG_IRQHandler /* RNG */ - .word FPU_IRQHandler /* FPU */ - .word UART7_IRQHandler /* UART7 */ - .word UART8_IRQHandler /* UART8 */ - .word SPI4_IRQHandler /* SPI4 */ - .word SPI5_IRQHandler /* SPI5 */ - .word 0 /* Reserved */ - .word SAI1_IRQHandler /* SAI1 */ - .word UART9_IRQHandler /* UART9 */ - .word UART10_IRQHandler /* UART10 */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word QUADSPI_IRQHandler /* QuadSPI */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word FMPI2C1_EV_IRQHandler /* FMPI2C1 Event */ - .word FMPI2C1_ER_IRQHandler /* FMPI2C1 Error */ - .word LPTIM1_IRQHandler /* LPTIM1 */ - .word DFSDM2_FLT0_IRQHandler /* DFSDM2 Filter0 */ - .word DFSDM2_FLT1_IRQHandler /* DFSDM2 Filter1 */ - .word DFSDM2_FLT2_IRQHandler /* DFSDM2 Filter2 */ - .word DFSDM2_FLT3_IRQHandler /* DFSDM2 Filter3 */ - -/******************************************************************************* -* -* Provide weak aliases for each Exception handler to the Default_Handler. -* As they are weak aliases, any function with the same name will override -* this definition. -* -*******************************************************************************/ - .weak NMI_Handler - .thumb_set NMI_Handler,Default_Handler - - .weak HardFault_Handler - .thumb_set HardFault_Handler,Default_Handler - - .weak MemManage_Handler - .thumb_set MemManage_Handler,Default_Handler - - .weak BusFault_Handler - .thumb_set BusFault_Handler,Default_Handler - - .weak UsageFault_Handler - .thumb_set UsageFault_Handler,Default_Handler - - .weak SVC_Handler - .thumb_set SVC_Handler,Default_Handler - - .weak DebugMon_Handler - .thumb_set DebugMon_Handler,Default_Handler - - .weak PendSV_Handler - .thumb_set PendSV_Handler,Default_Handler - - .weak SysTick_Handler - .thumb_set SysTick_Handler,Default_Handler - - .weak WWDG_IRQHandler - .thumb_set WWDG_IRQHandler,Default_Handler - - .weak PVD_IRQHandler - .thumb_set PVD_IRQHandler,Default_Handler - - .weak TAMP_STAMP_IRQHandler - .thumb_set TAMP_STAMP_IRQHandler,Default_Handler - - .weak RTC_WKUP_IRQHandler - .thumb_set RTC_WKUP_IRQHandler,Default_Handler - - .weak FLASH_IRQHandler - .thumb_set FLASH_IRQHandler,Default_Handler - - .weak RCC_IRQHandler - .thumb_set RCC_IRQHandler,Default_Handler - - .weak EXTI0_IRQHandler - .thumb_set EXTI0_IRQHandler,Default_Handler - - .weak EXTI1_IRQHandler - .thumb_set EXTI1_IRQHandler,Default_Handler - - .weak EXTI2_IRQHandler - .thumb_set EXTI2_IRQHandler,Default_Handler - - .weak EXTI3_IRQHandler - .thumb_set EXTI3_IRQHandler,Default_Handler - - .weak EXTI4_IRQHandler - .thumb_set EXTI4_IRQHandler,Default_Handler - - .weak DMA1_Stream0_IRQHandler - .thumb_set DMA1_Stream0_IRQHandler,Default_Handler - - .weak DMA1_Stream1_IRQHandler - .thumb_set DMA1_Stream1_IRQHandler,Default_Handler - - .weak DMA1_Stream2_IRQHandler - .thumb_set DMA1_Stream2_IRQHandler,Default_Handler - - .weak DMA1_Stream3_IRQHandler - .thumb_set DMA1_Stream3_IRQHandler,Default_Handler - - .weak DMA1_Stream4_IRQHandler - .thumb_set DMA1_Stream4_IRQHandler,Default_Handler - - .weak DMA1_Stream5_IRQHandler - .thumb_set DMA1_Stream5_IRQHandler,Default_Handler - - .weak DMA1_Stream6_IRQHandler - .thumb_set DMA1_Stream6_IRQHandler,Default_Handler - - .weak ADC_IRQHandler - .thumb_set ADC_IRQHandler,Default_Handler - - .weak CAN1_TX_IRQHandler - .thumb_set CAN1_TX_IRQHandler,Default_Handler - - .weak CAN1_RX0_IRQHandler - .thumb_set CAN1_RX0_IRQHandler,Default_Handler - - .weak CAN1_RX1_IRQHandler - .thumb_set CAN1_RX1_IRQHandler,Default_Handler - - .weak CAN1_SCE_IRQHandler - .thumb_set CAN1_SCE_IRQHandler,Default_Handler - - .weak EXTI9_5_IRQHandler - .thumb_set EXTI9_5_IRQHandler,Default_Handler - - .weak TIM1_BRK_TIM9_IRQHandler - .thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler - - .weak TIM1_UP_TIM10_IRQHandler - .thumb_set TIM1_UP_TIM10_IRQHandler,Default_Handler - - .weak TIM1_TRG_COM_TIM11_IRQHandler - .thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler - - .weak TIM1_CC_IRQHandler - .thumb_set TIM1_CC_IRQHandler,Default_Handler - - .weak TIM2_IRQHandler - .thumb_set TIM2_IRQHandler,Default_Handler - - .weak TIM3_IRQHandler - .thumb_set TIM3_IRQHandler,Default_Handler - - .weak TIM4_IRQHandler - .thumb_set TIM4_IRQHandler,Default_Handler - - .weak I2C1_EV_IRQHandler - .thumb_set I2C1_EV_IRQHandler,Default_Handler - - .weak I2C1_ER_IRQHandler - .thumb_set I2C1_ER_IRQHandler,Default_Handler - - .weak I2C2_EV_IRQHandler - .thumb_set I2C2_EV_IRQHandler,Default_Handler - - .weak I2C2_ER_IRQHandler - .thumb_set I2C2_ER_IRQHandler,Default_Handler - - .weak SPI1_IRQHandler - .thumb_set SPI1_IRQHandler,Default_Handler - - .weak SPI2_IRQHandler - .thumb_set SPI2_IRQHandler,Default_Handler - - .weak USART1_IRQHandler - .thumb_set USART1_IRQHandler,Default_Handler - - .weak USART2_IRQHandler - .thumb_set USART2_IRQHandler,Default_Handler - - .weak USART3_IRQHandler - .thumb_set USART3_IRQHandler,Default_Handler - - .weak EXTI15_10_IRQHandler - .thumb_set EXTI15_10_IRQHandler,Default_Handler - - .weak RTC_Alarm_IRQHandler - .thumb_set RTC_Alarm_IRQHandler,Default_Handler - - .weak OTG_FS_WKUP_IRQHandler - .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler - - .weak TIM8_BRK_TIM12_IRQHandler - .thumb_set TIM8_BRK_TIM12_IRQHandler,Default_Handler - - .weak TIM8_UP_TIM13_IRQHandler - .thumb_set TIM8_UP_TIM13_IRQHandler,Default_Handler - - .weak TIM8_TRG_COM_TIM14_IRQHandler - .thumb_set TIM8_TRG_COM_TIM14_IRQHandler,Default_Handler - - .weak TIM8_CC_IRQHandler - .thumb_set TIM8_CC_IRQHandler,Default_Handler - - .weak DMA1_Stream7_IRQHandler - .thumb_set DMA1_Stream7_IRQHandler,Default_Handler - - .weak FSMC_IRQHandler - .thumb_set FSMC_IRQHandler,Default_Handler - - .weak SDIO_IRQHandler - .thumb_set SDIO_IRQHandler,Default_Handler - - .weak TIM5_IRQHandler - .thumb_set TIM5_IRQHandler,Default_Handler - - .weak SPI3_IRQHandler - .thumb_set SPI3_IRQHandler,Default_Handler - - .weak UART4_IRQHandler - .thumb_set UART4_IRQHandler,Default_Handler - - .weak UART5_IRQHandler - .thumb_set UART5_IRQHandler,Default_Handler - - .weak TIM6_DAC_IRQHandler - .thumb_set TIM6_DAC_IRQHandler,Default_Handler - - .weak TIM7_IRQHandler - .thumb_set TIM7_IRQHandler,Default_Handler - - .weak DMA2_Stream0_IRQHandler - .thumb_set DMA2_Stream0_IRQHandler,Default_Handler - - .weak DMA2_Stream1_IRQHandler - .thumb_set DMA2_Stream1_IRQHandler,Default_Handler - - .weak DMA2_Stream2_IRQHandler - .thumb_set DMA2_Stream2_IRQHandler,Default_Handler - - .weak DMA2_Stream3_IRQHandler - .thumb_set DMA2_Stream3_IRQHandler,Default_Handler - - .weak DMA2_Stream4_IRQHandler - .thumb_set DMA2_Stream4_IRQHandler,Default_Handler - - .weak DFSDM1_FLT0_IRQHandler - .thumb_set DFSDM1_FLT0_IRQHandler,Default_Handler - - .weak DFSDM1_FLT1_IRQHandler - .thumb_set DFSDM1_FLT1_IRQHandler,Default_Handler - - .weak CAN2_TX_IRQHandler - .thumb_set CAN2_TX_IRQHandler,Default_Handler - - .weak CAN2_RX0_IRQHandler - .thumb_set CAN2_RX0_IRQHandler,Default_Handler - - .weak CAN2_RX1_IRQHandler - .thumb_set CAN2_RX1_IRQHandler,Default_Handler - - .weak CAN2_SCE_IRQHandler - .thumb_set CAN2_SCE_IRQHandler,Default_Handler - - .weak OTG_FS_IRQHandler - .thumb_set OTG_FS_IRQHandler,Default_Handler - - .weak DMA2_Stream5_IRQHandler - .thumb_set DMA2_Stream5_IRQHandler,Default_Handler - - .weak DMA2_Stream6_IRQHandler - .thumb_set DMA2_Stream6_IRQHandler,Default_Handler - - .weak DMA2_Stream7_IRQHandler - .thumb_set DMA2_Stream7_IRQHandler,Default_Handler - - .weak USART6_IRQHandler - .thumb_set USART6_IRQHandler,Default_Handler - - .weak I2C3_EV_IRQHandler - .thumb_set I2C3_EV_IRQHandler,Default_Handler - - .weak I2C3_ER_IRQHandler - .thumb_set I2C3_ER_IRQHandler,Default_Handler - - .weak CAN3_TX_IRQHandler - .thumb_set CAN3_TX_IRQHandler,Default_Handler - - .weak CAN3_RX0_IRQHandler - .thumb_set CAN3_RX0_IRQHandler,Default_Handler - - .weak CAN3_RX1_IRQHandler - .thumb_set CAN3_RX1_IRQHandler,Default_Handler - - .weak CAN3_SCE_IRQHandler - .thumb_set CAN3_SCE_IRQHandler,Default_Handler - - .weak RNG_IRQHandler - .thumb_set RNG_IRQHandler,Default_Handler - - .weak FPU_IRQHandler - .thumb_set FPU_IRQHandler,Default_Handler - - .weak UART7_IRQHandler - .thumb_set UART7_IRQHandler,Default_Handler - - .weak UART8_IRQHandler - .thumb_set UART8_IRQHandler,Default_Handler - - .weak SPI4_IRQHandler - .thumb_set SPI4_IRQHandler,Default_Handler - - .weak SPI5_IRQHandler - .thumb_set SPI5_IRQHandler,Default_Handler - - .weak SAI1_IRQHandler - .thumb_set SAI1_IRQHandler,Default_Handler - - .weak UART9_IRQHandler - .thumb_set UART9_IRQHandler,Default_Handler - - .weak UART10_IRQHandler - .thumb_set UART10_IRQHandler,Default_Handler - - .weak QUADSPI_IRQHandler - .thumb_set QUADSPI_IRQHandler,Default_Handler - - .weak FMPI2C1_EV_IRQHandler - .thumb_set FMPI2C1_EV_IRQHandler,Default_Handler - - .weak FMPI2C1_ER_IRQHandler - .thumb_set FMPI2C1_ER_IRQHandler,Default_Handler - - .weak LPTIM1_IRQHandler - .thumb_set LPTIM1_IRQHandler,Default_Handler - - .weak DFSDM2_FLT0_IRQHandler - .thumb_set DFSDM2_FLT0_IRQHandler,Default_Handler - - .weak DFSDM2_FLT1_IRQHandler - .thumb_set DFSDM2_FLT1_IRQHandler,Default_Handler - - .weak DFSDM2_FLT2_IRQHandler - .thumb_set DFSDM2_FLT2_IRQHandler,Default_Handler - - .weak DFSDM2_FLT3_IRQHandler - .thumb_set DFSDM2_FLT3_IRQHandler,Default_Handler -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/panda/board/stm32fx/stm32f2_flash.ld b/panda/board/stm32fx/stm32f2_flash.ld deleted file mode 100644 index bdc23bc8c..000000000 --- a/panda/board/stm32fx/stm32f2_flash.ld +++ /dev/null @@ -1,165 +0,0 @@ -/* -***************************************************************************** -** -** File : stm32f4_flash.ld -** -** Abstract : Linker script for STM32F407VG Device with -** 1024KByte FLASH, 192KByte RAM -** -** Set heap size, stack size and stack location according -** to application requirements. -** -** Set memory bank area and size if external memory is used. -** -** Target : STMicroelectronics STM32 -** -** Environment : Atollic TrueSTUDIO(R) -** -** Distribution: The file is distributed "as is," without any warranty -** of any kind. -** -** (c)Copyright Atollic AB. -** You may use this file as-is or modify it according to the needs of your -** project. Distribution of this file (unmodified or modified) is not -** permitted. Atollic AB permit registered Atollic TrueSTUDIO(R) users the -** rights to distribute the assembled, compiled & linked contents of this -** file as part of an application binary file, provided that it is built -** using the Atollic TrueSTUDIO(R) toolchain. -** -***************************************************************************** -*/ - -/* Entry Point */ -ENTRY(Reset_Handler) - -/* Highest address of the user mode stack */ -enter_bootloader_mode = 0x2001FFFC; -_estack = 0x2001FFFC; /* end of 128K RAM on AHB bus*/ -_app_start = 0x08004000; /* Reserve Sector 0(16K) for bootloader */ - -/* Generate a link error if heap and stack don't fit into RAM */ -_Min_Heap_Size = 0; /* required amount of heap */ -_Min_Stack_Size = 0x400; /* required amount of stack */ - -/* Specify the memory areas */ -MEMORY -{ - FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 128K - RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K - MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K -} - -/* Define output sections */ -SECTIONS -{ - /* The startup code goes first into FLASH */ - .isr_vector : - { - . = ALIGN(4); - KEEP(*(.isr_vector)) /* Startup code */ - . = ALIGN(4); - } >FLASH - - /* The program code and other data goes into FLASH */ - .text : - { - . = ALIGN(4); - *(.text) /* .text sections (code) */ - *(.text*) /* .text* sections (code) */ - *(.rodata) /* .rodata sections (constants, strings, etc.) */ - *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ - *(.glue_7) /* glue arm to thumb code */ - *(.glue_7t) /* glue thumb to arm code */ - *(.eh_frame) - - KEEP (*(.init)) - KEEP (*(.fini)) - - . = ALIGN(4); - _etext = .; /* define a global symbols at end of code */ - _exit = .; - } >FLASH - - - .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH - .ARM : { - __exidx_start = .; - *(.ARM.exidx*) - __exidx_end = .; - } >FLASH - - .preinit_array : - { - PROVIDE_HIDDEN (__preinit_array_start = .); - KEEP (*(.preinit_array*)) - PROVIDE_HIDDEN (__preinit_array_end = .); - } >FLASH - .init_array : - { - PROVIDE_HIDDEN (__init_array_start = .); - KEEP (*(SORT(.init_array.*))) - KEEP (*(.init_array*)) - PROVIDE_HIDDEN (__init_array_end = .); - } >FLASH - .fini_array : - { - PROVIDE_HIDDEN (__fini_array_start = .); - KEEP (*(.fini_array*)) - KEEP (*(SORT(.fini_array.*))) - PROVIDE_HIDDEN (__fini_array_end = .); - } >FLASH - - /* used by the startup to initialize data */ - _sidata = .; - - /* Initialized data sections goes into RAM, load LMA copy after code */ - .data : AT ( _sidata ) - { - . = ALIGN(4); - _sdata = .; /* create a global symbol at data start */ - *(.data) /* .data sections */ - *(.data*) /* .data* sections */ - - . = ALIGN(4); - _edata = .; /* define a global symbol at data end */ - } >RAM - - /* Uninitialized data section */ - . = ALIGN(4); - .bss : - { - /* This is used by the startup in order to initialize the .bss secion */ - _sbss = .; /* define a global symbol at bss start */ - __bss_start__ = _sbss; - *(.bss) - *(.bss*) - *(COMMON) - - . = ALIGN(4); - _ebss = .; /* define a global symbol at bss end */ - __bss_end__ = _ebss; - } >RAM - - /* User_heap_stack section, used to check that there is enough RAM left */ - ._user_heap_stack : - { - . = ALIGN(4); - PROVIDE ( end = . ); - PROVIDE ( _end = . ); - . = . + _Min_Heap_Size; - . = . + _Min_Stack_Size; - . = ALIGN(4); - } >RAM - - /* MEMORY_bank1 section, code must be located here explicitly */ - /* Example: extern int foo(void) __attribute__ ((section (".mb1text"))); */ - .memory_b1_text : - { - *(.mb1text) /* .mb1text sections (code) */ - *(.mb1text*) /* .mb1text* sections (code) */ - *(.mb1rodata) /* read-only data (constants) */ - *(.mb1rodata*) - } >MEMORY_B1 - - .ARM.attributes 0 : { *(.ARM.attributes) } -} diff --git a/panda/board/stm32fx/stm32f4_flash.ld b/panda/board/stm32fx/stm32f4_flash.ld deleted file mode 100644 index a601c1f60..000000000 --- a/panda/board/stm32fx/stm32f4_flash.ld +++ /dev/null @@ -1,166 +0,0 @@ -/* -***************************************************************************** -** -** File : stm32f4_flash.ld -** -** Abstract : Linker script for STM32F407VG Device with -** 1024KByte FLASH, 192KByte RAM -** -** Set heap size, stack size and stack location according -** to application requirements. -** -** Set memory bank area and size if external memory is used. -** -** Target : STMicroelectronics STM32 -** -** Environment : Atollic TrueSTUDIO(R) -** -** Distribution: The file is distributed "as is," without any warranty -** of any kind. -** -** (c)Copyright Atollic AB. -** You may use this file as-is or modify it according to the needs of your -** project. Distribution of this file (unmodified or modified) is not -** permitted. Atollic AB permit registered Atollic TrueSTUDIO(R) users the -** rights to distribute the assembled, compiled & linked contents of this -** file as part of an application binary file, provided that it is built -** using the Atollic TrueSTUDIO(R) toolchain. -** -***************************************************************************** -*/ - -/* Entry Point */ -ENTRY(Reset_Handler) - -/* Highest address of the user mode stack */ -enter_bootloader_mode = 0x2001FFFC; -_estack = 0x2001FFFC; /* end of 128K RAM on AHB bus*/ -_app_start = 0x08004000; /* Reserve Sector 0(16K) for bootloader */ - -/* Generate a link error if heap and stack don't fit into RAM */ -_Min_Heap_Size = 0; /* required amount of heap */ -_Min_Stack_Size = 0x400; /* required amount of stack */ - -/* Specify the memory areas */ -MEMORY -{ - FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 1024K - RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 256K - RAM2 (xrw) : ORIGIN = 0x20040000, LENGTH = 64K - MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K -} - -/* Define output sections */ -SECTIONS -{ - /* The startup code goes first into FLASH */ - .isr_vector : - { - . = ALIGN(4); - KEEP(*(.isr_vector)) /* Startup code */ - . = ALIGN(4); - } >FLASH - - /* The program code and other data goes into FLASH */ - .text : - { - . = ALIGN(4); - *(.text) /* .text sections (code) */ - *(.text*) /* .text* sections (code) */ - *(.rodata) /* .rodata sections (constants, strings, etc.) */ - *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ - *(.glue_7) /* glue arm to thumb code */ - *(.glue_7t) /* glue thumb to arm code */ - *(.eh_frame) - - KEEP (*(.init)) - KEEP (*(.fini)) - - . = ALIGN(4); - _etext = .; /* define a global symbols at end of code */ - _exit = .; - } >FLASH - - - .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH - .ARM : { - __exidx_start = .; - *(.ARM.exidx*) - __exidx_end = .; - } >FLASH - - .preinit_array : - { - PROVIDE_HIDDEN (__preinit_array_start = .); - KEEP (*(.preinit_array*)) - PROVIDE_HIDDEN (__preinit_array_end = .); - } >FLASH - .init_array : - { - PROVIDE_HIDDEN (__init_array_start = .); - KEEP (*(SORT(.init_array.*))) - KEEP (*(.init_array*)) - PROVIDE_HIDDEN (__init_array_end = .); - } >FLASH - .fini_array : - { - PROVIDE_HIDDEN (__fini_array_start = .); - KEEP (*(.fini_array*)) - KEEP (*(SORT(.fini_array.*))) - PROVIDE_HIDDEN (__fini_array_end = .); - } >FLASH - - /* used by the startup to initialize data */ - _sidata = .; - - /* Initialized data sections goes into RAM, load LMA copy after code */ - .data : AT ( _sidata ) - { - . = ALIGN(4); - _sdata = .; /* create a global symbol at data start */ - *(.data) /* .data sections */ - *(.data*) /* .data* sections */ - - . = ALIGN(4); - _edata = .; /* define a global symbol at data end */ - } >RAM - - /* Uninitialized data section */ - . = ALIGN(4); - .bss : - { - /* This is used by the startup in order to initialize the .bss secion */ - _sbss = .; /* define a global symbol at bss start */ - __bss_start__ = _sbss; - *(.bss) - *(.bss*) - *(COMMON) - - . = ALIGN(4); - _ebss = .; /* define a global symbol at bss end */ - __bss_end__ = _ebss; - } >RAM - - /* User_heap_stack section, used to check that there is enough RAM left */ - ._user_heap_stack : - { - . = ALIGN(4); - PROVIDE ( end = . ); - PROVIDE ( _end = . ); - . = . + _Min_Heap_Size; - . = . + _Min_Stack_Size; - . = ALIGN(4); - } >RAM - - /* MEMORY_bank1 section, code must be located here explicitly */ - /* Example: extern int foo(void) __attribute__ ((section (".mb1text"))); */ - .memory_b1_text : - { - *(.mb1text) /* .mb1text sections (code) */ - *(.mb1text*) /* .mb1text* sections (code) */ - *(.mb1rodata) /* read-only data (constants) */ - *(.mb1rodata*) - } >MEMORY_B1 - - .ARM.attributes 0 : { *(.ARM.attributes) } -} diff --git a/panda/board/stm32fx/stm32fx_config.h b/panda/board/stm32fx/stm32fx_config.h deleted file mode 100644 index dd026e98e..000000000 --- a/panda/board/stm32fx/stm32fx_config.h +++ /dev/null @@ -1,108 +0,0 @@ -#ifdef STM32F4 - #include "stm32fx/inc/stm32f4xx.h" - #include "stm32fx/inc/stm32f4xx_hal_gpio_ex.h" - #define MCU_IDCODE 0x463U -#else - #include "stm32fx/inc/stm32f2xx.h" - #include "stm32fx/inc/stm32f2xx_hal_gpio_ex.h" - #define MCU_IDCODE 0x411U -#endif -// from the linker script -#define APP_START_ADDRESS 0x8004000U - -#define CORE_FREQ 96U // in MHz -#define APB1_FREQ (CORE_FREQ/2U) -#define APB1_TIMER_FREQ (APB1_FREQ*2U) // APB1 is multiplied by 2 for the timer peripherals -#define APB2_FREQ (CORE_FREQ/2U) -#define APB2_TIMER_FREQ (APB2_FREQ*2U) // APB2 is multiplied by 2 for the timer peripherals - -#define BOOTLOADER_ADDRESS 0x1FFF0004U - -// Around (1Mbps / 8 bits/byte / 12 bytes per message) -#define CAN_INTERRUPT_RATE 12000U - -#define MAX_LED_FADE 8192U - -#define NUM_INTERRUPTS 102U // There are 102 external interrupt sources (see stm32f413.h) - -#define TICK_TIMER_IRQ TIM1_BRK_TIM9_IRQn -#define TICK_TIMER TIM9 - -#define MICROSECOND_TIMER TIM2 - -#define INTERRUPT_TIMER_IRQ TIM6_DAC_IRQn -#define INTERRUPT_TIMER TIM6 - -#define IND_WDG IWDG - -#define PROVISION_CHUNK_ADDRESS 0x1FFF79E0U -#define DEVICE_SERIAL_NUMBER_ADDRESS 0x1FFF79C0U - -#define LOGGING_FLASH_SECTOR_A 10U -#define LOGGING_FLASH_SECTOR_B 11U -#define LOGGING_FLASH_BASE_A 0x080C0000U -#define LOGGING_FLASH_BASE_B 0x080E0000U -#define LOGGING_FLASH_SECTOR_SIZE 0x20000U - -#include "can_definitions.h" -#include "comms_definitions.h" - -#ifndef BOOTSTUB - #ifdef PEDAL - #include "pedal/main_declarations.h" - #else - #include "main_declarations.h" - #endif -#else - #include "bootstub_declarations.h" -#endif - -#include "libc.h" -#include "critical.h" -#include "faults.h" -#include "utils.h" - -#include "drivers/registers.h" -#include "drivers/interrupts.h" -#include "drivers/gpio.h" -#include "stm32fx/peripherals.h" -#include "stm32fx/interrupt_handlers.h" -#include "drivers/timers.h" -#include "stm32fx/board.h" -#include "stm32fx/clock.h" -#include "drivers/watchdog.h" -#include "stm32fx/llflash.h" - -#if !defined(PEDAL) || defined(BOOTSTUB) - #include "drivers/spi.h" - #include "stm32fx/llspi.h" -#endif - -#if !defined(BOOTSTUB) && (!defined(PEDAL) || defined(PEDAL_USB)) - #include "drivers/uart.h" - #include "stm32fx/lluart.h" -#endif - -#if defined(PANDA) && !defined(BOOTSTUB) - #include "stm32fx/llexti.h" -#endif - -#ifndef BOOTSTUB - #include "stm32fx/llbxcan.h" -#endif - -#if !defined(PEDAL) || defined(PEDAL_USB) || defined(BOOTSTUB) - #include "stm32fx/llusb.h" -#endif - -#ifdef PEDAL - #include "stm32fx/lldac.h" -#endif - -void early_gpio_float(void) { - RCC->AHB1ENR = RCC_AHB1ENR_GPIOAEN | RCC_AHB1ENR_GPIOBEN | RCC_AHB1ENR_GPIOCEN; - - GPIOA->MODER = 0; GPIOB->MODER = 0; GPIOC->MODER = 0; - GPIOA->ODR = 0; GPIOB->ODR = 0; GPIOC->ODR = 0; - GPIOA->PUPDR = 0; GPIOB->PUPDR = 0; GPIOC->PUPDR = 0; -} diff --git a/panda/board/stm32h7/board.h b/panda/board/stm32h7/board.h deleted file mode 100644 index d991e433b..000000000 --- a/panda/board/stm32h7/board.h +++ /dev/null @@ -1,46 +0,0 @@ -// ///////////////////////////////////////////////////////////// // -// Hardware abstraction layer for all different supported boards // -// ///////////////////////////////////////////////////////////// // -#include "boards/board_declarations.h" -#include "boards/unused_funcs.h" - -// ///// Board definition and detection ///// // -#include "stm32h7/lladc.h" -#include "drivers/harness.h" -#include "drivers/fan.h" -#include "stm32h7/llfan.h" -#include "stm32h7/llrtc.h" -#include "stm32h7/lldac.h" -#include "drivers/fake_siren.h" -#include "drivers/rtc.h" -#include "drivers/clock_source.h" -#include "boards/red.h" -#include "boards/red_chiplet.h" -#include "boards/red_v2.h" -#include "boards/tres.h" - - -uint8_t get_board_id(void) { - return detect_with_pull(GPIOF, 7, PULL_UP) | - (detect_with_pull(GPIOF, 8, PULL_UP) << 1U) | - (detect_with_pull(GPIOF, 9, PULL_UP) << 2U) | - (detect_with_pull(GPIOF, 10, PULL_UP) << 3U); -} - -void detect_board_type(void) { - const uint8_t board_id = get_board_id(); - - if (board_id == 0U) { - hw_type = HW_TYPE_RED_PANDA; - current_board = &board_red; - } else if (board_id == 1U) { - hw_type = HW_TYPE_RED_PANDA_V2; - current_board = &board_red_v2; - } else if (board_id == 2U) { - hw_type = HW_TYPE_TRES; - current_board = &board_tres; - } else { - hw_type = HW_TYPE_UNKNOWN; - print("Hardware type is UNKNOWN!\n"); - } -} diff --git a/panda/board/stm32h7/clock.h b/panda/board/stm32h7/clock.h deleted file mode 100644 index b1846da26..000000000 --- a/panda/board/stm32h7/clock.h +++ /dev/null @@ -1,78 +0,0 @@ -/* -HSE: 25MHz -PLL1Q: 80MHz (for FDCAN) -HSI48 enabled (for USB) -CPU: 240MHz -CPU Systick: 240MHz -AXI: 120MHz -HCLK3: 60MHz -APB3 per: 60MHz -AHB1,2 per: 120MHz -APB1 per: 60MHz -APB1 tim: 120MHz -APB2 per: 60MHz -APB2 tim: 120MHz -AHB4 per: 120MHz -APB4 per: 60MHz -PCLK1: 60MHz (for USART2,3,4,5,7,8) -*/ - -void clock_init(void) { - //Set power mode to direct SMPS power supply(depends on the board layout) - register_set(&(PWR->CR3), PWR_CR3_SMPSEN, 0xFU); // powered only by SMPS - //Set VOS level (VOS3 to 170Mhz, VOS2 to 300Mhz, VOS1 to 400Mhz, VOS0 to 550Mhz) - register_set(&(PWR->D3CR), PWR_D3CR_VOS_1 | PWR_D3CR_VOS_0, 0xC000U); //VOS1, needed for 80Mhz CAN FD - while ((PWR->CSR1 & PWR_CSR1_ACTVOSRDY) == 0); - while ((PWR->CSR1 & PWR_CSR1_ACTVOS) != (PWR->D3CR & PWR_D3CR_VOS)); // check that VOS level was actually set - // Configure Flash ACR register LATENCY and WRHIGHFREQ (VOS0 range!) - register_set(&(FLASH->ACR), FLASH_ACR_LATENCY_2WS | 0x20U, 0x3FU); // VOS2, AXI 100MHz-150MHz - // enable external oscillator HSE - register_set_bits(&(RCC->CR), RCC_CR_HSEON); - while ((RCC->CR & RCC_CR_HSERDY) == 0); - // enable internal HSI48 for USB FS kernel - register_set_bits(&(RCC->CR), RCC_CR_HSI48ON); - while ((RCC->CR & RCC_CR_HSI48RDY) == 0); - // Specify the frequency source for PLL1, divider for DIVM1, DIVM2, DIVM3 : HSE, 5, 5, 5 - register_set(&(RCC->PLLCKSELR), RCC_PLLCKSELR_PLLSRC_HSE | RCC_PLLCKSELR_DIVM1_0 | RCC_PLLCKSELR_DIVM1_2 | RCC_PLLCKSELR_DIVM2_0 | RCC_PLLCKSELR_DIVM2_2 | RCC_PLLCKSELR_DIVM3_0 | RCC_PLLCKSELR_DIVM3_2, 0x3F3F3F3U); - - // *** PLL1 start *** - // Specify multiplier N and dividers P, Q, R for PLL1 : 48, 1, 3, 2 (clock 240Mhz, PLL1Q 80Mhz for CAN FD) - register_set(&(RCC->PLL1DIVR), 0x102002FU, 0x7F7FFFFFU); - // Specify the input and output frequency ranges, enable dividers for PLL1 - register_set(&(RCC->PLLCFGR), RCC_PLLCFGR_PLL1RGE_2 | RCC_PLLCFGR_DIVP1EN | RCC_PLLCFGR_DIVQ1EN | RCC_PLLCFGR_DIVR1EN, 0x7000CU); - // Enable PLL1 - register_set_bits(&(RCC->CR), RCC_CR_PLL1ON); - while((RCC->CR & RCC_CR_PLL1RDY) == 0); - // *** PLL1 end *** - - //////////////OTHER CLOCKS//////////////////// - // RCC HCLK Clock Source / RCC APB3 Clock Source / RCC SYS Clock Source - register_set(&(RCC->D1CFGR), RCC_D1CFGR_HPRE_DIV2 | RCC_D1CFGR_D1PPRE_DIV2 | RCC_D1CFGR_D1CPRE_DIV1, 0xF7FU); - // RCC APB1 Clock Source / RCC APB2 Clock Source - register_set(&(RCC->D2CFGR), RCC_D2CFGR_D2PPRE1_DIV2 | RCC_D2CFGR_D2PPRE2_DIV2, 0x770U); - // RCC APB4 Clock Source - register_set(&(RCC->D3CFGR), RCC_D3CFGR_D3PPRE_DIV2, 0x70U); - - // Set SysClock source to PLL - register_set(&(RCC->CFGR), RCC_CFGR_SW_PLL1, 0x7U); - while((RCC->CFGR & RCC_CFGR_SWS) != RCC_CFGR_SWS_PLL1); - - // SYSCFG peripheral clock enable - register_set_bits(&(RCC->AHB4ENR), RCC_APB4ENR_SYSCFGEN); - //////////////END OTHER CLOCKS//////////////////// - - // Configure clock source for USB (HSI48) - register_set(&(RCC->D2CCIP2R), RCC_D2CCIP2R_USBSEL_1 | RCC_D2CCIP2R_USBSEL_0, RCC_D2CCIP2R_USBSEL); - // Configure clock source for FDCAN (PLL1Q at 80Mhz) - register_set(&(RCC->D2CCIP1R), RCC_D2CCIP1R_FDCANSEL_0, RCC_D2CCIP1R_FDCANSEL); - // Configure clock source for ADC1,2,3 (per_ck(currently HSE)) - register_set(&(RCC->D3CCIPR), RCC_D3CCIPR_ADCSEL_1, RCC_D3CCIPR_ADCSEL); - //Enable the Clock Security System - register_set_bits(&(RCC->CR), RCC_CR_CSSHSEON); - //Enable Vdd33usb supply level detector - register_set_bits(&(PWR->CR3), PWR_CR3_USB33DEN); - - // Enable CPU access to SRAM1 and SRAM2 (in domain D2) - register_set_bits(&(RCC->AHB2ENR), RCC_AHB2ENR_SRAM1EN); - register_set_bits(&(RCC->AHB2ENR), RCC_AHB2ENR_SRAM2EN); -} diff --git a/panda/board/stm32h7/inc/cmsis_compiler.h b/panda/board/stm32h7/inc/cmsis_compiler.h deleted file mode 100644 index d0f39eef6..000000000 --- a/panda/board/stm32h7/inc/cmsis_compiler.h +++ /dev/null @@ -1,284 +0,0 @@ -/**************************************************************************//** - * @file cmsis_compiler.h - * @brief CMSIS compiler generic header file - * @version V5.1.0 - * @date 09. October 2018 - ******************************************************************************/ -/* - * Copyright (c) 2009-2018 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed under the Apache License, Version 2.0 (the License); you may - * not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an AS IS BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#ifndef __CMSIS_COMPILER_H -#define __CMSIS_COMPILER_H - -#include - -/* - * Arm Compiler 4/5 - */ -#if defined ( __CC_ARM ) - #include "cmsis_armcc.h" - - -/* - * Arm Compiler 6.6 LTM (armclang) - */ -#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) && (__ARMCC_VERSION < 6100100) - #include "cmsis_armclang_ltm.h" - - /* - * Arm Compiler above 6.10.1 (armclang) - */ -#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6100100) - #include "cmsis_armclang.h" - - -/* - * GNU Compiler - */ -#elif defined ( __GNUC__ ) - #include "cmsis_gcc.h" - - -/* - * IAR Compiler - */ -#elif defined ( __ICCARM__ ) - #include - - -/* - * TI Arm Compiler - */ -#elif defined ( __TI_ARM__ ) - #include - - #ifndef __ASM - #define __ASM __asm - #endif - #ifndef __INLINE - #define __INLINE inline - #endif - #ifndef __STATIC_INLINE - #define __STATIC_INLINE static inline - #endif - #ifndef __STATIC_FORCEINLINE - #define __STATIC_FORCEINLINE __STATIC_INLINE - #endif - #ifndef __NO_RETURN - #define __NO_RETURN __attribute__((noreturn)) - #endif - #ifndef __USED - #define __USED __attribute__((used)) - #endif - #ifndef __WEAK - #define __WEAK __attribute__((weak)) - #endif - #ifndef __PACKED - #define __PACKED __attribute__((packed)) - #endif - #ifndef __PACKED_STRUCT - #define __PACKED_STRUCT struct __attribute__((packed)) - #endif - #ifndef __PACKED_UNION - #define __PACKED_UNION union __attribute__((packed)) - #endif - #ifndef __UNALIGNED_UINT32 /* deprecated */ - struct __attribute__((packed)) T_UINT32 { uint32_t v; }; - #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) - #endif - #ifndef __UNALIGNED_UINT16_WRITE - __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; - #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void*)(addr))->v) = (val)) - #endif - #ifndef __UNALIGNED_UINT16_READ - __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; - #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) - #endif - #ifndef __UNALIGNED_UINT32_WRITE - __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; - #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) - #endif - #ifndef __UNALIGNED_UINT32_READ - __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; - #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) - #endif - #ifndef __ALIGNED - #define __ALIGNED(x) __attribute__((aligned(x))) - #endif - #ifndef __RESTRICT - #define __RESTRICT __restrict - #endif - #ifndef __COMPILER_BARRIER - #warning No compiler specific solution for __COMPILER_BARRIER. __COMPILER_BARRIER is ignored. - #define __COMPILER_BARRIER() (void)0 - #endif - - -/* - * TASKING Compiler - */ -#elif defined ( __TASKING__ ) - /* - * The CMSIS functions have been implemented as intrinsics in the compiler. - * Please use "carm -?i" to get an up to date list of all intrinsics, - * Including the CMSIS ones. - */ - - #ifndef __ASM - #define __ASM __asm - #endif - #ifndef __INLINE - #define __INLINE inline - #endif - #ifndef __STATIC_INLINE - #define __STATIC_INLINE static inline - #endif - #ifndef __STATIC_FORCEINLINE - #define __STATIC_FORCEINLINE __STATIC_INLINE - #endif - #ifndef __NO_RETURN - #define __NO_RETURN __attribute__((noreturn)) - #endif - #ifndef __USED - #define __USED __attribute__((used)) - #endif - #ifndef __WEAK - #define __WEAK __attribute__((weak)) - #endif - #ifndef __PACKED - #define __PACKED __packed__ - #endif - #ifndef __PACKED_STRUCT - #define __PACKED_STRUCT struct __packed__ - #endif - #ifndef __PACKED_UNION - #define __PACKED_UNION union __packed__ - #endif - #ifndef __UNALIGNED_UINT32 /* deprecated */ - struct __packed__ T_UINT32 { uint32_t v; }; - #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) - #endif - #ifndef __UNALIGNED_UINT16_WRITE - __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; - #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val)) - #endif - #ifndef __UNALIGNED_UINT16_READ - __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; - #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) - #endif - #ifndef __UNALIGNED_UINT32_WRITE - __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; - #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) - #endif - #ifndef __UNALIGNED_UINT32_READ - __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; - #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) - #endif - #ifndef __ALIGNED - #define __ALIGNED(x) __align(x) - #endif - #ifndef __RESTRICT - #warning No compiler specific solution for __RESTRICT. __RESTRICT is ignored. - #define __RESTRICT - #endif - #ifndef __COMPILER_BARRIER - #warning No compiler specific solution for __COMPILER_BARRIER. __COMPILER_BARRIER is ignored. - #define __COMPILER_BARRIER() (void)0 - #endif - - -/* - * COSMIC Compiler - */ -#elif defined ( __CSMC__ ) - #include - - #ifndef __ASM - #define __ASM _asm - #endif - #ifndef __INLINE - #define __INLINE inline - #endif - #ifndef __STATIC_INLINE - #define __STATIC_INLINE static inline - #endif - #ifndef __STATIC_FORCEINLINE - #define __STATIC_FORCEINLINE __STATIC_INLINE - #endif - #ifndef __NO_RETURN - // NO RETURN is automatically detected hence no warning here - #define __NO_RETURN - #endif - #ifndef __USED - #warning No compiler specific solution for __USED. __USED is ignored. - #define __USED - #endif - #ifndef __WEAK - #define __WEAK __weak - #endif - #ifndef __PACKED - #define __PACKED @packed - #endif - #ifndef __PACKED_STRUCT - #define __PACKED_STRUCT @packed struct - #endif - #ifndef __PACKED_UNION - #define __PACKED_UNION @packed union - #endif - #ifndef __UNALIGNED_UINT32 /* deprecated */ - @packed struct T_UINT32 { uint32_t v; }; - #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) - #endif - #ifndef __UNALIGNED_UINT16_WRITE - __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; - #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val)) - #endif - #ifndef __UNALIGNED_UINT16_READ - __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; - #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) - #endif - #ifndef __UNALIGNED_UINT32_WRITE - __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; - #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) - #endif - #ifndef __UNALIGNED_UINT32_READ - __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; - #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) - #endif - #ifndef __ALIGNED - #warning No compiler specific solution for __ALIGNED. __ALIGNED is ignored. - #define __ALIGNED(x) - #endif - #ifndef __RESTRICT - #warning No compiler specific solution for __RESTRICT. __RESTRICT is ignored. - #define __RESTRICT - #endif - #ifndef __COMPILER_BARRIER - #warning No compiler specific solution for __COMPILER_BARRIER. __COMPILER_BARRIER is ignored. - #define __COMPILER_BARRIER() (void)0 - #endif - - -#else - #error Unknown compiler. -#endif - - -#endif /* __CMSIS_COMPILER_H */ - - diff --git a/panda/board/stm32h7/inc/cmsis_gcc.h b/panda/board/stm32h7/inc/cmsis_gcc.h deleted file mode 100644 index 2f68473f6..000000000 --- a/panda/board/stm32h7/inc/cmsis_gcc.h +++ /dev/null @@ -1,2169 +0,0 @@ -/**************************************************************************//** - * @file cmsis_gcc.h - * @brief CMSIS compiler GCC header file - * @version V5.2.0 - * @date 08. May 2019 - ******************************************************************************/ -/* - * Copyright (c) 2009-2019 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed under the Apache License, Version 2.0 (the License); you may - * not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an AS IS BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#ifndef __CMSIS_GCC_H -#define __CMSIS_GCC_H - -/* ignore some GCC warnings */ -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wsign-conversion" -#pragma GCC diagnostic ignored "-Wconversion" -#pragma GCC diagnostic ignored "-Wunused-parameter" - -/* Fallback for __has_builtin */ -#ifndef __has_builtin - #define __has_builtin(x) (0) -#endif - -/* CMSIS compiler specific defines */ -#ifndef __ASM - #define __ASM __asm -#endif -#ifndef __INLINE - #define __INLINE inline -#endif -#ifndef __STATIC_INLINE - #define __STATIC_INLINE static inline -#endif -#ifndef __STATIC_FORCEINLINE - #define __STATIC_FORCEINLINE __attribute__((always_inline)) static inline -#endif -#ifndef __NO_RETURN - #define __NO_RETURN __attribute__((__noreturn__)) -#endif -#ifndef __USED - #define __USED __attribute__((used)) -#endif -#ifndef __WEAK - #define __WEAK __attribute__((weak)) -#endif -#ifndef __PACKED - #define __PACKED __attribute__((packed, aligned(1))) -#endif -#ifndef __PACKED_STRUCT - #define __PACKED_STRUCT struct __attribute__((packed, aligned(1))) -#endif -#ifndef __PACKED_UNION - #define __PACKED_UNION union __attribute__((packed, aligned(1))) -#endif -#ifndef __UNALIGNED_UINT32 /* deprecated */ - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wpacked" - #pragma GCC diagnostic ignored "-Wattributes" - struct __attribute__((packed)) T_UINT32 { uint32_t v; }; - #pragma GCC diagnostic pop - #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) -#endif -#ifndef __UNALIGNED_UINT16_WRITE - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wpacked" - #pragma GCC diagnostic ignored "-Wattributes" - __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; - #pragma GCC diagnostic pop - #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val)) -#endif -#ifndef __UNALIGNED_UINT16_READ - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wpacked" - #pragma GCC diagnostic ignored "-Wattributes" - __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; - #pragma GCC diagnostic pop - #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) -#endif -#ifndef __UNALIGNED_UINT32_WRITE - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wpacked" - #pragma GCC diagnostic ignored "-Wattributes" - __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; - #pragma GCC diagnostic pop - #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) -#endif -#ifndef __UNALIGNED_UINT32_READ - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wpacked" - #pragma GCC diagnostic ignored "-Wattributes" - __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; - #pragma GCC diagnostic pop - #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) -#endif -#ifndef __ALIGNED - #define __ALIGNED(x) __attribute__((aligned(x))) -#endif -#ifndef __RESTRICT - #define __RESTRICT __restrict -#endif -#ifndef __COMPILER_BARRIER - #define __COMPILER_BARRIER() __ASM volatile("":::"memory") -#endif - -/* ######################### Startup and Lowlevel Init ######################## */ - -#ifndef __PROGRAM_START - -/** - \brief Initializes data and bss sections - \details This default implementations initialized all data and additional bss - sections relying on .copy.table and .zero.table specified properly - in the used linker script. - - */ -__STATIC_FORCEINLINE __NO_RETURN void __cmsis_start(void) -{ - extern void _start(void) __NO_RETURN; - - typedef struct { - uint32_t const* src; - uint32_t* dest; - uint32_t wlen; - } __copy_table_t; - - typedef struct { - uint32_t* dest; - uint32_t wlen; - } __zero_table_t; - - extern const __copy_table_t __copy_table_start__; - extern const __copy_table_t __copy_table_end__; - extern const __zero_table_t __zero_table_start__; - extern const __zero_table_t __zero_table_end__; - - for (__copy_table_t const* pTable = &__copy_table_start__; pTable < &__copy_table_end__; ++pTable) { - for(uint32_t i=0u; iwlen; ++i) { - pTable->dest[i] = pTable->src[i]; - } - } - - for (__zero_table_t const* pTable = &__zero_table_start__; pTable < &__zero_table_end__; ++pTable) { - for(uint32_t i=0u; iwlen; ++i) { - pTable->dest[i] = 0u; - } - } - - _start(); -} - -#define __PROGRAM_START __cmsis_start -#endif - -#ifndef __INITIAL_SP -#define __INITIAL_SP __StackTop -#endif - -#ifndef __STACK_LIMIT -#define __STACK_LIMIT __StackLimit -#endif - -#ifndef __VECTOR_TABLE -#define __VECTOR_TABLE __Vectors -#endif - -#ifndef __VECTOR_TABLE_ATTRIBUTE -#define __VECTOR_TABLE_ATTRIBUTE __attribute((used, section(".vectors"))) -#endif - -/* ########################### Core Function Access ########################### */ -/** \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions - @{ - */ - -/** - \brief Enable IRQ Interrupts - \details Enables IRQ interrupts by clearing the I-bit in the CPSR. - Can only be executed in Privileged modes. - */ -__STATIC_FORCEINLINE void __enable_irq(void) -{ - __ASM volatile ("cpsie i" : : : "memory"); -} - - -/** - \brief Disable IRQ Interrupts - \details Disables IRQ interrupts by setting the I-bit in the CPSR. - Can only be executed in Privileged modes. - */ -__STATIC_FORCEINLINE void __disable_irq(void) -{ - __ASM volatile ("cpsid i" : : : "memory"); -} - - -/** - \brief Get Control Register - \details Returns the content of the Control Register. - \return Control Register value - */ -__STATIC_FORCEINLINE uint32_t __get_CONTROL(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, control" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Control Register (non-secure) - \details Returns the content of the non-secure Control Register when in secure mode. - \return non-secure Control Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_CONTROL_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, control_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Control Register - \details Writes the given value to the Control Register. - \param [in] control Control Register value to set - */ -__STATIC_FORCEINLINE void __set_CONTROL(uint32_t control) -{ - __ASM volatile ("MSR control, %0" : : "r" (control) : "memory"); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Control Register (non-secure) - \details Writes the given value to the non-secure Control Register when in secure state. - \param [in] control Control Register value to set - */ -__STATIC_FORCEINLINE void __TZ_set_CONTROL_NS(uint32_t control) -{ - __ASM volatile ("MSR control_ns, %0" : : "r" (control) : "memory"); -} -#endif - - -/** - \brief Get IPSR Register - \details Returns the content of the IPSR Register. - \return IPSR Register value - */ -__STATIC_FORCEINLINE uint32_t __get_IPSR(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, ipsr" : "=r" (result) ); - return(result); -} - - -/** - \brief Get APSR Register - \details Returns the content of the APSR Register. - \return APSR Register value - */ -__STATIC_FORCEINLINE uint32_t __get_APSR(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, apsr" : "=r" (result) ); - return(result); -} - - -/** - \brief Get xPSR Register - \details Returns the content of the xPSR Register. - \return xPSR Register value - */ -__STATIC_FORCEINLINE uint32_t __get_xPSR(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, xpsr" : "=r" (result) ); - return(result); -} - - -/** - \brief Get Process Stack Pointer - \details Returns the current value of the Process Stack Pointer (PSP). - \return PSP Register value - */ -__STATIC_FORCEINLINE uint32_t __get_PSP(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, psp" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Process Stack Pointer (non-secure) - \details Returns the current value of the non-secure Process Stack Pointer (PSP) when in secure state. - \return PSP Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_PSP_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, psp_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Process Stack Pointer - \details Assigns the given value to the Process Stack Pointer (PSP). - \param [in] topOfProcStack Process Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __set_PSP(uint32_t topOfProcStack) -{ - __ASM volatile ("MSR psp, %0" : : "r" (topOfProcStack) : ); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Process Stack Pointer (non-secure) - \details Assigns the given value to the non-secure Process Stack Pointer (PSP) when in secure state. - \param [in] topOfProcStack Process Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __TZ_set_PSP_NS(uint32_t topOfProcStack) -{ - __ASM volatile ("MSR psp_ns, %0" : : "r" (topOfProcStack) : ); -} -#endif - - -/** - \brief Get Main Stack Pointer - \details Returns the current value of the Main Stack Pointer (MSP). - \return MSP Register value - */ -__STATIC_FORCEINLINE uint32_t __get_MSP(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, msp" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Main Stack Pointer (non-secure) - \details Returns the current value of the non-secure Main Stack Pointer (MSP) when in secure state. - \return MSP Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_MSP_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, msp_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Main Stack Pointer - \details Assigns the given value to the Main Stack Pointer (MSP). - \param [in] topOfMainStack Main Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __set_MSP(uint32_t topOfMainStack) -{ - __ASM volatile ("MSR msp, %0" : : "r" (topOfMainStack) : ); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Main Stack Pointer (non-secure) - \details Assigns the given value to the non-secure Main Stack Pointer (MSP) when in secure state. - \param [in] topOfMainStack Main Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __TZ_set_MSP_NS(uint32_t topOfMainStack) -{ - __ASM volatile ("MSR msp_ns, %0" : : "r" (topOfMainStack) : ); -} -#endif - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Stack Pointer (non-secure) - \details Returns the current value of the non-secure Stack Pointer (SP) when in secure state. - \return SP Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_SP_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, sp_ns" : "=r" (result) ); - return(result); -} - - -/** - \brief Set Stack Pointer (non-secure) - \details Assigns the given value to the non-secure Stack Pointer (SP) when in secure state. - \param [in] topOfStack Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __TZ_set_SP_NS(uint32_t topOfStack) -{ - __ASM volatile ("MSR sp_ns, %0" : : "r" (topOfStack) : ); -} -#endif - - -/** - \brief Get Priority Mask - \details Returns the current state of the priority mask bit from the Priority Mask Register. - \return Priority Mask value - */ -__STATIC_FORCEINLINE uint32_t __get_PRIMASK(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, primask" : "=r" (result) :: "memory"); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Priority Mask (non-secure) - \details Returns the current state of the non-secure priority mask bit from the Priority Mask Register when in secure state. - \return Priority Mask value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_PRIMASK_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, primask_ns" : "=r" (result) :: "memory"); - return(result); -} -#endif - - -/** - \brief Set Priority Mask - \details Assigns the given value to the Priority Mask Register. - \param [in] priMask Priority Mask - */ -__STATIC_FORCEINLINE void __set_PRIMASK(uint32_t priMask) -{ - __ASM volatile ("MSR primask, %0" : : "r" (priMask) : "memory"); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Priority Mask (non-secure) - \details Assigns the given value to the non-secure Priority Mask Register when in secure state. - \param [in] priMask Priority Mask - */ -__STATIC_FORCEINLINE void __TZ_set_PRIMASK_NS(uint32_t priMask) -{ - __ASM volatile ("MSR primask_ns, %0" : : "r" (priMask) : "memory"); -} -#endif - - -#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) -/** - \brief Enable FIQ - \details Enables FIQ interrupts by clearing the F-bit in the CPSR. - Can only be executed in Privileged modes. - */ -__STATIC_FORCEINLINE void __enable_fault_irq(void) -{ - __ASM volatile ("cpsie f" : : : "memory"); -} - - -/** - \brief Disable FIQ - \details Disables FIQ interrupts by setting the F-bit in the CPSR. - Can only be executed in Privileged modes. - */ -__STATIC_FORCEINLINE void __disable_fault_irq(void) -{ - __ASM volatile ("cpsid f" : : : "memory"); -} - - -/** - \brief Get Base Priority - \details Returns the current value of the Base Priority register. - \return Base Priority register value - */ -__STATIC_FORCEINLINE uint32_t __get_BASEPRI(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, basepri" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Base Priority (non-secure) - \details Returns the current value of the non-secure Base Priority register when in secure state. - \return Base Priority register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_BASEPRI_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, basepri_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Base Priority - \details Assigns the given value to the Base Priority register. - \param [in] basePri Base Priority value to set - */ -__STATIC_FORCEINLINE void __set_BASEPRI(uint32_t basePri) -{ - __ASM volatile ("MSR basepri, %0" : : "r" (basePri) : "memory"); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Base Priority (non-secure) - \details Assigns the given value to the non-secure Base Priority register when in secure state. - \param [in] basePri Base Priority value to set - */ -__STATIC_FORCEINLINE void __TZ_set_BASEPRI_NS(uint32_t basePri) -{ - __ASM volatile ("MSR basepri_ns, %0" : : "r" (basePri) : "memory"); -} -#endif - - -/** - \brief Set Base Priority with condition - \details Assigns the given value to the Base Priority register only if BASEPRI masking is disabled, - or the new value increases the BASEPRI priority level. - \param [in] basePri Base Priority value to set - */ -__STATIC_FORCEINLINE void __set_BASEPRI_MAX(uint32_t basePri) -{ - __ASM volatile ("MSR basepri_max, %0" : : "r" (basePri) : "memory"); -} - - -/** - \brief Get Fault Mask - \details Returns the current value of the Fault Mask register. - \return Fault Mask register value - */ -__STATIC_FORCEINLINE uint32_t __get_FAULTMASK(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, faultmask" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Fault Mask (non-secure) - \details Returns the current value of the non-secure Fault Mask register when in secure state. - \return Fault Mask register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_FAULTMASK_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, faultmask_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Fault Mask - \details Assigns the given value to the Fault Mask register. - \param [in] faultMask Fault Mask value to set - */ -__STATIC_FORCEINLINE void __set_FAULTMASK(uint32_t faultMask) -{ - __ASM volatile ("MSR faultmask, %0" : : "r" (faultMask) : "memory"); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Fault Mask (non-secure) - \details Assigns the given value to the non-secure Fault Mask register when in secure state. - \param [in] faultMask Fault Mask value to set - */ -__STATIC_FORCEINLINE void __TZ_set_FAULTMASK_NS(uint32_t faultMask) -{ - __ASM volatile ("MSR faultmask_ns, %0" : : "r" (faultMask) : "memory"); -} -#endif - -#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ - - -#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) - -/** - \brief Get Process Stack Pointer Limit - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence zero is returned always in non-secure - mode. - - \details Returns the current value of the Process Stack Pointer Limit (PSPLIM). - \return PSPLIM Register value - */ -__STATIC_FORCEINLINE uint32_t __get_PSPLIM(void) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - return 0U; -#else - uint32_t result; - __ASM volatile ("MRS %0, psplim" : "=r" (result) ); - return result; -#endif -} - -#if (defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Process Stack Pointer Limit (non-secure) - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence zero is returned always. - - \details Returns the current value of the non-secure Process Stack Pointer Limit (PSPLIM) when in secure state. - \return PSPLIM Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_PSPLIM_NS(void) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - return 0U; -#else - uint32_t result; - __ASM volatile ("MRS %0, psplim_ns" : "=r" (result) ); - return result; -#endif -} -#endif - - -/** - \brief Set Process Stack Pointer Limit - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence the write is silently ignored in non-secure - mode. - - \details Assigns the given value to the Process Stack Pointer Limit (PSPLIM). - \param [in] ProcStackPtrLimit Process Stack Pointer Limit value to set - */ -__STATIC_FORCEINLINE void __set_PSPLIM(uint32_t ProcStackPtrLimit) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - (void)ProcStackPtrLimit; -#else - __ASM volatile ("MSR psplim, %0" : : "r" (ProcStackPtrLimit)); -#endif -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Process Stack Pointer (non-secure) - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence the write is silently ignored. - - \details Assigns the given value to the non-secure Process Stack Pointer Limit (PSPLIM) when in secure state. - \param [in] ProcStackPtrLimit Process Stack Pointer Limit value to set - */ -__STATIC_FORCEINLINE void __TZ_set_PSPLIM_NS(uint32_t ProcStackPtrLimit) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - (void)ProcStackPtrLimit; -#else - __ASM volatile ("MSR psplim_ns, %0\n" : : "r" (ProcStackPtrLimit)); -#endif -} -#endif - - -/** - \brief Get Main Stack Pointer Limit - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence zero is returned always in non-secure - mode. - - \details Returns the current value of the Main Stack Pointer Limit (MSPLIM). - \return MSPLIM Register value - */ -__STATIC_FORCEINLINE uint32_t __get_MSPLIM(void) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - return 0U; -#else - uint32_t result; - __ASM volatile ("MRS %0, msplim" : "=r" (result) ); - return result; -#endif -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Main Stack Pointer Limit (non-secure) - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence zero is returned always. - - \details Returns the current value of the non-secure Main Stack Pointer Limit(MSPLIM) when in secure state. - \return MSPLIM Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_MSPLIM_NS(void) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - return 0U; -#else - uint32_t result; - __ASM volatile ("MRS %0, msplim_ns" : "=r" (result) ); - return result; -#endif -} -#endif - - -/** - \brief Set Main Stack Pointer Limit - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence the write is silently ignored in non-secure - mode. - - \details Assigns the given value to the Main Stack Pointer Limit (MSPLIM). - \param [in] MainStackPtrLimit Main Stack Pointer Limit value to set - */ -__STATIC_FORCEINLINE void __set_MSPLIM(uint32_t MainStackPtrLimit) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - (void)MainStackPtrLimit; -#else - __ASM volatile ("MSR msplim, %0" : : "r" (MainStackPtrLimit)); -#endif -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Main Stack Pointer Limit (non-secure) - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence the write is silently ignored. - - \details Assigns the given value to the non-secure Main Stack Pointer Limit (MSPLIM) when in secure state. - \param [in] MainStackPtrLimit Main Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __TZ_set_MSPLIM_NS(uint32_t MainStackPtrLimit) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - (void)MainStackPtrLimit; -#else - __ASM volatile ("MSR msplim_ns, %0" : : "r" (MainStackPtrLimit)); -#endif -} -#endif - -#endif /* ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ - - -/** - \brief Get FPSCR - \details Returns the current value of the Floating Point Status/Control register. - \return Floating Point Status/Control register value - */ -__STATIC_FORCEINLINE uint32_t __get_FPSCR(void) -{ -#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ - (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) -#if __has_builtin(__builtin_arm_get_fpscr) -// Re-enable using built-in when GCC has been fixed -// || (__GNUC__ > 7) || (__GNUC__ == 7 && __GNUC_MINOR__ >= 2) - /* see https://gcc.gnu.org/ml/gcc-patches/2017-04/msg00443.html */ - return __builtin_arm_get_fpscr(); -#else - uint32_t result; - - __ASM volatile ("VMRS %0, fpscr" : "=r" (result) ); - return(result); -#endif -#else - return(0U); -#endif -} - - -/** - \brief Set FPSCR - \details Assigns the given value to the Floating Point Status/Control register. - \param [in] fpscr Floating Point Status/Control value to set - */ -__STATIC_FORCEINLINE void __set_FPSCR(uint32_t fpscr) -{ -#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ - (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) -#if __has_builtin(__builtin_arm_set_fpscr) -// Re-enable using built-in when GCC has been fixed -// || (__GNUC__ > 7) || (__GNUC__ == 7 && __GNUC_MINOR__ >= 2) - /* see https://gcc.gnu.org/ml/gcc-patches/2017-04/msg00443.html */ - __builtin_arm_set_fpscr(fpscr); -#else - __ASM volatile ("VMSR fpscr, %0" : : "r" (fpscr) : "vfpcc", "memory"); -#endif -#else - (void)fpscr; -#endif -} - - -/*@} end of CMSIS_Core_RegAccFunctions */ - - -/* ########################## Core Instruction Access ######################### */ -/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface - Access to dedicated instructions - @{ -*/ - -/* Define macros for porting to both thumb1 and thumb2. - * For thumb1, use low register (r0-r7), specified by constraint "l" - * Otherwise, use general registers, specified by constraint "r" */ -#if defined (__thumb__) && !defined (__thumb2__) -#define __CMSIS_GCC_OUT_REG(r) "=l" (r) -#define __CMSIS_GCC_RW_REG(r) "+l" (r) -#define __CMSIS_GCC_USE_REG(r) "l" (r) -#else -#define __CMSIS_GCC_OUT_REG(r) "=r" (r) -#define __CMSIS_GCC_RW_REG(r) "+r" (r) -#define __CMSIS_GCC_USE_REG(r) "r" (r) -#endif - -/** - \brief No Operation - \details No Operation does nothing. This instruction can be used for code alignment purposes. - */ -#define __NOP() __ASM volatile ("nop") - -/** - \brief Wait For Interrupt - \details Wait For Interrupt is a hint instruction that suspends execution until one of a number of events occurs. - */ -#define __WFI() __ASM volatile ("wfi") - - -/** - \brief Wait For Event - \details Wait For Event is a hint instruction that permits the processor to enter - a low-power state until one of a number of events occurs. - */ -#define __WFE() __ASM volatile ("wfe") - - -/** - \brief Send Event - \details Send Event is a hint instruction. It causes an event to be signaled to the CPU. - */ -#define __SEV() __ASM volatile ("sev") - - -/** - \brief Instruction Synchronization Barrier - \details Instruction Synchronization Barrier flushes the pipeline in the processor, - so that all instructions following the ISB are fetched from cache or memory, - after the instruction has been completed. - */ -__STATIC_FORCEINLINE void __ISB(void) -{ - __ASM volatile ("isb 0xF":::"memory"); -} - - -/** - \brief Data Synchronization Barrier - \details Acts as a special kind of Data Memory Barrier. - It completes when all explicit memory accesses before this instruction complete. - */ -__STATIC_FORCEINLINE void __DSB(void) -{ - __ASM volatile ("dsb 0xF":::"memory"); -} - - -/** - \brief Data Memory Barrier - \details Ensures the apparent order of the explicit memory operations before - and after the instruction, without ensuring their completion. - */ -__STATIC_FORCEINLINE void __DMB(void) -{ - __ASM volatile ("dmb 0xF":::"memory"); -} - - -/** - \brief Reverse byte order (32 bit) - \details Reverses the byte order in unsigned integer value. For example, 0x12345678 becomes 0x78563412. - \param [in] value Value to reverse - \return Reversed value - */ -__STATIC_FORCEINLINE uint32_t __REV(uint32_t value) -{ -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 5) - return __builtin_bswap32(value); -#else - uint32_t result; - - __ASM volatile ("rev %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); - return result; -#endif -} - - -/** - \brief Reverse byte order (16 bit) - \details Reverses the byte order within each halfword of a word. For example, 0x12345678 becomes 0x34127856. - \param [in] value Value to reverse - \return Reversed value - */ -__STATIC_FORCEINLINE uint32_t __REV16(uint32_t value) -{ - uint32_t result; - - __ASM volatile ("rev16 %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); - return result; -} - - -/** - \brief Reverse byte order (16 bit) - \details Reverses the byte order in a 16-bit value and returns the signed 16-bit result. For example, 0x0080 becomes 0x8000. - \param [in] value Value to reverse - \return Reversed value - */ -__STATIC_FORCEINLINE int16_t __REVSH(int16_t value) -{ -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) - return (int16_t)__builtin_bswap16(value); -#else - int16_t result; - - __ASM volatile ("revsh %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); - return result; -#endif -} - - -/** - \brief Rotate Right in unsigned value (32 bit) - \details Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits. - \param [in] op1 Value to rotate - \param [in] op2 Number of Bits to rotate - \return Rotated value - */ -__STATIC_FORCEINLINE uint32_t __ROR(uint32_t op1, uint32_t op2) -{ - op2 %= 32U; - if (op2 == 0U) - { - return op1; - } - return (op1 >> op2) | (op1 << (32U - op2)); -} - - -/** - \brief Breakpoint - \details Causes the processor to enter Debug state. - Debug tools can use this to investigate system state when the instruction at a particular address is reached. - \param [in] value is ignored by the processor. - If required, a debugger can use it to store additional information about the breakpoint. - */ -#define __BKPT(value) __ASM volatile ("bkpt "#value) - - -/** - \brief Reverse bit order of value - \details Reverses the bit order of the given value. - \param [in] value Value to reverse - \return Reversed value - */ -__STATIC_FORCEINLINE uint32_t __RBIT(uint32_t value) -{ - uint32_t result; - -#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) - __ASM volatile ("rbit %0, %1" : "=r" (result) : "r" (value) ); -#else - uint32_t s = (4U /*sizeof(v)*/ * 8U) - 1U; /* extra shift needed at end */ - - result = value; /* r will be reversed bits of v; first get LSB of v */ - for (value >>= 1U; value != 0U; value >>= 1U) - { - result <<= 1U; - result |= value & 1U; - s--; - } - result <<= s; /* shift when v's highest bits are zero */ -#endif - return result; -} - - -/** - \brief Count leading zeros - \details Counts the number of leading zeros of a data value. - \param [in] value Value to count the leading zeros - \return number of leading zeros in value - */ -__STATIC_FORCEINLINE uint8_t __CLZ(uint32_t value) -{ - /* Even though __builtin_clz produces a CLZ instruction on ARM, formally - __builtin_clz(0) is undefined behaviour, so handle this case specially. - This guarantees ARM-compatible results if happening to compile on a non-ARM - target, and ensures the compiler doesn't decide to activate any - optimisations using the logic "value was passed to __builtin_clz, so it - is non-zero". - ARM GCC 7.3 and possibly earlier will optimise this test away, leaving a - single CLZ instruction. - */ - if (value == 0U) - { - return 32U; - } - return __builtin_clz(value); -} - - -#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) -/** - \brief LDR Exclusive (8 bit) - \details Executes a exclusive LDR instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -__STATIC_FORCEINLINE uint8_t __LDREXB(volatile uint8_t *addr) -{ - uint32_t result; - -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) - __ASM volatile ("ldrexb %0, %1" : "=r" (result) : "Q" (*addr) ); -#else - /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not - accepted by assembler. So has to use following less efficient pattern. - */ - __ASM volatile ("ldrexb %0, [%1]" : "=r" (result) : "r" (addr) : "memory" ); -#endif - return ((uint8_t) result); /* Add explicit type cast here */ -} - - -/** - \brief LDR Exclusive (16 bit) - \details Executes a exclusive LDR instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -__STATIC_FORCEINLINE uint16_t __LDREXH(volatile uint16_t *addr) -{ - uint32_t result; - -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) - __ASM volatile ("ldrexh %0, %1" : "=r" (result) : "Q" (*addr) ); -#else - /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not - accepted by assembler. So has to use following less efficient pattern. - */ - __ASM volatile ("ldrexh %0, [%1]" : "=r" (result) : "r" (addr) : "memory" ); -#endif - return ((uint16_t) result); /* Add explicit type cast here */ -} - - -/** - \brief LDR Exclusive (32 bit) - \details Executes a exclusive LDR instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -__STATIC_FORCEINLINE uint32_t __LDREXW(volatile uint32_t *addr) -{ - uint32_t result; - - __ASM volatile ("ldrex %0, %1" : "=r" (result) : "Q" (*addr) ); - return(result); -} - - -/** - \brief STR Exclusive (8 bit) - \details Executes a exclusive STR instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__STATIC_FORCEINLINE uint32_t __STREXB(uint8_t value, volatile uint8_t *addr) -{ - uint32_t result; - - __ASM volatile ("strexb %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" ((uint32_t)value) ); - return(result); -} - - -/** - \brief STR Exclusive (16 bit) - \details Executes a exclusive STR instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__STATIC_FORCEINLINE uint32_t __STREXH(uint16_t value, volatile uint16_t *addr) -{ - uint32_t result; - - __ASM volatile ("strexh %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" ((uint32_t)value) ); - return(result); -} - - -/** - \brief STR Exclusive (32 bit) - \details Executes a exclusive STR instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__STATIC_FORCEINLINE uint32_t __STREXW(uint32_t value, volatile uint32_t *addr) -{ - uint32_t result; - - __ASM volatile ("strex %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" (value) ); - return(result); -} - - -/** - \brief Remove the exclusive lock - \details Removes the exclusive lock which is created by LDREX. - */ -__STATIC_FORCEINLINE void __CLREX(void) -{ - __ASM volatile ("clrex" ::: "memory"); -} - -#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ - - -#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) -/** - \brief Signed Saturate - \details Saturates a signed value. - \param [in] ARG1 Value to be saturated - \param [in] ARG2 Bit position to saturate to (1..32) - \return Saturated value - */ -#define __SSAT(ARG1,ARG2) \ -__extension__ \ -({ \ - int32_t __RES, __ARG1 = (ARG1); \ - __ASM ("ssat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ - __RES; \ - }) - - -/** - \brief Unsigned Saturate - \details Saturates an unsigned value. - \param [in] ARG1 Value to be saturated - \param [in] ARG2 Bit position to saturate to (0..31) - \return Saturated value - */ -#define __USAT(ARG1,ARG2) \ - __extension__ \ -({ \ - uint32_t __RES, __ARG1 = (ARG1); \ - __ASM ("usat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ - __RES; \ - }) - - -/** - \brief Rotate Right with Extend (32 bit) - \details Moves each bit of a bitstring right by one bit. - The carry input is shifted in at the left end of the bitstring. - \param [in] value Value to rotate - \return Rotated value - */ -__STATIC_FORCEINLINE uint32_t __RRX(uint32_t value) -{ - uint32_t result; - - __ASM volatile ("rrx %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); - return(result); -} - - -/** - \brief LDRT Unprivileged (8 bit) - \details Executes a Unprivileged LDRT instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -__STATIC_FORCEINLINE uint8_t __LDRBT(volatile uint8_t *ptr) -{ - uint32_t result; - -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) - __ASM volatile ("ldrbt %0, %1" : "=r" (result) : "Q" (*ptr) ); -#else - /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not - accepted by assembler. So has to use following less efficient pattern. - */ - __ASM volatile ("ldrbt %0, [%1]" : "=r" (result) : "r" (ptr) : "memory" ); -#endif - return ((uint8_t) result); /* Add explicit type cast here */ -} - - -/** - \brief LDRT Unprivileged (16 bit) - \details Executes a Unprivileged LDRT instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -__STATIC_FORCEINLINE uint16_t __LDRHT(volatile uint16_t *ptr) -{ - uint32_t result; - -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) - __ASM volatile ("ldrht %0, %1" : "=r" (result) : "Q" (*ptr) ); -#else - /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not - accepted by assembler. So has to use following less efficient pattern. - */ - __ASM volatile ("ldrht %0, [%1]" : "=r" (result) : "r" (ptr) : "memory" ); -#endif - return ((uint16_t) result); /* Add explicit type cast here */ -} - - -/** - \brief LDRT Unprivileged (32 bit) - \details Executes a Unprivileged LDRT instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -__STATIC_FORCEINLINE uint32_t __LDRT(volatile uint32_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldrt %0, %1" : "=r" (result) : "Q" (*ptr) ); - return(result); -} - - -/** - \brief STRT Unprivileged (8 bit) - \details Executes a Unprivileged STRT instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STRBT(uint8_t value, volatile uint8_t *ptr) -{ - __ASM volatile ("strbt %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief STRT Unprivileged (16 bit) - \details Executes a Unprivileged STRT instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STRHT(uint16_t value, volatile uint16_t *ptr) -{ - __ASM volatile ("strht %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief STRT Unprivileged (32 bit) - \details Executes a Unprivileged STRT instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STRT(uint32_t value, volatile uint32_t *ptr) -{ - __ASM volatile ("strt %1, %0" : "=Q" (*ptr) : "r" (value) ); -} - -#else /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ - -/** - \brief Signed Saturate - \details Saturates a signed value. - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (1..32) - \return Saturated value - */ -__STATIC_FORCEINLINE int32_t __SSAT(int32_t val, uint32_t sat) -{ - if ((sat >= 1U) && (sat <= 32U)) - { - const int32_t max = (int32_t)((1U << (sat - 1U)) - 1U); - const int32_t min = -1 - max ; - if (val > max) - { - return max; - } - else if (val < min) - { - return min; - } - } - return val; -} - -/** - \brief Unsigned Saturate - \details Saturates an unsigned value. - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (0..31) - \return Saturated value - */ -__STATIC_FORCEINLINE uint32_t __USAT(int32_t val, uint32_t sat) -{ - if (sat <= 31U) - { - const uint32_t max = ((1U << sat) - 1U); - if (val > (int32_t)max) - { - return max; - } - else if (val < 0) - { - return 0U; - } - } - return (uint32_t)val; -} - -#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ - - -#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) -/** - \brief Load-Acquire (8 bit) - \details Executes a LDAB instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -__STATIC_FORCEINLINE uint8_t __LDAB(volatile uint8_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldab %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint8_t) result); -} - - -/** - \brief Load-Acquire (16 bit) - \details Executes a LDAH instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -__STATIC_FORCEINLINE uint16_t __LDAH(volatile uint16_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldah %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint16_t) result); -} - - -/** - \brief Load-Acquire (32 bit) - \details Executes a LDA instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -__STATIC_FORCEINLINE uint32_t __LDA(volatile uint32_t *ptr) -{ - uint32_t result; - - __ASM volatile ("lda %0, %1" : "=r" (result) : "Q" (*ptr) ); - return(result); -} - - -/** - \brief Store-Release (8 bit) - \details Executes a STLB instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STLB(uint8_t value, volatile uint8_t *ptr) -{ - __ASM volatile ("stlb %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief Store-Release (16 bit) - \details Executes a STLH instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STLH(uint16_t value, volatile uint16_t *ptr) -{ - __ASM volatile ("stlh %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief Store-Release (32 bit) - \details Executes a STL instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STL(uint32_t value, volatile uint32_t *ptr) -{ - __ASM volatile ("stl %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief Load-Acquire Exclusive (8 bit) - \details Executes a LDAB exclusive instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -__STATIC_FORCEINLINE uint8_t __LDAEXB(volatile uint8_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldaexb %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint8_t) result); -} - - -/** - \brief Load-Acquire Exclusive (16 bit) - \details Executes a LDAH exclusive instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -__STATIC_FORCEINLINE uint16_t __LDAEXH(volatile uint16_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldaexh %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint16_t) result); -} - - -/** - \brief Load-Acquire Exclusive (32 bit) - \details Executes a LDA exclusive instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -__STATIC_FORCEINLINE uint32_t __LDAEX(volatile uint32_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldaex %0, %1" : "=r" (result) : "Q" (*ptr) ); - return(result); -} - - -/** - \brief Store-Release Exclusive (8 bit) - \details Executes a STLB exclusive instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__STATIC_FORCEINLINE uint32_t __STLEXB(uint8_t value, volatile uint8_t *ptr) -{ - uint32_t result; - - __ASM volatile ("stlexb %0, %2, %1" : "=&r" (result), "=Q" (*ptr) : "r" ((uint32_t)value) ); - return(result); -} - - -/** - \brief Store-Release Exclusive (16 bit) - \details Executes a STLH exclusive instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__STATIC_FORCEINLINE uint32_t __STLEXH(uint16_t value, volatile uint16_t *ptr) -{ - uint32_t result; - - __ASM volatile ("stlexh %0, %2, %1" : "=&r" (result), "=Q" (*ptr) : "r" ((uint32_t)value) ); - return(result); -} - - -/** - \brief Store-Release Exclusive (32 bit) - \details Executes a STL exclusive instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__STATIC_FORCEINLINE uint32_t __STLEX(uint32_t value, volatile uint32_t *ptr) -{ - uint32_t result; - - __ASM volatile ("stlex %0, %2, %1" : "=&r" (result), "=Q" (*ptr) : "r" ((uint32_t)value) ); - return(result); -} - -#endif /* ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ - -/*@}*/ /* end of group CMSIS_Core_InstructionInterface */ - - -/* ################### Compiler specific Intrinsics ########################### */ -/** \defgroup CMSIS_SIMD_intrinsics CMSIS SIMD Intrinsics - Access to dedicated SIMD instructions - @{ -*/ - -#if (defined (__ARM_FEATURE_DSP) && (__ARM_FEATURE_DSP == 1)) - -__STATIC_FORCEINLINE uint32_t __SADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - - -__STATIC_FORCEINLINE uint32_t __SSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("ssub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - - -__STATIC_FORCEINLINE uint32_t __SADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("ssub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("ssax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USAD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usad8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USADA8(uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("usada8 %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -#define __SSAT16(ARG1,ARG2) \ -({ \ - int32_t __RES, __ARG1 = (ARG1); \ - __ASM ("ssat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ - __RES; \ - }) - -#define __USAT16(ARG1,ARG2) \ -({ \ - uint32_t __RES, __ARG1 = (ARG1); \ - __ASM ("usat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ - __RES; \ - }) - -__STATIC_FORCEINLINE uint32_t __UXTB16(uint32_t op1) -{ - uint32_t result; - - __ASM volatile ("uxtb16 %0, %1" : "=r" (result) : "r" (op1)); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UXTAB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SXTB16(uint32_t op1) -{ - uint32_t result; - - __ASM volatile ("sxtb16 %0, %1" : "=r" (result) : "r" (op1)); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SXTAB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMUAD (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smuad %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMUADX (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smuadx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMLAD (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smlad %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMLADX (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smladx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__STATIC_FORCEINLINE uint64_t __SMLALD (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__STATIC_FORCEINLINE uint64_t __SMLALDX (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__STATIC_FORCEINLINE uint32_t __SMUSD (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smusd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMUSDX (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smusdx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMLSD (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smlsd %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMLSDX (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smlsdx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__STATIC_FORCEINLINE uint64_t __SMLSLD (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__STATIC_FORCEINLINE uint64_t __SMLSLDX (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__STATIC_FORCEINLINE uint32_t __SEL (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sel %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE int32_t __QADD( int32_t op1, int32_t op2) -{ - int32_t result; - - __ASM volatile ("qadd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE int32_t __QSUB( int32_t op1, int32_t op2) -{ - int32_t result; - - __ASM volatile ("qsub %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -#if 0 -#define __PKHBT(ARG1,ARG2,ARG3) \ -({ \ - uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \ - __ASM ("pkhbt %0, %1, %2, lsl %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \ - __RES; \ - }) - -#define __PKHTB(ARG1,ARG2,ARG3) \ -({ \ - uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \ - if (ARG3 == 0) \ - __ASM ("pkhtb %0, %1, %2" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2) ); \ - else \ - __ASM ("pkhtb %0, %1, %2, asr %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \ - __RES; \ - }) -#endif - -#define __PKHBT(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0x0000FFFFUL) | \ - ((((uint32_t)(ARG2)) << (ARG3)) & 0xFFFF0000UL) ) - -#define __PKHTB(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0xFFFF0000UL) | \ - ((((uint32_t)(ARG2)) >> (ARG3)) & 0x0000FFFFUL) ) - -__STATIC_FORCEINLINE int32_t __SMMLA (int32_t op1, int32_t op2, int32_t op3) -{ - int32_t result; - - __ASM volatile ("smmla %0, %1, %2, %3" : "=r" (result): "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -#endif /* (__ARM_FEATURE_DSP == 1) */ -/*@} end of group CMSIS_SIMD_intrinsics */ - - -#pragma GCC diagnostic pop - -#endif /* __CMSIS_GCC_H */ - diff --git a/panda/board/stm32h7/inc/cmsis_version.h b/panda/board/stm32h7/inc/cmsis_version.h deleted file mode 100644 index bf57cf3e8..000000000 --- a/panda/board/stm32h7/inc/cmsis_version.h +++ /dev/null @@ -1,40 +0,0 @@ -/**************************************************************************//** - * @file cmsis_version.h - * @brief CMSIS Core(M) Version definitions - * @version V5.0.3 - * @date 24. June 2019 - ******************************************************************************/ -/* - * Copyright (c) 2009-2019 ARM Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed under the Apache License, Version 2.0 (the License); you may - * not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an AS IS BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined (__clang__) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef __CMSIS_VERSION_H -#define __CMSIS_VERSION_H - -/* CMSIS Version definitions */ -#define __CM_CMSIS_VERSION_MAIN ( 5U) /*!< [31:16] CMSIS Core(M) main version */ -#define __CM_CMSIS_VERSION_SUB ( 3U) /*!< [15:0] CMSIS Core(M) sub version */ -#define __CM_CMSIS_VERSION ((__CM_CMSIS_VERSION_MAIN << 16U) | \ - __CM_CMSIS_VERSION_SUB ) /*!< CMSIS Core(M) version number */ -#endif - diff --git a/panda/board/stm32h7/inc/core_cm7.h b/panda/board/stm32h7/inc/core_cm7.h deleted file mode 100644 index 3da3c43e4..000000000 --- a/panda/board/stm32h7/inc/core_cm7.h +++ /dev/null @@ -1,2725 +0,0 @@ -/**************************************************************************//** - * @file core_cm7.h - * @brief CMSIS Cortex-M7 Core Peripheral Access Layer Header File - * @version V5.1.1 - * @date 28. March 2019 - ******************************************************************************/ -/* - * Copyright (c) 2009-2019 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed under the Apache License, Version 2.0 (the License); you may - * not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an AS IS BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined (__clang__) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef __CORE_CM7_H_GENERIC -#define __CORE_CM7_H_GENERIC - -#include - -#ifdef __cplusplus - extern "C" { -#endif - -/** - \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions - CMSIS violates the following MISRA-C:2004 rules: - - \li Required Rule 8.5, object/function definition in header file.
- Function definitions in header files are used to allow 'inlining'. - - \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
- Unions are used for effective representation of core registers. - - \li Advisory Rule 19.7, Function-like macro defined.
- Function-like macros are used to allow more efficient code. - */ - - -/******************************************************************************* - * CMSIS definitions - ******************************************************************************/ -/** - \ingroup Cortex_M7 - @{ - */ - -#include "cmsis_version.h" - -/* CMSIS CM7 definitions */ -#define __CM7_CMSIS_VERSION_MAIN (__CM_CMSIS_VERSION_MAIN) /*!< \deprecated [31:16] CMSIS HAL main version */ -#define __CM7_CMSIS_VERSION_SUB ( __CM_CMSIS_VERSION_SUB) /*!< \deprecated [15:0] CMSIS HAL sub version */ -#define __CM7_CMSIS_VERSION ((__CM7_CMSIS_VERSION_MAIN << 16U) | \ - __CM7_CMSIS_VERSION_SUB ) /*!< \deprecated CMSIS HAL version number */ - -#define __CORTEX_M (7U) /*!< Cortex-M Core */ - -/** __FPU_USED indicates whether an FPU is used or not. - For this, __FPU_PRESENT has to be checked prior to making use of FPU specific registers and functions. -*/ -#if defined ( __CC_ARM ) - #if defined __TARGET_FPU_VFP - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) - #if defined __ARM_FP - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __GNUC__ ) - #if defined (__VFP_FP__) && !defined(__SOFTFP__) - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __ICCARM__ ) - #if defined __ARMVFP__ - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __TI_ARM__ ) - #if defined __TI_VFP_SUPPORT__ - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __TASKING__ ) - #if defined __FPU_VFP__ - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __CSMC__ ) - #if ( __CSMC__ & 0x400U) - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#endif - -#include "cmsis_compiler.h" /* CMSIS compiler specific defines */ - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_CM7_H_GENERIC */ - -#ifndef __CMSIS_GENERIC - -#ifndef __CORE_CM7_H_DEPENDANT -#define __CORE_CM7_H_DEPENDANT - -#ifdef __cplusplus - extern "C" { -#endif - -/* check device defines and use defaults */ -#if defined __CHECK_DEVICE_DEFINES - #ifndef __CM7_REV - #define __CM7_REV 0x0000U - #warning "__CM7_REV not defined in device header file; using default!" - #endif - - #ifndef __FPU_PRESENT - #define __FPU_PRESENT 0U - #warning "__FPU_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __MPU_PRESENT - #define __MPU_PRESENT 0U - #warning "__MPU_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __ICACHE_PRESENT - #define __ICACHE_PRESENT 0U - #warning "__ICACHE_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __DCACHE_PRESENT - #define __DCACHE_PRESENT 0U - #warning "__DCACHE_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __DTCM_PRESENT - #define __DTCM_PRESENT 0U - #warning "__DTCM_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __NVIC_PRIO_BITS - #define __NVIC_PRIO_BITS 3U - #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" - #endif - - #ifndef __Vendor_SysTickConfig - #define __Vendor_SysTickConfig 0U - #warning "__Vendor_SysTickConfig not defined in device header file; using default!" - #endif -#endif - -/* IO definitions (access restrictions to peripheral registers) */ -/** - \defgroup CMSIS_glob_defs CMSIS Global Defines - - IO Type Qualifiers are used - \li to specify the access to peripheral variables. - \li for automatic generation of peripheral register debug information. -*/ -#ifdef __cplusplus - #define __I volatile /*!< Defines 'read only' permissions */ -#else - #define __I volatile const /*!< Defines 'read only' permissions */ -#endif -#define __O volatile /*!< Defines 'write only' permissions */ -#define __IO volatile /*!< Defines 'read / write' permissions */ - -/* following defines should be used for structure members */ -#define __IM volatile const /*! Defines 'read only' structure member permissions */ -#define __OM volatile /*! Defines 'write only' structure member permissions */ -#define __IOM volatile /*! Defines 'read / write' structure member permissions */ - -/*@} end of group Cortex_M7 */ - - - -/******************************************************************************* - * Register Abstraction - Core Register contain: - - Core Register - - Core NVIC Register - - Core SCB Register - - Core SysTick Register - - Core Debug Register - - Core MPU Register - - Core FPU Register - ******************************************************************************/ -/** - \defgroup CMSIS_core_register Defines and Type Definitions - \brief Type definitions and defines for Cortex-M processor based devices. -*/ - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CORE Status and Control Registers - \brief Core Register type definitions. - @{ - */ - -/** - \brief Union type to access the Application Program Status Register (APSR). - */ -typedef union -{ - struct - { - uint32_t _reserved0:16; /*!< bit: 0..15 Reserved */ - uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ - uint32_t _reserved1:7; /*!< bit: 20..26 Reserved */ - uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} APSR_Type; - -/* APSR Register Definitions */ -#define APSR_N_Pos 31U /*!< APSR: N Position */ -#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ - -#define APSR_Z_Pos 30U /*!< APSR: Z Position */ -#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ - -#define APSR_C_Pos 29U /*!< APSR: C Position */ -#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ - -#define APSR_V_Pos 28U /*!< APSR: V Position */ -#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ - -#define APSR_Q_Pos 27U /*!< APSR: Q Position */ -#define APSR_Q_Msk (1UL << APSR_Q_Pos) /*!< APSR: Q Mask */ - -#define APSR_GE_Pos 16U /*!< APSR: GE Position */ -#define APSR_GE_Msk (0xFUL << APSR_GE_Pos) /*!< APSR: GE Mask */ - - -/** - \brief Union type to access the Interrupt Program Status Register (IPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} IPSR_Type; - -/* IPSR Register Definitions */ -#define IPSR_ISR_Pos 0U /*!< IPSR: ISR Position */ -#define IPSR_ISR_Msk (0x1FFUL /*<< IPSR_ISR_Pos*/) /*!< IPSR: ISR Mask */ - - -/** - \brief Union type to access the Special-Purpose Program Status Registers (xPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:1; /*!< bit: 9 Reserved */ - uint32_t ICI_IT_1:6; /*!< bit: 10..15 ICI/IT part 1 */ - uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ - uint32_t _reserved1:4; /*!< bit: 20..23 Reserved */ - uint32_t T:1; /*!< bit: 24 Thumb bit */ - uint32_t ICI_IT_2:2; /*!< bit: 25..26 ICI/IT part 2 */ - uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} xPSR_Type; - -/* xPSR Register Definitions */ -#define xPSR_N_Pos 31U /*!< xPSR: N Position */ -#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ - -#define xPSR_Z_Pos 30U /*!< xPSR: Z Position */ -#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ - -#define xPSR_C_Pos 29U /*!< xPSR: C Position */ -#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ - -#define xPSR_V_Pos 28U /*!< xPSR: V Position */ -#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ - -#define xPSR_Q_Pos 27U /*!< xPSR: Q Position */ -#define xPSR_Q_Msk (1UL << xPSR_Q_Pos) /*!< xPSR: Q Mask */ - -#define xPSR_ICI_IT_2_Pos 25U /*!< xPSR: ICI/IT part 2 Position */ -#define xPSR_ICI_IT_2_Msk (3UL << xPSR_ICI_IT_2_Pos) /*!< xPSR: ICI/IT part 2 Mask */ - -#define xPSR_T_Pos 24U /*!< xPSR: T Position */ -#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ - -#define xPSR_GE_Pos 16U /*!< xPSR: GE Position */ -#define xPSR_GE_Msk (0xFUL << xPSR_GE_Pos) /*!< xPSR: GE Mask */ - -#define xPSR_ICI_IT_1_Pos 10U /*!< xPSR: ICI/IT part 1 Position */ -#define xPSR_ICI_IT_1_Msk (0x3FUL << xPSR_ICI_IT_1_Pos) /*!< xPSR: ICI/IT part 1 Mask */ - -#define xPSR_ISR_Pos 0U /*!< xPSR: ISR Position */ -#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ - - -/** - \brief Union type to access the Control Registers (CONTROL). - */ -typedef union -{ - struct - { - uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */ - uint32_t SPSEL:1; /*!< bit: 1 Stack to be used */ - uint32_t FPCA:1; /*!< bit: 2 FP extension active flag */ - uint32_t _reserved0:29; /*!< bit: 3..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} CONTROL_Type; - -/* CONTROL Register Definitions */ -#define CONTROL_FPCA_Pos 2U /*!< CONTROL: FPCA Position */ -#define CONTROL_FPCA_Msk (1UL << CONTROL_FPCA_Pos) /*!< CONTROL: FPCA Mask */ - -#define CONTROL_SPSEL_Pos 1U /*!< CONTROL: SPSEL Position */ -#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ - -#define CONTROL_nPRIV_Pos 0U /*!< CONTROL: nPRIV Position */ -#define CONTROL_nPRIV_Msk (1UL /*<< CONTROL_nPRIV_Pos*/) /*!< CONTROL: nPRIV Mask */ - -/*@} end of group CMSIS_CORE */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC) - \brief Type definitions for the NVIC Registers - @{ - */ - -/** - \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). - */ -typedef struct -{ - __IOM uint32_t ISER[8U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ - uint32_t RESERVED0[24U]; - __IOM uint32_t ICER[8U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ - uint32_t RESERVED1[24U]; - __IOM uint32_t ISPR[8U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ - uint32_t RESERVED2[24U]; - __IOM uint32_t ICPR[8U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ - uint32_t RESERVED3[24U]; - __IOM uint32_t IABR[8U]; /*!< Offset: 0x200 (R/W) Interrupt Active bit Register */ - uint32_t RESERVED4[56U]; - __IOM uint8_t IP[240U]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register (8Bit wide) */ - uint32_t RESERVED5[644U]; - __OM uint32_t STIR; /*!< Offset: 0xE00 ( /W) Software Trigger Interrupt Register */ -} NVIC_Type; - -/* Software Triggered Interrupt Register Definitions */ -#define NVIC_STIR_INTID_Pos 0U /*!< STIR: INTLINESNUM Position */ -#define NVIC_STIR_INTID_Msk (0x1FFUL /*<< NVIC_STIR_INTID_Pos*/) /*!< STIR: INTLINESNUM Mask */ - -/*@} end of group CMSIS_NVIC */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SCB System Control Block (SCB) - \brief Type definitions for the System Control Block Registers - @{ - */ - -/** - \brief Structure type to access the System Control Block (SCB). - */ -typedef struct -{ - __IM uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ - __IOM uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ - __IOM uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ - __IOM uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ - __IOM uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ - __IOM uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ - __IOM uint8_t SHPR[12U]; /*!< Offset: 0x018 (R/W) System Handlers Priority Registers (4-7, 8-11, 12-15) */ - __IOM uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ - __IOM uint32_t CFSR; /*!< Offset: 0x028 (R/W) Configurable Fault Status Register */ - __IOM uint32_t HFSR; /*!< Offset: 0x02C (R/W) HardFault Status Register */ - __IOM uint32_t DFSR; /*!< Offset: 0x030 (R/W) Debug Fault Status Register */ - __IOM uint32_t MMFAR; /*!< Offset: 0x034 (R/W) MemManage Fault Address Register */ - __IOM uint32_t BFAR; /*!< Offset: 0x038 (R/W) BusFault Address Register */ - __IOM uint32_t AFSR; /*!< Offset: 0x03C (R/W) Auxiliary Fault Status Register */ - __IM uint32_t ID_PFR[2U]; /*!< Offset: 0x040 (R/ ) Processor Feature Register */ - __IM uint32_t ID_DFR; /*!< Offset: 0x048 (R/ ) Debug Feature Register */ - __IM uint32_t ID_AFR; /*!< Offset: 0x04C (R/ ) Auxiliary Feature Register */ - __IM uint32_t ID_MFR[4U]; /*!< Offset: 0x050 (R/ ) Memory Model Feature Register */ - __IM uint32_t ID_ISAR[5U]; /*!< Offset: 0x060 (R/ ) Instruction Set Attributes Register */ - uint32_t RESERVED0[1U]; - __IM uint32_t CLIDR; /*!< Offset: 0x078 (R/ ) Cache Level ID register */ - __IM uint32_t CTR; /*!< Offset: 0x07C (R/ ) Cache Type register */ - __IM uint32_t CCSIDR; /*!< Offset: 0x080 (R/ ) Cache Size ID Register */ - __IOM uint32_t CSSELR; /*!< Offset: 0x084 (R/W) Cache Size Selection Register */ - __IOM uint32_t CPACR; /*!< Offset: 0x088 (R/W) Coprocessor Access Control Register */ - uint32_t RESERVED3[93U]; - __OM uint32_t STIR; /*!< Offset: 0x200 ( /W) Software Triggered Interrupt Register */ - uint32_t RESERVED4[15U]; - __IM uint32_t MVFR0; /*!< Offset: 0x240 (R/ ) Media and VFP Feature Register 0 */ - __IM uint32_t MVFR1; /*!< Offset: 0x244 (R/ ) Media and VFP Feature Register 1 */ - __IM uint32_t MVFR2; /*!< Offset: 0x248 (R/ ) Media and VFP Feature Register 2 */ - uint32_t RESERVED5[1U]; - __OM uint32_t ICIALLU; /*!< Offset: 0x250 ( /W) I-Cache Invalidate All to PoU */ - uint32_t RESERVED6[1U]; - __OM uint32_t ICIMVAU; /*!< Offset: 0x258 ( /W) I-Cache Invalidate by MVA to PoU */ - __OM uint32_t DCIMVAC; /*!< Offset: 0x25C ( /W) D-Cache Invalidate by MVA to PoC */ - __OM uint32_t DCISW; /*!< Offset: 0x260 ( /W) D-Cache Invalidate by Set-way */ - __OM uint32_t DCCMVAU; /*!< Offset: 0x264 ( /W) D-Cache Clean by MVA to PoU */ - __OM uint32_t DCCMVAC; /*!< Offset: 0x268 ( /W) D-Cache Clean by MVA to PoC */ - __OM uint32_t DCCSW; /*!< Offset: 0x26C ( /W) D-Cache Clean by Set-way */ - __OM uint32_t DCCIMVAC; /*!< Offset: 0x270 ( /W) D-Cache Clean and Invalidate by MVA to PoC */ - __OM uint32_t DCCISW; /*!< Offset: 0x274 ( /W) D-Cache Clean and Invalidate by Set-way */ - uint32_t RESERVED7[6U]; - __IOM uint32_t ITCMCR; /*!< Offset: 0x290 (R/W) Instruction Tightly-Coupled Memory Control Register */ - __IOM uint32_t DTCMCR; /*!< Offset: 0x294 (R/W) Data Tightly-Coupled Memory Control Registers */ - __IOM uint32_t AHBPCR; /*!< Offset: 0x298 (R/W) AHBP Control Register */ - __IOM uint32_t CACR; /*!< Offset: 0x29C (R/W) L1 Cache Control Register */ - __IOM uint32_t AHBSCR; /*!< Offset: 0x2A0 (R/W) AHB Slave Control Register */ - uint32_t RESERVED8[1U]; - __IOM uint32_t ABFSR; /*!< Offset: 0x2A8 (R/W) Auxiliary Bus Fault Status Register */ -} SCB_Type; - -/* SCB CPUID Register Definitions */ -#define SCB_CPUID_IMPLEMENTER_Pos 24U /*!< SCB CPUID: IMPLEMENTER Position */ -#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ - -#define SCB_CPUID_VARIANT_Pos 20U /*!< SCB CPUID: VARIANT Position */ -#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ - -#define SCB_CPUID_ARCHITECTURE_Pos 16U /*!< SCB CPUID: ARCHITECTURE Position */ -#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ - -#define SCB_CPUID_PARTNO_Pos 4U /*!< SCB CPUID: PARTNO Position */ -#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ - -#define SCB_CPUID_REVISION_Pos 0U /*!< SCB CPUID: REVISION Position */ -#define SCB_CPUID_REVISION_Msk (0xFUL /*<< SCB_CPUID_REVISION_Pos*/) /*!< SCB CPUID: REVISION Mask */ - -/* SCB Interrupt Control State Register Definitions */ -#define SCB_ICSR_NMIPENDSET_Pos 31U /*!< SCB ICSR: NMIPENDSET Position */ -#define SCB_ICSR_NMIPENDSET_Msk (1UL << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */ - -#define SCB_ICSR_PENDSVSET_Pos 28U /*!< SCB ICSR: PENDSVSET Position */ -#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ - -#define SCB_ICSR_PENDSVCLR_Pos 27U /*!< SCB ICSR: PENDSVCLR Position */ -#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ - -#define SCB_ICSR_PENDSTSET_Pos 26U /*!< SCB ICSR: PENDSTSET Position */ -#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ - -#define SCB_ICSR_PENDSTCLR_Pos 25U /*!< SCB ICSR: PENDSTCLR Position */ -#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ - -#define SCB_ICSR_ISRPREEMPT_Pos 23U /*!< SCB ICSR: ISRPREEMPT Position */ -#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ - -#define SCB_ICSR_ISRPENDING_Pos 22U /*!< SCB ICSR: ISRPENDING Position */ -#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ - -#define SCB_ICSR_VECTPENDING_Pos 12U /*!< SCB ICSR: VECTPENDING Position */ -#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ - -#define SCB_ICSR_RETTOBASE_Pos 11U /*!< SCB ICSR: RETTOBASE Position */ -#define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */ - -#define SCB_ICSR_VECTACTIVE_Pos 0U /*!< SCB ICSR: VECTACTIVE Position */ -#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */ - -/* SCB Vector Table Offset Register Definitions */ -#define SCB_VTOR_TBLOFF_Pos 7U /*!< SCB VTOR: TBLOFF Position */ -#define SCB_VTOR_TBLOFF_Msk (0x1FFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ - -/* SCB Application Interrupt and Reset Control Register Definitions */ -#define SCB_AIRCR_VECTKEY_Pos 16U /*!< SCB AIRCR: VECTKEY Position */ -#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ - -#define SCB_AIRCR_VECTKEYSTAT_Pos 16U /*!< SCB AIRCR: VECTKEYSTAT Position */ -#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ - -#define SCB_AIRCR_ENDIANESS_Pos 15U /*!< SCB AIRCR: ENDIANESS Position */ -#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ - -#define SCB_AIRCR_PRIGROUP_Pos 8U /*!< SCB AIRCR: PRIGROUP Position */ -#define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */ - -#define SCB_AIRCR_SYSRESETREQ_Pos 2U /*!< SCB AIRCR: SYSRESETREQ Position */ -#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ - -#define SCB_AIRCR_VECTCLRACTIVE_Pos 1U /*!< SCB AIRCR: VECTCLRACTIVE Position */ -#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ - -#define SCB_AIRCR_VECTRESET_Pos 0U /*!< SCB AIRCR: VECTRESET Position */ -#define SCB_AIRCR_VECTRESET_Msk (1UL /*<< SCB_AIRCR_VECTRESET_Pos*/) /*!< SCB AIRCR: VECTRESET Mask */ - -/* SCB System Control Register Definitions */ -#define SCB_SCR_SEVONPEND_Pos 4U /*!< SCB SCR: SEVONPEND Position */ -#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ - -#define SCB_SCR_SLEEPDEEP_Pos 2U /*!< SCB SCR: SLEEPDEEP Position */ -#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ - -#define SCB_SCR_SLEEPONEXIT_Pos 1U /*!< SCB SCR: SLEEPONEXIT Position */ -#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ - -/* SCB Configuration Control Register Definitions */ -#define SCB_CCR_BP_Pos 18U /*!< SCB CCR: Branch prediction enable bit Position */ -#define SCB_CCR_BP_Msk (1UL << SCB_CCR_BP_Pos) /*!< SCB CCR: Branch prediction enable bit Mask */ - -#define SCB_CCR_IC_Pos 17U /*!< SCB CCR: Instruction cache enable bit Position */ -#define SCB_CCR_IC_Msk (1UL << SCB_CCR_IC_Pos) /*!< SCB CCR: Instruction cache enable bit Mask */ - -#define SCB_CCR_DC_Pos 16U /*!< SCB CCR: Cache enable bit Position */ -#define SCB_CCR_DC_Msk (1UL << SCB_CCR_DC_Pos) /*!< SCB CCR: Cache enable bit Mask */ - -#define SCB_CCR_STKALIGN_Pos 9U /*!< SCB CCR: STKALIGN Position */ -#define SCB_CCR_STKALIGN_Msk (1UL << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */ - -#define SCB_CCR_BFHFNMIGN_Pos 8U /*!< SCB CCR: BFHFNMIGN Position */ -#define SCB_CCR_BFHFNMIGN_Msk (1UL << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */ - -#define SCB_CCR_DIV_0_TRP_Pos 4U /*!< SCB CCR: DIV_0_TRP Position */ -#define SCB_CCR_DIV_0_TRP_Msk (1UL << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP Mask */ - -#define SCB_CCR_UNALIGN_TRP_Pos 3U /*!< SCB CCR: UNALIGN_TRP Position */ -#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ - -#define SCB_CCR_USERSETMPEND_Pos 1U /*!< SCB CCR: USERSETMPEND Position */ -#define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */ - -#define SCB_CCR_NONBASETHRDENA_Pos 0U /*!< SCB CCR: NONBASETHRDENA Position */ -#define SCB_CCR_NONBASETHRDENA_Msk (1UL /*<< SCB_CCR_NONBASETHRDENA_Pos*/) /*!< SCB CCR: NONBASETHRDENA Mask */ - -/* SCB System Handler Control and State Register Definitions */ -#define SCB_SHCSR_USGFAULTENA_Pos 18U /*!< SCB SHCSR: USGFAULTENA Position */ -#define SCB_SHCSR_USGFAULTENA_Msk (1UL << SCB_SHCSR_USGFAULTENA_Pos) /*!< SCB SHCSR: USGFAULTENA Mask */ - -#define SCB_SHCSR_BUSFAULTENA_Pos 17U /*!< SCB SHCSR: BUSFAULTENA Position */ -#define SCB_SHCSR_BUSFAULTENA_Msk (1UL << SCB_SHCSR_BUSFAULTENA_Pos) /*!< SCB SHCSR: BUSFAULTENA Mask */ - -#define SCB_SHCSR_MEMFAULTENA_Pos 16U /*!< SCB SHCSR: MEMFAULTENA Position */ -#define SCB_SHCSR_MEMFAULTENA_Msk (1UL << SCB_SHCSR_MEMFAULTENA_Pos) /*!< SCB SHCSR: MEMFAULTENA Mask */ - -#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */ -#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ - -#define SCB_SHCSR_BUSFAULTPENDED_Pos 14U /*!< SCB SHCSR: BUSFAULTPENDED Position */ -#define SCB_SHCSR_BUSFAULTPENDED_Msk (1UL << SCB_SHCSR_BUSFAULTPENDED_Pos) /*!< SCB SHCSR: BUSFAULTPENDED Mask */ - -#define SCB_SHCSR_MEMFAULTPENDED_Pos 13U /*!< SCB SHCSR: MEMFAULTPENDED Position */ -#define SCB_SHCSR_MEMFAULTPENDED_Msk (1UL << SCB_SHCSR_MEMFAULTPENDED_Pos) /*!< SCB SHCSR: MEMFAULTPENDED Mask */ - -#define SCB_SHCSR_USGFAULTPENDED_Pos 12U /*!< SCB SHCSR: USGFAULTPENDED Position */ -#define SCB_SHCSR_USGFAULTPENDED_Msk (1UL << SCB_SHCSR_USGFAULTPENDED_Pos) /*!< SCB SHCSR: USGFAULTPENDED Mask */ - -#define SCB_SHCSR_SYSTICKACT_Pos 11U /*!< SCB SHCSR: SYSTICKACT Position */ -#define SCB_SHCSR_SYSTICKACT_Msk (1UL << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */ - -#define SCB_SHCSR_PENDSVACT_Pos 10U /*!< SCB SHCSR: PENDSVACT Position */ -#define SCB_SHCSR_PENDSVACT_Msk (1UL << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */ - -#define SCB_SHCSR_MONITORACT_Pos 8U /*!< SCB SHCSR: MONITORACT Position */ -#define SCB_SHCSR_MONITORACT_Msk (1UL << SCB_SHCSR_MONITORACT_Pos) /*!< SCB SHCSR: MONITORACT Mask */ - -#define SCB_SHCSR_SVCALLACT_Pos 7U /*!< SCB SHCSR: SVCALLACT Position */ -#define SCB_SHCSR_SVCALLACT_Msk (1UL << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */ - -#define SCB_SHCSR_USGFAULTACT_Pos 3U /*!< SCB SHCSR: USGFAULTACT Position */ -#define SCB_SHCSR_USGFAULTACT_Msk (1UL << SCB_SHCSR_USGFAULTACT_Pos) /*!< SCB SHCSR: USGFAULTACT Mask */ - -#define SCB_SHCSR_BUSFAULTACT_Pos 1U /*!< SCB SHCSR: BUSFAULTACT Position */ -#define SCB_SHCSR_BUSFAULTACT_Msk (1UL << SCB_SHCSR_BUSFAULTACT_Pos) /*!< SCB SHCSR: BUSFAULTACT Mask */ - -#define SCB_SHCSR_MEMFAULTACT_Pos 0U /*!< SCB SHCSR: MEMFAULTACT Position */ -#define SCB_SHCSR_MEMFAULTACT_Msk (1UL /*<< SCB_SHCSR_MEMFAULTACT_Pos*/) /*!< SCB SHCSR: MEMFAULTACT Mask */ - -/* SCB Configurable Fault Status Register Definitions */ -#define SCB_CFSR_USGFAULTSR_Pos 16U /*!< SCB CFSR: Usage Fault Status Register Position */ -#define SCB_CFSR_USGFAULTSR_Msk (0xFFFFUL << SCB_CFSR_USGFAULTSR_Pos) /*!< SCB CFSR: Usage Fault Status Register Mask */ - -#define SCB_CFSR_BUSFAULTSR_Pos 8U /*!< SCB CFSR: Bus Fault Status Register Position */ -#define SCB_CFSR_BUSFAULTSR_Msk (0xFFUL << SCB_CFSR_BUSFAULTSR_Pos) /*!< SCB CFSR: Bus Fault Status Register Mask */ - -#define SCB_CFSR_MEMFAULTSR_Pos 0U /*!< SCB CFSR: Memory Manage Fault Status Register Position */ -#define SCB_CFSR_MEMFAULTSR_Msk (0xFFUL /*<< SCB_CFSR_MEMFAULTSR_Pos*/) /*!< SCB CFSR: Memory Manage Fault Status Register Mask */ - -/* MemManage Fault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_MMARVALID_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 7U) /*!< SCB CFSR (MMFSR): MMARVALID Position */ -#define SCB_CFSR_MMARVALID_Msk (1UL << SCB_CFSR_MMARVALID_Pos) /*!< SCB CFSR (MMFSR): MMARVALID Mask */ - -#define SCB_CFSR_MLSPERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 5U) /*!< SCB CFSR (MMFSR): MLSPERR Position */ -#define SCB_CFSR_MLSPERR_Msk (1UL << SCB_CFSR_MLSPERR_Pos) /*!< SCB CFSR (MMFSR): MLSPERR Mask */ - -#define SCB_CFSR_MSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 4U) /*!< SCB CFSR (MMFSR): MSTKERR Position */ -#define SCB_CFSR_MSTKERR_Msk (1UL << SCB_CFSR_MSTKERR_Pos) /*!< SCB CFSR (MMFSR): MSTKERR Mask */ - -#define SCB_CFSR_MUNSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 3U) /*!< SCB CFSR (MMFSR): MUNSTKERR Position */ -#define SCB_CFSR_MUNSTKERR_Msk (1UL << SCB_CFSR_MUNSTKERR_Pos) /*!< SCB CFSR (MMFSR): MUNSTKERR Mask */ - -#define SCB_CFSR_DACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 1U) /*!< SCB CFSR (MMFSR): DACCVIOL Position */ -#define SCB_CFSR_DACCVIOL_Msk (1UL << SCB_CFSR_DACCVIOL_Pos) /*!< SCB CFSR (MMFSR): DACCVIOL Mask */ - -#define SCB_CFSR_IACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 0U) /*!< SCB CFSR (MMFSR): IACCVIOL Position */ -#define SCB_CFSR_IACCVIOL_Msk (1UL /*<< SCB_CFSR_IACCVIOL_Pos*/) /*!< SCB CFSR (MMFSR): IACCVIOL Mask */ - -/* BusFault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_BFARVALID_Pos (SCB_CFSR_BUSFAULTSR_Pos + 7U) /*!< SCB CFSR (BFSR): BFARVALID Position */ -#define SCB_CFSR_BFARVALID_Msk (1UL << SCB_CFSR_BFARVALID_Pos) /*!< SCB CFSR (BFSR): BFARVALID Mask */ - -#define SCB_CFSR_LSPERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 5U) /*!< SCB CFSR (BFSR): LSPERR Position */ -#define SCB_CFSR_LSPERR_Msk (1UL << SCB_CFSR_LSPERR_Pos) /*!< SCB CFSR (BFSR): LSPERR Mask */ - -#define SCB_CFSR_STKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 4U) /*!< SCB CFSR (BFSR): STKERR Position */ -#define SCB_CFSR_STKERR_Msk (1UL << SCB_CFSR_STKERR_Pos) /*!< SCB CFSR (BFSR): STKERR Mask */ - -#define SCB_CFSR_UNSTKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 3U) /*!< SCB CFSR (BFSR): UNSTKERR Position */ -#define SCB_CFSR_UNSTKERR_Msk (1UL << SCB_CFSR_UNSTKERR_Pos) /*!< SCB CFSR (BFSR): UNSTKERR Mask */ - -#define SCB_CFSR_IMPRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 2U) /*!< SCB CFSR (BFSR): IMPRECISERR Position */ -#define SCB_CFSR_IMPRECISERR_Msk (1UL << SCB_CFSR_IMPRECISERR_Pos) /*!< SCB CFSR (BFSR): IMPRECISERR Mask */ - -#define SCB_CFSR_PRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 1U) /*!< SCB CFSR (BFSR): PRECISERR Position */ -#define SCB_CFSR_PRECISERR_Msk (1UL << SCB_CFSR_PRECISERR_Pos) /*!< SCB CFSR (BFSR): PRECISERR Mask */ - -#define SCB_CFSR_IBUSERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 0U) /*!< SCB CFSR (BFSR): IBUSERR Position */ -#define SCB_CFSR_IBUSERR_Msk (1UL << SCB_CFSR_IBUSERR_Pos) /*!< SCB CFSR (BFSR): IBUSERR Mask */ - -/* UsageFault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_DIVBYZERO_Pos (SCB_CFSR_USGFAULTSR_Pos + 9U) /*!< SCB CFSR (UFSR): DIVBYZERO Position */ -#define SCB_CFSR_DIVBYZERO_Msk (1UL << SCB_CFSR_DIVBYZERO_Pos) /*!< SCB CFSR (UFSR): DIVBYZERO Mask */ - -#define SCB_CFSR_UNALIGNED_Pos (SCB_CFSR_USGFAULTSR_Pos + 8U) /*!< SCB CFSR (UFSR): UNALIGNED Position */ -#define SCB_CFSR_UNALIGNED_Msk (1UL << SCB_CFSR_UNALIGNED_Pos) /*!< SCB CFSR (UFSR): UNALIGNED Mask */ - -#define SCB_CFSR_NOCP_Pos (SCB_CFSR_USGFAULTSR_Pos + 3U) /*!< SCB CFSR (UFSR): NOCP Position */ -#define SCB_CFSR_NOCP_Msk (1UL << SCB_CFSR_NOCP_Pos) /*!< SCB CFSR (UFSR): NOCP Mask */ - -#define SCB_CFSR_INVPC_Pos (SCB_CFSR_USGFAULTSR_Pos + 2U) /*!< SCB CFSR (UFSR): INVPC Position */ -#define SCB_CFSR_INVPC_Msk (1UL << SCB_CFSR_INVPC_Pos) /*!< SCB CFSR (UFSR): INVPC Mask */ - -#define SCB_CFSR_INVSTATE_Pos (SCB_CFSR_USGFAULTSR_Pos + 1U) /*!< SCB CFSR (UFSR): INVSTATE Position */ -#define SCB_CFSR_INVSTATE_Msk (1UL << SCB_CFSR_INVSTATE_Pos) /*!< SCB CFSR (UFSR): INVSTATE Mask */ - -#define SCB_CFSR_UNDEFINSTR_Pos (SCB_CFSR_USGFAULTSR_Pos + 0U) /*!< SCB CFSR (UFSR): UNDEFINSTR Position */ -#define SCB_CFSR_UNDEFINSTR_Msk (1UL << SCB_CFSR_UNDEFINSTR_Pos) /*!< SCB CFSR (UFSR): UNDEFINSTR Mask */ - -/* SCB Hard Fault Status Register Definitions */ -#define SCB_HFSR_DEBUGEVT_Pos 31U /*!< SCB HFSR: DEBUGEVT Position */ -#define SCB_HFSR_DEBUGEVT_Msk (1UL << SCB_HFSR_DEBUGEVT_Pos) /*!< SCB HFSR: DEBUGEVT Mask */ - -#define SCB_HFSR_FORCED_Pos 30U /*!< SCB HFSR: FORCED Position */ -#define SCB_HFSR_FORCED_Msk (1UL << SCB_HFSR_FORCED_Pos) /*!< SCB HFSR: FORCED Mask */ - -#define SCB_HFSR_VECTTBL_Pos 1U /*!< SCB HFSR: VECTTBL Position */ -#define SCB_HFSR_VECTTBL_Msk (1UL << SCB_HFSR_VECTTBL_Pos) /*!< SCB HFSR: VECTTBL Mask */ - -/* SCB Debug Fault Status Register Definitions */ -#define SCB_DFSR_EXTERNAL_Pos 4U /*!< SCB DFSR: EXTERNAL Position */ -#define SCB_DFSR_EXTERNAL_Msk (1UL << SCB_DFSR_EXTERNAL_Pos) /*!< SCB DFSR: EXTERNAL Mask */ - -#define SCB_DFSR_VCATCH_Pos 3U /*!< SCB DFSR: VCATCH Position */ -#define SCB_DFSR_VCATCH_Msk (1UL << SCB_DFSR_VCATCH_Pos) /*!< SCB DFSR: VCATCH Mask */ - -#define SCB_DFSR_DWTTRAP_Pos 2U /*!< SCB DFSR: DWTTRAP Position */ -#define SCB_DFSR_DWTTRAP_Msk (1UL << SCB_DFSR_DWTTRAP_Pos) /*!< SCB DFSR: DWTTRAP Mask */ - -#define SCB_DFSR_BKPT_Pos 1U /*!< SCB DFSR: BKPT Position */ -#define SCB_DFSR_BKPT_Msk (1UL << SCB_DFSR_BKPT_Pos) /*!< SCB DFSR: BKPT Mask */ - -#define SCB_DFSR_HALTED_Pos 0U /*!< SCB DFSR: HALTED Position */ -#define SCB_DFSR_HALTED_Msk (1UL /*<< SCB_DFSR_HALTED_Pos*/) /*!< SCB DFSR: HALTED Mask */ - -/* SCB Cache Level ID Register Definitions */ -#define SCB_CLIDR_LOUU_Pos 27U /*!< SCB CLIDR: LoUU Position */ -#define SCB_CLIDR_LOUU_Msk (7UL << SCB_CLIDR_LOUU_Pos) /*!< SCB CLIDR: LoUU Mask */ - -#define SCB_CLIDR_LOC_Pos 24U /*!< SCB CLIDR: LoC Position */ -#define SCB_CLIDR_LOC_Msk (7UL << SCB_CLIDR_LOC_Pos) /*!< SCB CLIDR: LoC Mask */ - -/* SCB Cache Type Register Definitions */ -#define SCB_CTR_FORMAT_Pos 29U /*!< SCB CTR: Format Position */ -#define SCB_CTR_FORMAT_Msk (7UL << SCB_CTR_FORMAT_Pos) /*!< SCB CTR: Format Mask */ - -#define SCB_CTR_CWG_Pos 24U /*!< SCB CTR: CWG Position */ -#define SCB_CTR_CWG_Msk (0xFUL << SCB_CTR_CWG_Pos) /*!< SCB CTR: CWG Mask */ - -#define SCB_CTR_ERG_Pos 20U /*!< SCB CTR: ERG Position */ -#define SCB_CTR_ERG_Msk (0xFUL << SCB_CTR_ERG_Pos) /*!< SCB CTR: ERG Mask */ - -#define SCB_CTR_DMINLINE_Pos 16U /*!< SCB CTR: DminLine Position */ -#define SCB_CTR_DMINLINE_Msk (0xFUL << SCB_CTR_DMINLINE_Pos) /*!< SCB CTR: DminLine Mask */ - -#define SCB_CTR_IMINLINE_Pos 0U /*!< SCB CTR: ImInLine Position */ -#define SCB_CTR_IMINLINE_Msk (0xFUL /*<< SCB_CTR_IMINLINE_Pos*/) /*!< SCB CTR: ImInLine Mask */ - -/* SCB Cache Size ID Register Definitions */ -#define SCB_CCSIDR_WT_Pos 31U /*!< SCB CCSIDR: WT Position */ -#define SCB_CCSIDR_WT_Msk (1UL << SCB_CCSIDR_WT_Pos) /*!< SCB CCSIDR: WT Mask */ - -#define SCB_CCSIDR_WB_Pos 30U /*!< SCB CCSIDR: WB Position */ -#define SCB_CCSIDR_WB_Msk (1UL << SCB_CCSIDR_WB_Pos) /*!< SCB CCSIDR: WB Mask */ - -#define SCB_CCSIDR_RA_Pos 29U /*!< SCB CCSIDR: RA Position */ -#define SCB_CCSIDR_RA_Msk (1UL << SCB_CCSIDR_RA_Pos) /*!< SCB CCSIDR: RA Mask */ - -#define SCB_CCSIDR_WA_Pos 28U /*!< SCB CCSIDR: WA Position */ -#define SCB_CCSIDR_WA_Msk (1UL << SCB_CCSIDR_WA_Pos) /*!< SCB CCSIDR: WA Mask */ - -#define SCB_CCSIDR_NUMSETS_Pos 13U /*!< SCB CCSIDR: NumSets Position */ -#define SCB_CCSIDR_NUMSETS_Msk (0x7FFFUL << SCB_CCSIDR_NUMSETS_Pos) /*!< SCB CCSIDR: NumSets Mask */ - -#define SCB_CCSIDR_ASSOCIATIVITY_Pos 3U /*!< SCB CCSIDR: Associativity Position */ -#define SCB_CCSIDR_ASSOCIATIVITY_Msk (0x3FFUL << SCB_CCSIDR_ASSOCIATIVITY_Pos) /*!< SCB CCSIDR: Associativity Mask */ - -#define SCB_CCSIDR_LINESIZE_Pos 0U /*!< SCB CCSIDR: LineSize Position */ -#define SCB_CCSIDR_LINESIZE_Msk (7UL /*<< SCB_CCSIDR_LINESIZE_Pos*/) /*!< SCB CCSIDR: LineSize Mask */ - -/* SCB Cache Size Selection Register Definitions */ -#define SCB_CSSELR_LEVEL_Pos 1U /*!< SCB CSSELR: Level Position */ -#define SCB_CSSELR_LEVEL_Msk (7UL << SCB_CSSELR_LEVEL_Pos) /*!< SCB CSSELR: Level Mask */ - -#define SCB_CSSELR_IND_Pos 0U /*!< SCB CSSELR: InD Position */ -#define SCB_CSSELR_IND_Msk (1UL /*<< SCB_CSSELR_IND_Pos*/) /*!< SCB CSSELR: InD Mask */ - -/* SCB Software Triggered Interrupt Register Definitions */ -#define SCB_STIR_INTID_Pos 0U /*!< SCB STIR: INTID Position */ -#define SCB_STIR_INTID_Msk (0x1FFUL /*<< SCB_STIR_INTID_Pos*/) /*!< SCB STIR: INTID Mask */ - -/* SCB D-Cache Invalidate by Set-way Register Definitions */ -#define SCB_DCISW_WAY_Pos 30U /*!< SCB DCISW: Way Position */ -#define SCB_DCISW_WAY_Msk (3UL << SCB_DCISW_WAY_Pos) /*!< SCB DCISW: Way Mask */ - -#define SCB_DCISW_SET_Pos 5U /*!< SCB DCISW: Set Position */ -#define SCB_DCISW_SET_Msk (0x1FFUL << SCB_DCISW_SET_Pos) /*!< SCB DCISW: Set Mask */ - -/* SCB D-Cache Clean by Set-way Register Definitions */ -#define SCB_DCCSW_WAY_Pos 30U /*!< SCB DCCSW: Way Position */ -#define SCB_DCCSW_WAY_Msk (3UL << SCB_DCCSW_WAY_Pos) /*!< SCB DCCSW: Way Mask */ - -#define SCB_DCCSW_SET_Pos 5U /*!< SCB DCCSW: Set Position */ -#define SCB_DCCSW_SET_Msk (0x1FFUL << SCB_DCCSW_SET_Pos) /*!< SCB DCCSW: Set Mask */ - -/* SCB D-Cache Clean and Invalidate by Set-way Register Definitions */ -#define SCB_DCCISW_WAY_Pos 30U /*!< SCB DCCISW: Way Position */ -#define SCB_DCCISW_WAY_Msk (3UL << SCB_DCCISW_WAY_Pos) /*!< SCB DCCISW: Way Mask */ - -#define SCB_DCCISW_SET_Pos 5U /*!< SCB DCCISW: Set Position */ -#define SCB_DCCISW_SET_Msk (0x1FFUL << SCB_DCCISW_SET_Pos) /*!< SCB DCCISW: Set Mask */ - -/* Instruction Tightly-Coupled Memory Control Register Definitions */ -#define SCB_ITCMCR_SZ_Pos 3U /*!< SCB ITCMCR: SZ Position */ -#define SCB_ITCMCR_SZ_Msk (0xFUL << SCB_ITCMCR_SZ_Pos) /*!< SCB ITCMCR: SZ Mask */ - -#define SCB_ITCMCR_RETEN_Pos 2U /*!< SCB ITCMCR: RETEN Position */ -#define SCB_ITCMCR_RETEN_Msk (1UL << SCB_ITCMCR_RETEN_Pos) /*!< SCB ITCMCR: RETEN Mask */ - -#define SCB_ITCMCR_RMW_Pos 1U /*!< SCB ITCMCR: RMW Position */ -#define SCB_ITCMCR_RMW_Msk (1UL << SCB_ITCMCR_RMW_Pos) /*!< SCB ITCMCR: RMW Mask */ - -#define SCB_ITCMCR_EN_Pos 0U /*!< SCB ITCMCR: EN Position */ -#define SCB_ITCMCR_EN_Msk (1UL /*<< SCB_ITCMCR_EN_Pos*/) /*!< SCB ITCMCR: EN Mask */ - -/* Data Tightly-Coupled Memory Control Register Definitions */ -#define SCB_DTCMCR_SZ_Pos 3U /*!< SCB DTCMCR: SZ Position */ -#define SCB_DTCMCR_SZ_Msk (0xFUL << SCB_DTCMCR_SZ_Pos) /*!< SCB DTCMCR: SZ Mask */ - -#define SCB_DTCMCR_RETEN_Pos 2U /*!< SCB DTCMCR: RETEN Position */ -#define SCB_DTCMCR_RETEN_Msk (1UL << SCB_DTCMCR_RETEN_Pos) /*!< SCB DTCMCR: RETEN Mask */ - -#define SCB_DTCMCR_RMW_Pos 1U /*!< SCB DTCMCR: RMW Position */ -#define SCB_DTCMCR_RMW_Msk (1UL << SCB_DTCMCR_RMW_Pos) /*!< SCB DTCMCR: RMW Mask */ - -#define SCB_DTCMCR_EN_Pos 0U /*!< SCB DTCMCR: EN Position */ -#define SCB_DTCMCR_EN_Msk (1UL /*<< SCB_DTCMCR_EN_Pos*/) /*!< SCB DTCMCR: EN Mask */ - -/* AHBP Control Register Definitions */ -#define SCB_AHBPCR_SZ_Pos 1U /*!< SCB AHBPCR: SZ Position */ -#define SCB_AHBPCR_SZ_Msk (7UL << SCB_AHBPCR_SZ_Pos) /*!< SCB AHBPCR: SZ Mask */ - -#define SCB_AHBPCR_EN_Pos 0U /*!< SCB AHBPCR: EN Position */ -#define SCB_AHBPCR_EN_Msk (1UL /*<< SCB_AHBPCR_EN_Pos*/) /*!< SCB AHBPCR: EN Mask */ - -/* L1 Cache Control Register Definitions */ -#define SCB_CACR_FORCEWT_Pos 2U /*!< SCB CACR: FORCEWT Position */ -#define SCB_CACR_FORCEWT_Msk (1UL << SCB_CACR_FORCEWT_Pos) /*!< SCB CACR: FORCEWT Mask */ - -#define SCB_CACR_ECCEN_Pos 1U /*!< SCB CACR: ECCEN Position */ -#define SCB_CACR_ECCEN_Msk (1UL << SCB_CACR_ECCEN_Pos) /*!< SCB CACR: ECCEN Mask */ - -#define SCB_CACR_SIWT_Pos 0U /*!< SCB CACR: SIWT Position */ -#define SCB_CACR_SIWT_Msk (1UL /*<< SCB_CACR_SIWT_Pos*/) /*!< SCB CACR: SIWT Mask */ - -/* AHBS Control Register Definitions */ -#define SCB_AHBSCR_INITCOUNT_Pos 11U /*!< SCB AHBSCR: INITCOUNT Position */ -#define SCB_AHBSCR_INITCOUNT_Msk (0x1FUL << SCB_AHBPCR_INITCOUNT_Pos) /*!< SCB AHBSCR: INITCOUNT Mask */ - -#define SCB_AHBSCR_TPRI_Pos 2U /*!< SCB AHBSCR: TPRI Position */ -#define SCB_AHBSCR_TPRI_Msk (0x1FFUL << SCB_AHBPCR_TPRI_Pos) /*!< SCB AHBSCR: TPRI Mask */ - -#define SCB_AHBSCR_CTL_Pos 0U /*!< SCB AHBSCR: CTL Position*/ -#define SCB_AHBSCR_CTL_Msk (3UL /*<< SCB_AHBPCR_CTL_Pos*/) /*!< SCB AHBSCR: CTL Mask */ - -/* Auxiliary Bus Fault Status Register Definitions */ -#define SCB_ABFSR_AXIMTYPE_Pos 8U /*!< SCB ABFSR: AXIMTYPE Position*/ -#define SCB_ABFSR_AXIMTYPE_Msk (3UL << SCB_ABFSR_AXIMTYPE_Pos) /*!< SCB ABFSR: AXIMTYPE Mask */ - -#define SCB_ABFSR_EPPB_Pos 4U /*!< SCB ABFSR: EPPB Position*/ -#define SCB_ABFSR_EPPB_Msk (1UL << SCB_ABFSR_EPPB_Pos) /*!< SCB ABFSR: EPPB Mask */ - -#define SCB_ABFSR_AXIM_Pos 3U /*!< SCB ABFSR: AXIM Position*/ -#define SCB_ABFSR_AXIM_Msk (1UL << SCB_ABFSR_AXIM_Pos) /*!< SCB ABFSR: AXIM Mask */ - -#define SCB_ABFSR_AHBP_Pos 2U /*!< SCB ABFSR: AHBP Position*/ -#define SCB_ABFSR_AHBP_Msk (1UL << SCB_ABFSR_AHBP_Pos) /*!< SCB ABFSR: AHBP Mask */ - -#define SCB_ABFSR_DTCM_Pos 1U /*!< SCB ABFSR: DTCM Position*/ -#define SCB_ABFSR_DTCM_Msk (1UL << SCB_ABFSR_DTCM_Pos) /*!< SCB ABFSR: DTCM Mask */ - -#define SCB_ABFSR_ITCM_Pos 0U /*!< SCB ABFSR: ITCM Position*/ -#define SCB_ABFSR_ITCM_Msk (1UL /*<< SCB_ABFSR_ITCM_Pos*/) /*!< SCB ABFSR: ITCM Mask */ - -/*@} end of group CMSIS_SCB */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SCnSCB System Controls not in SCB (SCnSCB) - \brief Type definitions for the System Control and ID Register not in the SCB - @{ - */ - -/** - \brief Structure type to access the System Control and ID Register not in the SCB. - */ -typedef struct -{ - uint32_t RESERVED0[1U]; - __IM uint32_t ICTR; /*!< Offset: 0x004 (R/ ) Interrupt Controller Type Register */ - __IOM uint32_t ACTLR; /*!< Offset: 0x008 (R/W) Auxiliary Control Register */ -} SCnSCB_Type; - -/* Interrupt Controller Type Register Definitions */ -#define SCnSCB_ICTR_INTLINESNUM_Pos 0U /*!< ICTR: INTLINESNUM Position */ -#define SCnSCB_ICTR_INTLINESNUM_Msk (0xFUL /*<< SCnSCB_ICTR_INTLINESNUM_Pos*/) /*!< ICTR: INTLINESNUM Mask */ - -/* Auxiliary Control Register Definitions */ -#define SCnSCB_ACTLR_DISDYNADD_Pos 26U /*!< ACTLR: DISDYNADD Position */ -#define SCnSCB_ACTLR_DISDYNADD_Msk (1UL << SCnSCB_ACTLR_DISDYNADD_Pos) /*!< ACTLR: DISDYNADD Mask */ - -#define SCnSCB_ACTLR_DISISSCH1_Pos 21U /*!< ACTLR: DISISSCH1 Position */ -#define SCnSCB_ACTLR_DISISSCH1_Msk (0x1FUL << SCnSCB_ACTLR_DISISSCH1_Pos) /*!< ACTLR: DISISSCH1 Mask */ - -#define SCnSCB_ACTLR_DISDI_Pos 16U /*!< ACTLR: DISDI Position */ -#define SCnSCB_ACTLR_DISDI_Msk (0x1FUL << SCnSCB_ACTLR_DISDI_Pos) /*!< ACTLR: DISDI Mask */ - -#define SCnSCB_ACTLR_DISCRITAXIRUR_Pos 15U /*!< ACTLR: DISCRITAXIRUR Position */ -#define SCnSCB_ACTLR_DISCRITAXIRUR_Msk (1UL << SCnSCB_ACTLR_DISCRITAXIRUR_Pos) /*!< ACTLR: DISCRITAXIRUR Mask */ - -#define SCnSCB_ACTLR_DISBTACALLOC_Pos 14U /*!< ACTLR: DISBTACALLOC Position */ -#define SCnSCB_ACTLR_DISBTACALLOC_Msk (1UL << SCnSCB_ACTLR_DISBTACALLOC_Pos) /*!< ACTLR: DISBTACALLOC Mask */ - -#define SCnSCB_ACTLR_DISBTACREAD_Pos 13U /*!< ACTLR: DISBTACREAD Position */ -#define SCnSCB_ACTLR_DISBTACREAD_Msk (1UL << SCnSCB_ACTLR_DISBTACREAD_Pos) /*!< ACTLR: DISBTACREAD Mask */ - -#define SCnSCB_ACTLR_DISITMATBFLUSH_Pos 12U /*!< ACTLR: DISITMATBFLUSH Position */ -#define SCnSCB_ACTLR_DISITMATBFLUSH_Msk (1UL << SCnSCB_ACTLR_DISITMATBFLUSH_Pos) /*!< ACTLR: DISITMATBFLUSH Mask */ - -#define SCnSCB_ACTLR_DISRAMODE_Pos 11U /*!< ACTLR: DISRAMODE Position */ -#define SCnSCB_ACTLR_DISRAMODE_Msk (1UL << SCnSCB_ACTLR_DISRAMODE_Pos) /*!< ACTLR: DISRAMODE Mask */ - -#define SCnSCB_ACTLR_FPEXCODIS_Pos 10U /*!< ACTLR: FPEXCODIS Position */ -#define SCnSCB_ACTLR_FPEXCODIS_Msk (1UL << SCnSCB_ACTLR_FPEXCODIS_Pos) /*!< ACTLR: FPEXCODIS Mask */ - -#define SCnSCB_ACTLR_DISFOLD_Pos 2U /*!< ACTLR: DISFOLD Position */ -#define SCnSCB_ACTLR_DISFOLD_Msk (1UL << SCnSCB_ACTLR_DISFOLD_Pos) /*!< ACTLR: DISFOLD Mask */ - -#define SCnSCB_ACTLR_DISMCYCINT_Pos 0U /*!< ACTLR: DISMCYCINT Position */ -#define SCnSCB_ACTLR_DISMCYCINT_Msk (1UL /*<< SCnSCB_ACTLR_DISMCYCINT_Pos*/) /*!< ACTLR: DISMCYCINT Mask */ - -/*@} end of group CMSIS_SCnotSCB */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SysTick System Tick Timer (SysTick) - \brief Type definitions for the System Timer Registers. - @{ - */ - -/** - \brief Structure type to access the System Timer (SysTick). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ - __IOM uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ - __IOM uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ - __IM uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ -} SysTick_Type; - -/* SysTick Control / Status Register Definitions */ -#define SysTick_CTRL_COUNTFLAG_Pos 16U /*!< SysTick CTRL: COUNTFLAG Position */ -#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ - -#define SysTick_CTRL_CLKSOURCE_Pos 2U /*!< SysTick CTRL: CLKSOURCE Position */ -#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ - -#define SysTick_CTRL_TICKINT_Pos 1U /*!< SysTick CTRL: TICKINT Position */ -#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ - -#define SysTick_CTRL_ENABLE_Pos 0U /*!< SysTick CTRL: ENABLE Position */ -#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ - -/* SysTick Reload Register Definitions */ -#define SysTick_LOAD_RELOAD_Pos 0U /*!< SysTick LOAD: RELOAD Position */ -#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ - -/* SysTick Current Register Definitions */ -#define SysTick_VAL_CURRENT_Pos 0U /*!< SysTick VAL: CURRENT Position */ -#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ - -/* SysTick Calibration Register Definitions */ -#define SysTick_CALIB_NOREF_Pos 31U /*!< SysTick CALIB: NOREF Position */ -#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ - -#define SysTick_CALIB_SKEW_Pos 30U /*!< SysTick CALIB: SKEW Position */ -#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ - -#define SysTick_CALIB_TENMS_Pos 0U /*!< SysTick CALIB: TENMS Position */ -#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ - -/*@} end of group CMSIS_SysTick */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_ITM Instrumentation Trace Macrocell (ITM) - \brief Type definitions for the Instrumentation Trace Macrocell (ITM) - @{ - */ - -/** - \brief Structure type to access the Instrumentation Trace Macrocell Register (ITM). - */ -typedef struct -{ - __OM union - { - __OM uint8_t u8; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 8-bit */ - __OM uint16_t u16; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 16-bit */ - __OM uint32_t u32; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 32-bit */ - } PORT [32U]; /*!< Offset: 0x000 ( /W) ITM Stimulus Port Registers */ - uint32_t RESERVED0[864U]; - __IOM uint32_t TER; /*!< Offset: 0xE00 (R/W) ITM Trace Enable Register */ - uint32_t RESERVED1[15U]; - __IOM uint32_t TPR; /*!< Offset: 0xE40 (R/W) ITM Trace Privilege Register */ - uint32_t RESERVED2[15U]; - __IOM uint32_t TCR; /*!< Offset: 0xE80 (R/W) ITM Trace Control Register */ - uint32_t RESERVED3[32U]; - uint32_t RESERVED4[43U]; - __OM uint32_t LAR; /*!< Offset: 0xFB0 ( /W) ITM Lock Access Register */ - __IM uint32_t LSR; /*!< Offset: 0xFB4 (R/ ) ITM Lock Status Register */ - uint32_t RESERVED5[6U]; - __IM uint32_t PID4; /*!< Offset: 0xFD0 (R/ ) ITM Peripheral Identification Register #4 */ - __IM uint32_t PID5; /*!< Offset: 0xFD4 (R/ ) ITM Peripheral Identification Register #5 */ - __IM uint32_t PID6; /*!< Offset: 0xFD8 (R/ ) ITM Peripheral Identification Register #6 */ - __IM uint32_t PID7; /*!< Offset: 0xFDC (R/ ) ITM Peripheral Identification Register #7 */ - __IM uint32_t PID0; /*!< Offset: 0xFE0 (R/ ) ITM Peripheral Identification Register #0 */ - __IM uint32_t PID1; /*!< Offset: 0xFE4 (R/ ) ITM Peripheral Identification Register #1 */ - __IM uint32_t PID2; /*!< Offset: 0xFE8 (R/ ) ITM Peripheral Identification Register #2 */ - __IM uint32_t PID3; /*!< Offset: 0xFEC (R/ ) ITM Peripheral Identification Register #3 */ - __IM uint32_t CID0; /*!< Offset: 0xFF0 (R/ ) ITM Component Identification Register #0 */ - __IM uint32_t CID1; /*!< Offset: 0xFF4 (R/ ) ITM Component Identification Register #1 */ - __IM uint32_t CID2; /*!< Offset: 0xFF8 (R/ ) ITM Component Identification Register #2 */ - __IM uint32_t CID3; /*!< Offset: 0xFFC (R/ ) ITM Component Identification Register #3 */ -} ITM_Type; - -/* ITM Trace Privilege Register Definitions */ -#define ITM_TPR_PRIVMASK_Pos 0U /*!< ITM TPR: PRIVMASK Position */ -#define ITM_TPR_PRIVMASK_Msk (0xFFFFFFFFUL /*<< ITM_TPR_PRIVMASK_Pos*/) /*!< ITM TPR: PRIVMASK Mask */ - -/* ITM Trace Control Register Definitions */ -#define ITM_TCR_BUSY_Pos 23U /*!< ITM TCR: BUSY Position */ -#define ITM_TCR_BUSY_Msk (1UL << ITM_TCR_BUSY_Pos) /*!< ITM TCR: BUSY Mask */ - -#define ITM_TCR_TraceBusID_Pos 16U /*!< ITM TCR: ATBID Position */ -#define ITM_TCR_TraceBusID_Msk (0x7FUL << ITM_TCR_TraceBusID_Pos) /*!< ITM TCR: ATBID Mask */ - -#define ITM_TCR_GTSFREQ_Pos 10U /*!< ITM TCR: Global timestamp frequency Position */ -#define ITM_TCR_GTSFREQ_Msk (3UL << ITM_TCR_GTSFREQ_Pos) /*!< ITM TCR: Global timestamp frequency Mask */ - -#define ITM_TCR_TSPrescale_Pos 8U /*!< ITM TCR: TSPrescale Position */ -#define ITM_TCR_TSPrescale_Msk (3UL << ITM_TCR_TSPrescale_Pos) /*!< ITM TCR: TSPrescale Mask */ - -#define ITM_TCR_SWOENA_Pos 4U /*!< ITM TCR: SWOENA Position */ -#define ITM_TCR_SWOENA_Msk (1UL << ITM_TCR_SWOENA_Pos) /*!< ITM TCR: SWOENA Mask */ - -#define ITM_TCR_DWTENA_Pos 3U /*!< ITM TCR: DWTENA Position */ -#define ITM_TCR_DWTENA_Msk (1UL << ITM_TCR_DWTENA_Pos) /*!< ITM TCR: DWTENA Mask */ - -#define ITM_TCR_SYNCENA_Pos 2U /*!< ITM TCR: SYNCENA Position */ -#define ITM_TCR_SYNCENA_Msk (1UL << ITM_TCR_SYNCENA_Pos) /*!< ITM TCR: SYNCENA Mask */ - -#define ITM_TCR_TSENA_Pos 1U /*!< ITM TCR: TSENA Position */ -#define ITM_TCR_TSENA_Msk (1UL << ITM_TCR_TSENA_Pos) /*!< ITM TCR: TSENA Mask */ - -#define ITM_TCR_ITMENA_Pos 0U /*!< ITM TCR: ITM Enable bit Position */ -#define ITM_TCR_ITMENA_Msk (1UL /*<< ITM_TCR_ITMENA_Pos*/) /*!< ITM TCR: ITM Enable bit Mask */ - -/* ITM Lock Status Register Definitions */ -#define ITM_LSR_ByteAcc_Pos 2U /*!< ITM LSR: ByteAcc Position */ -#define ITM_LSR_ByteAcc_Msk (1UL << ITM_LSR_ByteAcc_Pos) /*!< ITM LSR: ByteAcc Mask */ - -#define ITM_LSR_Access_Pos 1U /*!< ITM LSR: Access Position */ -#define ITM_LSR_Access_Msk (1UL << ITM_LSR_Access_Pos) /*!< ITM LSR: Access Mask */ - -#define ITM_LSR_Present_Pos 0U /*!< ITM LSR: Present Position */ -#define ITM_LSR_Present_Msk (1UL /*<< ITM_LSR_Present_Pos*/) /*!< ITM LSR: Present Mask */ - -/*@}*/ /* end of group CMSIS_ITM */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_DWT Data Watchpoint and Trace (DWT) - \brief Type definitions for the Data Watchpoint and Trace (DWT) - @{ - */ - -/** - \brief Structure type to access the Data Watchpoint and Trace Register (DWT). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) Control Register */ - __IOM uint32_t CYCCNT; /*!< Offset: 0x004 (R/W) Cycle Count Register */ - __IOM uint32_t CPICNT; /*!< Offset: 0x008 (R/W) CPI Count Register */ - __IOM uint32_t EXCCNT; /*!< Offset: 0x00C (R/W) Exception Overhead Count Register */ - __IOM uint32_t SLEEPCNT; /*!< Offset: 0x010 (R/W) Sleep Count Register */ - __IOM uint32_t LSUCNT; /*!< Offset: 0x014 (R/W) LSU Count Register */ - __IOM uint32_t FOLDCNT; /*!< Offset: 0x018 (R/W) Folded-instruction Count Register */ - __IM uint32_t PCSR; /*!< Offset: 0x01C (R/ ) Program Counter Sample Register */ - __IOM uint32_t COMP0; /*!< Offset: 0x020 (R/W) Comparator Register 0 */ - __IOM uint32_t MASK0; /*!< Offset: 0x024 (R/W) Mask Register 0 */ - __IOM uint32_t FUNCTION0; /*!< Offset: 0x028 (R/W) Function Register 0 */ - uint32_t RESERVED0[1U]; - __IOM uint32_t COMP1; /*!< Offset: 0x030 (R/W) Comparator Register 1 */ - __IOM uint32_t MASK1; /*!< Offset: 0x034 (R/W) Mask Register 1 */ - __IOM uint32_t FUNCTION1; /*!< Offset: 0x038 (R/W) Function Register 1 */ - uint32_t RESERVED1[1U]; - __IOM uint32_t COMP2; /*!< Offset: 0x040 (R/W) Comparator Register 2 */ - __IOM uint32_t MASK2; /*!< Offset: 0x044 (R/W) Mask Register 2 */ - __IOM uint32_t FUNCTION2; /*!< Offset: 0x048 (R/W) Function Register 2 */ - uint32_t RESERVED2[1U]; - __IOM uint32_t COMP3; /*!< Offset: 0x050 (R/W) Comparator Register 3 */ - __IOM uint32_t MASK3; /*!< Offset: 0x054 (R/W) Mask Register 3 */ - __IOM uint32_t FUNCTION3; /*!< Offset: 0x058 (R/W) Function Register 3 */ - uint32_t RESERVED3[981U]; - __OM uint32_t LAR; /*!< Offset: 0xFB0 ( W) Lock Access Register */ - __IM uint32_t LSR; /*!< Offset: 0xFB4 (R ) Lock Status Register */ -} DWT_Type; - -/* DWT Control Register Definitions */ -#define DWT_CTRL_NUMCOMP_Pos 28U /*!< DWT CTRL: NUMCOMP Position */ -#define DWT_CTRL_NUMCOMP_Msk (0xFUL << DWT_CTRL_NUMCOMP_Pos) /*!< DWT CTRL: NUMCOMP Mask */ - -#define DWT_CTRL_NOTRCPKT_Pos 27U /*!< DWT CTRL: NOTRCPKT Position */ -#define DWT_CTRL_NOTRCPKT_Msk (0x1UL << DWT_CTRL_NOTRCPKT_Pos) /*!< DWT CTRL: NOTRCPKT Mask */ - -#define DWT_CTRL_NOEXTTRIG_Pos 26U /*!< DWT CTRL: NOEXTTRIG Position */ -#define DWT_CTRL_NOEXTTRIG_Msk (0x1UL << DWT_CTRL_NOEXTTRIG_Pos) /*!< DWT CTRL: NOEXTTRIG Mask */ - -#define DWT_CTRL_NOCYCCNT_Pos 25U /*!< DWT CTRL: NOCYCCNT Position */ -#define DWT_CTRL_NOCYCCNT_Msk (0x1UL << DWT_CTRL_NOCYCCNT_Pos) /*!< DWT CTRL: NOCYCCNT Mask */ - -#define DWT_CTRL_NOPRFCNT_Pos 24U /*!< DWT CTRL: NOPRFCNT Position */ -#define DWT_CTRL_NOPRFCNT_Msk (0x1UL << DWT_CTRL_NOPRFCNT_Pos) /*!< DWT CTRL: NOPRFCNT Mask */ - -#define DWT_CTRL_CYCEVTENA_Pos 22U /*!< DWT CTRL: CYCEVTENA Position */ -#define DWT_CTRL_CYCEVTENA_Msk (0x1UL << DWT_CTRL_CYCEVTENA_Pos) /*!< DWT CTRL: CYCEVTENA Mask */ - -#define DWT_CTRL_FOLDEVTENA_Pos 21U /*!< DWT CTRL: FOLDEVTENA Position */ -#define DWT_CTRL_FOLDEVTENA_Msk (0x1UL << DWT_CTRL_FOLDEVTENA_Pos) /*!< DWT CTRL: FOLDEVTENA Mask */ - -#define DWT_CTRL_LSUEVTENA_Pos 20U /*!< DWT CTRL: LSUEVTENA Position */ -#define DWT_CTRL_LSUEVTENA_Msk (0x1UL << DWT_CTRL_LSUEVTENA_Pos) /*!< DWT CTRL: LSUEVTENA Mask */ - -#define DWT_CTRL_SLEEPEVTENA_Pos 19U /*!< DWT CTRL: SLEEPEVTENA Position */ -#define DWT_CTRL_SLEEPEVTENA_Msk (0x1UL << DWT_CTRL_SLEEPEVTENA_Pos) /*!< DWT CTRL: SLEEPEVTENA Mask */ - -#define DWT_CTRL_EXCEVTENA_Pos 18U /*!< DWT CTRL: EXCEVTENA Position */ -#define DWT_CTRL_EXCEVTENA_Msk (0x1UL << DWT_CTRL_EXCEVTENA_Pos) /*!< DWT CTRL: EXCEVTENA Mask */ - -#define DWT_CTRL_CPIEVTENA_Pos 17U /*!< DWT CTRL: CPIEVTENA Position */ -#define DWT_CTRL_CPIEVTENA_Msk (0x1UL << DWT_CTRL_CPIEVTENA_Pos) /*!< DWT CTRL: CPIEVTENA Mask */ - -#define DWT_CTRL_EXCTRCENA_Pos 16U /*!< DWT CTRL: EXCTRCENA Position */ -#define DWT_CTRL_EXCTRCENA_Msk (0x1UL << DWT_CTRL_EXCTRCENA_Pos) /*!< DWT CTRL: EXCTRCENA Mask */ - -#define DWT_CTRL_PCSAMPLENA_Pos 12U /*!< DWT CTRL: PCSAMPLENA Position */ -#define DWT_CTRL_PCSAMPLENA_Msk (0x1UL << DWT_CTRL_PCSAMPLENA_Pos) /*!< DWT CTRL: PCSAMPLENA Mask */ - -#define DWT_CTRL_SYNCTAP_Pos 10U /*!< DWT CTRL: SYNCTAP Position */ -#define DWT_CTRL_SYNCTAP_Msk (0x3UL << DWT_CTRL_SYNCTAP_Pos) /*!< DWT CTRL: SYNCTAP Mask */ - -#define DWT_CTRL_CYCTAP_Pos 9U /*!< DWT CTRL: CYCTAP Position */ -#define DWT_CTRL_CYCTAP_Msk (0x1UL << DWT_CTRL_CYCTAP_Pos) /*!< DWT CTRL: CYCTAP Mask */ - -#define DWT_CTRL_POSTINIT_Pos 5U /*!< DWT CTRL: POSTINIT Position */ -#define DWT_CTRL_POSTINIT_Msk (0xFUL << DWT_CTRL_POSTINIT_Pos) /*!< DWT CTRL: POSTINIT Mask */ - -#define DWT_CTRL_POSTPRESET_Pos 1U /*!< DWT CTRL: POSTPRESET Position */ -#define DWT_CTRL_POSTPRESET_Msk (0xFUL << DWT_CTRL_POSTPRESET_Pos) /*!< DWT CTRL: POSTPRESET Mask */ - -#define DWT_CTRL_CYCCNTENA_Pos 0U /*!< DWT CTRL: CYCCNTENA Position */ -#define DWT_CTRL_CYCCNTENA_Msk (0x1UL /*<< DWT_CTRL_CYCCNTENA_Pos*/) /*!< DWT CTRL: CYCCNTENA Mask */ - -/* DWT CPI Count Register Definitions */ -#define DWT_CPICNT_CPICNT_Pos 0U /*!< DWT CPICNT: CPICNT Position */ -#define DWT_CPICNT_CPICNT_Msk (0xFFUL /*<< DWT_CPICNT_CPICNT_Pos*/) /*!< DWT CPICNT: CPICNT Mask */ - -/* DWT Exception Overhead Count Register Definitions */ -#define DWT_EXCCNT_EXCCNT_Pos 0U /*!< DWT EXCCNT: EXCCNT Position */ -#define DWT_EXCCNT_EXCCNT_Msk (0xFFUL /*<< DWT_EXCCNT_EXCCNT_Pos*/) /*!< DWT EXCCNT: EXCCNT Mask */ - -/* DWT Sleep Count Register Definitions */ -#define DWT_SLEEPCNT_SLEEPCNT_Pos 0U /*!< DWT SLEEPCNT: SLEEPCNT Position */ -#define DWT_SLEEPCNT_SLEEPCNT_Msk (0xFFUL /*<< DWT_SLEEPCNT_SLEEPCNT_Pos*/) /*!< DWT SLEEPCNT: SLEEPCNT Mask */ - -/* DWT LSU Count Register Definitions */ -#define DWT_LSUCNT_LSUCNT_Pos 0U /*!< DWT LSUCNT: LSUCNT Position */ -#define DWT_LSUCNT_LSUCNT_Msk (0xFFUL /*<< DWT_LSUCNT_LSUCNT_Pos*/) /*!< DWT LSUCNT: LSUCNT Mask */ - -/* DWT Folded-instruction Count Register Definitions */ -#define DWT_FOLDCNT_FOLDCNT_Pos 0U /*!< DWT FOLDCNT: FOLDCNT Position */ -#define DWT_FOLDCNT_FOLDCNT_Msk (0xFFUL /*<< DWT_FOLDCNT_FOLDCNT_Pos*/) /*!< DWT FOLDCNT: FOLDCNT Mask */ - -/* DWT Comparator Mask Register Definitions */ -#define DWT_MASK_MASK_Pos 0U /*!< DWT MASK: MASK Position */ -#define DWT_MASK_MASK_Msk (0x1FUL /*<< DWT_MASK_MASK_Pos*/) /*!< DWT MASK: MASK Mask */ - -/* DWT Comparator Function Register Definitions */ -#define DWT_FUNCTION_MATCHED_Pos 24U /*!< DWT FUNCTION: MATCHED Position */ -#define DWT_FUNCTION_MATCHED_Msk (0x1UL << DWT_FUNCTION_MATCHED_Pos) /*!< DWT FUNCTION: MATCHED Mask */ - -#define DWT_FUNCTION_DATAVADDR1_Pos 16U /*!< DWT FUNCTION: DATAVADDR1 Position */ -#define DWT_FUNCTION_DATAVADDR1_Msk (0xFUL << DWT_FUNCTION_DATAVADDR1_Pos) /*!< DWT FUNCTION: DATAVADDR1 Mask */ - -#define DWT_FUNCTION_DATAVADDR0_Pos 12U /*!< DWT FUNCTION: DATAVADDR0 Position */ -#define DWT_FUNCTION_DATAVADDR0_Msk (0xFUL << DWT_FUNCTION_DATAVADDR0_Pos) /*!< DWT FUNCTION: DATAVADDR0 Mask */ - -#define DWT_FUNCTION_DATAVSIZE_Pos 10U /*!< DWT FUNCTION: DATAVSIZE Position */ -#define DWT_FUNCTION_DATAVSIZE_Msk (0x3UL << DWT_FUNCTION_DATAVSIZE_Pos) /*!< DWT FUNCTION: DATAVSIZE Mask */ - -#define DWT_FUNCTION_LNK1ENA_Pos 9U /*!< DWT FUNCTION: LNK1ENA Position */ -#define DWT_FUNCTION_LNK1ENA_Msk (0x1UL << DWT_FUNCTION_LNK1ENA_Pos) /*!< DWT FUNCTION: LNK1ENA Mask */ - -#define DWT_FUNCTION_DATAVMATCH_Pos 8U /*!< DWT FUNCTION: DATAVMATCH Position */ -#define DWT_FUNCTION_DATAVMATCH_Msk (0x1UL << DWT_FUNCTION_DATAVMATCH_Pos) /*!< DWT FUNCTION: DATAVMATCH Mask */ - -#define DWT_FUNCTION_CYCMATCH_Pos 7U /*!< DWT FUNCTION: CYCMATCH Position */ -#define DWT_FUNCTION_CYCMATCH_Msk (0x1UL << DWT_FUNCTION_CYCMATCH_Pos) /*!< DWT FUNCTION: CYCMATCH Mask */ - -#define DWT_FUNCTION_EMITRANGE_Pos 5U /*!< DWT FUNCTION: EMITRANGE Position */ -#define DWT_FUNCTION_EMITRANGE_Msk (0x1UL << DWT_FUNCTION_EMITRANGE_Pos) /*!< DWT FUNCTION: EMITRANGE Mask */ - -#define DWT_FUNCTION_FUNCTION_Pos 0U /*!< DWT FUNCTION: FUNCTION Position */ -#define DWT_FUNCTION_FUNCTION_Msk (0xFUL /*<< DWT_FUNCTION_FUNCTION_Pos*/) /*!< DWT FUNCTION: FUNCTION Mask */ - -/*@}*/ /* end of group CMSIS_DWT */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_TPI Trace Port Interface (TPI) - \brief Type definitions for the Trace Port Interface (TPI) - @{ - */ - -/** - \brief Structure type to access the Trace Port Interface Register (TPI). - */ -typedef struct -{ - __IM uint32_t SSPSR; /*!< Offset: 0x000 (R/ ) Supported Parallel Port Size Register */ - __IOM uint32_t CSPSR; /*!< Offset: 0x004 (R/W) Current Parallel Port Size Register */ - uint32_t RESERVED0[2U]; - __IOM uint32_t ACPR; /*!< Offset: 0x010 (R/W) Asynchronous Clock Prescaler Register */ - uint32_t RESERVED1[55U]; - __IOM uint32_t SPPR; /*!< Offset: 0x0F0 (R/W) Selected Pin Protocol Register */ - uint32_t RESERVED2[131U]; - __IM uint32_t FFSR; /*!< Offset: 0x300 (R/ ) Formatter and Flush Status Register */ - __IOM uint32_t FFCR; /*!< Offset: 0x304 (R/W) Formatter and Flush Control Register */ - __IM uint32_t FSCR; /*!< Offset: 0x308 (R/ ) Formatter Synchronization Counter Register */ - uint32_t RESERVED3[759U]; - __IM uint32_t TRIGGER; /*!< Offset: 0xEE8 (R/ ) TRIGGER Register */ - __IM uint32_t FIFO0; /*!< Offset: 0xEEC (R/ ) Integration ETM Data */ - __IM uint32_t ITATBCTR2; /*!< Offset: 0xEF0 (R/ ) ITATBCTR2 */ - uint32_t RESERVED4[1U]; - __IM uint32_t ITATBCTR0; /*!< Offset: 0xEF8 (R/ ) ITATBCTR0 */ - __IM uint32_t FIFO1; /*!< Offset: 0xEFC (R/ ) Integration ITM Data */ - __IOM uint32_t ITCTRL; /*!< Offset: 0xF00 (R/W) Integration Mode Control */ - uint32_t RESERVED5[39U]; - __IOM uint32_t CLAIMSET; /*!< Offset: 0xFA0 (R/W) Claim tag set */ - __IOM uint32_t CLAIMCLR; /*!< Offset: 0xFA4 (R/W) Claim tag clear */ - uint32_t RESERVED7[8U]; - __IM uint32_t DEVID; /*!< Offset: 0xFC8 (R/ ) TPIU_DEVID */ - __IM uint32_t DEVTYPE; /*!< Offset: 0xFCC (R/ ) TPIU_DEVTYPE */ -} TPI_Type; - -/* TPI Asynchronous Clock Prescaler Register Definitions */ -#define TPI_ACPR_PRESCALER_Pos 0U /*!< TPI ACPR: PRESCALER Position */ -#define TPI_ACPR_PRESCALER_Msk (0x1FFFUL /*<< TPI_ACPR_PRESCALER_Pos*/) /*!< TPI ACPR: PRESCALER Mask */ - -/* TPI Selected Pin Protocol Register Definitions */ -#define TPI_SPPR_TXMODE_Pos 0U /*!< TPI SPPR: TXMODE Position */ -#define TPI_SPPR_TXMODE_Msk (0x3UL /*<< TPI_SPPR_TXMODE_Pos*/) /*!< TPI SPPR: TXMODE Mask */ - -/* TPI Formatter and Flush Status Register Definitions */ -#define TPI_FFSR_FtNonStop_Pos 3U /*!< TPI FFSR: FtNonStop Position */ -#define TPI_FFSR_FtNonStop_Msk (0x1UL << TPI_FFSR_FtNonStop_Pos) /*!< TPI FFSR: FtNonStop Mask */ - -#define TPI_FFSR_TCPresent_Pos 2U /*!< TPI FFSR: TCPresent Position */ -#define TPI_FFSR_TCPresent_Msk (0x1UL << TPI_FFSR_TCPresent_Pos) /*!< TPI FFSR: TCPresent Mask */ - -#define TPI_FFSR_FtStopped_Pos 1U /*!< TPI FFSR: FtStopped Position */ -#define TPI_FFSR_FtStopped_Msk (0x1UL << TPI_FFSR_FtStopped_Pos) /*!< TPI FFSR: FtStopped Mask */ - -#define TPI_FFSR_FlInProg_Pos 0U /*!< TPI FFSR: FlInProg Position */ -#define TPI_FFSR_FlInProg_Msk (0x1UL /*<< TPI_FFSR_FlInProg_Pos*/) /*!< TPI FFSR: FlInProg Mask */ - -/* TPI Formatter and Flush Control Register Definitions */ -#define TPI_FFCR_TrigIn_Pos 8U /*!< TPI FFCR: TrigIn Position */ -#define TPI_FFCR_TrigIn_Msk (0x1UL << TPI_FFCR_TrigIn_Pos) /*!< TPI FFCR: TrigIn Mask */ - -#define TPI_FFCR_EnFCont_Pos 1U /*!< TPI FFCR: EnFCont Position */ -#define TPI_FFCR_EnFCont_Msk (0x1UL << TPI_FFCR_EnFCont_Pos) /*!< TPI FFCR: EnFCont Mask */ - -/* TPI TRIGGER Register Definitions */ -#define TPI_TRIGGER_TRIGGER_Pos 0U /*!< TPI TRIGGER: TRIGGER Position */ -#define TPI_TRIGGER_TRIGGER_Msk (0x1UL /*<< TPI_TRIGGER_TRIGGER_Pos*/) /*!< TPI TRIGGER: TRIGGER Mask */ - -/* TPI Integration ETM Data Register Definitions (FIFO0) */ -#define TPI_FIFO0_ITM_ATVALID_Pos 29U /*!< TPI FIFO0: ITM_ATVALID Position */ -#define TPI_FIFO0_ITM_ATVALID_Msk (0x1UL << TPI_FIFO0_ITM_ATVALID_Pos) /*!< TPI FIFO0: ITM_ATVALID Mask */ - -#define TPI_FIFO0_ITM_bytecount_Pos 27U /*!< TPI FIFO0: ITM_bytecount Position */ -#define TPI_FIFO0_ITM_bytecount_Msk (0x3UL << TPI_FIFO0_ITM_bytecount_Pos) /*!< TPI FIFO0: ITM_bytecount Mask */ - -#define TPI_FIFO0_ETM_ATVALID_Pos 26U /*!< TPI FIFO0: ETM_ATVALID Position */ -#define TPI_FIFO0_ETM_ATVALID_Msk (0x1UL << TPI_FIFO0_ETM_ATVALID_Pos) /*!< TPI FIFO0: ETM_ATVALID Mask */ - -#define TPI_FIFO0_ETM_bytecount_Pos 24U /*!< TPI FIFO0: ETM_bytecount Position */ -#define TPI_FIFO0_ETM_bytecount_Msk (0x3UL << TPI_FIFO0_ETM_bytecount_Pos) /*!< TPI FIFO0: ETM_bytecount Mask */ - -#define TPI_FIFO0_ETM2_Pos 16U /*!< TPI FIFO0: ETM2 Position */ -#define TPI_FIFO0_ETM2_Msk (0xFFUL << TPI_FIFO0_ETM2_Pos) /*!< TPI FIFO0: ETM2 Mask */ - -#define TPI_FIFO0_ETM1_Pos 8U /*!< TPI FIFO0: ETM1 Position */ -#define TPI_FIFO0_ETM1_Msk (0xFFUL << TPI_FIFO0_ETM1_Pos) /*!< TPI FIFO0: ETM1 Mask */ - -#define TPI_FIFO0_ETM0_Pos 0U /*!< TPI FIFO0: ETM0 Position */ -#define TPI_FIFO0_ETM0_Msk (0xFFUL /*<< TPI_FIFO0_ETM0_Pos*/) /*!< TPI FIFO0: ETM0 Mask */ - -/* TPI ITATBCTR2 Register Definitions */ -#define TPI_ITATBCTR2_ATREADY2_Pos 0U /*!< TPI ITATBCTR2: ATREADY2 Position */ -#define TPI_ITATBCTR2_ATREADY2_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY2_Pos*/) /*!< TPI ITATBCTR2: ATREADY2 Mask */ - -#define TPI_ITATBCTR2_ATREADY1_Pos 0U /*!< TPI ITATBCTR2: ATREADY1 Position */ -#define TPI_ITATBCTR2_ATREADY1_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY1_Pos*/) /*!< TPI ITATBCTR2: ATREADY1 Mask */ - -/* TPI Integration ITM Data Register Definitions (FIFO1) */ -#define TPI_FIFO1_ITM_ATVALID_Pos 29U /*!< TPI FIFO1: ITM_ATVALID Position */ -#define TPI_FIFO1_ITM_ATVALID_Msk (0x1UL << TPI_FIFO1_ITM_ATVALID_Pos) /*!< TPI FIFO1: ITM_ATVALID Mask */ - -#define TPI_FIFO1_ITM_bytecount_Pos 27U /*!< TPI FIFO1: ITM_bytecount Position */ -#define TPI_FIFO1_ITM_bytecount_Msk (0x3UL << TPI_FIFO1_ITM_bytecount_Pos) /*!< TPI FIFO1: ITM_bytecount Mask */ - -#define TPI_FIFO1_ETM_ATVALID_Pos 26U /*!< TPI FIFO1: ETM_ATVALID Position */ -#define TPI_FIFO1_ETM_ATVALID_Msk (0x1UL << TPI_FIFO1_ETM_ATVALID_Pos) /*!< TPI FIFO1: ETM_ATVALID Mask */ - -#define TPI_FIFO1_ETM_bytecount_Pos 24U /*!< TPI FIFO1: ETM_bytecount Position */ -#define TPI_FIFO1_ETM_bytecount_Msk (0x3UL << TPI_FIFO1_ETM_bytecount_Pos) /*!< TPI FIFO1: ETM_bytecount Mask */ - -#define TPI_FIFO1_ITM2_Pos 16U /*!< TPI FIFO1: ITM2 Position */ -#define TPI_FIFO1_ITM2_Msk (0xFFUL << TPI_FIFO1_ITM2_Pos) /*!< TPI FIFO1: ITM2 Mask */ - -#define TPI_FIFO1_ITM1_Pos 8U /*!< TPI FIFO1: ITM1 Position */ -#define TPI_FIFO1_ITM1_Msk (0xFFUL << TPI_FIFO1_ITM1_Pos) /*!< TPI FIFO1: ITM1 Mask */ - -#define TPI_FIFO1_ITM0_Pos 0U /*!< TPI FIFO1: ITM0 Position */ -#define TPI_FIFO1_ITM0_Msk (0xFFUL /*<< TPI_FIFO1_ITM0_Pos*/) /*!< TPI FIFO1: ITM0 Mask */ - -/* TPI ITATBCTR0 Register Definitions */ -#define TPI_ITATBCTR0_ATREADY2_Pos 0U /*!< TPI ITATBCTR0: ATREADY2 Position */ -#define TPI_ITATBCTR0_ATREADY2_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY2_Pos*/) /*!< TPI ITATBCTR0: ATREADY2 Mask */ - -#define TPI_ITATBCTR0_ATREADY1_Pos 0U /*!< TPI ITATBCTR0: ATREADY1 Position */ -#define TPI_ITATBCTR0_ATREADY1_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY1_Pos*/) /*!< TPI ITATBCTR0: ATREADY1 Mask */ - -/* TPI Integration Mode Control Register Definitions */ -#define TPI_ITCTRL_Mode_Pos 0U /*!< TPI ITCTRL: Mode Position */ -#define TPI_ITCTRL_Mode_Msk (0x3UL /*<< TPI_ITCTRL_Mode_Pos*/) /*!< TPI ITCTRL: Mode Mask */ - -/* TPI DEVID Register Definitions */ -#define TPI_DEVID_NRZVALID_Pos 11U /*!< TPI DEVID: NRZVALID Position */ -#define TPI_DEVID_NRZVALID_Msk (0x1UL << TPI_DEVID_NRZVALID_Pos) /*!< TPI DEVID: NRZVALID Mask */ - -#define TPI_DEVID_MANCVALID_Pos 10U /*!< TPI DEVID: MANCVALID Position */ -#define TPI_DEVID_MANCVALID_Msk (0x1UL << TPI_DEVID_MANCVALID_Pos) /*!< TPI DEVID: MANCVALID Mask */ - -#define TPI_DEVID_PTINVALID_Pos 9U /*!< TPI DEVID: PTINVALID Position */ -#define TPI_DEVID_PTINVALID_Msk (0x1UL << TPI_DEVID_PTINVALID_Pos) /*!< TPI DEVID: PTINVALID Mask */ - -#define TPI_DEVID_MinBufSz_Pos 6U /*!< TPI DEVID: MinBufSz Position */ -#define TPI_DEVID_MinBufSz_Msk (0x7UL << TPI_DEVID_MinBufSz_Pos) /*!< TPI DEVID: MinBufSz Mask */ - -#define TPI_DEVID_AsynClkIn_Pos 5U /*!< TPI DEVID: AsynClkIn Position */ -#define TPI_DEVID_AsynClkIn_Msk (0x1UL << TPI_DEVID_AsynClkIn_Pos) /*!< TPI DEVID: AsynClkIn Mask */ - -#define TPI_DEVID_NrTraceInput_Pos 0U /*!< TPI DEVID: NrTraceInput Position */ -#define TPI_DEVID_NrTraceInput_Msk (0x1FUL /*<< TPI_DEVID_NrTraceInput_Pos*/) /*!< TPI DEVID: NrTraceInput Mask */ - -/* TPI DEVTYPE Register Definitions */ -#define TPI_DEVTYPE_SubType_Pos 4U /*!< TPI DEVTYPE: SubType Position */ -#define TPI_DEVTYPE_SubType_Msk (0xFUL /*<< TPI_DEVTYPE_SubType_Pos*/) /*!< TPI DEVTYPE: SubType Mask */ - -#define TPI_DEVTYPE_MajorType_Pos 0U /*!< TPI DEVTYPE: MajorType Position */ -#define TPI_DEVTYPE_MajorType_Msk (0xFUL << TPI_DEVTYPE_MajorType_Pos) /*!< TPI DEVTYPE: MajorType Mask */ - -/*@}*/ /* end of group CMSIS_TPI */ - - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_MPU Memory Protection Unit (MPU) - \brief Type definitions for the Memory Protection Unit (MPU) - @{ - */ - -/** - \brief Structure type to access the Memory Protection Unit (MPU). - */ -typedef struct -{ - __IM uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */ - __IOM uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */ - __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region RNRber Register */ - __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */ - __IOM uint32_t RASR; /*!< Offset: 0x010 (R/W) MPU Region Attribute and Size Register */ - __IOM uint32_t RBAR_A1; /*!< Offset: 0x014 (R/W) MPU Alias 1 Region Base Address Register */ - __IOM uint32_t RASR_A1; /*!< Offset: 0x018 (R/W) MPU Alias 1 Region Attribute and Size Register */ - __IOM uint32_t RBAR_A2; /*!< Offset: 0x01C (R/W) MPU Alias 2 Region Base Address Register */ - __IOM uint32_t RASR_A2; /*!< Offset: 0x020 (R/W) MPU Alias 2 Region Attribute and Size Register */ - __IOM uint32_t RBAR_A3; /*!< Offset: 0x024 (R/W) MPU Alias 3 Region Base Address Register */ - __IOM uint32_t RASR_A3; /*!< Offset: 0x028 (R/W) MPU Alias 3 Region Attribute and Size Register */ -} MPU_Type; - -#define MPU_TYPE_RALIASES 4U - -/* MPU Type Register Definitions */ -#define MPU_TYPE_IREGION_Pos 16U /*!< MPU TYPE: IREGION Position */ -#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */ - -#define MPU_TYPE_DREGION_Pos 8U /*!< MPU TYPE: DREGION Position */ -#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ - -#define MPU_TYPE_SEPARATE_Pos 0U /*!< MPU TYPE: SEPARATE Position */ -#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */ - -/* MPU Control Register Definitions */ -#define MPU_CTRL_PRIVDEFENA_Pos 2U /*!< MPU CTRL: PRIVDEFENA Position */ -#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */ - -#define MPU_CTRL_HFNMIENA_Pos 1U /*!< MPU CTRL: HFNMIENA Position */ -#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ - -#define MPU_CTRL_ENABLE_Pos 0U /*!< MPU CTRL: ENABLE Position */ -#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */ - -/* MPU Region Number Register Definitions */ -#define MPU_RNR_REGION_Pos 0U /*!< MPU RNR: REGION Position */ -#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */ - -/* MPU Region Base Address Register Definitions */ -#define MPU_RBAR_ADDR_Pos 5U /*!< MPU RBAR: ADDR Position */ -#define MPU_RBAR_ADDR_Msk (0x7FFFFFFUL << MPU_RBAR_ADDR_Pos) /*!< MPU RBAR: ADDR Mask */ - -#define MPU_RBAR_VALID_Pos 4U /*!< MPU RBAR: VALID Position */ -#define MPU_RBAR_VALID_Msk (1UL << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */ - -#define MPU_RBAR_REGION_Pos 0U /*!< MPU RBAR: REGION Position */ -#define MPU_RBAR_REGION_Msk (0xFUL /*<< MPU_RBAR_REGION_Pos*/) /*!< MPU RBAR: REGION Mask */ - -/* MPU Region Attribute and Size Register Definitions */ -#define MPU_RASR_ATTRS_Pos 16U /*!< MPU RASR: MPU Region Attribute field Position */ -#define MPU_RASR_ATTRS_Msk (0xFFFFUL << MPU_RASR_ATTRS_Pos) /*!< MPU RASR: MPU Region Attribute field Mask */ - -#define MPU_RASR_XN_Pos 28U /*!< MPU RASR: ATTRS.XN Position */ -#define MPU_RASR_XN_Msk (1UL << MPU_RASR_XN_Pos) /*!< MPU RASR: ATTRS.XN Mask */ - -#define MPU_RASR_AP_Pos 24U /*!< MPU RASR: ATTRS.AP Position */ -#define MPU_RASR_AP_Msk (0x7UL << MPU_RASR_AP_Pos) /*!< MPU RASR: ATTRS.AP Mask */ - -#define MPU_RASR_TEX_Pos 19U /*!< MPU RASR: ATTRS.TEX Position */ -#define MPU_RASR_TEX_Msk (0x7UL << MPU_RASR_TEX_Pos) /*!< MPU RASR: ATTRS.TEX Mask */ - -#define MPU_RASR_S_Pos 18U /*!< MPU RASR: ATTRS.S Position */ -#define MPU_RASR_S_Msk (1UL << MPU_RASR_S_Pos) /*!< MPU RASR: ATTRS.S Mask */ - -#define MPU_RASR_C_Pos 17U /*!< MPU RASR: ATTRS.C Position */ -#define MPU_RASR_C_Msk (1UL << MPU_RASR_C_Pos) /*!< MPU RASR: ATTRS.C Mask */ - -#define MPU_RASR_B_Pos 16U /*!< MPU RASR: ATTRS.B Position */ -#define MPU_RASR_B_Msk (1UL << MPU_RASR_B_Pos) /*!< MPU RASR: ATTRS.B Mask */ - -#define MPU_RASR_SRD_Pos 8U /*!< MPU RASR: Sub-Region Disable Position */ -#define MPU_RASR_SRD_Msk (0xFFUL << MPU_RASR_SRD_Pos) /*!< MPU RASR: Sub-Region Disable Mask */ - -#define MPU_RASR_SIZE_Pos 1U /*!< MPU RASR: Region Size Field Position */ -#define MPU_RASR_SIZE_Msk (0x1FUL << MPU_RASR_SIZE_Pos) /*!< MPU RASR: Region Size Field Mask */ - -#define MPU_RASR_ENABLE_Pos 0U /*!< MPU RASR: Region enable bit Position */ -#define MPU_RASR_ENABLE_Msk (1UL /*<< MPU_RASR_ENABLE_Pos*/) /*!< MPU RASR: Region enable bit Disable Mask */ - -/*@} end of group CMSIS_MPU */ -#endif /* defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_FPU Floating Point Unit (FPU) - \brief Type definitions for the Floating Point Unit (FPU) - @{ - */ - -/** - \brief Structure type to access the Floating Point Unit (FPU). - */ -typedef struct -{ - uint32_t RESERVED0[1U]; - __IOM uint32_t FPCCR; /*!< Offset: 0x004 (R/W) Floating-Point Context Control Register */ - __IOM uint32_t FPCAR; /*!< Offset: 0x008 (R/W) Floating-Point Context Address Register */ - __IOM uint32_t FPDSCR; /*!< Offset: 0x00C (R/W) Floating-Point Default Status Control Register */ - __IM uint32_t MVFR0; /*!< Offset: 0x010 (R/ ) Media and FP Feature Register 0 */ - __IM uint32_t MVFR1; /*!< Offset: 0x014 (R/ ) Media and FP Feature Register 1 */ - __IM uint32_t MVFR2; /*!< Offset: 0x018 (R/ ) Media and FP Feature Register 2 */ -} FPU_Type; - -/* Floating-Point Context Control Register Definitions */ -#define FPU_FPCCR_ASPEN_Pos 31U /*!< FPCCR: ASPEN bit Position */ -#define FPU_FPCCR_ASPEN_Msk (1UL << FPU_FPCCR_ASPEN_Pos) /*!< FPCCR: ASPEN bit Mask */ - -#define FPU_FPCCR_LSPEN_Pos 30U /*!< FPCCR: LSPEN Position */ -#define FPU_FPCCR_LSPEN_Msk (1UL << FPU_FPCCR_LSPEN_Pos) /*!< FPCCR: LSPEN bit Mask */ - -#define FPU_FPCCR_MONRDY_Pos 8U /*!< FPCCR: MONRDY Position */ -#define FPU_FPCCR_MONRDY_Msk (1UL << FPU_FPCCR_MONRDY_Pos) /*!< FPCCR: MONRDY bit Mask */ - -#define FPU_FPCCR_BFRDY_Pos 6U /*!< FPCCR: BFRDY Position */ -#define FPU_FPCCR_BFRDY_Msk (1UL << FPU_FPCCR_BFRDY_Pos) /*!< FPCCR: BFRDY bit Mask */ - -#define FPU_FPCCR_MMRDY_Pos 5U /*!< FPCCR: MMRDY Position */ -#define FPU_FPCCR_MMRDY_Msk (1UL << FPU_FPCCR_MMRDY_Pos) /*!< FPCCR: MMRDY bit Mask */ - -#define FPU_FPCCR_HFRDY_Pos 4U /*!< FPCCR: HFRDY Position */ -#define FPU_FPCCR_HFRDY_Msk (1UL << FPU_FPCCR_HFRDY_Pos) /*!< FPCCR: HFRDY bit Mask */ - -#define FPU_FPCCR_THREAD_Pos 3U /*!< FPCCR: processor mode bit Position */ -#define FPU_FPCCR_THREAD_Msk (1UL << FPU_FPCCR_THREAD_Pos) /*!< FPCCR: processor mode active bit Mask */ - -#define FPU_FPCCR_USER_Pos 1U /*!< FPCCR: privilege level bit Position */ -#define FPU_FPCCR_USER_Msk (1UL << FPU_FPCCR_USER_Pos) /*!< FPCCR: privilege level bit Mask */ - -#define FPU_FPCCR_LSPACT_Pos 0U /*!< FPCCR: Lazy state preservation active bit Position */ -#define FPU_FPCCR_LSPACT_Msk (1UL /*<< FPU_FPCCR_LSPACT_Pos*/) /*!< FPCCR: Lazy state preservation active bit Mask */ - -/* Floating-Point Context Address Register Definitions */ -#define FPU_FPCAR_ADDRESS_Pos 3U /*!< FPCAR: ADDRESS bit Position */ -#define FPU_FPCAR_ADDRESS_Msk (0x1FFFFFFFUL << FPU_FPCAR_ADDRESS_Pos) /*!< FPCAR: ADDRESS bit Mask */ - -/* Floating-Point Default Status Control Register Definitions */ -#define FPU_FPDSCR_AHP_Pos 26U /*!< FPDSCR: AHP bit Position */ -#define FPU_FPDSCR_AHP_Msk (1UL << FPU_FPDSCR_AHP_Pos) /*!< FPDSCR: AHP bit Mask */ - -#define FPU_FPDSCR_DN_Pos 25U /*!< FPDSCR: DN bit Position */ -#define FPU_FPDSCR_DN_Msk (1UL << FPU_FPDSCR_DN_Pos) /*!< FPDSCR: DN bit Mask */ - -#define FPU_FPDSCR_FZ_Pos 24U /*!< FPDSCR: FZ bit Position */ -#define FPU_FPDSCR_FZ_Msk (1UL << FPU_FPDSCR_FZ_Pos) /*!< FPDSCR: FZ bit Mask */ - -#define FPU_FPDSCR_RMode_Pos 22U /*!< FPDSCR: RMode bit Position */ -#define FPU_FPDSCR_RMode_Msk (3UL << FPU_FPDSCR_RMode_Pos) /*!< FPDSCR: RMode bit Mask */ - -/* Media and FP Feature Register 0 Definitions */ -#define FPU_MVFR0_FP_rounding_modes_Pos 28U /*!< MVFR0: FP rounding modes bits Position */ -#define FPU_MVFR0_FP_rounding_modes_Msk (0xFUL << FPU_MVFR0_FP_rounding_modes_Pos) /*!< MVFR0: FP rounding modes bits Mask */ - -#define FPU_MVFR0_Short_vectors_Pos 24U /*!< MVFR0: Short vectors bits Position */ -#define FPU_MVFR0_Short_vectors_Msk (0xFUL << FPU_MVFR0_Short_vectors_Pos) /*!< MVFR0: Short vectors bits Mask */ - -#define FPU_MVFR0_Square_root_Pos 20U /*!< MVFR0: Square root bits Position */ -#define FPU_MVFR0_Square_root_Msk (0xFUL << FPU_MVFR0_Square_root_Pos) /*!< MVFR0: Square root bits Mask */ - -#define FPU_MVFR0_Divide_Pos 16U /*!< MVFR0: Divide bits Position */ -#define FPU_MVFR0_Divide_Msk (0xFUL << FPU_MVFR0_Divide_Pos) /*!< MVFR0: Divide bits Mask */ - -#define FPU_MVFR0_FP_excep_trapping_Pos 12U /*!< MVFR0: FP exception trapping bits Position */ -#define FPU_MVFR0_FP_excep_trapping_Msk (0xFUL << FPU_MVFR0_FP_excep_trapping_Pos) /*!< MVFR0: FP exception trapping bits Mask */ - -#define FPU_MVFR0_Double_precision_Pos 8U /*!< MVFR0: Double-precision bits Position */ -#define FPU_MVFR0_Double_precision_Msk (0xFUL << FPU_MVFR0_Double_precision_Pos) /*!< MVFR0: Double-precision bits Mask */ - -#define FPU_MVFR0_Single_precision_Pos 4U /*!< MVFR0: Single-precision bits Position */ -#define FPU_MVFR0_Single_precision_Msk (0xFUL << FPU_MVFR0_Single_precision_Pos) /*!< MVFR0: Single-precision bits Mask */ - -#define FPU_MVFR0_A_SIMD_registers_Pos 0U /*!< MVFR0: A_SIMD registers bits Position */ -#define FPU_MVFR0_A_SIMD_registers_Msk (0xFUL /*<< FPU_MVFR0_A_SIMD_registers_Pos*/) /*!< MVFR0: A_SIMD registers bits Mask */ - -/* Media and FP Feature Register 1 Definitions */ -#define FPU_MVFR1_FP_fused_MAC_Pos 28U /*!< MVFR1: FP fused MAC bits Position */ -#define FPU_MVFR1_FP_fused_MAC_Msk (0xFUL << FPU_MVFR1_FP_fused_MAC_Pos) /*!< MVFR1: FP fused MAC bits Mask */ - -#define FPU_MVFR1_FP_HPFP_Pos 24U /*!< MVFR1: FP HPFP bits Position */ -#define FPU_MVFR1_FP_HPFP_Msk (0xFUL << FPU_MVFR1_FP_HPFP_Pos) /*!< MVFR1: FP HPFP bits Mask */ - -#define FPU_MVFR1_D_NaN_mode_Pos 4U /*!< MVFR1: D_NaN mode bits Position */ -#define FPU_MVFR1_D_NaN_mode_Msk (0xFUL << FPU_MVFR1_D_NaN_mode_Pos) /*!< MVFR1: D_NaN mode bits Mask */ - -#define FPU_MVFR1_FtZ_mode_Pos 0U /*!< MVFR1: FtZ mode bits Position */ -#define FPU_MVFR1_FtZ_mode_Msk (0xFUL /*<< FPU_MVFR1_FtZ_mode_Pos*/) /*!< MVFR1: FtZ mode bits Mask */ - -/* Media and FP Feature Register 2 Definitions */ - -#define FPU_MVFR2_VFP_Misc_Pos 4U /*!< MVFR2: VFP Misc bits Position */ -#define FPU_MVFR2_VFP_Misc_Msk (0xFUL << FPU_MVFR2_VFP_Misc_Pos) /*!< MVFR2: VFP Misc bits Mask */ - -/*@} end of group CMSIS_FPU */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug) - \brief Type definitions for the Core Debug Registers - @{ - */ - -/** - \brief Structure type to access the Core Debug Register (CoreDebug). - */ -typedef struct -{ - __IOM uint32_t DHCSR; /*!< Offset: 0x000 (R/W) Debug Halting Control and Status Register */ - __OM uint32_t DCRSR; /*!< Offset: 0x004 ( /W) Debug Core Register Selector Register */ - __IOM uint32_t DCRDR; /*!< Offset: 0x008 (R/W) Debug Core Register Data Register */ - __IOM uint32_t DEMCR; /*!< Offset: 0x00C (R/W) Debug Exception and Monitor Control Register */ -} CoreDebug_Type; - -/* Debug Halting Control and Status Register Definitions */ -#define CoreDebug_DHCSR_DBGKEY_Pos 16U /*!< CoreDebug DHCSR: DBGKEY Position */ -#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFUL << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */ - -#define CoreDebug_DHCSR_S_RESET_ST_Pos 25U /*!< CoreDebug DHCSR: S_RESET_ST Position */ -#define CoreDebug_DHCSR_S_RESET_ST_Msk (1UL << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */ - -#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24U /*!< CoreDebug DHCSR: S_RETIRE_ST Position */ -#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1UL << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */ - -#define CoreDebug_DHCSR_S_LOCKUP_Pos 19U /*!< CoreDebug DHCSR: S_LOCKUP Position */ -#define CoreDebug_DHCSR_S_LOCKUP_Msk (1UL << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */ - -#define CoreDebug_DHCSR_S_SLEEP_Pos 18U /*!< CoreDebug DHCSR: S_SLEEP Position */ -#define CoreDebug_DHCSR_S_SLEEP_Msk (1UL << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */ - -#define CoreDebug_DHCSR_S_HALT_Pos 17U /*!< CoreDebug DHCSR: S_HALT Position */ -#define CoreDebug_DHCSR_S_HALT_Msk (1UL << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */ - -#define CoreDebug_DHCSR_S_REGRDY_Pos 16U /*!< CoreDebug DHCSR: S_REGRDY Position */ -#define CoreDebug_DHCSR_S_REGRDY_Msk (1UL << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */ - -#define CoreDebug_DHCSR_C_SNAPSTALL_Pos 5U /*!< CoreDebug DHCSR: C_SNAPSTALL Position */ -#define CoreDebug_DHCSR_C_SNAPSTALL_Msk (1UL << CoreDebug_DHCSR_C_SNAPSTALL_Pos) /*!< CoreDebug DHCSR: C_SNAPSTALL Mask */ - -#define CoreDebug_DHCSR_C_MASKINTS_Pos 3U /*!< CoreDebug DHCSR: C_MASKINTS Position */ -#define CoreDebug_DHCSR_C_MASKINTS_Msk (1UL << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */ - -#define CoreDebug_DHCSR_C_STEP_Pos 2U /*!< CoreDebug DHCSR: C_STEP Position */ -#define CoreDebug_DHCSR_C_STEP_Msk (1UL << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */ - -#define CoreDebug_DHCSR_C_HALT_Pos 1U /*!< CoreDebug DHCSR: C_HALT Position */ -#define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */ - -#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0U /*!< CoreDebug DHCSR: C_DEBUGEN Position */ -#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL /*<< CoreDebug_DHCSR_C_DEBUGEN_Pos*/) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ - -/* Debug Core Register Selector Register Definitions */ -#define CoreDebug_DCRSR_REGWnR_Pos 16U /*!< CoreDebug DCRSR: REGWnR Position */ -#define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */ - -#define CoreDebug_DCRSR_REGSEL_Pos 0U /*!< CoreDebug DCRSR: REGSEL Position */ -#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL /*<< CoreDebug_DCRSR_REGSEL_Pos*/) /*!< CoreDebug DCRSR: REGSEL Mask */ - -/* Debug Exception and Monitor Control Register Definitions */ -#define CoreDebug_DEMCR_TRCENA_Pos 24U /*!< CoreDebug DEMCR: TRCENA Position */ -#define CoreDebug_DEMCR_TRCENA_Msk (1UL << CoreDebug_DEMCR_TRCENA_Pos) /*!< CoreDebug DEMCR: TRCENA Mask */ - -#define CoreDebug_DEMCR_MON_REQ_Pos 19U /*!< CoreDebug DEMCR: MON_REQ Position */ -#define CoreDebug_DEMCR_MON_REQ_Msk (1UL << CoreDebug_DEMCR_MON_REQ_Pos) /*!< CoreDebug DEMCR: MON_REQ Mask */ - -#define CoreDebug_DEMCR_MON_STEP_Pos 18U /*!< CoreDebug DEMCR: MON_STEP Position */ -#define CoreDebug_DEMCR_MON_STEP_Msk (1UL << CoreDebug_DEMCR_MON_STEP_Pos) /*!< CoreDebug DEMCR: MON_STEP Mask */ - -#define CoreDebug_DEMCR_MON_PEND_Pos 17U /*!< CoreDebug DEMCR: MON_PEND Position */ -#define CoreDebug_DEMCR_MON_PEND_Msk (1UL << CoreDebug_DEMCR_MON_PEND_Pos) /*!< CoreDebug DEMCR: MON_PEND Mask */ - -#define CoreDebug_DEMCR_MON_EN_Pos 16U /*!< CoreDebug DEMCR: MON_EN Position */ -#define CoreDebug_DEMCR_MON_EN_Msk (1UL << CoreDebug_DEMCR_MON_EN_Pos) /*!< CoreDebug DEMCR: MON_EN Mask */ - -#define CoreDebug_DEMCR_VC_HARDERR_Pos 10U /*!< CoreDebug DEMCR: VC_HARDERR Position */ -#define CoreDebug_DEMCR_VC_HARDERR_Msk (1UL << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */ - -#define CoreDebug_DEMCR_VC_INTERR_Pos 9U /*!< CoreDebug DEMCR: VC_INTERR Position */ -#define CoreDebug_DEMCR_VC_INTERR_Msk (1UL << CoreDebug_DEMCR_VC_INTERR_Pos) /*!< CoreDebug DEMCR: VC_INTERR Mask */ - -#define CoreDebug_DEMCR_VC_BUSERR_Pos 8U /*!< CoreDebug DEMCR: VC_BUSERR Position */ -#define CoreDebug_DEMCR_VC_BUSERR_Msk (1UL << CoreDebug_DEMCR_VC_BUSERR_Pos) /*!< CoreDebug DEMCR: VC_BUSERR Mask */ - -#define CoreDebug_DEMCR_VC_STATERR_Pos 7U /*!< CoreDebug DEMCR: VC_STATERR Position */ -#define CoreDebug_DEMCR_VC_STATERR_Msk (1UL << CoreDebug_DEMCR_VC_STATERR_Pos) /*!< CoreDebug DEMCR: VC_STATERR Mask */ - -#define CoreDebug_DEMCR_VC_CHKERR_Pos 6U /*!< CoreDebug DEMCR: VC_CHKERR Position */ -#define CoreDebug_DEMCR_VC_CHKERR_Msk (1UL << CoreDebug_DEMCR_VC_CHKERR_Pos) /*!< CoreDebug DEMCR: VC_CHKERR Mask */ - -#define CoreDebug_DEMCR_VC_NOCPERR_Pos 5U /*!< CoreDebug DEMCR: VC_NOCPERR Position */ -#define CoreDebug_DEMCR_VC_NOCPERR_Msk (1UL << CoreDebug_DEMCR_VC_NOCPERR_Pos) /*!< CoreDebug DEMCR: VC_NOCPERR Mask */ - -#define CoreDebug_DEMCR_VC_MMERR_Pos 4U /*!< CoreDebug DEMCR: VC_MMERR Position */ -#define CoreDebug_DEMCR_VC_MMERR_Msk (1UL << CoreDebug_DEMCR_VC_MMERR_Pos) /*!< CoreDebug DEMCR: VC_MMERR Mask */ - -#define CoreDebug_DEMCR_VC_CORERESET_Pos 0U /*!< CoreDebug DEMCR: VC_CORERESET Position */ -#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL /*<< CoreDebug_DEMCR_VC_CORERESET_Pos*/) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ - -/*@} end of group CMSIS_CoreDebug */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_bitfield Core register bit field macros - \brief Macros for use with bit field definitions (xxx_Pos, xxx_Msk). - @{ - */ - -/** - \brief Mask and shift a bit field value for use in a register bit range. - \param[in] field Name of the register bit field. - \param[in] value Value of the bit field. This parameter is interpreted as an uint32_t type. - \return Masked and shifted value. -*/ -#define _VAL2FLD(field, value) (((uint32_t)(value) << field ## _Pos) & field ## _Msk) - -/** - \brief Mask and shift a register value to extract a bit filed value. - \param[in] field Name of the register bit field. - \param[in] value Value of register. This parameter is interpreted as an uint32_t type. - \return Masked and shifted bit field value. -*/ -#define _FLD2VAL(field, value) (((uint32_t)(value) & field ## _Msk) >> field ## _Pos) - -/*@} end of group CMSIS_core_bitfield */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_base Core Definitions - \brief Definitions for base addresses, unions, and structures. - @{ - */ - -/* Memory mapping of Core Hardware */ -#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ -#define ITM_BASE (0xE0000000UL) /*!< ITM Base Address */ -#define DWT_BASE (0xE0001000UL) /*!< DWT Base Address */ -#define TPI_BASE (0xE0040000UL) /*!< TPI Base Address */ -#define CoreDebug_BASE (0xE000EDF0UL) /*!< Core Debug Base Address */ -#define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ -#define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ -#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ - -#define SCnSCB ((SCnSCB_Type *) SCS_BASE ) /*!< System control Register not in SCB */ -#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ -#define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ -#define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ -#define ITM ((ITM_Type *) ITM_BASE ) /*!< ITM configuration struct */ -#define DWT ((DWT_Type *) DWT_BASE ) /*!< DWT configuration struct */ -#define TPI ((TPI_Type *) TPI_BASE ) /*!< TPI configuration struct */ -#define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE) /*!< Core Debug configuration struct */ - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */ - #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */ -#endif - -#define FPU_BASE (SCS_BASE + 0x0F30UL) /*!< Floating Point Unit */ -#define FPU ((FPU_Type *) FPU_BASE ) /*!< Floating Point Unit */ - -/*@} */ - - - -/******************************************************************************* - * Hardware Abstraction Layer - Core Function Interface contains: - - Core NVIC Functions - - Core SysTick Functions - - Core Debug Functions - - Core Register Access Functions - ******************************************************************************/ -/** - \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference -*/ - - - -/* ########################## NVIC functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_NVICFunctions NVIC Functions - \brief Functions that manage interrupts and exceptions via the NVIC. - @{ - */ - -#ifdef CMSIS_NVIC_VIRTUAL - #ifndef CMSIS_NVIC_VIRTUAL_HEADER_FILE - #define CMSIS_NVIC_VIRTUAL_HEADER_FILE "cmsis_nvic_virtual.h" - #endif - #include CMSIS_NVIC_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetPriorityGrouping __NVIC_SetPriorityGrouping - #define NVIC_GetPriorityGrouping __NVIC_GetPriorityGrouping - #define NVIC_EnableIRQ __NVIC_EnableIRQ - #define NVIC_GetEnableIRQ __NVIC_GetEnableIRQ - #define NVIC_DisableIRQ __NVIC_DisableIRQ - #define NVIC_GetPendingIRQ __NVIC_GetPendingIRQ - #define NVIC_SetPendingIRQ __NVIC_SetPendingIRQ - #define NVIC_ClearPendingIRQ __NVIC_ClearPendingIRQ - #define NVIC_GetActive __NVIC_GetActive - #define NVIC_SetPriority __NVIC_SetPriority - #define NVIC_GetPriority __NVIC_GetPriority - #define NVIC_SystemReset __NVIC_SystemReset -#endif /* CMSIS_NVIC_VIRTUAL */ - -#ifdef CMSIS_VECTAB_VIRTUAL - #ifndef CMSIS_VECTAB_VIRTUAL_HEADER_FILE - #define CMSIS_VECTAB_VIRTUAL_HEADER_FILE "cmsis_vectab_virtual.h" - #endif - #include CMSIS_VECTAB_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetVector __NVIC_SetVector - #define NVIC_GetVector __NVIC_GetVector -#endif /* (CMSIS_VECTAB_VIRTUAL) */ - -#define NVIC_USER_IRQ_OFFSET 16 - - -/* The following EXC_RETURN values are saved the LR on exception entry */ -#define EXC_RETURN_HANDLER (0xFFFFFFF1UL) /* return to Handler mode, uses MSP after return */ -#define EXC_RETURN_THREAD_MSP (0xFFFFFFF9UL) /* return to Thread mode, uses MSP after return */ -#define EXC_RETURN_THREAD_PSP (0xFFFFFFFDUL) /* return to Thread mode, uses PSP after return */ -#define EXC_RETURN_HANDLER_FPU (0xFFFFFFE1UL) /* return to Handler mode, uses MSP after return, restore floating-point state */ -#define EXC_RETURN_THREAD_MSP_FPU (0xFFFFFFE9UL) /* return to Thread mode, uses MSP after return, restore floating-point state */ -#define EXC_RETURN_THREAD_PSP_FPU (0xFFFFFFEDUL) /* return to Thread mode, uses PSP after return, restore floating-point state */ - - -/** - \brief Set Priority Grouping - \details Sets the priority grouping field using the required unlock sequence. - The parameter PriorityGroup is assigned to the field SCB->AIRCR [10:8] PRIGROUP field. - Only values from 0..7 are used. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. - \param [in] PriorityGroup Priority grouping field. - */ -__STATIC_INLINE void __NVIC_SetPriorityGrouping(uint32_t PriorityGroup) -{ - uint32_t reg_value; - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - - reg_value = SCB->AIRCR; /* read old register configuration */ - reg_value &= ~((uint32_t)(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk)); /* clear bits to change */ - reg_value = (reg_value | - ((uint32_t)0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - (PriorityGroupTmp << SCB_AIRCR_PRIGROUP_Pos) ); /* Insert write key and priority group */ - SCB->AIRCR = reg_value; -} - - -/** - \brief Get Priority Grouping - \details Reads the priority grouping field from the NVIC Interrupt Controller. - \return Priority grouping field (SCB->AIRCR [10:8] PRIGROUP field). - */ -__STATIC_INLINE uint32_t __NVIC_GetPriorityGrouping(void) -{ - return ((uint32_t)((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos)); -} - - -/** - \brief Enable Interrupt - \details Enables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_EnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - __COMPILER_BARRIER(); - NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - __COMPILER_BARRIER(); - } -} - - -/** - \brief Get Interrupt Enable status - \details Returns a device specific interrupt enable status from the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt is not enabled. - \return 1 Interrupt is enabled. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetEnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Disable Interrupt - \details Disables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_DisableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - __DSB(); - __ISB(); - } -} - - -/** - \brief Get Pending Interrupt - \details Reads the NVIC pending register and returns the pending bit for the specified device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not pending. - \return 1 Interrupt status is pending. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Pending Interrupt - \details Sets the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_SetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Clear Pending Interrupt - \details Clears the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_ClearPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Active Interrupt - \details Reads the active register in the NVIC and returns the active bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not active. - \return 1 Interrupt status is active. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetActive(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Interrupt Priority - \details Sets the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \param [in] priority Priority to set. - \note The priority cannot be set for every processor exception. - */ -__STATIC_INLINE void __NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->IP[((uint32_t)IRQn)] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); - } - else - { - SCB->SHPR[(((uint32_t)IRQn) & 0xFUL)-4UL] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); - } -} - - -/** - \brief Get Interrupt Priority - \details Reads the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Interrupt Priority. - Value is aligned automatically to the implemented priority bits of the microcontroller. - */ -__STATIC_INLINE uint32_t __NVIC_GetPriority(IRQn_Type IRQn) -{ - - if ((int32_t)(IRQn) >= 0) - { - return(((uint32_t)NVIC->IP[((uint32_t)IRQn)] >> (8U - __NVIC_PRIO_BITS))); - } - else - { - return(((uint32_t)SCB->SHPR[(((uint32_t)IRQn) & 0xFUL)-4UL] >> (8U - __NVIC_PRIO_BITS))); - } -} - - -/** - \brief Encode Priority - \details Encodes the priority for an interrupt with the given priority group, - preemptive priority value, and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. - \param [in] PriorityGroup Used priority group. - \param [in] PreemptPriority Preemptive priority value (starting from 0). - \param [in] SubPriority Subpriority value (starting from 0). - \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority(). - */ -__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - return ( - ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | - ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) - ); -} - - -/** - \brief Decode Priority - \details Decodes an interrupt priority value with a given priority group to - preemptive priority value and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set. - \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority(). - \param [in] PriorityGroup Used priority group. - \param [out] pPreemptPriority Preemptive priority value (starting from 0). - \param [out] pSubPriority Subpriority value (starting from 0). - */ -__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* const pPreemptPriority, uint32_t* const pSubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - *pPreemptPriority = (Priority >> SubPriorityBits) & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL); - *pSubPriority = (Priority ) & (uint32_t)((1UL << (SubPriorityBits )) - 1UL); -} - - -/** - \brief Set Interrupt Vector - \details Sets an interrupt vector in SRAM based interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - VTOR must been relocated to SRAM before. - \param [in] IRQn Interrupt number - \param [in] vector Address of interrupt handler function - */ -__STATIC_INLINE void __NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) -{ - uint32_t vectors = (uint32_t )SCB->VTOR; - (* (int *) (vectors + ((int32_t)IRQn + NVIC_USER_IRQ_OFFSET) * 4)) = vector; - __DSB(); -} - - -/** - \brief Get Interrupt Vector - \details Reads an interrupt vector from interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Address of interrupt handler function - */ -__STATIC_INLINE uint32_t __NVIC_GetVector(IRQn_Type IRQn) -{ - uint32_t vectors = (uint32_t )SCB->VTOR; - return (uint32_t)(* (int *) (vectors + ((int32_t)IRQn + NVIC_USER_IRQ_OFFSET) * 4)); -} - - -/** - \brief System Reset - \details Initiates a system reset request to reset the MCU. - */ -__NO_RETURN __STATIC_INLINE void __NVIC_SystemReset(void) -{ - __DSB(); /* Ensure all outstanding memory accesses included - buffered write are completed before reset */ - SCB->AIRCR = (uint32_t)((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) | - SCB_AIRCR_SYSRESETREQ_Msk ); /* Keep priority group unchanged */ - __DSB(); /* Ensure completion of memory access */ - - for(;;) /* wait until reset */ - { - __NOP(); - } -} - -/*@} end of CMSIS_Core_NVICFunctions */ - - -/* ########################## MPU functions #################################### */ - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - -#include "mpu_armv7.h" - -#endif - - -/* ########################## FPU functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_FpuFunctions FPU Functions - \brief Function that provides FPU type. - @{ - */ - -/** - \brief get FPU type - \details returns the FPU type - \returns - - \b 0: No FPU - - \b 1: Single precision FPU - - \b 2: Double + Single precision FPU - */ -__STATIC_INLINE uint32_t SCB_GetFPUType(void) -{ - uint32_t mvfr0; - - mvfr0 = SCB->MVFR0; - if ((mvfr0 & (FPU_MVFR0_Single_precision_Msk | FPU_MVFR0_Double_precision_Msk)) == 0x220U) - { - return 2U; /* Double + Single precision FPU */ - } - else if ((mvfr0 & (FPU_MVFR0_Single_precision_Msk | FPU_MVFR0_Double_precision_Msk)) == 0x020U) - { - return 1U; /* Single precision FPU */ - } - else - { - return 0U; /* No FPU */ - } -} - -/*@} end of CMSIS_Core_FpuFunctions */ - - - -/* ########################## Cache functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_CacheFunctions Cache Functions - \brief Functions that configure Instruction and Data cache. - @{ - */ - -/* Cache Size ID Register Macros */ -#define CCSIDR_WAYS(x) (((x) & SCB_CCSIDR_ASSOCIATIVITY_Msk) >> SCB_CCSIDR_ASSOCIATIVITY_Pos) -#define CCSIDR_SETS(x) (((x) & SCB_CCSIDR_NUMSETS_Msk ) >> SCB_CCSIDR_NUMSETS_Pos ) - -#define __SCB_DCACHE_LINE_SIZE 32U /*!< Cortex-M7 cache line size is fixed to 32 bytes (8 words). See also register SCB_CCSIDR */ -#define __SCB_ICACHE_LINE_SIZE 32U /*!< Cortex-M7 cache line size is fixed to 32 bytes (8 words). See also register SCB_CCSIDR */ - -/** - \brief Enable I-Cache - \details Turns on I-Cache - */ -__STATIC_FORCEINLINE void SCB_EnableICache (void) -{ - #if defined (__ICACHE_PRESENT) && (__ICACHE_PRESENT == 1U) - if (SCB->CCR & SCB_CCR_IC_Msk) return; /* return if ICache is already enabled */ - - __DSB(); - __ISB(); - SCB->ICIALLU = 0UL; /* invalidate I-Cache */ - __DSB(); - __ISB(); - SCB->CCR |= (uint32_t)SCB_CCR_IC_Msk; /* enable I-Cache */ - __DSB(); - __ISB(); - #endif -} - - -/** - \brief Disable I-Cache - \details Turns off I-Cache - */ -__STATIC_FORCEINLINE void SCB_DisableICache (void) -{ - #if defined (__ICACHE_PRESENT) && (__ICACHE_PRESENT == 1U) - __DSB(); - __ISB(); - SCB->CCR &= ~(uint32_t)SCB_CCR_IC_Msk; /* disable I-Cache */ - SCB->ICIALLU = 0UL; /* invalidate I-Cache */ - __DSB(); - __ISB(); - #endif -} - - -/** - \brief Invalidate I-Cache - \details Invalidates I-Cache - */ -__STATIC_FORCEINLINE void SCB_InvalidateICache (void) -{ - #if defined (__ICACHE_PRESENT) && (__ICACHE_PRESENT == 1U) - __DSB(); - __ISB(); - SCB->ICIALLU = 0UL; - __DSB(); - __ISB(); - #endif -} - - -/** - \brief I-Cache Invalidate by address - \details Invalidates I-Cache for the given address. - I-Cache is invalidated starting from a 32 byte aligned address in 32 byte granularity. - I-Cache memory blocks which are part of given address + given size are invalidated. - \param[in] addr address - \param[in] isize size of memory block (in number of bytes) -*/ -__STATIC_FORCEINLINE void SCB_InvalidateICache_by_Addr (void *addr, int32_t isize) -{ - #if defined (__ICACHE_PRESENT) && (__ICACHE_PRESENT == 1U) - if ( isize > 0 ) { - int32_t op_size = isize + (((uint32_t)addr) & (__SCB_ICACHE_LINE_SIZE - 1U)); - uint32_t op_addr = (uint32_t)addr /* & ~(__SCB_ICACHE_LINE_SIZE - 1U) */; - - __DSB(); - - do { - SCB->ICIMVAU = op_addr; /* register accepts only 32byte aligned values, only bits 31..5 are valid */ - op_addr += __SCB_ICACHE_LINE_SIZE; - op_size -= __SCB_ICACHE_LINE_SIZE; - } while ( op_size > 0 ); - - __DSB(); - __ISB(); - } - #endif -} - - -/** - \brief Enable D-Cache - \details Turns on D-Cache - */ -__STATIC_FORCEINLINE void SCB_EnableDCache (void) -{ - #if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U) - uint32_t ccsidr; - uint32_t sets; - uint32_t ways; - - if (SCB->CCR & SCB_CCR_DC_Msk) return; /* return if DCache is already enabled */ - - SCB->CSSELR = 0U; /* select Level 1 data cache */ - __DSB(); - - ccsidr = SCB->CCSIDR; - - /* invalidate D-Cache */ - sets = (uint32_t)(CCSIDR_SETS(ccsidr)); - do { - ways = (uint32_t)(CCSIDR_WAYS(ccsidr)); - do { - SCB->DCISW = (((sets << SCB_DCISW_SET_Pos) & SCB_DCISW_SET_Msk) | - ((ways << SCB_DCISW_WAY_Pos) & SCB_DCISW_WAY_Msk) ); - #if defined ( __CC_ARM ) - __schedule_barrier(); - #endif - } while (ways-- != 0U); - } while(sets-- != 0U); - __DSB(); - - SCB->CCR |= (uint32_t)SCB_CCR_DC_Msk; /* enable D-Cache */ - - __DSB(); - __ISB(); - #endif -} - - -/** - \brief Disable D-Cache - \details Turns off D-Cache - */ -__STATIC_FORCEINLINE void SCB_DisableDCache (void) -{ - #if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U) - uint32_t ccsidr; - uint32_t sets; - uint32_t ways; - - SCB->CSSELR = 0U; /* select Level 1 data cache */ - __DSB(); - - SCB->CCR &= ~(uint32_t)SCB_CCR_DC_Msk; /* disable D-Cache */ - __DSB(); - - ccsidr = SCB->CCSIDR; - - /* clean & invalidate D-Cache */ - sets = (uint32_t)(CCSIDR_SETS(ccsidr)); - do { - ways = (uint32_t)(CCSIDR_WAYS(ccsidr)); - do { - SCB->DCCISW = (((sets << SCB_DCCISW_SET_Pos) & SCB_DCCISW_SET_Msk) | - ((ways << SCB_DCCISW_WAY_Pos) & SCB_DCCISW_WAY_Msk) ); - #if defined ( __CC_ARM ) - __schedule_barrier(); - #endif - } while (ways-- != 0U); - } while(sets-- != 0U); - - __DSB(); - __ISB(); - #endif -} - - -/** - \brief Invalidate D-Cache - \details Invalidates D-Cache - */ -__STATIC_FORCEINLINE void SCB_InvalidateDCache (void) -{ - #if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U) - uint32_t ccsidr; - uint32_t sets; - uint32_t ways; - - SCB->CSSELR = 0U; /* select Level 1 data cache */ - __DSB(); - - ccsidr = SCB->CCSIDR; - - /* invalidate D-Cache */ - sets = (uint32_t)(CCSIDR_SETS(ccsidr)); - do { - ways = (uint32_t)(CCSIDR_WAYS(ccsidr)); - do { - SCB->DCISW = (((sets << SCB_DCISW_SET_Pos) & SCB_DCISW_SET_Msk) | - ((ways << SCB_DCISW_WAY_Pos) & SCB_DCISW_WAY_Msk) ); - #if defined ( __CC_ARM ) - __schedule_barrier(); - #endif - } while (ways-- != 0U); - } while(sets-- != 0U); - - __DSB(); - __ISB(); - #endif -} - - -/** - \brief Clean D-Cache - \details Cleans D-Cache - */ -__STATIC_FORCEINLINE void SCB_CleanDCache (void) -{ - #if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U) - uint32_t ccsidr; - uint32_t sets; - uint32_t ways; - - SCB->CSSELR = 0U; /* select Level 1 data cache */ - __DSB(); - - ccsidr = SCB->CCSIDR; - - /* clean D-Cache */ - sets = (uint32_t)(CCSIDR_SETS(ccsidr)); - do { - ways = (uint32_t)(CCSIDR_WAYS(ccsidr)); - do { - SCB->DCCSW = (((sets << SCB_DCCSW_SET_Pos) & SCB_DCCSW_SET_Msk) | - ((ways << SCB_DCCSW_WAY_Pos) & SCB_DCCSW_WAY_Msk) ); - #if defined ( __CC_ARM ) - __schedule_barrier(); - #endif - } while (ways-- != 0U); - } while(sets-- != 0U); - - __DSB(); - __ISB(); - #endif -} - - -/** - \brief Clean & Invalidate D-Cache - \details Cleans and Invalidates D-Cache - */ -__STATIC_FORCEINLINE void SCB_CleanInvalidateDCache (void) -{ - #if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U) - uint32_t ccsidr; - uint32_t sets; - uint32_t ways; - - SCB->CSSELR = 0U; /* select Level 1 data cache */ - __DSB(); - - ccsidr = SCB->CCSIDR; - - /* clean & invalidate D-Cache */ - sets = (uint32_t)(CCSIDR_SETS(ccsidr)); - do { - ways = (uint32_t)(CCSIDR_WAYS(ccsidr)); - do { - SCB->DCCISW = (((sets << SCB_DCCISW_SET_Pos) & SCB_DCCISW_SET_Msk) | - ((ways << SCB_DCCISW_WAY_Pos) & SCB_DCCISW_WAY_Msk) ); - #if defined ( __CC_ARM ) - __schedule_barrier(); - #endif - } while (ways-- != 0U); - } while(sets-- != 0U); - - __DSB(); - __ISB(); - #endif -} - - -/** - \brief D-Cache Invalidate by address - \details Invalidates D-Cache for the given address. - D-Cache is invalidated starting from a 32 byte aligned address in 32 byte granularity. - D-Cache memory blocks which are part of given address + given size are invalidated. - \param[in] addr address - \param[in] dsize size of memory block (in number of bytes) -*/ -__STATIC_FORCEINLINE void SCB_InvalidateDCache_by_Addr (void *addr, int32_t dsize) -{ - #if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U) - if ( dsize > 0 ) { - int32_t op_size = dsize + (((uint32_t)addr) & (__SCB_DCACHE_LINE_SIZE - 1U)); - uint32_t op_addr = (uint32_t)addr /* & ~(__SCB_DCACHE_LINE_SIZE - 1U) */; - - __DSB(); - - do { - SCB->DCIMVAC = op_addr; /* register accepts only 32byte aligned values, only bits 31..5 are valid */ - op_addr += __SCB_DCACHE_LINE_SIZE; - op_size -= __SCB_DCACHE_LINE_SIZE; - } while ( op_size > 0 ); - - __DSB(); - __ISB(); - } - #endif -} - - -/** - \brief D-Cache Clean by address - \details Cleans D-Cache for the given address - D-Cache is cleaned starting from a 32 byte aligned address in 32 byte granularity. - D-Cache memory blocks which are part of given address + given size are cleaned. - \param[in] addr address - \param[in] dsize size of memory block (in number of bytes) -*/ -__STATIC_FORCEINLINE void SCB_CleanDCache_by_Addr (uint32_t *addr, int32_t dsize) -{ - #if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U) - if ( dsize > 0 ) { - int32_t op_size = dsize + (((uint32_t)addr) & (__SCB_DCACHE_LINE_SIZE - 1U)); - uint32_t op_addr = (uint32_t)addr /* & ~(__SCB_DCACHE_LINE_SIZE - 1U) */; - - __DSB(); - - do { - SCB->DCCMVAC = op_addr; /* register accepts only 32byte aligned values, only bits 31..5 are valid */ - op_addr += __SCB_DCACHE_LINE_SIZE; - op_size -= __SCB_DCACHE_LINE_SIZE; - } while ( op_size > 0 ); - - __DSB(); - __ISB(); - } - #endif -} - - -/** - \brief D-Cache Clean and Invalidate by address - \details Cleans and invalidates D_Cache for the given address - D-Cache is cleaned and invalidated starting from a 32 byte aligned address in 32 byte granularity. - D-Cache memory blocks which are part of given address + given size are cleaned and invalidated. - \param[in] addr address (aligned to 32-byte boundary) - \param[in] dsize size of memory block (in number of bytes) -*/ -__STATIC_FORCEINLINE void SCB_CleanInvalidateDCache_by_Addr (uint32_t *addr, int32_t dsize) -{ - #if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U) - if ( dsize > 0 ) { - int32_t op_size = dsize + (((uint32_t)addr) & (__SCB_DCACHE_LINE_SIZE - 1U)); - uint32_t op_addr = (uint32_t)addr /* & ~(__SCB_DCACHE_LINE_SIZE - 1U) */; - - __DSB(); - - do { - SCB->DCCIMVAC = op_addr; /* register accepts only 32byte aligned values, only bits 31..5 are valid */ - op_addr += __SCB_DCACHE_LINE_SIZE; - op_size -= __SCB_DCACHE_LINE_SIZE; - } while ( op_size > 0 ); - - __DSB(); - __ISB(); - } - #endif -} - -/*@} end of CMSIS_Core_CacheFunctions */ - - - -/* ################################## SysTick function ############################################ */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_SysTickFunctions SysTick Functions - \brief Functions that configure the System. - @{ - */ - -#if defined (__Vendor_SysTickConfig) && (__Vendor_SysTickConfig == 0U) - -/** - \brief System Tick Configuration - \details Initializes the System Timer and its interrupt, and starts the System Tick Timer. - Counter is in free running mode to generate periodic interrupts. - \param [in] ticks Number of ticks between two interrupts. - \return 0 Function succeeded. - \return 1 Function failed. - \note When the variable __Vendor_SysTickConfig is set to 1, then the - function SysTick_Config is not included. In this case, the file device.h - must contain a vendor-specific implementation of this function. - */ -__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) -{ - if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) - { - return (1UL); /* Reload value impossible */ - } - - SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ - NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ - SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ - SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | - SysTick_CTRL_TICKINT_Msk | - SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ - return (0UL); /* Function successful */ -} - -#endif - -/*@} end of CMSIS_Core_SysTickFunctions */ - - - -/* ##################################### Debug In/Output function ########################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_core_DebugFunctions ITM Functions - \brief Functions that access the ITM debug interface. - @{ - */ - -extern volatile int32_t ITM_RxBuffer; /*!< External variable to receive characters. */ -#define ITM_RXBUFFER_EMPTY ((int32_t)0x5AA55AA5U) /*!< Value identifying \ref ITM_RxBuffer is ready for next character. */ - - -/** - \brief ITM Send Character - \details Transmits a character via the ITM channel 0, and - \li Just returns when no debugger is connected that has booked the output. - \li Is blocking when a debugger is connected, but the previous character sent has not been transmitted. - \param [in] ch Character to transmit. - \returns Character to transmit. - */ -__STATIC_INLINE uint32_t ITM_SendChar (uint32_t ch) -{ - if (((ITM->TCR & ITM_TCR_ITMENA_Msk) != 0UL) && /* ITM enabled */ - ((ITM->TER & 1UL ) != 0UL) ) /* ITM Port #0 enabled */ - { - while (ITM->PORT[0U].u32 == 0UL) - { - __NOP(); - } - ITM->PORT[0U].u8 = (uint8_t)ch; - } - return (ch); -} - - -/** - \brief ITM Receive Character - \details Inputs a character via the external variable \ref ITM_RxBuffer. - \return Received character. - \return -1 No character pending. - */ -__STATIC_INLINE int32_t ITM_ReceiveChar (void) -{ - int32_t ch = -1; /* no character available */ - - if (ITM_RxBuffer != ITM_RXBUFFER_EMPTY) - { - ch = ITM_RxBuffer; - ITM_RxBuffer = ITM_RXBUFFER_EMPTY; /* ready for next character */ - } - - return (ch); -} - - -/** - \brief ITM Check Character - \details Checks whether a character is pending for reading in the variable \ref ITM_RxBuffer. - \return 0 No character available. - \return 1 Character available. - */ -__STATIC_INLINE int32_t ITM_CheckChar (void) -{ - - if (ITM_RxBuffer == ITM_RXBUFFER_EMPTY) - { - return (0); /* no character available */ - } - else - { - return (1); /* character available */ - } -} - -/*@} end of CMSIS_core_DebugFunctions */ - - - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_CM7_H_DEPENDANT */ - -#endif /* __CMSIS_GENERIC */ diff --git a/panda/board/stm32h7/inc/mpu_armv8.h b/panda/board/stm32h7/inc/mpu_armv8.h deleted file mode 100644 index 2fe28b687..000000000 --- a/panda/board/stm32h7/inc/mpu_armv8.h +++ /dev/null @@ -1,346 +0,0 @@ -/****************************************************************************** - * @file mpu_armv8.h - * @brief CMSIS MPU API for Armv8-M and Armv8.1-M MPU - * @version V5.1.0 - * @date 08. March 2019 - ******************************************************************************/ -/* - * Copyright (c) 2017-2019 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed under the Apache License, Version 2.0 (the License); you may - * not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an AS IS BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined (__clang__) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef ARM_MPU_ARMV8_H -#define ARM_MPU_ARMV8_H - -/** \brief Attribute for device memory (outer only) */ -#define ARM_MPU_ATTR_DEVICE ( 0U ) - -/** \brief Attribute for non-cacheable, normal memory */ -#define ARM_MPU_ATTR_NON_CACHEABLE ( 4U ) - -/** \brief Attribute for normal memory (outer and inner) -* \param NT Non-Transient: Set to 1 for non-transient data. -* \param WB Write-Back: Set to 1 to use write-back update policy. -* \param RA Read Allocation: Set to 1 to use cache allocation on read miss. -* \param WA Write Allocation: Set to 1 to use cache allocation on write miss. -*/ -#define ARM_MPU_ATTR_MEMORY_(NT, WB, RA, WA) \ - (((NT & 1U) << 3U) | ((WB & 1U) << 2U) | ((RA & 1U) << 1U) | (WA & 1U)) - -/** \brief Device memory type non Gathering, non Re-ordering, non Early Write Acknowledgement */ -#define ARM_MPU_ATTR_DEVICE_nGnRnE (0U) - -/** \brief Device memory type non Gathering, non Re-ordering, Early Write Acknowledgement */ -#define ARM_MPU_ATTR_DEVICE_nGnRE (1U) - -/** \brief Device memory type non Gathering, Re-ordering, Early Write Acknowledgement */ -#define ARM_MPU_ATTR_DEVICE_nGRE (2U) - -/** \brief Device memory type Gathering, Re-ordering, Early Write Acknowledgement */ -#define ARM_MPU_ATTR_DEVICE_GRE (3U) - -/** \brief Memory Attribute -* \param O Outer memory attributes -* \param I O == ARM_MPU_ATTR_DEVICE: Device memory attributes, else: Inner memory attributes -*/ -#define ARM_MPU_ATTR(O, I) (((O & 0xFU) << 4U) | (((O & 0xFU) != 0U) ? (I & 0xFU) : ((I & 0x3U) << 2U))) - -/** \brief Normal memory non-shareable */ -#define ARM_MPU_SH_NON (0U) - -/** \brief Normal memory outer shareable */ -#define ARM_MPU_SH_OUTER (2U) - -/** \brief Normal memory inner shareable */ -#define ARM_MPU_SH_INNER (3U) - -/** \brief Memory access permissions -* \param RO Read-Only: Set to 1 for read-only memory. -* \param NP Non-Privileged: Set to 1 for non-privileged memory. -*/ -#define ARM_MPU_AP_(RO, NP) (((RO & 1U) << 1U) | (NP & 1U)) - -/** \brief Region Base Address Register value -* \param BASE The base address bits [31:5] of a memory region. The value is zero extended. Effective address gets 32 byte aligned. -* \param SH Defines the Shareability domain for this memory region. -* \param RO Read-Only: Set to 1 for a read-only memory region. -* \param NP Non-Privileged: Set to 1 for a non-privileged memory region. -* \oaram XN eXecute Never: Set to 1 for a non-executable memory region. -*/ -#define ARM_MPU_RBAR(BASE, SH, RO, NP, XN) \ - ((BASE & MPU_RBAR_BASE_Msk) | \ - ((SH << MPU_RBAR_SH_Pos) & MPU_RBAR_SH_Msk) | \ - ((ARM_MPU_AP_(RO, NP) << MPU_RBAR_AP_Pos) & MPU_RBAR_AP_Msk) | \ - ((XN << MPU_RBAR_XN_Pos) & MPU_RBAR_XN_Msk)) - -/** \brief Region Limit Address Register value -* \param LIMIT The limit address bits [31:5] for this memory region. The value is one extended. -* \param IDX The attribute index to be associated with this memory region. -*/ -#define ARM_MPU_RLAR(LIMIT, IDX) \ - ((LIMIT & MPU_RLAR_LIMIT_Msk) | \ - ((IDX << MPU_RLAR_AttrIndx_Pos) & MPU_RLAR_AttrIndx_Msk) | \ - (MPU_RLAR_EN_Msk)) - -#if defined(MPU_RLAR_PXN_Pos) - -/** \brief Region Limit Address Register with PXN value -* \param LIMIT The limit address bits [31:5] for this memory region. The value is one extended. -* \param PXN Privileged execute never. Defines whether code can be executed from this privileged region. -* \param IDX The attribute index to be associated with this memory region. -*/ -#define ARM_MPU_RLAR_PXN(LIMIT, PXN, IDX) \ - ((LIMIT & MPU_RLAR_LIMIT_Msk) | \ - ((PXN << MPU_RLAR_PXN_Pos) & MPU_RLAR_PXN_Msk) | \ - ((IDX << MPU_RLAR_AttrIndx_Pos) & MPU_RLAR_AttrIndx_Msk) | \ - (MPU_RLAR_EN_Msk)) - -#endif - -/** -* Struct for a single MPU Region -*/ -typedef struct { - uint32_t RBAR; /*!< Region Base Address Register value */ - uint32_t RLAR; /*!< Region Limit Address Register value */ -} ARM_MPU_Region_t; - -/** Enable the MPU. -* \param MPU_Control Default access permissions for unconfigured regions. -*/ -__STATIC_INLINE void ARM_MPU_Enable(uint32_t MPU_Control) -{ - MPU->CTRL = MPU_Control | MPU_CTRL_ENABLE_Msk; -#ifdef SCB_SHCSR_MEMFAULTENA_Msk - SCB->SHCSR |= SCB_SHCSR_MEMFAULTENA_Msk; -#endif - __DSB(); - __ISB(); -} - -/** Disable the MPU. -*/ -__STATIC_INLINE void ARM_MPU_Disable(void) -{ - __DMB(); -#ifdef SCB_SHCSR_MEMFAULTENA_Msk - SCB->SHCSR &= ~SCB_SHCSR_MEMFAULTENA_Msk; -#endif - MPU->CTRL &= ~MPU_CTRL_ENABLE_Msk; -} - -#ifdef MPU_NS -/** Enable the Non-secure MPU. -* \param MPU_Control Default access permissions for unconfigured regions. -*/ -__STATIC_INLINE void ARM_MPU_Enable_NS(uint32_t MPU_Control) -{ - MPU_NS->CTRL = MPU_Control | MPU_CTRL_ENABLE_Msk; -#ifdef SCB_SHCSR_MEMFAULTENA_Msk - SCB_NS->SHCSR |= SCB_SHCSR_MEMFAULTENA_Msk; -#endif - __DSB(); - __ISB(); -} - -/** Disable the Non-secure MPU. -*/ -__STATIC_INLINE void ARM_MPU_Disable_NS(void) -{ - __DMB(); -#ifdef SCB_SHCSR_MEMFAULTENA_Msk - SCB_NS->SHCSR &= ~SCB_SHCSR_MEMFAULTENA_Msk; -#endif - MPU_NS->CTRL &= ~MPU_CTRL_ENABLE_Msk; -} -#endif - -/** Set the memory attribute encoding to the given MPU. -* \param mpu Pointer to the MPU to be configured. -* \param idx The attribute index to be set [0-7] -* \param attr The attribute value to be set. -*/ -__STATIC_INLINE void ARM_MPU_SetMemAttrEx(MPU_Type* mpu, uint8_t idx, uint8_t attr) -{ - const uint8_t reg = idx / 4U; - const uint32_t pos = ((idx % 4U) * 8U); - const uint32_t mask = 0xFFU << pos; - - if (reg >= (sizeof(mpu->MAIR) / sizeof(mpu->MAIR[0]))) { - return; // invalid index - } - - mpu->MAIR[reg] = ((mpu->MAIR[reg] & ~mask) | ((attr << pos) & mask)); -} - -/** Set the memory attribute encoding. -* \param idx The attribute index to be set [0-7] -* \param attr The attribute value to be set. -*/ -__STATIC_INLINE void ARM_MPU_SetMemAttr(uint8_t idx, uint8_t attr) -{ - ARM_MPU_SetMemAttrEx(MPU, idx, attr); -} - -#ifdef MPU_NS -/** Set the memory attribute encoding to the Non-secure MPU. -* \param idx The attribute index to be set [0-7] -* \param attr The attribute value to be set. -*/ -__STATIC_INLINE void ARM_MPU_SetMemAttr_NS(uint8_t idx, uint8_t attr) -{ - ARM_MPU_SetMemAttrEx(MPU_NS, idx, attr); -} -#endif - -/** Clear and disable the given MPU region of the given MPU. -* \param mpu Pointer to MPU to be used. -* \param rnr Region number to be cleared. -*/ -__STATIC_INLINE void ARM_MPU_ClrRegionEx(MPU_Type* mpu, uint32_t rnr) -{ - mpu->RNR = rnr; - mpu->RLAR = 0U; -} - -/** Clear and disable the given MPU region. -* \param rnr Region number to be cleared. -*/ -__STATIC_INLINE void ARM_MPU_ClrRegion(uint32_t rnr) -{ - ARM_MPU_ClrRegionEx(MPU, rnr); -} - -#ifdef MPU_NS -/** Clear and disable the given Non-secure MPU region. -* \param rnr Region number to be cleared. -*/ -__STATIC_INLINE void ARM_MPU_ClrRegion_NS(uint32_t rnr) -{ - ARM_MPU_ClrRegionEx(MPU_NS, rnr); -} -#endif - -/** Configure the given MPU region of the given MPU. -* \param mpu Pointer to MPU to be used. -* \param rnr Region number to be configured. -* \param rbar Value for RBAR register. -* \param rlar Value for RLAR register. -*/ -__STATIC_INLINE void ARM_MPU_SetRegionEx(MPU_Type* mpu, uint32_t rnr, uint32_t rbar, uint32_t rlar) -{ - mpu->RNR = rnr; - mpu->RBAR = rbar; - mpu->RLAR = rlar; -} - -/** Configure the given MPU region. -* \param rnr Region number to be configured. -* \param rbar Value for RBAR register. -* \param rlar Value for RLAR register. -*/ -__STATIC_INLINE void ARM_MPU_SetRegion(uint32_t rnr, uint32_t rbar, uint32_t rlar) -{ - ARM_MPU_SetRegionEx(MPU, rnr, rbar, rlar); -} - -#ifdef MPU_NS -/** Configure the given Non-secure MPU region. -* \param rnr Region number to be configured. -* \param rbar Value for RBAR register. -* \param rlar Value for RLAR register. -*/ -__STATIC_INLINE void ARM_MPU_SetRegion_NS(uint32_t rnr, uint32_t rbar, uint32_t rlar) -{ - ARM_MPU_SetRegionEx(MPU_NS, rnr, rbar, rlar); -} -#endif - -/** Memcopy with strictly ordered memory access, e.g. for register targets. -* \param dst Destination data is copied to. -* \param src Source data is copied from. -* \param len Amount of data words to be copied. -*/ -__STATIC_INLINE void ARM_MPU_OrderedMemcpy(volatile uint32_t* dst, const uint32_t* __RESTRICT src, uint32_t len) -{ - uint32_t i; - for (i = 0U; i < len; ++i) - { - dst[i] = src[i]; - } -} - -/** Load the given number of MPU regions from a table to the given MPU. -* \param mpu Pointer to the MPU registers to be used. -* \param rnr First region number to be configured. -* \param table Pointer to the MPU configuration table. -* \param cnt Amount of regions to be configured. -*/ -__STATIC_INLINE void ARM_MPU_LoadEx(MPU_Type* mpu, uint32_t rnr, ARM_MPU_Region_t const* table, uint32_t cnt) -{ - const uint32_t rowWordSize = sizeof(ARM_MPU_Region_t)/4U; - if (cnt == 1U) { - mpu->RNR = rnr; - ARM_MPU_OrderedMemcpy(&(mpu->RBAR), &(table->RBAR), rowWordSize); - } else { - uint32_t rnrBase = rnr & ~(MPU_TYPE_RALIASES-1U); - uint32_t rnrOffset = rnr % MPU_TYPE_RALIASES; - - mpu->RNR = rnrBase; - while ((rnrOffset + cnt) > MPU_TYPE_RALIASES) { - uint32_t c = MPU_TYPE_RALIASES - rnrOffset; - ARM_MPU_OrderedMemcpy(&(mpu->RBAR)+(rnrOffset*2U), &(table->RBAR), c*rowWordSize); - table += c; - cnt -= c; - rnrOffset = 0U; - rnrBase += MPU_TYPE_RALIASES; - mpu->RNR = rnrBase; - } - - ARM_MPU_OrderedMemcpy(&(mpu->RBAR)+(rnrOffset*2U), &(table->RBAR), cnt*rowWordSize); - } -} - -/** Load the given number of MPU regions from a table. -* \param rnr First region number to be configured. -* \param table Pointer to the MPU configuration table. -* \param cnt Amount of regions to be configured. -*/ -__STATIC_INLINE void ARM_MPU_Load(uint32_t rnr, ARM_MPU_Region_t const* table, uint32_t cnt) -{ - ARM_MPU_LoadEx(MPU, rnr, table, cnt); -} - -#ifdef MPU_NS -/** Load the given number of MPU regions from a table to the Non-secure MPU. -* \param rnr First region number to be configured. -* \param table Pointer to the MPU configuration table. -* \param cnt Amount of regions to be configured. -*/ -__STATIC_INLINE void ARM_MPU_Load_NS(uint32_t rnr, ARM_MPU_Region_t const* table, uint32_t cnt) -{ - ARM_MPU_LoadEx(MPU_NS, rnr, table, cnt); -} -#endif - -#endif - diff --git a/panda/board/stm32h7/inc/stm32h725xx.h b/panda/board/stm32h7/inc/stm32h725xx.h deleted file mode 100644 index 0e0d4a9d6..000000000 --- a/panda/board/stm32h7/inc/stm32h725xx.h +++ /dev/null @@ -1,24740 +0,0 @@ -/** - ****************************************************************************** - * @file stm32h735xx.h - * @author MCD Application Team - * @brief CMSIS STM32H735xx Device Peripheral Access Layer Header File. - * - * This file contains: - * - Data structures and the address mapping for all peripherals - * - Peripheral's registers declarations and bits definition - * - Macros to access peripheral's registers hardware - * - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2019 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/** @addtogroup CMSIS_Device - * @{ - */ - -/** @addtogroup stm32h735xx - * @{ - */ - -#ifndef STM32H735xx_H -#define STM32H735xx_H - -#ifdef __cplusplus - extern "C" { -#endif /* __cplusplus */ - -/** @addtogroup Peripheral_interrupt_number_definition - * @{ - */ - -/** - * @brief STM32H7XX Interrupt Number Definition, according to the selected device - * in @ref Library_configuration_section - */ -typedef enum -{ -/****** Cortex-M Processor Exceptions Numbers *****************************************************************/ - NonMaskableInt_IRQn = -14, /*!< 2 Non Maskable Interrupt */ - HardFault_IRQn = -13, /*!< 4 Cortex-M Memory Management Interrupt */ - MemoryManagement_IRQn = -12, /*!< 4 Cortex-M Memory Management Interrupt */ - BusFault_IRQn = -11, /*!< 5 Cortex-M Bus Fault Interrupt */ - UsageFault_IRQn = -10, /*!< 6 Cortex-M Usage Fault Interrupt */ - SVCall_IRQn = -5, /*!< 11 Cortex-M SV Call Interrupt */ - DebugMonitor_IRQn = -4, /*!< 12 Cortex-M Debug Monitor Interrupt */ - PendSV_IRQn = -2, /*!< 14 Cortex-M Pend SV Interrupt */ - SysTick_IRQn = -1, /*!< 15 Cortex-M System Tick Interrupt */ -/****** STM32 specific Interrupt Numbers **********************************************************************/ - WWDG_IRQn = 0, /*!< Window WatchDog Interrupt ( wwdg1_it, wwdg2_it) */ - PVD_AVD_IRQn = 1, /*!< PVD/AVD through EXTI Line detection Interrupt */ - TAMP_STAMP_IRQn = 2, /*!< Tamper and TimeStamp interrupts through the EXTI line */ - RTC_WKUP_IRQn = 3, /*!< RTC Wakeup interrupt through the EXTI line */ - FLASH_IRQn = 4, /*!< FLASH global Interrupt */ - RCC_IRQn = 5, /*!< RCC global Interrupt */ - EXTI0_IRQn = 6, /*!< EXTI Line0 Interrupt */ - EXTI1_IRQn = 7, /*!< EXTI Line1 Interrupt */ - EXTI2_IRQn = 8, /*!< EXTI Line2 Interrupt */ - EXTI3_IRQn = 9, /*!< EXTI Line3 Interrupt */ - EXTI4_IRQn = 10, /*!< EXTI Line4 Interrupt */ - DMA1_Stream0_IRQn = 11, /*!< DMA1 Stream 0 global Interrupt */ - DMA1_Stream1_IRQn = 12, /*!< DMA1 Stream 1 global Interrupt */ - DMA1_Stream2_IRQn = 13, /*!< DMA1 Stream 2 global Interrupt */ - DMA1_Stream3_IRQn = 14, /*!< DMA1 Stream 3 global Interrupt */ - DMA1_Stream4_IRQn = 15, /*!< DMA1 Stream 4 global Interrupt */ - DMA1_Stream5_IRQn = 16, /*!< DMA1 Stream 5 global Interrupt */ - DMA1_Stream6_IRQn = 17, /*!< DMA1 Stream 6 global Interrupt */ - ADC_IRQn = 18, /*!< ADC1 and ADC2 global Interrupts */ - FDCAN1_IT0_IRQn = 19, /*!< FDCAN1 Interrupt line 0 */ - FDCAN2_IT0_IRQn = 20, /*!< FDCAN2 Interrupt line 0 */ - FDCAN1_IT1_IRQn = 21, /*!< FDCAN1 Interrupt line 1 */ - FDCAN2_IT1_IRQn = 22, /*!< FDCAN2 Interrupt line 1 */ - EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ - TIM1_BRK_IRQn = 24, /*!< TIM1 Break Interrupt */ - TIM1_UP_IRQn = 25, /*!< TIM1 Update Interrupt */ - TIM1_TRG_COM_IRQn = 26, /*!< TIM1 Trigger and Commutation Interrupt */ - TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ - TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ - TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ - TIM4_IRQn = 30, /*!< TIM4 global Interrupt */ - I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ - I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ - I2C2_EV_IRQn = 33, /*!< I2C2 Event Interrupt */ - I2C2_ER_IRQn = 34, /*!< I2C2 Error Interrupt */ - SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ - SPI2_IRQn = 36, /*!< SPI2 global Interrupt */ - USART1_IRQn = 37, /*!< USART1 global Interrupt */ - USART2_IRQn = 38, /*!< USART2 global Interrupt */ - USART3_IRQn = 39, /*!< USART3 global Interrupt */ - EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ - RTC_Alarm_IRQn = 41, /*!< RTC Alarm (A and B) through EXTI Line Interrupt */ - TIM8_BRK_TIM12_IRQn = 43, /*!< TIM8 Break Interrupt and TIM12 global interrupt */ - TIM8_UP_TIM13_IRQn = 44, /*!< TIM8 Update Interrupt and TIM13 global interrupt */ - TIM8_TRG_COM_TIM14_IRQn = 45, /*!< TIM8 Trigger and Commutation Interrupt and TIM14 global interrupt */ - TIM8_CC_IRQn = 46, /*!< TIM8 Capture Compare Interrupt */ - DMA1_Stream7_IRQn = 47, /*!< DMA1 Stream7 Interrupt */ - FMC_IRQn = 48, /*!< FMC global Interrupt */ - SDMMC1_IRQn = 49, /*!< SDMMC1 global Interrupt */ - TIM5_IRQn = 50, /*!< TIM5 global Interrupt */ - SPI3_IRQn = 51, /*!< SPI3 global Interrupt */ - UART4_IRQn = 52, /*!< UART4 global Interrupt */ - UART5_IRQn = 53, /*!< UART5 global Interrupt */ - TIM6_DAC_IRQn = 54, /*!< TIM6 global and DAC1&2 underrun error interrupts */ - TIM7_IRQn = 55, /*!< TIM7 global interrupt */ - DMA2_Stream0_IRQn = 56, /*!< DMA2 Stream 0 global Interrupt */ - DMA2_Stream1_IRQn = 57, /*!< DMA2 Stream 1 global Interrupt */ - DMA2_Stream2_IRQn = 58, /*!< DMA2 Stream 2 global Interrupt */ - DMA2_Stream3_IRQn = 59, /*!< DMA2 Stream 3 global Interrupt */ - DMA2_Stream4_IRQn = 60, /*!< DMA2 Stream 4 global Interrupt */ - ETH_IRQn = 61, /*!< Ethernet global Interrupt */ - ETH_WKUP_IRQn = 62, /*!< Ethernet Wakeup through EXTI line Interrupt */ - FDCAN_CAL_IRQn = 63, /*!< FDCAN Calibration unit Interrupt */ - DMA2_Stream5_IRQn = 68, /*!< DMA2 Stream 5 global interrupt */ - DMA2_Stream6_IRQn = 69, /*!< DMA2 Stream 6 global interrupt */ - DMA2_Stream7_IRQn = 70, /*!< DMA2 Stream 7 global interrupt */ - USART6_IRQn = 71, /*!< USART6 global interrupt */ - I2C3_EV_IRQn = 72, /*!< I2C3 event interrupt */ - I2C3_ER_IRQn = 73, /*!< I2C3 error interrupt */ - OTG_HS_EP1_OUT_IRQn = 74, /*!< USB OTG HS End Point 1 Out global interrupt */ - OTG_HS_EP1_IN_IRQn = 75, /*!< USB OTG HS End Point 1 In global interrupt */ - OTG_HS_WKUP_IRQn = 76, /*!< USB OTG HS Wakeup through EXTI interrupt */ - OTG_HS_IRQn = 77, /*!< USB OTG HS global interrupt */ - DCMI_PSSI_IRQn = 78, /*!< DCMI and PSSI global interrupt */ - CRYP_IRQn = 79, /*!< CRYP crypto global interrupt */ - HASH_RNG_IRQn = 80, /*!< HASH and RNG global interrupt */ - FPU_IRQn = 81, /*!< FPU global interrupt */ - UART7_IRQn = 82, /*!< UART7 global interrupt */ - UART8_IRQn = 83, /*!< UART8 global interrupt */ - SPI4_IRQn = 84, /*!< SPI4 global Interrupt */ - SPI5_IRQn = 85, /*!< SPI5 global Interrupt */ - SPI6_IRQn = 86, /*!< SPI6 global Interrupt */ - SAI1_IRQn = 87, /*!< SAI1 global Interrupt */ - LTDC_IRQn = 88, /*!< LTDC global Interrupt */ - LTDC_ER_IRQn = 89, /*!< LTDC Error global Interrupt */ - DMA2D_IRQn = 90, /*!< DMA2D global Interrupt */ - OCTOSPI1_IRQn = 92, /*!< OCTOSPI1 global interrupt */ - LPTIM1_IRQn = 93, /*!< LP TIM1 interrupt */ - CEC_IRQn = 94, /*!< HDMI-CEC global Interrupt */ - I2C4_EV_IRQn = 95, /*!< I2C4 Event Interrupt */ - I2C4_ER_IRQn = 96, /*!< I2C4 Error Interrupt */ - SPDIF_RX_IRQn = 97, /*!< SPDIF-RX global Interrupt */ - DMAMUX1_OVR_IRQn = 102, /*! - -/** @addtogroup Peripheral_registers_structures - * @{ - */ - -/** - * @brief Analog to Digital Converter - */ - -typedef struct -{ - __IO uint32_t ISR; /*!< ADC Interrupt and Status Register, Address offset: 0x00 */ - __IO uint32_t IER; /*!< ADC Interrupt Enable Register, Address offset: 0x04 */ - __IO uint32_t CR; /*!< ADC control register, Address offset: 0x08 */ - __IO uint32_t CFGR; /*!< ADC Configuration register, Address offset: 0x0C */ - __IO uint32_t CFGR2; /*!< ADC Configuration register 2, Address offset: 0x10 */ - __IO uint32_t SMPR1; /*!< ADC sample time register 1, Address offset: 0x14 */ - __IO uint32_t SMPR2; /*!< ADC sample time register 2, Address offset: 0x18 */ - __IO uint32_t PCSEL_RES0; /*!< Rserved for ADC3, ADC1/2 pre-channel selection, Address offset: 0x1C */ - __IO uint32_t LTR1_TR1; /*!< ADC watchdog Lower threshold register 1, Address offset: 0x20 */ - __IO uint32_t HTR1_TR2; /*!< ADC watchdog higher threshold register 1, Address offset: 0x24 */ - __IO uint32_t RES1_TR3; /*!< Rserved for ADC1/2, ADC3 threshold register, Address offset: 0x28 */ - uint32_t RESERVED2; /*!< Reserved, 0x02C */ - __IO uint32_t SQR1; /*!< ADC regular sequence register 1, Address offset: 0x30 */ - __IO uint32_t SQR2; /*!< ADC regular sequence register 2, Address offset: 0x34 */ - __IO uint32_t SQR3; /*!< ADC regular sequence register 3, Address offset: 0x38 */ - __IO uint32_t SQR4; /*!< ADC regular sequence register 4, Address offset: 0x3C */ - __IO uint32_t DR; /*!< ADC regular data register, Address offset: 0x40 */ - uint32_t RESERVED3; /*!< Reserved, 0x044 */ - uint32_t RESERVED4; /*!< Reserved, 0x048 */ - __IO uint32_t JSQR; /*!< ADC injected sequence register, Address offset: 0x4C */ - uint32_t RESERVED5[4]; /*!< Reserved, 0x050 - 0x05C */ - __IO uint32_t OFR1; /*!< ADC offset register 1, Address offset: 0x60 */ - __IO uint32_t OFR2; /*!< ADC offset register 2, Address offset: 0x64 */ - __IO uint32_t OFR3; /*!< ADC offset register 3, Address offset: 0x68 */ - __IO uint32_t OFR4; /*!< ADC offset register 4, Address offset: 0x6C */ - uint32_t RESERVED6[4]; /*!< Reserved, 0x070 - 0x07C */ - __IO uint32_t JDR1; /*!< ADC injected data register 1, Address offset: 0x80 */ - __IO uint32_t JDR2; /*!< ADC injected data register 2, Address offset: 0x84 */ - __IO uint32_t JDR3; /*!< ADC injected data register 3, Address offset: 0x88 */ - __IO uint32_t JDR4; /*!< ADC injected data register 4, Address offset: 0x8C */ - uint32_t RESERVED7[4]; /*!< Reserved, 0x090 - 0x09C */ - __IO uint32_t AWD2CR; /*!< ADC Analog Watchdog 2 Configuration Register, Address offset: 0xA0 */ - __IO uint32_t AWD3CR; /*!< ADC Analog Watchdog 3 Configuration Register, Address offset: 0xA4 */ - uint32_t RESERVED8; /*!< Reserved, 0x0A8 */ - uint32_t RESERVED9; /*!< Reserved, 0x0AC */ - __IO uint32_t LTR2_DIFSEL; /*!< ADC watchdog Lower threshold register 2, Difsel for ADC3, Address offset: 0xB0 */ - __IO uint32_t HTR2_CALFACT; /*!< ADC watchdog Higher threshold register 2, Calfact for ADC3, Address offset: 0xB4 */ - __IO uint32_t LTR3_RES10; /*!< ADC watchdog Lower threshold register 3, specific ADC1/2, Address offset: 0xB8 */ - __IO uint32_t HTR3_RES11; /*!< ADC watchdog Higher threshold register 3, specific ADC1/2, Address offset: 0xBC */ - __IO uint32_t DIFSEL_RES12; /*!< ADC Differential Mode Selection Register specific ADC1/2, Address offset: 0xC0 */ - __IO uint32_t CALFACT_RES13; /*!< ADC Calibration Factors specific ADC1/2, Address offset: 0xC4 */ - __IO uint32_t CALFACT2_RES14; /*!< ADC Linearity Calibration Factors specific ADC1/2, Address offset: 0xC8 */ -} ADC_TypeDef; - - -typedef struct -{ -__IO uint32_t CSR; /*!< ADC Common status register, Address offset: ADC1/3 base address + 0x300 */ -uint32_t RESERVED; /*!< Reserved, ADC1/3 base address + 0x304 */ -__IO uint32_t CCR; /*!< ADC common control register, Address offset: ADC1/3 base address + 0x308 */ -__IO uint32_t CDR; /*!< ADC common regular data register for dual Address offset: ADC1/3 base address + 0x30C */ -__IO uint32_t CDR2; /*!< ADC common regular data register for 32-bit dual mode Address offset: ADC1/3 base address + 0x310 */ - -} ADC_Common_TypeDef; - - -/** - * @brief VREFBUF - */ - -typedef struct -{ - __IO uint32_t CSR; /*!< VREFBUF control and status register, Address offset: 0x00 */ - __IO uint32_t CCR; /*!< VREFBUF calibration and control register, Address offset: 0x04 */ -} VREFBUF_TypeDef; - - -/** - * @brief FD Controller Area Network - */ - -typedef struct -{ - __IO uint32_t CREL; /*!< FDCAN Core Release register, Address offset: 0x000 */ - __IO uint32_t ENDN; /*!< FDCAN Endian register, Address offset: 0x004 */ - __IO uint32_t RESERVED1; /*!< Reserved, 0x008 */ - __IO uint32_t DBTP; /*!< FDCAN Data Bit Timing & Prescaler register, Address offset: 0x00C */ - __IO uint32_t TEST; /*!< FDCAN Test register, Address offset: 0x010 */ - __IO uint32_t RWD; /*!< FDCAN RAM Watchdog register, Address offset: 0x014 */ - __IO uint32_t CCCR; /*!< FDCAN CC Control register, Address offset: 0x018 */ - __IO uint32_t NBTP; /*!< FDCAN Nominal Bit Timing & Prescaler register, Address offset: 0x01C */ - __IO uint32_t TSCC; /*!< FDCAN Timestamp Counter Configuration register, Address offset: 0x020 */ - __IO uint32_t TSCV; /*!< FDCAN Timestamp Counter Value register, Address offset: 0x024 */ - __IO uint32_t TOCC; /*!< FDCAN Timeout Counter Configuration register, Address offset: 0x028 */ - __IO uint32_t TOCV; /*!< FDCAN Timeout Counter Value register, Address offset: 0x02C */ - __IO uint32_t RESERVED2[4]; /*!< Reserved, 0x030 - 0x03C */ - __IO uint32_t ECR; /*!< FDCAN Error Counter register, Address offset: 0x040 */ - __IO uint32_t PSR; /*!< FDCAN Protocol Status register, Address offset: 0x044 */ - __IO uint32_t TDCR; /*!< FDCAN Transmitter Delay Compensation register, Address offset: 0x048 */ - __IO uint32_t RESERVED3; /*!< Reserved, 0x04C */ - __IO uint32_t IR; /*!< FDCAN Interrupt register, Address offset: 0x050 */ - __IO uint32_t IE; /*!< FDCAN Interrupt Enable register, Address offset: 0x054 */ - __IO uint32_t ILS; /*!< FDCAN Interrupt Line Select register, Address offset: 0x058 */ - __IO uint32_t ILE; /*!< FDCAN Interrupt Line Enable register, Address offset: 0x05C */ - __IO uint32_t RESERVED4[8]; /*!< Reserved, 0x060 - 0x07C */ - __IO uint32_t GFC; /*!< FDCAN Global Filter Configuration register, Address offset: 0x080 */ - __IO uint32_t SIDFC; /*!< FDCAN Standard ID Filter Configuration register, Address offset: 0x084 */ - __IO uint32_t XIDFC; /*!< FDCAN Extended ID Filter Configuration register, Address offset: 0x088 */ - __IO uint32_t RESERVED5; /*!< Reserved, 0x08C */ - __IO uint32_t XIDAM; /*!< FDCAN Extended ID AND Mask register, Address offset: 0x090 */ - __IO uint32_t HPMS; /*!< FDCAN High Priority Message Status register, Address offset: 0x094 */ - __IO uint32_t NDAT1; /*!< FDCAN New Data 1 register, Address offset: 0x098 */ - __IO uint32_t NDAT2; /*!< FDCAN New Data 2 register, Address offset: 0x09C */ - __IO uint32_t RXF0C; /*!< FDCAN Rx FIFO 0 Configuration register, Address offset: 0x0A0 */ - __IO uint32_t RXF0S; /*!< FDCAN Rx FIFO 0 Status register, Address offset: 0x0A4 */ - __IO uint32_t RXF0A; /*!< FDCAN Rx FIFO 0 Acknowledge register, Address offset: 0x0A8 */ - __IO uint32_t RXBC; /*!< FDCAN Rx Buffer Configuration register, Address offset: 0x0AC */ - __IO uint32_t RXF1C; /*!< FDCAN Rx FIFO 1 Configuration register, Address offset: 0x0B0 */ - __IO uint32_t RXF1S; /*!< FDCAN Rx FIFO 1 Status register, Address offset: 0x0B4 */ - __IO uint32_t RXF1A; /*!< FDCAN Rx FIFO 1 Acknowledge register, Address offset: 0x0B8 */ - __IO uint32_t RXESC; /*!< FDCAN Rx Buffer/FIFO Element Size Configuration register, Address offset: 0x0BC */ - __IO uint32_t TXBC; /*!< FDCAN Tx Buffer Configuration register, Address offset: 0x0C0 */ - __IO uint32_t TXFQS; /*!< FDCAN Tx FIFO/Queue Status register, Address offset: 0x0C4 */ - __IO uint32_t TXESC; /*!< FDCAN Tx Buffer Element Size Configuration register, Address offset: 0x0C8 */ - __IO uint32_t TXBRP; /*!< FDCAN Tx Buffer Request Pending register, Address offset: 0x0CC */ - __IO uint32_t TXBAR; /*!< FDCAN Tx Buffer Add Request register, Address offset: 0x0D0 */ - __IO uint32_t TXBCR; /*!< FDCAN Tx Buffer Cancellation Request register, Address offset: 0x0D4 */ - __IO uint32_t TXBTO; /*!< FDCAN Tx Buffer Transmission Occurred register, Address offset: 0x0D8 */ - __IO uint32_t TXBCF; /*!< FDCAN Tx Buffer Cancellation Finished register, Address offset: 0x0DC */ - __IO uint32_t TXBTIE; /*!< FDCAN Tx Buffer Transmission Interrupt Enable register, Address offset: 0x0E0 */ - __IO uint32_t TXBCIE; /*!< FDCAN Tx Buffer Cancellation Finished Interrupt Enable register, Address offset: 0x0E4 */ - __IO uint32_t RESERVED6[2]; /*!< Reserved, 0x0E8 - 0x0EC */ - __IO uint32_t TXEFC; /*!< FDCAN Tx Event FIFO Configuration register, Address offset: 0x0F0 */ - __IO uint32_t TXEFS; /*!< FDCAN Tx Event FIFO Status register, Address offset: 0x0F4 */ - __IO uint32_t TXEFA; /*!< FDCAN Tx Event FIFO Acknowledge register, Address offset: 0x0F8 */ - __IO uint32_t RESERVED7; /*!< Reserved, 0x0FC */ -} FDCAN_GlobalTypeDef; - -/** - * @brief TTFD Controller Area Network - */ - -typedef struct -{ - __IO uint32_t TTTMC; /*!< TT Trigger Memory Configuration register, Address offset: 0x100 */ - __IO uint32_t TTRMC; /*!< TT Reference Message Configuration register, Address offset: 0x104 */ - __IO uint32_t TTOCF; /*!< TT Operation Configuration register, Address offset: 0x108 */ - __IO uint32_t TTMLM; /*!< TT Matrix Limits register, Address offset: 0x10C */ - __IO uint32_t TURCF; /*!< TUR Configuration register, Address offset: 0x110 */ - __IO uint32_t TTOCN; /*!< TT Operation Control register, Address offset: 0x114 */ - __IO uint32_t TTGTP; /*!< TT Global Time Preset register, Address offset: 0x118 */ - __IO uint32_t TTTMK; /*!< TT Time Mark register, Address offset: 0x11C */ - __IO uint32_t TTIR; /*!< TT Interrupt register, Address offset: 0x120 */ - __IO uint32_t TTIE; /*!< TT Interrupt Enable register, Address offset: 0x124 */ - __IO uint32_t TTILS; /*!< TT Interrupt Line Select register, Address offset: 0x128 */ - __IO uint32_t TTOST; /*!< TT Operation Status register, Address offset: 0x12C */ - __IO uint32_t TURNA; /*!< TT TUR Numerator Actual register, Address offset: 0x130 */ - __IO uint32_t TTLGT; /*!< TT Local and Global Time register, Address offset: 0x134 */ - __IO uint32_t TTCTC; /*!< TT Cycle Time and Count register, Address offset: 0x138 */ - __IO uint32_t TTCPT; /*!< TT Capture Time register, Address offset: 0x13C */ - __IO uint32_t TTCSM; /*!< TT Cycle Sync Mark register, Address offset: 0x140 */ - __IO uint32_t RESERVED1[111]; /*!< Reserved, 0x144 - 0x2FC */ - __IO uint32_t TTTS; /*!< TT Trigger Select register, Address offset: 0x300 */ -} TTCAN_TypeDef; - -/** - * @brief FD Controller Area Network - */ - -typedef struct -{ - __IO uint32_t CREL; /*!< Clock Calibration Unit Core Release register, Address offset: 0x00 */ - __IO uint32_t CCFG; /*!< Calibration Configuration register, Address offset: 0x04 */ - __IO uint32_t CSTAT; /*!< Calibration Status register, Address offset: 0x08 */ - __IO uint32_t CWD; /*!< Calibration Watchdog register, Address offset: 0x0C */ - __IO uint32_t IR; /*!< CCU Interrupt register, Address offset: 0x10 */ - __IO uint32_t IE; /*!< CCU Interrupt Enable register, Address offset: 0x14 */ -} FDCAN_ClockCalibrationUnit_TypeDef; - - -/** - * @brief Consumer Electronics Control - */ - -typedef struct -{ - __IO uint32_t CR; /*!< CEC control register, Address offset:0x00 */ - __IO uint32_t CFGR; /*!< CEC configuration register, Address offset:0x04 */ - __IO uint32_t TXDR; /*!< CEC Tx data register , Address offset:0x08 */ - __IO uint32_t RXDR; /*!< CEC Rx Data Register, Address offset:0x0C */ - __IO uint32_t ISR; /*!< CEC Interrupt and Status Register, Address offset:0x10 */ - __IO uint32_t IER; /*!< CEC interrupt enable register, Address offset:0x14 */ -}CEC_TypeDef; - -/** - * @brief COordincate Rotation DIgital Computer - */ -typedef struct -{ - __IO uint32_t CSR; /*!< CORDIC control and status register, Address offset: 0x00 */ - __IO uint32_t WDATA; /*!< CORDIC argument register, Address offset: 0x04 */ - __IO uint32_t RDATA; /*!< CORDIC result register, Address offset: 0x08 */ -} CORDIC_TypeDef; - -/** - * @brief CRC calculation unit - */ - -typedef struct -{ - __IO uint32_t DR; /*!< CRC Data register, Address offset: 0x00 */ - __IO uint32_t IDR; /*!< CRC Independent data register, Address offset: 0x04 */ - __IO uint32_t CR; /*!< CRC Control register, Address offset: 0x08 */ - uint32_t RESERVED2; /*!< Reserved, 0x0C */ - __IO uint32_t INIT; /*!< Initial CRC value register, Address offset: 0x10 */ - __IO uint32_t POL; /*!< CRC polynomial register, Address offset: 0x14 */ -} CRC_TypeDef; - - -/** - * @brief Clock Recovery System - */ -typedef struct -{ -__IO uint32_t CR; /*!< CRS ccontrol register, Address offset: 0x00 */ -__IO uint32_t CFGR; /*!< CRS configuration register, Address offset: 0x04 */ -__IO uint32_t ISR; /*!< CRS interrupt and status register, Address offset: 0x08 */ -__IO uint32_t ICR; /*!< CRS interrupt flag clear register, Address offset: 0x0C */ -} CRS_TypeDef; - - -/** - * @brief Digital to Analog Converter - */ - -typedef struct -{ - __IO uint32_t CR; /*!< DAC control register, Address offset: 0x00 */ - __IO uint32_t SWTRIGR; /*!< DAC software trigger register, Address offset: 0x04 */ - __IO uint32_t DHR12R1; /*!< DAC channel1 12-bit right-aligned data holding register, Address offset: 0x08 */ - __IO uint32_t DHR12L1; /*!< DAC channel1 12-bit left aligned data holding register, Address offset: 0x0C */ - __IO uint32_t DHR8R1; /*!< DAC channel1 8-bit right aligned data holding register, Address offset: 0x10 */ - __IO uint32_t DHR12R2; /*!< DAC channel2 12-bit right aligned data holding register, Address offset: 0x14 */ - __IO uint32_t DHR12L2; /*!< DAC channel2 12-bit left aligned data holding register, Address offset: 0x18 */ - __IO uint32_t DHR8R2; /*!< DAC channel2 8-bit right-aligned data holding register, Address offset: 0x1C */ - __IO uint32_t DHR12RD; /*!< Dual DAC 12-bit right-aligned data holding register, Address offset: 0x20 */ - __IO uint32_t DHR12LD; /*!< DUAL DAC 12-bit left aligned data holding register, Address offset: 0x24 */ - __IO uint32_t DHR8RD; /*!< DUAL DAC 8-bit right aligned data holding register, Address offset: 0x28 */ - __IO uint32_t DOR1; /*!< DAC channel1 data output register, Address offset: 0x2C */ - __IO uint32_t DOR2; /*!< DAC channel2 data output register, Address offset: 0x30 */ - __IO uint32_t SR; /*!< DAC status register, Address offset: 0x34 */ - __IO uint32_t CCR; /*!< DAC calibration control register, Address offset: 0x38 */ - __IO uint32_t MCR; /*!< DAC mode control register, Address offset: 0x3C */ - __IO uint32_t SHSR1; /*!< DAC Sample and Hold sample time register 1, Address offset: 0x40 */ - __IO uint32_t SHSR2; /*!< DAC Sample and Hold sample time register 2, Address offset: 0x44 */ - __IO uint32_t SHHR; /*!< DAC Sample and Hold hold time register, Address offset: 0x48 */ - __IO uint32_t SHRR; /*!< DAC Sample and Hold refresh time register, Address offset: 0x4C */ -} DAC_TypeDef; - -/** - * @brief DFSDM module registers - */ -typedef struct -{ - __IO uint32_t FLTCR1; /*!< DFSDM control register1, Address offset: 0x100 */ - __IO uint32_t FLTCR2; /*!< DFSDM control register2, Address offset: 0x104 */ - __IO uint32_t FLTISR; /*!< DFSDM interrupt and status register, Address offset: 0x108 */ - __IO uint32_t FLTICR; /*!< DFSDM interrupt flag clear register, Address offset: 0x10C */ - __IO uint32_t FLTJCHGR; /*!< DFSDM injected channel group selection register, Address offset: 0x110 */ - __IO uint32_t FLTFCR; /*!< DFSDM filter control register, Address offset: 0x114 */ - __IO uint32_t FLTJDATAR; /*!< DFSDM data register for injected group, Address offset: 0x118 */ - __IO uint32_t FLTRDATAR; /*!< DFSDM data register for regular group, Address offset: 0x11C */ - __IO uint32_t FLTAWHTR; /*!< DFSDM analog watchdog high threshold register, Address offset: 0x120 */ - __IO uint32_t FLTAWLTR; /*!< DFSDM analog watchdog low threshold register, Address offset: 0x124 */ - __IO uint32_t FLTAWSR; /*!< DFSDM analog watchdog status register Address offset: 0x128 */ - __IO uint32_t FLTAWCFR; /*!< DFSDM analog watchdog clear flag register Address offset: 0x12C */ - __IO uint32_t FLTEXMAX; /*!< DFSDM extreme detector maximum register, Address offset: 0x130 */ - __IO uint32_t FLTEXMIN; /*!< DFSDM extreme detector minimum register Address offset: 0x134 */ - __IO uint32_t FLTCNVTIMR; /*!< DFSDM conversion timer, Address offset: 0x138 */ -} DFSDM_Filter_TypeDef; - -/** - * @brief DFSDM channel configuration registers - */ -typedef struct -{ - __IO uint32_t CHCFGR1; /*!< DFSDM channel configuration register1, Address offset: 0x00 */ - __IO uint32_t CHCFGR2; /*!< DFSDM channel configuration register2, Address offset: 0x04 */ - __IO uint32_t CHAWSCDR; /*!< DFSDM channel analog watchdog and - short circuit detector register, Address offset: 0x08 */ - __IO uint32_t CHWDATAR; /*!< DFSDM channel watchdog filter data register, Address offset: 0x0C */ - __IO uint32_t CHDATINR; /*!< DFSDM channel data input register, Address offset: 0x10 */ -} DFSDM_Channel_TypeDef; - -/** - * @brief Debug MCU - */ -typedef struct -{ - __IO uint32_t IDCODE; /*!< MCU device ID code, Address offset: 0x00 */ - __IO uint32_t CR; /*!< Debug MCU configuration register, Address offset: 0x04 */ - uint32_t RESERVED4[11]; /*!< Reserved, Address offset: 0x08 */ - __IO uint32_t APB3FZ1; /*!< Debug MCU APB3FZ1 freeze register, Address offset: 0x34 */ - uint32_t RESERVED5; /*!< Reserved, Address offset: 0x38 */ - __IO uint32_t APB1LFZ1; /*!< Debug MCU APB1LFZ1 freeze register, Address offset: 0x3C */ - uint32_t RESERVED6; /*!< Reserved, Address offset: 0x40 */ - __IO uint32_t APB1HFZ1; /*!< Debug MCU APB1LFZ1 freeze register, Address offset: 0x44 */ - uint32_t RESERVED7; /*!< Reserved, Address offset: 0x48 */ - __IO uint32_t APB2FZ1; /*!< Debug MCU APB2FZ1 freeze register, Address offset: 0x4C */ - uint32_t RESERVED8; /*!< Reserved, Address offset: 0x50 */ - __IO uint32_t APB4FZ1; /*!< Debug MCU APB4FZ1 freeze register, Address offset: 0x54 */ - __IO uint32_t RESERVED9[990]; /*!< Reserved, Address offset: 0x58-0xFCC */ - __IO uint32_t PIDR4; /*!< Debug MCU peripheral identity register 4, Address offset: 0xFD0 */ - __IO uint32_t RESERVED10[3];/*!< Reserved, Address offset: 0xFD4-0xFDC */ - __IO uint32_t PIDR0; /*!< Debug MCU peripheral identity register 0, Address offset: 0xFE0 */ - __IO uint32_t PIDR1; /*!< Debug MCU peripheral identity register 1, Address offset: 0xFE4 */ - __IO uint32_t PIDR2; /*!< Debug MCU peripheral identity register 2, Address offset: 0xFE8 */ - __IO uint32_t PIDR3; /*!< Debug MCU peripheral identity register 3, Address offset: 0xFEC */ - __IO uint32_t CIDR0; /*!< Debug MCU component identity register 0, Address offset: 0xFF0 */ - __IO uint32_t CIDR1; /*!< Debug MCU component identity register 1, Address offset: 0xFF4 */ - __IO uint32_t CIDR2; /*!< Debug MCU component identity register 2, Address offset: 0xFF8 */ - __IO uint32_t CIDR3; /*!< Debug MCU component identity register 3, Address offset: 0xFFC */ -}DBGMCU_TypeDef; -/** - * @brief DCMI - */ - -typedef struct -{ - __IO uint32_t CR; /*!< DCMI control register 1, Address offset: 0x00 */ - __IO uint32_t SR; /*!< DCMI status register, Address offset: 0x04 */ - __IO uint32_t RISR; /*!< DCMI raw interrupt status register, Address offset: 0x08 */ - __IO uint32_t IER; /*!< DCMI interrupt enable register, Address offset: 0x0C */ - __IO uint32_t MISR; /*!< DCMI masked interrupt status register, Address offset: 0x10 */ - __IO uint32_t ICR; /*!< DCMI interrupt clear register, Address offset: 0x14 */ - __IO uint32_t ESCR; /*!< DCMI embedded synchronization code register, Address offset: 0x18 */ - __IO uint32_t ESUR; /*!< DCMI embedded synchronization unmask register, Address offset: 0x1C */ - __IO uint32_t CWSTRTR; /*!< DCMI crop window start, Address offset: 0x20 */ - __IO uint32_t CWSIZER; /*!< DCMI crop window size, Address offset: 0x24 */ - __IO uint32_t DR; /*!< DCMI data register, Address offset: 0x28 */ -} DCMI_TypeDef; - -/** - * @brief PSSI - */ - -typedef struct -{ - __IO uint32_t CR; /*!< PSSI control register 1, Address offset: 0x000 */ - __IO uint32_t SR; /*!< PSSI status register, Address offset: 0x004 */ - __IO uint32_t RIS; /*!< PSSI raw interrupt status register, Address offset: 0x008 */ - __IO uint32_t IER; /*!< PSSI interrupt enable register, Address offset: 0x00C */ - __IO uint32_t MIS; /*!< PSSI masked interrupt status register, Address offset: 0x010 */ - __IO uint32_t ICR; /*!< PSSI interrupt clear register, Address offset: 0x014 */ - __IO uint32_t RESERVED1[4]; /*!< Reserved, 0x018 - 0x024 */ - __IO uint32_t DR; /*!< PSSI data register, Address offset: 0x028 */ - __IO uint32_t RESERVED2[241]; /*!< Reserved, 0x02C - 0x3EC */ - __IO uint32_t HWCFGR; /*!< PSSI IP HW configuration register, Address offset: 0x3F0 */ - __IO uint32_t VERR; /*!< PSSI IP version register, Address offset: 0x3F4 */ - __IO uint32_t IPIDR; /*!< PSSI IP ID register, Address offset: 0x3F8 */ - __IO uint32_t SIDR; /*!< PSSI SIZE ID register, Address offset: 0x3FC */ -} PSSI_TypeDef; - -/** - * @brief DMA Controller - */ - -typedef struct -{ - __IO uint32_t CR; /*!< DMA stream x configuration register */ - __IO uint32_t NDTR; /*!< DMA stream x number of data register */ - __IO uint32_t PAR; /*!< DMA stream x peripheral address register */ - __IO uint32_t M0AR; /*!< DMA stream x memory 0 address register */ - __IO uint32_t M1AR; /*!< DMA stream x memory 1 address register */ - __IO uint32_t FCR; /*!< DMA stream x FIFO control register */ -} DMA_Stream_TypeDef; - -typedef struct -{ - __IO uint32_t LISR; /*!< DMA low interrupt status register, Address offset: 0x00 */ - __IO uint32_t HISR; /*!< DMA high interrupt status register, Address offset: 0x04 */ - __IO uint32_t LIFCR; /*!< DMA low interrupt flag clear register, Address offset: 0x08 */ - __IO uint32_t HIFCR; /*!< DMA high interrupt flag clear register, Address offset: 0x0C */ -} DMA_TypeDef; - -typedef struct -{ - __IO uint32_t CCR; /*!< DMA channel x configuration register */ - __IO uint32_t CNDTR; /*!< DMA channel x number of data register */ - __IO uint32_t CPAR; /*!< DMA channel x peripheral address register */ - __IO uint32_t CM0AR; /*!< DMA channel x memory 0 address register */ - __IO uint32_t CM1AR; /*!< DMA channel x memory 1 address register */ -} BDMA_Channel_TypeDef; - -typedef struct -{ - __IO uint32_t ISR; /*!< DMA interrupt status register, Address offset: 0x00 */ - __IO uint32_t IFCR; /*!< DMA interrupt flag clear register, Address offset: 0x04 */ -} BDMA_TypeDef; - -typedef struct -{ - __IO uint32_t CCR; /*!< DMA Multiplexer Channel x Control Register */ -}DMAMUX_Channel_TypeDef; - -typedef struct -{ - __IO uint32_t CSR; /*!< DMA Channel Status Register */ - __IO uint32_t CFR; /*!< DMA Channel Clear Flag Register */ -}DMAMUX_ChannelStatus_TypeDef; - -typedef struct -{ - __IO uint32_t RGCR; /*!< DMA Request Generator x Control Register */ -}DMAMUX_RequestGen_TypeDef; - -typedef struct -{ - __IO uint32_t RGSR; /*!< DMA Request Generator Status Register */ - __IO uint32_t RGCFR; /*!< DMA Request Generator Clear Flag Register */ -}DMAMUX_RequestGenStatus_TypeDef; - -/** - * @brief MDMA Controller - */ -typedef struct -{ - __IO uint32_t GISR0; /*!< MDMA Global Interrupt/Status Register 0, Address offset: 0x00 */ -}MDMA_TypeDef; - -typedef struct -{ - __IO uint32_t CISR; /*!< MDMA channel x interrupt/status register, Address offset: 0x40 */ - __IO uint32_t CIFCR; /*!< MDMA channel x interrupt flag clear register, Address offset: 0x44 */ - __IO uint32_t CESR; /*!< MDMA Channel x error status register, Address offset: 0x48 */ - __IO uint32_t CCR; /*!< MDMA channel x control register, Address offset: 0x4C */ - __IO uint32_t CTCR; /*!< MDMA channel x Transfer Configuration register, Address offset: 0x50 */ - __IO uint32_t CBNDTR; /*!< MDMA Channel x block number of data register, Address offset: 0x54 */ - __IO uint32_t CSAR; /*!< MDMA channel x source address register, Address offset: 0x58 */ - __IO uint32_t CDAR; /*!< MDMA channel x destination address register, Address offset: 0x5C */ - __IO uint32_t CBRUR; /*!< MDMA channel x Block Repeat address Update register, Address offset: 0x60 */ - __IO uint32_t CLAR; /*!< MDMA channel x Link Address register, Address offset: 0x64 */ - __IO uint32_t CTBR; /*!< MDMA channel x Trigger and Bus selection Register, Address offset: 0x68 */ - uint32_t RESERVED0; /*!< Reserved, 0x6C */ - __IO uint32_t CMAR; /*!< MDMA channel x Mask address register, Address offset: 0x70 */ - __IO uint32_t CMDR; /*!< MDMA channel x Mask Data register, Address offset: 0x74 */ -}MDMA_Channel_TypeDef; - -/** - * @brief DMA2D Controller - */ - -typedef struct -{ - __IO uint32_t CR; /*!< DMA2D Control Register, Address offset: 0x00 */ - __IO uint32_t ISR; /*!< DMA2D Interrupt Status Register, Address offset: 0x04 */ - __IO uint32_t IFCR; /*!< DMA2D Interrupt Flag Clear Register, Address offset: 0x08 */ - __IO uint32_t FGMAR; /*!< DMA2D Foreground Memory Address Register, Address offset: 0x0C */ - __IO uint32_t FGOR; /*!< DMA2D Foreground Offset Register, Address offset: 0x10 */ - __IO uint32_t BGMAR; /*!< DMA2D Background Memory Address Register, Address offset: 0x14 */ - __IO uint32_t BGOR; /*!< DMA2D Background Offset Register, Address offset: 0x18 */ - __IO uint32_t FGPFCCR; /*!< DMA2D Foreground PFC Control Register, Address offset: 0x1C */ - __IO uint32_t FGCOLR; /*!< DMA2D Foreground Color Register, Address offset: 0x20 */ - __IO uint32_t BGPFCCR; /*!< DMA2D Background PFC Control Register, Address offset: 0x24 */ - __IO uint32_t BGCOLR; /*!< DMA2D Background Color Register, Address offset: 0x28 */ - __IO uint32_t FGCMAR; /*!< DMA2D Foreground CLUT Memory Address Register, Address offset: 0x2C */ - __IO uint32_t BGCMAR; /*!< DMA2D Background CLUT Memory Address Register, Address offset: 0x30 */ - __IO uint32_t OPFCCR; /*!< DMA2D Output PFC Control Register, Address offset: 0x34 */ - __IO uint32_t OCOLR; /*!< DMA2D Output Color Register, Address offset: 0x38 */ - __IO uint32_t OMAR; /*!< DMA2D Output Memory Address Register, Address offset: 0x3C */ - __IO uint32_t OOR; /*!< DMA2D Output Offset Register, Address offset: 0x40 */ - __IO uint32_t NLR; /*!< DMA2D Number of Line Register, Address offset: 0x44 */ - __IO uint32_t LWR; /*!< DMA2D Line Watermark Register, Address offset: 0x48 */ - __IO uint32_t AMTCR; /*!< DMA2D AHB Master Timer Configuration Register, Address offset: 0x4C */ - uint32_t RESERVED[236]; /*!< Reserved, 0x50-0x3FF */ - __IO uint32_t FGCLUT[256]; /*!< DMA2D Foreground CLUT, Address offset:400-7FF */ - __IO uint32_t BGCLUT[256]; /*!< DMA2D Background CLUT, Address offset:800-BFF */ -} DMA2D_TypeDef; - - -/** - * @brief Ethernet MAC - */ -typedef struct -{ - __IO uint32_t MACCR; - __IO uint32_t MACECR; - __IO uint32_t MACPFR; - __IO uint32_t MACWTR; - __IO uint32_t MACHT0R; - __IO uint32_t MACHT1R; - uint32_t RESERVED1[14]; - __IO uint32_t MACVTR; - uint32_t RESERVED2; - __IO uint32_t MACVHTR; - uint32_t RESERVED3; - __IO uint32_t MACVIR; - __IO uint32_t MACIVIR; - uint32_t RESERVED4[2]; - __IO uint32_t MACTFCR; - uint32_t RESERVED5[7]; - __IO uint32_t MACRFCR; - uint32_t RESERVED6[7]; - __IO uint32_t MACISR; - __IO uint32_t MACIER; - __IO uint32_t MACRXTXSR; - uint32_t RESERVED7; - __IO uint32_t MACPCSR; - __IO uint32_t MACRWKPFR; - uint32_t RESERVED8[2]; - __IO uint32_t MACLCSR; - __IO uint32_t MACLTCR; - __IO uint32_t MACLETR; - __IO uint32_t MAC1USTCR; - uint32_t RESERVED9[12]; - __IO uint32_t MACVR; - __IO uint32_t MACDR; - uint32_t RESERVED10; - __IO uint32_t MACHWF0R; - __IO uint32_t MACHWF1R; - __IO uint32_t MACHWF2R; - uint32_t RESERVED11[54]; - __IO uint32_t MACMDIOAR; - __IO uint32_t MACMDIODR; - uint32_t RESERVED12[2]; - __IO uint32_t MACARPAR; - uint32_t RESERVED13[59]; - __IO uint32_t MACA0HR; - __IO uint32_t MACA0LR; - __IO uint32_t MACA1HR; - __IO uint32_t MACA1LR; - __IO uint32_t MACA2HR; - __IO uint32_t MACA2LR; - __IO uint32_t MACA3HR; - __IO uint32_t MACA3LR; - uint32_t RESERVED14[248]; - __IO uint32_t MMCCR; - __IO uint32_t MMCRIR; - __IO uint32_t MMCTIR; - __IO uint32_t MMCRIMR; - __IO uint32_t MMCTIMR; - uint32_t RESERVED15[14]; - __IO uint32_t MMCTSCGPR; - __IO uint32_t MMCTMCGPR; - uint32_t RESERVED16[5]; - __IO uint32_t MMCTPCGR; - uint32_t RESERVED17[10]; - __IO uint32_t MMCRCRCEPR; - __IO uint32_t MMCRAEPR; - uint32_t RESERVED18[10]; - __IO uint32_t MMCRUPGR; - uint32_t RESERVED19[9]; - __IO uint32_t MMCTLPIMSTR; - __IO uint32_t MMCTLPITCR; - __IO uint32_t MMCRLPIMSTR; - __IO uint32_t MMCRLPITCR; - uint32_t RESERVED20[65]; - __IO uint32_t MACL3L4C0R; - __IO uint32_t MACL4A0R; - uint32_t RESERVED21[2]; - __IO uint32_t MACL3A0R0R; - __IO uint32_t MACL3A1R0R; - __IO uint32_t MACL3A2R0R; - __IO uint32_t MACL3A3R0R; - uint32_t RESERVED22[4]; - __IO uint32_t MACL3L4C1R; - __IO uint32_t MACL4A1R; - uint32_t RESERVED23[2]; - __IO uint32_t MACL3A0R1R; - __IO uint32_t MACL3A1R1R; - __IO uint32_t MACL3A2R1R; - __IO uint32_t MACL3A3R1R; - uint32_t RESERVED24[108]; - __IO uint32_t MACTSCR; - __IO uint32_t MACSSIR; - __IO uint32_t MACSTSR; - __IO uint32_t MACSTNR; - __IO uint32_t MACSTSUR; - __IO uint32_t MACSTNUR; - __IO uint32_t MACTSAR; - uint32_t RESERVED25; - __IO uint32_t MACTSSR; - uint32_t RESERVED26[3]; - __IO uint32_t MACTTSSNR; - __IO uint32_t MACTTSSSR; - uint32_t RESERVED27[2]; - __IO uint32_t MACACR; - uint32_t RESERVED28; - __IO uint32_t MACATSNR; - __IO uint32_t MACATSSR; - __IO uint32_t MACTSIACR; - __IO uint32_t MACTSEACR; - __IO uint32_t MACTSICNR; - __IO uint32_t MACTSECNR; - uint32_t RESERVED29[4]; - __IO uint32_t MACPPSCR; - uint32_t RESERVED30[3]; - __IO uint32_t MACPPSTTSR; - __IO uint32_t MACPPSTTNR; - __IO uint32_t MACPPSIR; - __IO uint32_t MACPPSWR; - uint32_t RESERVED31[12]; - __IO uint32_t MACPOCR; - __IO uint32_t MACSPI0R; - __IO uint32_t MACSPI1R; - __IO uint32_t MACSPI2R; - __IO uint32_t MACLMIR; - uint32_t RESERVED32[11]; - __IO uint32_t MTLOMR; - uint32_t RESERVED33[7]; - __IO uint32_t MTLISR; - uint32_t RESERVED34[55]; - __IO uint32_t MTLTQOMR; - __IO uint32_t MTLTQUR; - __IO uint32_t MTLTQDR; - uint32_t RESERVED35[8]; - __IO uint32_t MTLQICSR; - __IO uint32_t MTLRQOMR; - __IO uint32_t MTLRQMPOCR; - __IO uint32_t MTLRQDR; - uint32_t RESERVED36[177]; - __IO uint32_t DMAMR; - __IO uint32_t DMASBMR; - __IO uint32_t DMAISR; - __IO uint32_t DMADSR; - uint32_t RESERVED37[60]; - __IO uint32_t DMACCR; - __IO uint32_t DMACTCR; - __IO uint32_t DMACRCR; - uint32_t RESERVED38[2]; - __IO uint32_t DMACTDLAR; - uint32_t RESERVED39; - __IO uint32_t DMACRDLAR; - __IO uint32_t DMACTDTPR; - uint32_t RESERVED40; - __IO uint32_t DMACRDTPR; - __IO uint32_t DMACTDRLR; - __IO uint32_t DMACRDRLR; - __IO uint32_t DMACIER; - __IO uint32_t DMACRIWTR; -__IO uint32_t DMACSFCSR; - uint32_t RESERVED41; - __IO uint32_t DMACCATDR; - uint32_t RESERVED42; - __IO uint32_t DMACCARDR; - uint32_t RESERVED43; - __IO uint32_t DMACCATBR; - uint32_t RESERVED44; - __IO uint32_t DMACCARBR; - __IO uint32_t DMACSR; -uint32_t RESERVED45[2]; -__IO uint32_t DMACMFCR; -}ETH_TypeDef; -/** - * @brief External Interrupt/Event Controller - */ - -typedef struct -{ -__IO uint32_t RTSR1; /*!< EXTI Rising trigger selection register, Address offset: 0x00 */ -__IO uint32_t FTSR1; /*!< EXTI Falling trigger selection register, Address offset: 0x04 */ -__IO uint32_t SWIER1; /*!< EXTI Software interrupt event register, Address offset: 0x08 */ -__IO uint32_t D3PMR1; /*!< EXTI D3 Pending mask register, (same register as to SRDPMR1) Address offset: 0x0C */ -__IO uint32_t D3PCR1L; /*!< EXTI D3 Pending clear selection register low, (same register as to SRDPCR1L) Address offset: 0x10 */ -__IO uint32_t D3PCR1H; /*!< EXTI D3 Pending clear selection register High, (same register as to SRDPCR1H) Address offset: 0x14 */ -uint32_t RESERVED1[2]; /*!< Reserved, 0x18 to 0x1C */ -__IO uint32_t RTSR2; /*!< EXTI Rising trigger selection register, Address offset: 0x20 */ -__IO uint32_t FTSR2; /*!< EXTI Falling trigger selection register, Address offset: 0x24 */ -__IO uint32_t SWIER2; /*!< EXTI Software interrupt event register, Address offset: 0x28 */ -__IO uint32_t D3PMR2; /*!< EXTI D3 Pending mask register, (same register as to SRDPMR2) Address offset: 0x2C */ -__IO uint32_t D3PCR2L; /*!< EXTI D3 Pending clear selection register low, (same register as to SRDPCR2L) Address offset: 0x30 */ -__IO uint32_t D3PCR2H; /*!< EXTI D3 Pending clear selection register High, (same register as to SRDPCR2H) Address offset: 0x34 */ -uint32_t RESERVED2[2]; /*!< Reserved, 0x38 to 0x3C */ -__IO uint32_t RTSR3; /*!< EXTI Rising trigger selection register, Address offset: 0x40 */ -__IO uint32_t FTSR3; /*!< EXTI Falling trigger selection register, Address offset: 0x44 */ -__IO uint32_t SWIER3; /*!< EXTI Software interrupt event register, Address offset: 0x48 */ -__IO uint32_t D3PMR3; /*!< EXTI D3 Pending mask register, (same register as to SRDPMR3) Address offset: 0x4C */ -__IO uint32_t D3PCR3L; /*!< EXTI D3 Pending clear selection register low, (same register as to SRDPCR3L) Address offset: 0x50 */ -__IO uint32_t D3PCR3H; /*!< EXTI D3 Pending clear selection register High, (same register as to SRDPCR3H) Address offset: 0x54 */ -uint32_t RESERVED3[10]; /*!< Reserved, 0x58 to 0x7C */ -__IO uint32_t IMR1; /*!< EXTI Interrupt mask register, Address offset: 0x80 */ -__IO uint32_t EMR1; /*!< EXTI Event mask register, Address offset: 0x84 */ -__IO uint32_t PR1; /*!< EXTI Pending register, Address offset: 0x88 */ -uint32_t RESERVED4; /*!< Reserved, 0x8C */ -__IO uint32_t IMR2; /*!< EXTI Interrupt mask register, Address offset: 0x90 */ -__IO uint32_t EMR2; /*!< EXTI Event mask register, Address offset: 0x94 */ -__IO uint32_t PR2; /*!< EXTI Pending register, Address offset: 0x98 */ -uint32_t RESERVED5; /*!< Reserved, 0x9C */ -__IO uint32_t IMR3; /*!< EXTI Interrupt mask register, Address offset: 0xA0 */ -__IO uint32_t EMR3; /*!< EXTI Event mask register, Address offset: 0xA4 */ -__IO uint32_t PR3; /*!< EXTI Pending register, Address offset: 0xA8 */ -}EXTI_TypeDef; - -/** - * @brief This structure registers corresponds to EXTI_Typdef CPU1/CPU2 registers subset (IMRx, EMRx and PRx), allowing to define EXTI_D1/EXTI_D2 - * with rapid/common access to these IMRx, EMRx, PRx registers for CPU1 and CPU2. - * Note that EXTI_D1 and EXTI_D2 bases addresses are calculated to point to CPUx first register: - * IMR1 in case of EXTI_D1 that is addressing CPU1 (Coretx-M7) - * C2IMR1 in case of EXTI_D2 that is addressing CPU2 (Coretx-M4) - * Note: EXTI_D2 and corresponding C2IMRx, C2EMRx and C2PRx registers are available for Dual Core devices only - */ - -typedef struct -{ -__IO uint32_t IMR1; /*!< EXTI Interrupt mask register, Address offset: 0x00 */ -__IO uint32_t EMR1; /*!< EXTI Event mask register, Address offset: 0x04 */ -__IO uint32_t PR1; /*!< EXTI Pending register, Address offset: 0x08 */ -uint32_t RESERVED1; /*!< Reserved, 0x0C */ -__IO uint32_t IMR2; /*!< EXTI Interrupt mask register, Address offset: 0x10 */ -__IO uint32_t EMR2; /*!< EXTI Event mask register, Address offset: 0x14 */ -__IO uint32_t PR2; /*!< EXTI Pending register, Address offset: 0x18 */ -uint32_t RESERVED2; /*!< Reserved, 0x1C */ -__IO uint32_t IMR3; /*!< EXTI Interrupt mask register, Address offset: 0x20 */ -__IO uint32_t EMR3; /*!< EXTI Event mask register, Address offset: 0x24 */ -__IO uint32_t PR3; /*!< EXTI Pending register, Address offset: 0x28 */ -}EXTI_Core_TypeDef; - - -/** - * @brief FLASH Registers - */ - -typedef struct -{ - __IO uint32_t ACR; /*!< FLASH access control register, Address offset: 0x00 */ - __IO uint32_t KEYR1; /*!< Flash Key Register for bank1, Address offset: 0x04 */ - __IO uint32_t OPTKEYR; /*!< Flash Option Key Register, Address offset: 0x08 */ - __IO uint32_t CR1; /*!< Flash Control Register for bank1, Address offset: 0x0C */ - __IO uint32_t SR1; /*!< Flash Status Register for bank1, Address offset: 0x10 */ - __IO uint32_t CCR1; /*!< Flash Control Register for bank1, Address offset: 0x14 */ - __IO uint32_t OPTCR; /*!< Flash Option Control Register, Address offset: 0x18 */ - __IO uint32_t OPTSR_CUR; /*!< Flash Option Status Current Register, Address offset: 0x1C */ - __IO uint32_t OPTSR_PRG; /*!< Flash Option Status to Program Register, Address offset: 0x20 */ - __IO uint32_t OPTCCR; /*!< Flash Option Clear Control Register, Address offset: 0x24 */ - __IO uint32_t PRAR_CUR1; /*!< Flash Current Protection Address Register for bank1, Address offset: 0x28 */ - __IO uint32_t PRAR_PRG1; /*!< Flash Protection Address to Program Register for bank1, Address offset: 0x2C */ - __IO uint32_t SCAR_CUR1; /*!< Flash Current Secure Address Register for bank1, Address offset: 0x30 */ - __IO uint32_t SCAR_PRG1; /*!< Flash Secure Address to Program Register for bank1, Address offset: 0x34 */ - __IO uint32_t WPSN_CUR1; /*!< Flash Current Write Protection Register on bank1, Address offset: 0x38 */ - __IO uint32_t WPSN_PRG1; /*!< Flash Write Protection to Program Register on bank1, Address offset: 0x3C */ - __IO uint32_t BOOT_CUR; /*!< Flash Current Boot Address for Pelican Core Register, Address offset: 0x40 */ - __IO uint32_t BOOT_PRG; /*!< Flash Boot Address to Program for Pelican Core Register, Address offset: 0x44 */ - uint32_t RESERVED0[2]; /*!< Reserved, 0x48 to 0x4C */ - __IO uint32_t CRCCR1; /*!< Flash CRC Control register For Bank1 Register , Address offset: 0x50 */ - __IO uint32_t CRCSADD1; /*!< Flash CRC Start Address Register for Bank1 , Address offset: 0x54 */ - __IO uint32_t CRCEADD1; /*!< Flash CRC End Address Register for Bank1 , Address offset: 0x58 */ - __IO uint32_t CRCDATA; /*!< Flash CRC Data Register for Bank1 , Address offset: 0x5C */ - __IO uint32_t ECC_FA1; /*!< Flash ECC Fail Address For Bank1 Register , Address offset: 0x60 */ - uint32_t RESERVED[3]; /*!< Reserved, 0x64 to 0x6C */ - __IO uint32_t OPTSR2_CUR; /*!< Flash Option Status Current Register 2, Address offset: 0x70 */ - __IO uint32_t OPTSR2_PRG; /*!< Flash Option Status to Program Register 2, Address offset: 0x74 */ -} FLASH_TypeDef; - -/** - * @brief Filter and Mathematical ACcelerator - */ -typedef struct -{ - __IO uint32_t X1BUFCFG; /*!< FMAC X1 Buffer Configuration register, Address offset: 0x00 */ - __IO uint32_t X2BUFCFG; /*!< FMAC X2 Buffer Configuration register, Address offset: 0x04 */ - __IO uint32_t YBUFCFG; /*!< FMAC Y Buffer Configuration register, Address offset: 0x08 */ - __IO uint32_t PARAM; /*!< FMAC Parameter register, Address offset: 0x0C */ - __IO uint32_t CR; /*!< FMAC Control register, Address offset: 0x10 */ - __IO uint32_t SR; /*!< FMAC Status register, Address offset: 0x14 */ - __IO uint32_t WDATA; /*!< FMAC Write Data register, Address offset: 0x18 */ - __IO uint32_t RDATA; /*!< FMAC Read Data register, Address offset: 0x1C */ -} FMAC_TypeDef; - -/** - * @brief Flexible Memory Controller - */ - -typedef struct -{ - __IO uint32_t BTCR[8]; /*!< NOR/PSRAM chip-select control register(BCR) and chip-select timing register(BTR), Address offset: 0x00-1C */ -} FMC_Bank1_TypeDef; - -/** - * @brief Flexible Memory Controller Bank1E - */ - -typedef struct -{ - __IO uint32_t BWTR[7]; /*!< NOR/PSRAM write timing registers, Address offset: 0x104-0x11C */ -} FMC_Bank1E_TypeDef; - -/** - * @brief Flexible Memory Controller Bank2 - */ - -typedef struct -{ - __IO uint32_t PCR2; /*!< NAND Flash control register 2, Address offset: 0x60 */ - __IO uint32_t SR2; /*!< NAND Flash FIFO status and interrupt register 2, Address offset: 0x64 */ - __IO uint32_t PMEM2; /*!< NAND Flash Common memory space timing register 2, Address offset: 0x68 */ - __IO uint32_t PATT2; /*!< NAND Flash Attribute memory space timing register 2, Address offset: 0x6C */ - uint32_t RESERVED0; /*!< Reserved, 0x70 */ - __IO uint32_t ECCR2; /*!< NAND Flash ECC result registers 2, Address offset: 0x74 */ -} FMC_Bank2_TypeDef; - -/** - * @brief Flexible Memory Controller Bank3 - */ - -typedef struct -{ - __IO uint32_t PCR; /*!< NAND Flash control register 3, Address offset: 0x80 */ - __IO uint32_t SR; /*!< NAND Flash FIFO status and interrupt register 3, Address offset: 0x84 */ - __IO uint32_t PMEM; /*!< NAND Flash Common memory space timing register 3, Address offset: 0x88 */ - __IO uint32_t PATT; /*!< NAND Flash Attribute memory space timing register 3, Address offset: 0x8C */ - uint32_t RESERVED; /*!< Reserved, 0x90 */ - __IO uint32_t ECCR; /*!< NAND Flash ECC result registers 3, Address offset: 0x94 */ -} FMC_Bank3_TypeDef; - -/** - * @brief Flexible Memory Controller Bank5 and 6 - */ - - -typedef struct -{ - __IO uint32_t SDCR[2]; /*!< SDRAM Control registers , Address offset: 0x140-0x144 */ - __IO uint32_t SDTR[2]; /*!< SDRAM Timing registers , Address offset: 0x148-0x14C */ - __IO uint32_t SDCMR; /*!< SDRAM Command Mode register, Address offset: 0x150 */ - __IO uint32_t SDRTR; /*!< SDRAM Refresh Timer register, Address offset: 0x154 */ - __IO uint32_t SDSR; /*!< SDRAM Status register, Address offset: 0x158 */ -} FMC_Bank5_6_TypeDef; - -/** - * @brief General Purpose I/O - */ - -typedef struct -{ - __IO uint32_t MODER; /*!< GPIO port mode register, Address offset: 0x00 */ - __IO uint32_t OTYPER; /*!< GPIO port output type register, Address offset: 0x04 */ - __IO uint32_t OSPEEDR; /*!< GPIO port output speed register, Address offset: 0x08 */ - __IO uint32_t PUPDR; /*!< GPIO port pull-up/pull-down register, Address offset: 0x0C */ - __IO uint32_t IDR; /*!< GPIO port input data register, Address offset: 0x10 */ - __IO uint32_t ODR; /*!< GPIO port output data register, Address offset: 0x14 */ - __IO uint32_t BSRR; /*!< GPIO port bit set/reset, Address offset: 0x18 */ - __IO uint32_t LCKR; /*!< GPIO port configuration lock register, Address offset: 0x1C */ - __IO uint32_t AFR[2]; /*!< GPIO alternate function registers, Address offset: 0x20-0x24 */ -} GPIO_TypeDef; - -/** - * @brief Operational Amplifier (OPAMP) - */ - -typedef struct -{ - __IO uint32_t CSR; /*!< OPAMP control/status register, Address offset: 0x00 */ - __IO uint32_t OTR; /*!< OPAMP offset trimming register for normal mode, Address offset: 0x04 */ - __IO uint32_t HSOTR; /*!< OPAMP offset trimming register for high speed mode, Address offset: 0x08 */ -} OPAMP_TypeDef; - -/** - * @brief System configuration controller - */ - -typedef struct -{ - uint32_t RESERVED1; /*!< Reserved, Address offset: 0x00 */ - __IO uint32_t PMCR; /*!< SYSCFG peripheral mode configuration register, Address offset: 0x04 */ - __IO uint32_t EXTICR[4]; /*!< SYSCFG external interrupt configuration registers, Address offset: 0x08-0x14 */ - __IO uint32_t CFGR; /*!< SYSCFG configuration registers, Address offset: 0x18 */ - uint32_t RESERVED2; /*!< Reserved, Address offset: 0x1C */ - __IO uint32_t CCCSR; /*!< SYSCFG compensation cell control/status register, Address offset: 0x20 */ - __IO uint32_t CCVR; /*!< SYSCFG compensation cell value register, Address offset: 0x24 */ - __IO uint32_t CCCR; /*!< SYSCFG compensation cell code register, Address offset: 0x28 */ - uint32_t RESERVED3; /*!< Reserved, Address offset: 0x2C */ - __IO uint32_t ADC2ALT; /*!< ADC2 internal input alternate connection register, Address offset: 0x30 */ - uint32_t RESERVED4[60]; /*!< Reserved, 0x34-0x120 */ - __IO uint32_t PKGR; /*!< SYSCFG package register, Address offset: 0x124 */ - uint32_t RESERVED5[118]; /*!< Reserved, 0x128-0x2FC */ - __IO uint32_t UR0; /*!< SYSCFG user register 0, Address offset: 0x300 */ - __IO uint32_t UR1; /*!< SYSCFG user register 1, Address offset: 0x304 */ - __IO uint32_t UR2; /*!< SYSCFG user register 2, Address offset: 0x308 */ - __IO uint32_t UR3; /*!< SYSCFG user register 3, Address offset: 0x30C */ - __IO uint32_t UR4; /*!< SYSCFG user register 4, Address offset: 0x310 */ - __IO uint32_t UR5; /*!< SYSCFG user register 5, Address offset: 0x314 */ - __IO uint32_t UR6; /*!< SYSCFG user register 6, Address offset: 0x318 */ - __IO uint32_t UR7; /*!< SYSCFG user register 7, Address offset: 0x31C */ - uint32_t RESERVED6[3]; /*!< Reserved, Address offset: 0x320-0x328 */ - __IO uint32_t UR11; /*!< SYSCFG user register 11, Address offset: 0x32C */ - __IO uint32_t UR12; /*!< SYSCFG user register 12, Address offset: 0x330 */ - __IO uint32_t UR13; /*!< SYSCFG user register 13, Address offset: 0x334 */ - __IO uint32_t UR14; /*!< SYSCFG user register 14, Address offset: 0x338 */ - __IO uint32_t UR15; /*!< SYSCFG user register 15, Address offset: 0x33C */ - __IO uint32_t UR16; /*!< SYSCFG user register 16, Address offset: 0x340 */ - __IO uint32_t UR17; /*!< SYSCFG user register 17, Address offset: 0x344 */ - __IO uint32_t UR18; /*!< SYSCFG user register 18, Address offset: 0x348 */ - -} SYSCFG_TypeDef; - -/** - * @brief Inter-integrated Circuit Interface - */ - -typedef struct -{ - __IO uint32_t CR1; /*!< I2C Control register 1, Address offset: 0x00 */ - __IO uint32_t CR2; /*!< I2C Control register 2, Address offset: 0x04 */ - __IO uint32_t OAR1; /*!< I2C Own address 1 register, Address offset: 0x08 */ - __IO uint32_t OAR2; /*!< I2C Own address 2 register, Address offset: 0x0C */ - __IO uint32_t TIMINGR; /*!< I2C Timing register, Address offset: 0x10 */ - __IO uint32_t TIMEOUTR; /*!< I2C Timeout register, Address offset: 0x14 */ - __IO uint32_t ISR; /*!< I2C Interrupt and status register, Address offset: 0x18 */ - __IO uint32_t ICR; /*!< I2C Interrupt clear register, Address offset: 0x1C */ - __IO uint32_t PECR; /*!< I2C PEC register, Address offset: 0x20 */ - __IO uint32_t RXDR; /*!< I2C Receive data register, Address offset: 0x24 */ - __IO uint32_t TXDR; /*!< I2C Transmit data register, Address offset: 0x28 */ -} I2C_TypeDef; - -/** - * @brief Independent WATCHDOG - */ - -typedef struct -{ - __IO uint32_t KR; /*!< IWDG Key register, Address offset: 0x00 */ - __IO uint32_t PR; /*!< IWDG Prescaler register, Address offset: 0x04 */ - __IO uint32_t RLR; /*!< IWDG Reload register, Address offset: 0x08 */ - __IO uint32_t SR; /*!< IWDG Status register, Address offset: 0x0C */ - __IO uint32_t WINR; /*!< IWDG Window register, Address offset: 0x10 */ -} IWDG_TypeDef; - - -/** - * @brief LCD-TFT Display Controller - */ - -typedef struct -{ - uint32_t RESERVED0[2]; /*!< Reserved, 0x00-0x04 */ - __IO uint32_t SSCR; /*!< LTDC Synchronization Size Configuration Register, Address offset: 0x08 */ - __IO uint32_t BPCR; /*!< LTDC Back Porch Configuration Register, Address offset: 0x0C */ - __IO uint32_t AWCR; /*!< LTDC Active Width Configuration Register, Address offset: 0x10 */ - __IO uint32_t TWCR; /*!< LTDC Total Width Configuration Register, Address offset: 0x14 */ - __IO uint32_t GCR; /*!< LTDC Global Control Register, Address offset: 0x18 */ - uint32_t RESERVED1[2]; /*!< Reserved, 0x1C-0x20 */ - __IO uint32_t SRCR; /*!< LTDC Shadow Reload Configuration Register, Address offset: 0x24 */ - uint32_t RESERVED2[1]; /*!< Reserved, 0x28 */ - __IO uint32_t BCCR; /*!< LTDC Background Color Configuration Register, Address offset: 0x2C */ - uint32_t RESERVED3[1]; /*!< Reserved, 0x30 */ - __IO uint32_t IER; /*!< LTDC Interrupt Enable Register, Address offset: 0x34 */ - __IO uint32_t ISR; /*!< LTDC Interrupt Status Register, Address offset: 0x38 */ - __IO uint32_t ICR; /*!< LTDC Interrupt Clear Register, Address offset: 0x3C */ - __IO uint32_t LIPCR; /*!< LTDC Line Interrupt Position Configuration Register, Address offset: 0x40 */ - __IO uint32_t CPSR; /*!< LTDC Current Position Status Register, Address offset: 0x44 */ - __IO uint32_t CDSR; /*!< LTDC Current Display Status Register, Address offset: 0x48 */ -} LTDC_TypeDef; - -/** - * @brief LCD-TFT Display layer x Controller - */ - -typedef struct -{ - __IO uint32_t CR; /*!< LTDC Layerx Control Register Address offset: 0x84 */ - __IO uint32_t WHPCR; /*!< LTDC Layerx Window Horizontal Position Configuration Register Address offset: 0x88 */ - __IO uint32_t WVPCR; /*!< LTDC Layerx Window Vertical Position Configuration Register Address offset: 0x8C */ - __IO uint32_t CKCR; /*!< LTDC Layerx Color Keying Configuration Register Address offset: 0x90 */ - __IO uint32_t PFCR; /*!< LTDC Layerx Pixel Format Configuration Register Address offset: 0x94 */ - __IO uint32_t CACR; /*!< LTDC Layerx Constant Alpha Configuration Register Address offset: 0x98 */ - __IO uint32_t DCCR; /*!< LTDC Layerx Default Color Configuration Register Address offset: 0x9C */ - __IO uint32_t BFCR; /*!< LTDC Layerx Blending Factors Configuration Register Address offset: 0xA0 */ - uint32_t RESERVED0[2]; /*!< Reserved */ - __IO uint32_t CFBAR; /*!< LTDC Layerx Color Frame Buffer Address Register Address offset: 0xAC */ - __IO uint32_t CFBLR; /*!< LTDC Layerx Color Frame Buffer Length Register Address offset: 0xB0 */ - __IO uint32_t CFBLNR; /*!< LTDC Layerx ColorFrame Buffer Line Number Register Address offset: 0xB4 */ - uint32_t RESERVED1[3]; /*!< Reserved */ - __IO uint32_t CLUTWR; /*!< LTDC Layerx CLUT Write Register Address offset: 0x144 */ - -} LTDC_Layer_TypeDef; - -/** - * @brief Power Control - */ - -typedef struct -{ - __IO uint32_t CR1; /*!< PWR power control register 1, Address offset: 0x00 */ - __IO uint32_t CSR1; /*!< PWR power control status register 1, Address offset: 0x04 */ - __IO uint32_t CR2; /*!< PWR power control register 2, Address offset: 0x08 */ - __IO uint32_t CR3; /*!< PWR power control register 3, Address offset: 0x0C */ - __IO uint32_t CPUCR; /*!< PWR CPU control register, Address offset: 0x10 */ - uint32_t RESERVED0; /*!< Reserved, Address offset: 0x14 */ - __IO uint32_t D3CR; /*!< PWR D3 domain control register, Address offset: 0x18 */ - uint32_t RESERVED1; /*!< Reserved, Address offset: 0x1C */ - __IO uint32_t WKUPCR; /*!< PWR wakeup clear register, Address offset: 0x20 */ - __IO uint32_t WKUPFR; /*!< PWR wakeup flag register, Address offset: 0x24 */ - __IO uint32_t WKUPEPR; /*!< PWR wakeup enable and polarity register, Address offset: 0x28 */ -} PWR_TypeDef; - -/** - * @brief Reset and Clock Control - */ - -typedef struct -{ - __IO uint32_t CR; /*!< RCC clock control register, Address offset: 0x00 */ - __IO uint32_t HSICFGR; /*!< HSI Clock Calibration Register, Address offset: 0x04 */ - __IO uint32_t CRRCR; /*!< Clock Recovery RC Register, Address offset: 0x08 */ - __IO uint32_t CSICFGR; /*!< CSI Clock Calibration Register, Address offset: 0x0C */ - __IO uint32_t CFGR; /*!< RCC clock configuration register, Address offset: 0x10 */ - uint32_t RESERVED1; /*!< Reserved, Address offset: 0x14 */ - __IO uint32_t D1CFGR; /*!< RCC Domain 1 configuration register, Address offset: 0x18 */ - __IO uint32_t D2CFGR; /*!< RCC Domain 2 configuration register, Address offset: 0x1C */ - __IO uint32_t D3CFGR; /*!< RCC Domain 3 configuration register, Address offset: 0x20 */ - uint32_t RESERVED2; /*!< Reserved, Address offset: 0x24 */ - __IO uint32_t PLLCKSELR; /*!< RCC PLLs Clock Source Selection Register, Address offset: 0x28 */ - __IO uint32_t PLLCFGR; /*!< RCC PLLs Configuration Register, Address offset: 0x2C */ - __IO uint32_t PLL1DIVR; /*!< RCC PLL1 Dividers Configuration Register, Address offset: 0x30 */ - __IO uint32_t PLL1FRACR; /*!< RCC PLL1 Fractional Divider Configuration Register, Address offset: 0x34 */ - __IO uint32_t PLL2DIVR; /*!< RCC PLL2 Dividers Configuration Register, Address offset: 0x38 */ - __IO uint32_t PLL2FRACR; /*!< RCC PLL2 Fractional Divider Configuration Register, Address offset: 0x3C */ - __IO uint32_t PLL3DIVR; /*!< RCC PLL3 Dividers Configuration Register, Address offset: 0x40 */ - __IO uint32_t PLL3FRACR; /*!< RCC PLL3 Fractional Divider Configuration Register, Address offset: 0x44 */ - uint32_t RESERVED3; /*!< Reserved, Address offset: 0x48 */ - __IO uint32_t D1CCIPR; /*!< RCC Domain 1 Kernel Clock Configuration Register Address offset: 0x4C */ - __IO uint32_t D2CCIP1R; /*!< RCC Domain 2 Kernel Clock Configuration Register Address offset: 0x50 */ - __IO uint32_t D2CCIP2R; /*!< RCC Domain 2 Kernel Clock Configuration Register Address offset: 0x54 */ - __IO uint32_t D3CCIPR; /*!< RCC Domain 3 Kernel Clock Configuration Register Address offset: 0x58 */ - uint32_t RESERVED4; /*!< Reserved, Address offset: 0x5C */ - __IO uint32_t CIER; /*!< RCC Clock Source Interrupt Enable Register Address offset: 0x60 */ - __IO uint32_t CIFR; /*!< RCC Clock Source Interrupt Flag Register Address offset: 0x64 */ - __IO uint32_t CICR; /*!< RCC Clock Source Interrupt Clear Register Address offset: 0x68 */ - uint32_t RESERVED5; /*!< Reserved, Address offset: 0x6C */ - __IO uint32_t BDCR; /*!< RCC Vswitch Backup Domain Control Register, Address offset: 0x70 */ - __IO uint32_t CSR; /*!< RCC clock control & status register, Address offset: 0x74 */ - uint32_t RESERVED6; /*!< Reserved, Address offset: 0x78 */ - __IO uint32_t AHB3RSTR; /*!< RCC AHB3 peripheral reset register, Address offset: 0x7C */ - __IO uint32_t AHB1RSTR; /*!< RCC AHB1 peripheral reset register, Address offset: 0x80 */ - __IO uint32_t AHB2RSTR; /*!< RCC AHB2 peripheral reset register, Address offset: 0x84 */ - __IO uint32_t AHB4RSTR; /*!< RCC AHB4 peripheral reset register, Address offset: 0x88 */ - __IO uint32_t APB3RSTR; /*!< RCC APB3 peripheral reset register, Address offset: 0x8C */ - __IO uint32_t APB1LRSTR; /*!< RCC APB1 peripheral reset Low Word register, Address offset: 0x90 */ - __IO uint32_t APB1HRSTR; /*!< RCC APB1 peripheral reset High Word register, Address offset: 0x94 */ - __IO uint32_t APB2RSTR; /*!< RCC APB2 peripheral reset register, Address offset: 0x98 */ - __IO uint32_t APB4RSTR; /*!< RCC APB4 peripheral reset register, Address offset: 0x9C */ - __IO uint32_t GCR; /*!< RCC RCC Global Control Register, Address offset: 0xA0 */ - uint32_t RESERVED8; /*!< Reserved, Address offset: 0xA4 */ - __IO uint32_t D3AMR; /*!< RCC Domain 3 Autonomous Mode Register, Address offset: 0xA8 */ - uint32_t RESERVED11[9]; /*!< Reserved, 0xAC-0xCC Address offset: 0xAC */ - __IO uint32_t RSR; /*!< RCC Reset status register, Address offset: 0xD0 */ - __IO uint32_t AHB3ENR; /*!< RCC AHB3 peripheral clock register, Address offset: 0xD4 */ - __IO uint32_t AHB1ENR; /*!< RCC AHB1 peripheral clock register, Address offset: 0xD8 */ - __IO uint32_t AHB2ENR; /*!< RCC AHB2 peripheral clock register, Address offset: 0xDC */ - __IO uint32_t AHB4ENR; /*!< RCC AHB4 peripheral clock register, Address offset: 0xE0 */ - __IO uint32_t APB3ENR; /*!< RCC APB3 peripheral clock register, Address offset: 0xE4 */ - __IO uint32_t APB1LENR; /*!< RCC APB1 peripheral clock Low Word register, Address offset: 0xE8 */ - __IO uint32_t APB1HENR; /*!< RCC APB1 peripheral clock High Word register, Address offset: 0xEC */ - __IO uint32_t APB2ENR; /*!< RCC APB2 peripheral clock register, Address offset: 0xF0 */ - __IO uint32_t APB4ENR; /*!< RCC APB4 peripheral clock register, Address offset: 0xF4 */ - uint32_t RESERVED12; /*!< Reserved, Address offset: 0xF8 */ - __IO uint32_t AHB3LPENR; /*!< RCC AHB3 peripheral sleep clock register, Address offset: 0xFC */ - __IO uint32_t AHB1LPENR; /*!< RCC AHB1 peripheral sleep clock register, Address offset: 0x100 */ - __IO uint32_t AHB2LPENR; /*!< RCC AHB2 peripheral sleep clock register, Address offset: 0x104 */ - __IO uint32_t AHB4LPENR; /*!< RCC AHB4 peripheral sleep clock register, Address offset: 0x108 */ - __IO uint32_t APB3LPENR; /*!< RCC APB3 peripheral sleep clock register, Address offset: 0x10C */ - __IO uint32_t APB1LLPENR; /*!< RCC APB1 peripheral sleep clock Low Word register, Address offset: 0x110 */ - __IO uint32_t APB1HLPENR; /*!< RCC APB1 peripheral sleep clock High Word register, Address offset: 0x114 */ - __IO uint32_t APB2LPENR; /*!< RCC APB2 peripheral sleep clock register, Address offset: 0x118 */ - __IO uint32_t APB4LPENR; /*!< RCC APB4 peripheral sleep clock register, Address offset: 0x11C */ - uint32_t RESERVED13[4]; /*!< Reserved, 0x120-0x12C Address offset: 0x120 */ - -} RCC_TypeDef; - - -/** - * @brief Real-Time Clock - */ -typedef struct -{ - __IO uint32_t TR; /*!< RTC time register, Address offset: 0x00 */ - __IO uint32_t DR; /*!< RTC date register, Address offset: 0x04 */ - __IO uint32_t CR; /*!< RTC control register, Address offset: 0x08 */ - __IO uint32_t ISR; /*!< RTC initialization and status register, Address offset: 0x0C */ - __IO uint32_t PRER; /*!< RTC prescaler register, Address offset: 0x10 */ - __IO uint32_t WUTR; /*!< RTC wakeup timer register, Address offset: 0x14 */ - uint32_t RESERVED; /*!< Reserved, Address offset: 0x18 */ - __IO uint32_t ALRMAR; /*!< RTC alarm A register, Address offset: 0x1C */ - __IO uint32_t ALRMBR; /*!< RTC alarm B register, Address offset: 0x20 */ - __IO uint32_t WPR; /*!< RTC write protection register, Address offset: 0x24 */ - __IO uint32_t SSR; /*!< RTC sub second register, Address offset: 0x28 */ - __IO uint32_t SHIFTR; /*!< RTC shift control register, Address offset: 0x2C */ - __IO uint32_t TSTR; /*!< RTC time stamp time register, Address offset: 0x30 */ - __IO uint32_t TSDR; /*!< RTC time stamp date register, Address offset: 0x34 */ - __IO uint32_t TSSSR; /*!< RTC time-stamp sub second register, Address offset: 0x38 */ - __IO uint32_t CALR; /*!< RTC calibration register, Address offset: 0x3C */ - __IO uint32_t TAMPCR; /*!< RTC tamper configuration register, Address offset: 0x40 */ - __IO uint32_t ALRMASSR; /*!< RTC alarm A sub second register, Address offset: 0x44 */ - __IO uint32_t ALRMBSSR; /*!< RTC alarm B sub second register, Address offset: 0x48 */ - __IO uint32_t OR; /*!< RTC option register, Address offset: 0x4C */ - __IO uint32_t BKP0R; /*!< RTC backup register 0, Address offset: 0x50 */ - __IO uint32_t BKP1R; /*!< RTC backup register 1, Address offset: 0x54 */ - __IO uint32_t BKP2R; /*!< RTC backup register 2, Address offset: 0x58 */ - __IO uint32_t BKP3R; /*!< RTC backup register 3, Address offset: 0x5C */ - __IO uint32_t BKP4R; /*!< RTC backup register 4, Address offset: 0x60 */ - __IO uint32_t BKP5R; /*!< RTC backup register 5, Address offset: 0x64 */ - __IO uint32_t BKP6R; /*!< RTC backup register 6, Address offset: 0x68 */ - __IO uint32_t BKP7R; /*!< RTC backup register 7, Address offset: 0x6C */ - __IO uint32_t BKP8R; /*!< RTC backup register 8, Address offset: 0x70 */ - __IO uint32_t BKP9R; /*!< RTC backup register 9, Address offset: 0x74 */ - __IO uint32_t BKP10R; /*!< RTC backup register 10, Address offset: 0x78 */ - __IO uint32_t BKP11R; /*!< RTC backup register 11, Address offset: 0x7C */ - __IO uint32_t BKP12R; /*!< RTC backup register 12, Address offset: 0x80 */ - __IO uint32_t BKP13R; /*!< RTC backup register 13, Address offset: 0x84 */ - __IO uint32_t BKP14R; /*!< RTC backup register 14, Address offset: 0x88 */ - __IO uint32_t BKP15R; /*!< RTC backup register 15, Address offset: 0x8C */ - __IO uint32_t BKP16R; /*!< RTC backup register 16, Address offset: 0x90 */ - __IO uint32_t BKP17R; /*!< RTC backup register 17, Address offset: 0x94 */ - __IO uint32_t BKP18R; /*!< RTC backup register 18, Address offset: 0x98 */ - __IO uint32_t BKP19R; /*!< RTC backup register 19, Address offset: 0x9C */ - __IO uint32_t BKP20R; /*!< RTC backup register 20, Address offset: 0xA0 */ - __IO uint32_t BKP21R; /*!< RTC backup register 21, Address offset: 0xA4 */ - __IO uint32_t BKP22R; /*!< RTC backup register 22, Address offset: 0xA8 */ - __IO uint32_t BKP23R; /*!< RTC backup register 23, Address offset: 0xAC */ - __IO uint32_t BKP24R; /*!< RTC backup register 24, Address offset: 0xB0 */ - __IO uint32_t BKP25R; /*!< RTC backup register 25, Address offset: 0xB4 */ - __IO uint32_t BKP26R; /*!< RTC backup register 26, Address offset: 0xB8 */ - __IO uint32_t BKP27R; /*!< RTC backup register 27, Address offset: 0xBC */ - __IO uint32_t BKP28R; /*!< RTC backup register 28, Address offset: 0xC0 */ - __IO uint32_t BKP29R; /*!< RTC backup register 29, Address offset: 0xC4 */ - __IO uint32_t BKP30R; /*!< RTC backup register 30, Address offset: 0xC8 */ - __IO uint32_t BKP31R; /*!< RTC backup register 31, Address offset: 0xCC */ -} RTC_TypeDef; - -/** - * @brief Serial Audio Interface - */ - -typedef struct -{ - __IO uint32_t GCR; /*!< SAI global configuration register, Address offset: 0x00 */ - uint32_t RESERVED0[16]; /*!< Reserved, 0x04 - 0x43 */ - __IO uint32_t PDMCR; /*!< SAI PDM control register, Address offset: 0x44 */ - __IO uint32_t PDMDLY; /*!< SAI PDM delay register, Address offset: 0x48 */ -} SAI_TypeDef; - -typedef struct -{ - __IO uint32_t CR1; /*!< SAI block x configuration register 1, Address offset: 0x04 */ - __IO uint32_t CR2; /*!< SAI block x configuration register 2, Address offset: 0x08 */ - __IO uint32_t FRCR; /*!< SAI block x frame configuration register, Address offset: 0x0C */ - __IO uint32_t SLOTR; /*!< SAI block x slot register, Address offset: 0x10 */ - __IO uint32_t IMR; /*!< SAI block x interrupt mask register, Address offset: 0x14 */ - __IO uint32_t SR; /*!< SAI block x status register, Address offset: 0x18 */ - __IO uint32_t CLRFR; /*!< SAI block x clear flag register, Address offset: 0x1C */ - __IO uint32_t DR; /*!< SAI block x data register, Address offset: 0x20 */ -} SAI_Block_TypeDef; - -/** - * @brief SPDIF-RX Interface - */ - -typedef struct -{ - __IO uint32_t CR; /*!< Control register, Address offset: 0x00 */ - __IO uint32_t IMR; /*!< Interrupt mask register, Address offset: 0x04 */ - __IO uint32_t SR; /*!< Status register, Address offset: 0x08 */ - __IO uint32_t IFCR; /*!< Interrupt Flag Clear register, Address offset: 0x0C */ - __IO uint32_t DR; /*!< Data input register, Address offset: 0x10 */ - __IO uint32_t CSR; /*!< Channel Status register, Address offset: 0x14 */ - __IO uint32_t DIR; /*!< Debug Information register, Address offset: 0x18 */ - uint32_t RESERVED2; /*!< Reserved, 0x1A */ -} SPDIFRX_TypeDef; - - -/** - * @brief Secure digital input/output Interface - */ - -typedef struct -{ - __IO uint32_t POWER; /*!< SDMMC power control register, Address offset: 0x00 */ - __IO uint32_t CLKCR; /*!< SDMMC clock control register, Address offset: 0x04 */ - __IO uint32_t ARG; /*!< SDMMC argument register, Address offset: 0x08 */ - __IO uint32_t CMD; /*!< SDMMC command register, Address offset: 0x0C */ - __I uint32_t RESPCMD; /*!< SDMMC command response register, Address offset: 0x10 */ - __I uint32_t RESP1; /*!< SDMMC response 1 register, Address offset: 0x14 */ - __I uint32_t RESP2; /*!< SDMMC response 2 register, Address offset: 0x18 */ - __I uint32_t RESP3; /*!< SDMMC response 3 register, Address offset: 0x1C */ - __I uint32_t RESP4; /*!< SDMMC response 4 register, Address offset: 0x20 */ - __IO uint32_t DTIMER; /*!< SDMMC data timer register, Address offset: 0x24 */ - __IO uint32_t DLEN; /*!< SDMMC data length register, Address offset: 0x28 */ - __IO uint32_t DCTRL; /*!< SDMMC data control register, Address offset: 0x2C */ - __I uint32_t DCOUNT; /*!< SDMMC data counter register, Address offset: 0x30 */ - __I uint32_t STA; /*!< SDMMC status register, Address offset: 0x34 */ - __IO uint32_t ICR; /*!< SDMMC interrupt clear register, Address offset: 0x38 */ - __IO uint32_t MASK; /*!< SDMMC mask register, Address offset: 0x3C */ - __IO uint32_t ACKTIME; /*!< SDMMC Acknowledgement timer register, Address offset: 0x40 */ - uint32_t RESERVED0[3]; /*!< Reserved, 0x44 - 0x4C - 0x4C */ - __IO uint32_t IDMACTRL; /*!< SDMMC DMA control register, Address offset: 0x50 */ - __IO uint32_t IDMABSIZE; /*!< SDMMC DMA buffer size register, Address offset: 0x54 */ - __IO uint32_t IDMABASE0; /*!< SDMMC DMA buffer 0 base address register, Address offset: 0x58 */ - __IO uint32_t IDMABASE1; /*!< SDMMC DMA buffer 1 base address register, Address offset: 0x5C */ - uint32_t RESERVED1[8]; /*!< Reserved, 0x60-0x7C */ - __IO uint32_t FIFO; /*!< SDMMC data FIFO register, Address offset: 0x80 */ - uint32_t RESERVED2[222]; /*!< Reserved, 0x84-0x3F8 */ - __IO uint32_t IPVR; /*!< SDMMC data FIFO register, Address offset: 0x3FC */ -} SDMMC_TypeDef; - - -/** - * @brief Delay Block DLYB - */ - -typedef struct -{ - __IO uint32_t CR; /*!< DELAY BLOCK control register, Address offset: 0x00 */ - __IO uint32_t CFGR; /*!< DELAY BLOCK configuration register, Address offset: 0x04 */ -} DLYB_TypeDef; - -/** - * @brief HW Semaphore HSEM - */ - -typedef struct -{ - __IO uint32_t R[32]; /*!< 2-step write lock and read back registers, Address offset: 00h-7Ch */ - __IO uint32_t RLR[32]; /*!< 1-step read lock registers, Address offset: 80h-FCh */ - __IO uint32_t C1IER; /*!< HSEM Interrupt enable register , Address offset: 100h */ - __IO uint32_t C1ICR; /*!< HSEM Interrupt clear register , Address offset: 104h */ - __IO uint32_t C1ISR; /*!< HSEM Interrupt Status register , Address offset: 108h */ - __IO uint32_t C1MISR; /*!< HSEM Interrupt Masked Status register , Address offset: 10Ch */ - uint32_t Reserved[12]; /* Reserved Address offset: 110h-13Ch */ - __IO uint32_t CR; /*!< HSEM Semaphore clear register , Address offset: 140h */ - __IO uint32_t KEYR; /*!< HSEM Semaphore clear key register , Address offset: 144h */ - -} HSEM_TypeDef; - -typedef struct -{ - __IO uint32_t IER; /*!< HSEM interrupt enable register , Address offset: 0h */ - __IO uint32_t ICR; /*!< HSEM interrupt clear register , Address offset: 4h */ - __IO uint32_t ISR; /*!< HSEM interrupt status register , Address offset: 8h */ - __IO uint32_t MISR; /*!< HSEM masked interrupt status register , Address offset: Ch */ -} HSEM_Common_TypeDef; - -/** - * @brief Serial Peripheral Interface - */ - -typedef struct -{ - __IO uint32_t CR1; /*!< SPI/I2S Control register 1, Address offset: 0x00 */ - __IO uint32_t CR2; /*!< SPI Control register 2, Address offset: 0x04 */ - __IO uint32_t CFG1; /*!< SPI Configuration register 1, Address offset: 0x08 */ - __IO uint32_t CFG2; /*!< SPI Configuration register 2, Address offset: 0x0C */ - __IO uint32_t IER; /*!< SPI/I2S Interrupt Enable register, Address offset: 0x10 */ - __IO uint32_t SR; /*!< SPI/I2S Status register, Address offset: 0x14 */ - __IO uint32_t IFCR; /*!< SPI/I2S Interrupt/Status flags clear register, Address offset: 0x18 */ - uint32_t RESERVED0; /*!< Reserved, 0x1C */ - __IO uint32_t TXDR; /*!< SPI/I2S Transmit data register, Address offset: 0x20 */ - uint32_t RESERVED1[3]; /*!< Reserved, 0x24-0x2C */ - __IO uint32_t RXDR; /*!< SPI/I2S Receive data register, Address offset: 0x30 */ - uint32_t RESERVED2[3]; /*!< Reserved, 0x34-0x3C */ - __IO uint32_t CRCPOLY; /*!< SPI CRC Polynomial register, Address offset: 0x40 */ - __IO uint32_t TXCRC; /*!< SPI Transmitter CRC register, Address offset: 0x44 */ - __IO uint32_t RXCRC; /*!< SPI Receiver CRC register, Address offset: 0x48 */ - __IO uint32_t UDRDR; /*!< SPI Underrun data register, Address offset: 0x4C */ - __IO uint32_t I2SCFGR; /*!< I2S Configuration register, Address offset: 0x50 */ - -} SPI_TypeDef; - -/** - * @brief DTS - */ -typedef struct -{ - __IO uint32_t CFGR1; /*!< DTS configuration register, Address offset: 0x00 */ - uint32_t RESERVED0; /*!< Reserved, Address offset: 0x04 */ - __IO uint32_t T0VALR1; /*!< DTS T0 Value register, Address offset: 0x08 */ - uint32_t RESERVED1; /*!< Reserved, Address offset: 0x0C */ - __IO uint32_t RAMPVALR; /*!< DTS Ramp value register, Address offset: 0x10 */ - __IO uint32_t ITR1; /*!< DTS Interrupt threshold register, Address offset: 0x14 */ - uint32_t RESERVED2; /*!< Reserved, Address offset: 0x18 */ - __IO uint32_t DR; /*!< DTS data register, Address offset: 0x1C */ - __IO uint32_t SR; /*!< DTS status register Address offset: 0x20 */ - __IO uint32_t ITENR; /*!< DTS Interrupt enable register, Address offset: 0x24 */ - __IO uint32_t ICIFR; /*!< DTS Clear Interrupt flag register, Address offset: 0x28 */ - __IO uint32_t OR; /*!< DTS option register 1, Address offset: 0x2C */ -} -DTS_TypeDef; - -/** - * @brief TIM - */ - -typedef struct -{ - __IO uint32_t CR1; /*!< TIM control register 1, Address offset: 0x00 */ - __IO uint32_t CR2; /*!< TIM control register 2, Address offset: 0x04 */ - __IO uint32_t SMCR; /*!< TIM slave mode control register, Address offset: 0x08 */ - __IO uint32_t DIER; /*!< TIM DMA/interrupt enable register, Address offset: 0x0C */ - __IO uint32_t SR; /*!< TIM status register, Address offset: 0x10 */ - __IO uint32_t EGR; /*!< TIM event generation register, Address offset: 0x14 */ - __IO uint32_t CCMR1; /*!< TIM capture/compare mode register 1, Address offset: 0x18 */ - __IO uint32_t CCMR2; /*!< TIM capture/compare mode register 2, Address offset: 0x1C */ - __IO uint32_t CCER; /*!< TIM capture/compare enable register, Address offset: 0x20 */ - __IO uint32_t CNT; /*!< TIM counter register, Address offset: 0x24 */ - __IO uint32_t PSC; /*!< TIM prescaler, Address offset: 0x28 */ - __IO uint32_t ARR; /*!< TIM auto-reload register, Address offset: 0x2C */ - __IO uint32_t RCR; /*!< TIM repetition counter register, Address offset: 0x30 */ - __IO uint32_t CCR1; /*!< TIM capture/compare register 1, Address offset: 0x34 */ - __IO uint32_t CCR2; /*!< TIM capture/compare register 2, Address offset: 0x38 */ - __IO uint32_t CCR3; /*!< TIM capture/compare register 3, Address offset: 0x3C */ - __IO uint32_t CCR4; /*!< TIM capture/compare register 4, Address offset: 0x40 */ - __IO uint32_t BDTR; /*!< TIM break and dead-time register, Address offset: 0x44 */ - __IO uint32_t DCR; /*!< TIM DMA control register, Address offset: 0x48 */ - __IO uint32_t DMAR; /*!< TIM DMA address for full transfer, Address offset: 0x4C */ - uint32_t RESERVED1; /*!< Reserved, 0x50 */ - __IO uint32_t CCMR3; /*!< TIM capture/compare mode register 3, Address offset: 0x54 */ - __IO uint32_t CCR5; /*!< TIM capture/compare register5, Address offset: 0x58 */ - __IO uint32_t CCR6; /*!< TIM capture/compare register6, Address offset: 0x5C */ - __IO uint32_t AF1; /*!< TIM alternate function option register 1, Address offset: 0x60 */ - __IO uint32_t AF2; /*!< TIM alternate function option register 2, Address offset: 0x64 */ - __IO uint32_t TISEL; /*!< TIM Input Selection register, Address offset: 0x68 */ -} TIM_TypeDef; - -/** - * @brief LPTIMIMER - */ -typedef struct -{ - __IO uint32_t ISR; /*!< LPTIM Interrupt and Status register, Address offset: 0x00 */ - __IO uint32_t ICR; /*!< LPTIM Interrupt Clear register, Address offset: 0x04 */ - __IO uint32_t IER; /*!< LPTIM Interrupt Enable register, Address offset: 0x08 */ - __IO uint32_t CFGR; /*!< LPTIM Configuration register, Address offset: 0x0C */ - __IO uint32_t CR; /*!< LPTIM Control register, Address offset: 0x10 */ - __IO uint32_t CMP; /*!< LPTIM Compare register, Address offset: 0x14 */ - __IO uint32_t ARR; /*!< LPTIM Autoreload register, Address offset: 0x18 */ - __IO uint32_t CNT; /*!< LPTIM Counter register, Address offset: 0x1C */ - uint32_t RESERVED1; /*!< Reserved, 0x20 */ - __IO uint32_t CFGR2; /*!< LPTIM Configuration register, Address offset: 0x24 */ -} LPTIM_TypeDef; - -/** - * @brief Comparator - */ -typedef struct -{ - __IO uint32_t SR; /*!< Comparator status register, Address offset: 0x00 */ - __IO uint32_t ICFR; /*!< Comparator interrupt clear flag register, Address offset: 0x04 */ - __IO uint32_t OR; /*!< Comparator option register, Address offset: 0x08 */ -} COMPOPT_TypeDef; - -typedef struct -{ - __IO uint32_t CFGR; /*!< Comparator configuration register , Address offset: 0x00 */ -} COMP_TypeDef; - -typedef struct -{ - __IO uint32_t CFGR; /*!< COMP control and status register, used for bits common to several COMP instances, Address offset: 0x00 */ -} COMP_Common_TypeDef; -/** - * @brief Universal Synchronous Asynchronous Receiver Transmitter - */ - -typedef struct -{ - __IO uint32_t CR1; /*!< USART Control register 1, Address offset: 0x00 */ - __IO uint32_t CR2; /*!< USART Control register 2, Address offset: 0x04 */ - __IO uint32_t CR3; /*!< USART Control register 3, Address offset: 0x08 */ - __IO uint32_t BRR; /*!< USART Baud rate register, Address offset: 0x0C */ - __IO uint32_t GTPR; /*!< USART Guard time and prescaler register, Address offset: 0x10 */ - __IO uint32_t RTOR; /*!< USART Receiver Time Out register, Address offset: 0x14 */ - __IO uint32_t RQR; /*!< USART Request register, Address offset: 0x18 */ - __IO uint32_t ISR; /*!< USART Interrupt and status register, Address offset: 0x1C */ - __IO uint32_t ICR; /*!< USART Interrupt flag Clear register, Address offset: 0x20 */ - __IO uint32_t RDR; /*!< USART Receive Data register, Address offset: 0x24 */ - __IO uint32_t TDR; /*!< USART Transmit Data register, Address offset: 0x28 */ - __IO uint32_t PRESC; /*!< USART clock Prescaler register, Address offset: 0x2C */ -} USART_TypeDef; - -/** - * @brief Single Wire Protocol Master Interface SPWMI - */ -typedef struct -{ - __IO uint32_t CR; /*!< SWPMI Configuration/Control register, Address offset: 0x00 */ - __IO uint32_t BRR; /*!< SWPMI bitrate register, Address offset: 0x04 */ - uint32_t RESERVED1; /*!< Reserved, 0x08 */ - __IO uint32_t ISR; /*!< SWPMI Interrupt and Status register, Address offset: 0x0C */ - __IO uint32_t ICR; /*!< SWPMI Interrupt Flag Clear register, Address offset: 0x10 */ - __IO uint32_t IER; /*!< SWPMI Interrupt Enable register, Address offset: 0x14 */ - __IO uint32_t RFL; /*!< SWPMI Receive Frame Length register, Address offset: 0x18 */ - __IO uint32_t TDR; /*!< SWPMI Transmit data register, Address offset: 0x1C */ - __IO uint32_t RDR; /*!< SWPMI Receive data register, Address offset: 0x20 */ - __IO uint32_t OR; /*!< SWPMI Option register, Address offset: 0x24 */ -} SWPMI_TypeDef; - -/** - * @brief Window WATCHDOG - */ - -typedef struct -{ - __IO uint32_t CR; /*!< WWDG Control register, Address offset: 0x00 */ - __IO uint32_t CFR; /*!< WWDG Configuration register, Address offset: 0x04 */ - __IO uint32_t SR; /*!< WWDG Status register, Address offset: 0x08 */ -} WWDG_TypeDef; - - -/** - * @brief RAM_ECC_Specific_Registers - */ -typedef struct -{ - __IO uint32_t CR; /*!< RAMECC monitor configuration register */ - __IO uint32_t SR; /*!< RAMECC monitor status register */ - __IO uint32_t FAR; /*!< RAMECC monitor failing address register */ - __IO uint32_t FDRL; /*!< RAMECC monitor failing data low register */ - __IO uint32_t FDRH; /*!< RAMECC monitor failing data high register */ - __IO uint32_t FECR; /*!< RAMECC monitor failing ECC error code register */ -} RAMECC_MonitorTypeDef; - -typedef struct -{ - __IO uint32_t IER; /*!< RAMECC interrupt enable register */ -} RAMECC_TypeDef; -/** - * @} - */ - - -/** - * @brief Crypto Processor - */ - -typedef struct -{ - __IO uint32_t CR; /*!< CRYP control register, Address offset: 0x00 */ - __IO uint32_t SR; /*!< CRYP status register, Address offset: 0x04 */ - __IO uint32_t DIN; /*!< CRYP data input register, Address offset: 0x08 */ - __IO uint32_t DOUT; /*!< CRYP data output register, Address offset: 0x0C */ - __IO uint32_t DMACR; /*!< CRYP DMA control register, Address offset: 0x10 */ - __IO uint32_t IMSCR; /*!< CRYP interrupt mask set/clear register, Address offset: 0x14 */ - __IO uint32_t RISR; /*!< CRYP raw interrupt status register, Address offset: 0x18 */ - __IO uint32_t MISR; /*!< CRYP masked interrupt status register, Address offset: 0x1C */ - __IO uint32_t K0LR; /*!< CRYP key left register 0, Address offset: 0x20 */ - __IO uint32_t K0RR; /*!< CRYP key right register 0, Address offset: 0x24 */ - __IO uint32_t K1LR; /*!< CRYP key left register 1, Address offset: 0x28 */ - __IO uint32_t K1RR; /*!< CRYP key right register 1, Address offset: 0x2C */ - __IO uint32_t K2LR; /*!< CRYP key left register 2, Address offset: 0x30 */ - __IO uint32_t K2RR; /*!< CRYP key right register 2, Address offset: 0x34 */ - __IO uint32_t K3LR; /*!< CRYP key left register 3, Address offset: 0x38 */ - __IO uint32_t K3RR; /*!< CRYP key right register 3, Address offset: 0x3C */ - __IO uint32_t IV0LR; /*!< CRYP initialization vector left-word register 0, Address offset: 0x40 */ - __IO uint32_t IV0RR; /*!< CRYP initialization vector right-word register 0, Address offset: 0x44 */ - __IO uint32_t IV1LR; /*!< CRYP initialization vector left-word register 1, Address offset: 0x48 */ - __IO uint32_t IV1RR; /*!< CRYP initialization vector right-word register 1, Address offset: 0x4C */ - __IO uint32_t CSGCMCCM0R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 0, Address offset: 0x50 */ - __IO uint32_t CSGCMCCM1R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 1, Address offset: 0x54 */ - __IO uint32_t CSGCMCCM2R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 2, Address offset: 0x58 */ - __IO uint32_t CSGCMCCM3R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 3, Address offset: 0x5C */ - __IO uint32_t CSGCMCCM4R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 4, Address offset: 0x60 */ - __IO uint32_t CSGCMCCM5R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 5, Address offset: 0x64 */ - __IO uint32_t CSGCMCCM6R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 6, Address offset: 0x68 */ - __IO uint32_t CSGCMCCM7R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 7, Address offset: 0x6C */ - __IO uint32_t CSGCM0R; /*!< CRYP GCM/GMAC context swap register 0, Address offset: 0x70 */ - __IO uint32_t CSGCM1R; /*!< CRYP GCM/GMAC context swap register 1, Address offset: 0x74 */ - __IO uint32_t CSGCM2R; /*!< CRYP GCM/GMAC context swap register 2, Address offset: 0x78 */ - __IO uint32_t CSGCM3R; /*!< CRYP GCM/GMAC context swap register 3, Address offset: 0x7C */ - __IO uint32_t CSGCM4R; /*!< CRYP GCM/GMAC context swap register 4, Address offset: 0x80 */ - __IO uint32_t CSGCM5R; /*!< CRYP GCM/GMAC context swap register 5, Address offset: 0x84 */ - __IO uint32_t CSGCM6R; /*!< CRYP GCM/GMAC context swap register 6, Address offset: 0x88 */ - __IO uint32_t CSGCM7R; /*!< CRYP GCM/GMAC context swap register 7, Address offset: 0x8C */ -} CRYP_TypeDef; - -/** - * @brief HASH - */ - -typedef struct -{ - __IO uint32_t CR; /*!< HASH control register, Address offset: 0x00 */ - __IO uint32_t DIN; /*!< HASH data input register, Address offset: 0x04 */ - __IO uint32_t STR; /*!< HASH start register, Address offset: 0x08 */ - __IO uint32_t HR[5]; /*!< HASH digest registers, Address offset: 0x0C-0x1C */ - __IO uint32_t IMR; /*!< HASH interrupt enable register, Address offset: 0x20 */ - __IO uint32_t SR; /*!< HASH status register, Address offset: 0x24 */ - uint32_t RESERVED[52]; /*!< Reserved, 0x28-0xF4 */ - __IO uint32_t CSR[54]; /*!< HASH context swap registers, Address offset: 0x0F8-0x1CC */ -} HASH_TypeDef; - -/** - * @brief HASH_DIGEST - */ - -typedef struct -{ - __IO uint32_t HR[8]; /*!< HASH digest registers, Address offset: 0x310-0x32C */ -} HASH_DIGEST_TypeDef; - - -/** - * @brief RNG - */ - -typedef struct -{ - __IO uint32_t CR; /*!< RNG control register, Address offset: 0x00 */ - __IO uint32_t SR; /*!< RNG status register, Address offset: 0x04 */ - __IO uint32_t DR; /*!< RNG data register, Address offset: 0x08 */ - uint32_t RESERVED; - __IO uint32_t HTCR; /*!< RNG health test configuration register, Address offset: 0x10 */ -} RNG_TypeDef; - -/** - * @brief MDIOS - */ - -typedef struct -{ - __IO uint32_t CR; - __IO uint32_t WRFR; - __IO uint32_t CWRFR; - __IO uint32_t RDFR; - __IO uint32_t CRDFR; - __IO uint32_t SR; - __IO uint32_t CLRFR; - uint32_t RESERVED[57]; - __IO uint32_t DINR0; - __IO uint32_t DINR1; - __IO uint32_t DINR2; - __IO uint32_t DINR3; - __IO uint32_t DINR4; - __IO uint32_t DINR5; - __IO uint32_t DINR6; - __IO uint32_t DINR7; - __IO uint32_t DINR8; - __IO uint32_t DINR9; - __IO uint32_t DINR10; - __IO uint32_t DINR11; - __IO uint32_t DINR12; - __IO uint32_t DINR13; - __IO uint32_t DINR14; - __IO uint32_t DINR15; - __IO uint32_t DINR16; - __IO uint32_t DINR17; - __IO uint32_t DINR18; - __IO uint32_t DINR19; - __IO uint32_t DINR20; - __IO uint32_t DINR21; - __IO uint32_t DINR22; - __IO uint32_t DINR23; - __IO uint32_t DINR24; - __IO uint32_t DINR25; - __IO uint32_t DINR26; - __IO uint32_t DINR27; - __IO uint32_t DINR28; - __IO uint32_t DINR29; - __IO uint32_t DINR30; - __IO uint32_t DINR31; - __IO uint32_t DOUTR0; - __IO uint32_t DOUTR1; - __IO uint32_t DOUTR2; - __IO uint32_t DOUTR3; - __IO uint32_t DOUTR4; - __IO uint32_t DOUTR5; - __IO uint32_t DOUTR6; - __IO uint32_t DOUTR7; - __IO uint32_t DOUTR8; - __IO uint32_t DOUTR9; - __IO uint32_t DOUTR10; - __IO uint32_t DOUTR11; - __IO uint32_t DOUTR12; - __IO uint32_t DOUTR13; - __IO uint32_t DOUTR14; - __IO uint32_t DOUTR15; - __IO uint32_t DOUTR16; - __IO uint32_t DOUTR17; - __IO uint32_t DOUTR18; - __IO uint32_t DOUTR19; - __IO uint32_t DOUTR20; - __IO uint32_t DOUTR21; - __IO uint32_t DOUTR22; - __IO uint32_t DOUTR23; - __IO uint32_t DOUTR24; - __IO uint32_t DOUTR25; - __IO uint32_t DOUTR26; - __IO uint32_t DOUTR27; - __IO uint32_t DOUTR28; - __IO uint32_t DOUTR29; - __IO uint32_t DOUTR30; - __IO uint32_t DOUTR31; -} MDIOS_TypeDef; - - -/** - * @brief USB_OTG_Core_Registers - */ -typedef struct -{ - __IO uint32_t GOTGCTL; /*!< USB_OTG Control and Status Register 000h */ - __IO uint32_t GOTGINT; /*!< USB_OTG Interrupt Register 004h */ - __IO uint32_t GAHBCFG; /*!< Core AHB Configuration Register 008h */ - __IO uint32_t GUSBCFG; /*!< Core USB Configuration Register 00Ch */ - __IO uint32_t GRSTCTL; /*!< Core Reset Register 010h */ - __IO uint32_t GINTSTS; /*!< Core Interrupt Register 014h */ - __IO uint32_t GINTMSK; /*!< Core Interrupt Mask Register 018h */ - __IO uint32_t GRXSTSR; /*!< Receive Sts Q Read Register 01Ch */ - __IO uint32_t GRXSTSP; /*!< Receive Sts Q Read & POP Register 020h */ - __IO uint32_t GRXFSIZ; /*!< Receive FIFO Size Register 024h */ - __IO uint32_t DIEPTXF0_HNPTXFSIZ; /*!< EP0 / Non Periodic Tx FIFO Size Register 028h */ - __IO uint32_t HNPTXSTS; /*!< Non Periodic Tx FIFO/Queue Sts reg 02Ch */ - uint32_t Reserved30[2]; /*!< Reserved 030h */ - __IO uint32_t GCCFG; /*!< General Purpose IO Register 038h */ - __IO uint32_t CID; /*!< User ID Register 03Ch */ - __IO uint32_t GSNPSID; /* USB_OTG core ID 040h*/ - __IO uint32_t GHWCFG1; /* User HW config1 044h*/ - __IO uint32_t GHWCFG2; /* User HW config2 048h*/ - __IO uint32_t GHWCFG3; /*!< User HW config3 04Ch */ - uint32_t Reserved6; /*!< Reserved 050h */ - __IO uint32_t GLPMCFG; /*!< LPM Register 054h */ - __IO uint32_t GPWRDN; /*!< Power Down Register 058h */ - __IO uint32_t GDFIFOCFG; /*!< DFIFO Software Config Register 05Ch */ - __IO uint32_t GADPCTL; /*!< ADP Timer, Control and Status Register 60Ch */ - uint32_t Reserved43[39]; /*!< Reserved 058h-0FFh */ - __IO uint32_t HPTXFSIZ; /*!< Host Periodic Tx FIFO Size Reg 100h */ - __IO uint32_t DIEPTXF[0x0F]; /*!< dev Periodic Transmit FIFO */ -} USB_OTG_GlobalTypeDef; - - -/** - * @brief USB_OTG_device_Registers - */ -typedef struct -{ - __IO uint32_t DCFG; /*!< dev Configuration Register 800h */ - __IO uint32_t DCTL; /*!< dev Control Register 804h */ - __IO uint32_t DSTS; /*!< dev Status Register (RO) 808h */ - uint32_t Reserved0C; /*!< Reserved 80Ch */ - __IO uint32_t DIEPMSK; /*!< dev IN Endpoint Mask 810h */ - __IO uint32_t DOEPMSK; /*!< dev OUT Endpoint Mask 814h */ - __IO uint32_t DAINT; /*!< dev All Endpoints Itr Reg 818h */ - __IO uint32_t DAINTMSK; /*!< dev All Endpoints Itr Mask 81Ch */ - uint32_t Reserved20; /*!< Reserved 820h */ - uint32_t Reserved9; /*!< Reserved 824h */ - __IO uint32_t DVBUSDIS; /*!< dev VBUS discharge Register 828h */ - __IO uint32_t DVBUSPULSE; /*!< dev VBUS Pulse Register 82Ch */ - __IO uint32_t DTHRCTL; /*!< dev threshold 830h */ - __IO uint32_t DIEPEMPMSK; /*!< dev empty msk 834h */ - __IO uint32_t DEACHINT; /*!< dedicated EP interrupt 838h */ - __IO uint32_t DEACHMSK; /*!< dedicated EP msk 83Ch */ - uint32_t Reserved40; /*!< dedicated EP mask 840h */ - __IO uint32_t DINEP1MSK; /*!< dedicated EP mask 844h */ - uint32_t Reserved44[15]; /*!< Reserved 844-87Ch */ - __IO uint32_t DOUTEP1MSK; /*!< dedicated EP msk 884h */ -} USB_OTG_DeviceTypeDef; - - -/** - * @brief USB_OTG_IN_Endpoint-Specific_Register - */ -typedef struct -{ - __IO uint32_t DIEPCTL; /*!< dev IN Endpoint Control Reg 900h + (ep_num * 20h) + 00h */ - uint32_t Reserved04; /*!< Reserved 900h + (ep_num * 20h) + 04h */ - __IO uint32_t DIEPINT; /*!< dev IN Endpoint Itr Reg 900h + (ep_num * 20h) + 08h */ - uint32_t Reserved0C; /*!< Reserved 900h + (ep_num * 20h) + 0Ch */ - __IO uint32_t DIEPTSIZ; /*!< IN Endpoint Txfer Size 900h + (ep_num * 20h) + 10h */ - __IO uint32_t DIEPDMA; /*!< IN Endpoint DMA Address Reg 900h + (ep_num * 20h) + 14h */ - __IO uint32_t DTXFSTS; /*!< IN Endpoint Tx FIFO Status Reg 900h + (ep_num * 20h) + 18h */ - uint32_t Reserved18; /*!< Reserved 900h+(ep_num*20h)+1Ch-900h+ (ep_num * 20h) + 1Ch */ -} USB_OTG_INEndpointTypeDef; - - -/** - * @brief USB_OTG_OUT_Endpoint-Specific_Registers - */ -typedef struct -{ - __IO uint32_t DOEPCTL; /*!< dev OUT Endpoint Control Reg B00h + (ep_num * 20h) + 00h */ - uint32_t Reserved04; /*!< Reserved B00h + (ep_num * 20h) + 04h */ - __IO uint32_t DOEPINT; /*!< dev OUT Endpoint Itr Reg B00h + (ep_num * 20h) + 08h */ - uint32_t Reserved0C; /*!< Reserved B00h + (ep_num * 20h) + 0Ch */ - __IO uint32_t DOEPTSIZ; /*!< dev OUT Endpoint Txfer Size B00h + (ep_num * 20h) + 10h */ - __IO uint32_t DOEPDMA; /*!< dev OUT Endpoint DMA Address B00h + (ep_num * 20h) + 14h */ - uint32_t Reserved18[2]; /*!< Reserved B00h + (ep_num * 20h) + 18h - B00h + (ep_num * 20h) + 1Ch */ -} USB_OTG_OUTEndpointTypeDef; - - -/** - * @brief USB_OTG_Host_Mode_Register_Structures - */ -typedef struct -{ - __IO uint32_t HCFG; /*!< Host Configuration Register 400h */ - __IO uint32_t HFIR; /*!< Host Frame Interval Register 404h */ - __IO uint32_t HFNUM; /*!< Host Frame Nbr/Frame Remaining 408h */ - uint32_t Reserved40C; /*!< Reserved 40Ch */ - __IO uint32_t HPTXSTS; /*!< Host Periodic Tx FIFO/ Queue Status 410h */ - __IO uint32_t HAINT; /*!< Host All Channels Interrupt Register 414h */ - __IO uint32_t HAINTMSK; /*!< Host All Channels Interrupt Mask 418h */ -} USB_OTG_HostTypeDef; - -/** - * @brief USB_OTG_Host_Channel_Specific_Registers - */ -typedef struct -{ - __IO uint32_t HCCHAR; /*!< Host Channel Characteristics Register 500h */ - __IO uint32_t HCSPLT; /*!< Host Channel Split Control Register 504h */ - __IO uint32_t HCINT; /*!< Host Channel Interrupt Register 508h */ - __IO uint32_t HCINTMSK; /*!< Host Channel Interrupt Mask Register 50Ch */ - __IO uint32_t HCTSIZ; /*!< Host Channel Transfer Size Register 510h */ - __IO uint32_t HCDMA; /*!< Host Channel DMA Address Register 514h */ - uint32_t Reserved[2]; /*!< Reserved */ -} USB_OTG_HostChannelTypeDef; -/** - * @} - */ - -/** - * @brief OCTO Serial Peripheral Interface - */ - -typedef struct -{ - __IO uint32_t CR; /*!< OCTOSPI Control register, Address offset: 0x000 */ - uint32_t RESERVED; /*!< Reserved, Address offset: 0x004 */ - __IO uint32_t DCR1; /*!< OCTOSPI Device Configuration register 1, Address offset: 0x008 */ - __IO uint32_t DCR2; /*!< OCTOSPI Device Configuration register 2, Address offset: 0x00C */ - __IO uint32_t DCR3; /*!< OCTOSPI Device Configuration register 3, Address offset: 0x010 */ - __IO uint32_t DCR4; /*!< OCTOSPI Device Configuration register 4, Address offset: 0x014 */ - uint32_t RESERVED1[2]; /*!< Reserved, Address offset: 0x018-0x01C */ - __IO uint32_t SR; /*!< OCTOSPI Status register, Address offset: 0x020 */ - __IO uint32_t FCR; /*!< OCTOSPI Flag Clear register, Address offset: 0x024 */ - uint32_t RESERVED2[6]; /*!< Reserved, Address offset: 0x028-0x03C */ - __IO uint32_t DLR; /*!< OCTOSPI Data Length register, Address offset: 0x040 */ - uint32_t RESERVED3; /*!< Reserved, Address offset: 0x044 */ - __IO uint32_t AR; /*!< OCTOSPI Address register, Address offset: 0x048 */ - uint32_t RESERVED4; /*!< Reserved, Address offset: 0x04C */ - __IO uint32_t DR; /*!< OCTOSPI Data register, Address offset: 0x050 */ - uint32_t RESERVED5[11]; /*!< Reserved, Address offset: 0x054-0x07C */ - __IO uint32_t PSMKR; /*!< OCTOSPI Polling Status Mask register, Address offset: 0x080 */ - uint32_t RESERVED6; /*!< Reserved, Address offset: 0x084 */ - __IO uint32_t PSMAR; /*!< OCTOSPI Polling Status Match register, Address offset: 0x088 */ - uint32_t RESERVED7; /*!< Reserved, Address offset: 0x08C */ - __IO uint32_t PIR; /*!< OCTOSPI Polling Interval register, Address offset: 0x090 */ - uint32_t RESERVED8[27]; /*!< Reserved, Address offset: 0x094-0x0FC */ - __IO uint32_t CCR; /*!< OCTOSPI Communication Configuration register, Address offset: 0x100 */ - uint32_t RESERVED9; /*!< Reserved, Address offset: 0x104 */ - __IO uint32_t TCR; /*!< OCTOSPI Timing Configuration register, Address offset: 0x108 */ - uint32_t RESERVED10; /*!< Reserved, Address offset: 0x10C */ - __IO uint32_t IR; /*!< OCTOSPI Instruction register, Address offset: 0x110 */ - uint32_t RESERVED11[3]; /*!< Reserved, Address offset: 0x114-0x11C */ - __IO uint32_t ABR; /*!< OCTOSPI Alternate Bytes register, Address offset: 0x120 */ - uint32_t RESERVED12[3]; /*!< Reserved, Address offset: 0x124-0x12C */ - __IO uint32_t LPTR; /*!< OCTOSPI Low Power Timeout register, Address offset: 0x130 */ - uint32_t RESERVED13[3]; /*!< Reserved, Address offset: 0x134-0x13C */ - __IO uint32_t WPCCR; /*!< OCTOSPI Wrap Communication Configuration register, Address offset: 0x140 */ - uint32_t RESERVED14; /*!< Reserved, Address offset: 0x144 */ - __IO uint32_t WPTCR; /*!< OCTOSPI Wrap Timing Configuration register, Address offset: 0x148 */ - uint32_t RESERVED15; /*!< Reserved, Address offset: 0x14C */ - __IO uint32_t WPIR; /*!< OCTOSPI Wrap Instruction register, Address offset: 0x150 */ - uint32_t RESERVED16[3]; /*!< Reserved, Address offset: 0x154-0x15C */ - __IO uint32_t WPABR; /*!< OCTOSPI Wrap Alternate Bytes register, Address offset: 0x160 */ - uint32_t RESERVED17[7]; /*!< Reserved, Address offset: 0x164-0x17C */ - __IO uint32_t WCCR; /*!< OCTOSPI Write Communication Configuration register, Address offset: 0x180 */ - uint32_t RESERVED18; /*!< Reserved, Address offset: 0x184 */ - __IO uint32_t WTCR; /*!< OCTOSPI Write Timing Configuration register, Address offset: 0x188 */ - uint32_t RESERVED19; /*!< Reserved, Address offset: 0x18C */ - __IO uint32_t WIR; /*!< OCTOSPI Write Instruction register, Address offset: 0x190 */ - uint32_t RESERVED20[3]; /*!< Reserved, Address offset: 0x194-0x19C */ - __IO uint32_t WABR; /*!< OCTOSPI Write Alternate Bytes register, Address offset: 0x1A0 */ - uint32_t RESERVED21[23]; /*!< Reserved, Address offset: 0x1A4-0x1FC */ - __IO uint32_t HLCR; /*!< OCTOSPI Hyperbus Latency Configuration register, Address offset: 0x200 */ - uint32_t RESERVED22[122]; /*!< Reserved, Address offset: 0x204-0x3EC */ - __IO uint32_t HWCFGR; /*!< OCTOSPI HW Configuration register, Address offset: 0x3F0 */ - __IO uint32_t VER; /*!< OCTOSPI Version register, Address offset: 0x3F4 */ - __IO uint32_t ID; /*!< OCTOSPI Identification register, Address offset: 0x3F8 */ - __IO uint32_t MID; /*!< OCTOPSI HW Magic ID register, Address offset: 0x3FC */ -} OCTOSPI_TypeDef; - -/** - * @} - */ -/** - * @brief OCTO Serial Peripheral Interface IO Manager - */ - -typedef struct -{ - __IO uint32_t CR; /*!< OCTOSPI IO Manager Control register, Address offset: 0x00 */ - __IO uint32_t PCR[3]; /*!< OCTOSPI IO Manager Port[1:3] Configuration register, Address offset: 0x04-0x20 */ -} OCTOSPIM_TypeDef; - -/** - * @} - */ - -/** - * @brief OTFD register - */ -typedef struct -{ - __IO uint32_t REG_CONFIGR; - __IO uint32_t REG_START_ADDR; - __IO uint32_t REG_END_ADDR; - __IO uint32_t REG_NONCER0; - __IO uint32_t REG_NONCER1; - __IO uint32_t REG_KEYR0; - __IO uint32_t REG_KEYR1; - __IO uint32_t REG_KEYR2; - __IO uint32_t REG_KEYR3; -} OTFDEC_Region_TypeDef; - -typedef struct -{ - __IO uint32_t CR; - uint32_t RESERVED1[191]; - __IO uint32_t ISR; - __IO uint32_t ICR; - __IO uint32_t IER; - uint32_t RESERVED2[56]; - __IO uint32_t HWCFGR2; - __IO uint32_t HWCFGR1; - __IO uint32_t VERR; - __IO uint32_t IPIDR; - __IO uint32_t SIDR; -} OTFDEC_TypeDef; -/** - * @} - */ - -/** - * @brief Global Programmer View - */ - -typedef struct -{ - uint32_t RESERVED0[2036]; /*!< Reserved, Address offset: 0x00-0x1FCC */ - __IO uint32_t AXI_PERIPH_ID_4; /*!< AXI interconnect - peripheral ID4 register, Address offset: 0x1FD0 */ - uint32_t AXI_PERIPH_ID_5; /*!< Reserved, Address offset: 0x1FD4 */ - uint32_t AXI_PERIPH_ID_6; /*!< Reserved, Address offset: 0x1FD8 */ - uint32_t AXI_PERIPH_ID_7; /*!< Reserved, Address offset: 0x1FDC */ - __IO uint32_t AXI_PERIPH_ID_0; /*!< AXI interconnect - peripheral ID0 register, Address offset: 0x1FE0 */ - __IO uint32_t AXI_PERIPH_ID_1; /*!< AXI interconnect - peripheral ID1 register, Address offset: 0x1FE4 */ - __IO uint32_t AXI_PERIPH_ID_2; /*!< AXI interconnect - peripheral ID2 register, Address offset: 0x1FE8 */ - __IO uint32_t AXI_PERIPH_ID_3; /*!< AXI interconnect - peripheral ID3 register, Address offset: 0x1FEC */ - __IO uint32_t AXI_COMP_ID_0; /*!< AXI interconnect - component ID0 register, Address offset: 0x1FF0 */ - __IO uint32_t AXI_COMP_ID_1; /*!< AXI interconnect - component ID1 register, Address offset: 0x1FF4 */ - __IO uint32_t AXI_COMP_ID_2; /*!< AXI interconnect - component ID2 register, Address offset: 0x1FF8 */ - __IO uint32_t AXI_COMP_ID_3; /*!< AXI interconnect - component ID3 register, Address offset: 0x1FFC */ - uint32_t RESERVED1[2]; /*!< Reserved, Address offset: 0x2000-0x2004 */ - __IO uint32_t AXI_TARG1_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 1 bus matrix issuing functionality register, Address offset: 0x2008 */ - uint32_t RESERVED2[6]; /*!< Reserved, Address offset: 0x200C-0x2020 */ - __IO uint32_t AXI_TARG1_FN_MOD2; /*!< AXI interconnect - TARG 1 bus matrix functionality 2 register, Address offset: 0x2024 */ - uint32_t RESERVED3; /*!< Reserved, Address offset: 0x2028 */ - __IO uint32_t AXI_TARG1_FN_MOD_LB; /*!< AXI interconnect - TARG 1 long burst functionality modification register, Address offset: 0x202C */ - uint32_t RESERVED4[54]; /*!< Reserved, Address offset: 0x2030-0x2104 */ - __IO uint32_t AXI_TARG1_FN_MOD; /*!< AXI interconnect - TARG 1 issuing functionality modification register, Address offset: 0x2108 */ - uint32_t RESERVED5[959]; /*!< Reserved, Address offset: 0x210C-0x3004 */ - __IO uint32_t AXI_TARG2_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 2 bus matrix issuing functionality register, Address offset: 0x3008 */ - uint32_t RESERVED6[6]; /*!< Reserved, Address offset: 0x300C-0x3020 */ - __IO uint32_t AXI_TARG2_FN_MOD2; /*!< AXI interconnect - TARG 2 bus matrix functionality 2 register, Address offset: 0x3024 */ - uint32_t RESERVED7; /*!< Reserved, Address offset: 0x3028 */ - __IO uint32_t AXI_TARG2_FN_MOD_LB; /*!< AXI interconnect - TARG 2 long burst functionality modification register, Address offset: 0x302C */ - uint32_t RESERVED8[54]; /*!< Reserved, Address offset: 0x3030-0x3104 */ - __IO uint32_t AXI_TARG2_FN_MOD; /*!< AXI interconnect - TARG 2 issuing functionality modification register, Address offset: 0x3108 */ - uint32_t RESERVED9[959]; /*!< Reserved, Address offset: 0x310C-0x4004 */ - __IO uint32_t AXI_TARG3_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 3 bus matrix issuing functionality register, Address offset: 0x4008 */ - uint32_t RESERVED10[1023]; /*!< Reserved, Address offset: 0x400C-0x5004 */ - __IO uint32_t AXI_TARG4_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 4 bus matrix issuing functionality register, Address offset: 0x5008 */ - uint32_t RESERVED11[1023]; /*!< Reserved, Address offset: 0x500C-0x6004 */ - __IO uint32_t AXI_TARG5_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 5 bus matrix issuing functionality register, Address offset: 0x6008 */ - uint32_t RESERVED12[1023]; /*!< Reserved, Address offset: 0x600C-0x7004 */ - __IO uint32_t AXI_TARG6_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 6 bus matrix issuing functionality register, Address offset: 0x7008 */ - uint32_t RESERVED13[1023]; /*!< Reserved, Address offset: 0x700C-0x8004 */ - __IO uint32_t AXI_TARG7_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 7 bus matrix issuing functionality register, Address offset: 0x8008 */ - uint32_t RESERVED14[6]; /*!< Reserved, Address offset: 0x800C-0x8020 */ - __IO uint32_t AXI_TARG7_FN_MOD2; /*!< AXI interconnect - TARG 7 bus matrix functionality 2 register, Address offset: 0x8024 */ - uint32_t RESERVED15; /*!< Reserved, Address offset: 0x8028 */ - __IO uint32_t AXI_TARG7_FN_MOD_LB; /*!< AXI interconnect - TARG 7 long burst functionality modification register, Address offset: 0x802C */ - uint32_t RESERVED16[54]; /*!< Reserved, Address offset: 0x8030-0x8104 */ - __IO uint32_t AXI_TARG7_FN_MOD; /*!< AXI interconnect - TARG 7 issuing functionality modification register, Address offset: 0x8108 */ - uint32_t RESERVED17[959]; /*!< Reserved, Address offset: 0x810C-0x9004 */ - __IO uint32_t AXI_TARG8_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 8 bus matrix issuing functionality register, Address offset: 0x9008 */ - uint32_t RESERVED117[6]; /*!< Reserved, Address offset: 0x900C-0x9020 */ - __IO uint32_t AXI_TARG8_FN_MOD2; /*!< AXI interconnect - TARG 8 bus matrix functionality 2 register, Address offset: 0x9024 */ - uint32_t RESERVED118[56]; /*!< Reserved, Address offset: 0x9028-0x9104 */ - __IO uint32_t AXI_TARG8_FN_MOD; /*!< AXI interconnect - TARG 8 issuing functionality modification register, Address offset: 0x9108 */ - uint32_t RESERVED119[58310]; /*!< Reserved, Address offset: 0x910C-0x42020 */ - __IO uint32_t AXI_INI1_FN_MOD2; /*!< AXI interconnect - INI 1 functionality modification 2 register, Address offset: 0x42024 */ - __IO uint32_t AXI_INI1_FN_MOD_AHB; /*!< AXI interconnect - INI 1 AHB functionality modification register, Address offset: 0x42028 */ - uint32_t RESERVED18[53]; /*!< Reserved, Address offset: 0x4202C-0x420FC */ - __IO uint32_t AXI_INI1_READ_QOS; /*!< AXI interconnect - INI 1 read QoS register, Address offset: 0x42100 */ - __IO uint32_t AXI_INI1_WRITE_QOS; /*!< AXI interconnect - INI 1 write QoS register, Address offset: 0x42104 */ - __IO uint32_t AXI_INI1_FN_MOD; /*!< AXI interconnect - INI 1 issuing functionality modification register, Address offset: 0x42108 */ - uint32_t RESERVED19[1021]; /*!< Reserved, Address offset: 0x4210C-0x430FC */ - __IO uint32_t AXI_INI2_READ_QOS; /*!< AXI interconnect - INI 2 read QoS register, Address offset: 0x43100 */ - __IO uint32_t AXI_INI2_WRITE_QOS; /*!< AXI interconnect - INI 2 write QoS register, Address offset: 0x43104 */ - __IO uint32_t AXI_INI2_FN_MOD; /*!< AXI interconnect - INI 2 issuing functionality modification register, Address offset: 0x43108 */ - uint32_t RESERVED20[966]; /*!< Reserved, Address offset: 0x4310C-0x44020 */ - __IO uint32_t AXI_INI3_FN_MOD2; /*!< AXI interconnect - INI 3 functionality modification 2 register, Address offset: 0x44024 */ - __IO uint32_t AXI_INI3_FN_MOD_AHB; /*!< AXI interconnect - INI 3 AHB functionality modification register, Address offset: 0x44028 */ - uint32_t RESERVED21[53]; /*!< Reserved, Address offset: 0x4402C-0x440FC */ - __IO uint32_t AXI_INI3_READ_QOS; /*!< AXI interconnect - INI 3 read QoS register, Address offset: 0x44100 */ - __IO uint32_t AXI_INI3_WRITE_QOS; /*!< AXI interconnect - INI 3 write QoS register, Address offset: 0x44104 */ - __IO uint32_t AXI_INI3_FN_MOD; /*!< AXI interconnect - INI 3 issuing functionality modification register, Address offset: 0x44108 */ - uint32_t RESERVED22[1021]; /*!< Reserved, Address offset: 0x4410C-0x450FC */ - __IO uint32_t AXI_INI4_READ_QOS; /*!< AXI interconnect - INI 4 read QoS register, Address offset: 0x45100 */ - __IO uint32_t AXI_INI4_WRITE_QOS; /*!< AXI interconnect - INI 4 write QoS register, Address offset: 0x45104 */ - __IO uint32_t AXI_INI4_FN_MOD; /*!< AXI interconnect - INI 4 issuing functionality modification register, Address offset: 0x45108 */ - uint32_t RESERVED23[1021]; /*!< Reserved, Address offset: 0x4510C-0x460FC */ - __IO uint32_t AXI_INI5_READ_QOS; /*!< AXI interconnect - INI 5 read QoS register, Address offset: 0x46100 */ - __IO uint32_t AXI_INI5_WRITE_QOS; /*!< AXI interconnect - INI 5 write QoS register, Address offset: 0x46104 */ - __IO uint32_t AXI_INI5_FN_MOD; /*!< AXI interconnect - INI 5 issuing functionality modification register, Address offset: 0x46108 */ - uint32_t RESERVED24[1021]; /*!< Reserved, Address offset: 0x4610C-0x470FC */ - __IO uint32_t AXI_INI6_READ_QOS; /*!< AXI interconnect - INI 6 read QoS register, Address offset: 0x47100 */ - __IO uint32_t AXI_INI6_WRITE_QOS; /*!< AXI interconnect - INI 6 write QoS register, Address offset: 0x47104 */ - __IO uint32_t AXI_INI6_FN_MOD; /*!< AXI interconnect - INI 6 issuing functionality modification register, Address offset: 0x47108 */ - -} GPV_TypeDef; - -/** @addtogroup Peripheral_memory_map - * @{ - */ -#define D1_ITCMRAM_BASE (0x00000000UL) /*!< Base address of : 64KB RAM reserved for CPU execution/instruction accessible over ITCM */ -#define D1_ITCMICP_BASE (0x00100000UL) /*!< Base address of : (up to 128KB) embedded Test FLASH memory accessible over ITCM */ -#define D1_DTCMRAM_BASE (0x20000000UL) /*!< Base address of : 128KB system data RAM accessible over DTCM */ -#define D1_AXIFLASH_BASE (0x08000000UL) /*!< Base address of : (up to 1 MB) embedded FLASH memory accessible over AXI */ -#define D1_AXIICP_BASE (0x1FF00000UL) /*!< Base address of : (up to 128KB) embedded Test FLASH memory accessible over AXI */ -#define D1_AXISRAM1_BASE (0x24000000UL) /*!< Base address of : (up to 128KB) system data RAM1 accessible over over AXI */ -#define D1_AXISRAM2_BASE (0x24020000UL) /*!< Base address of : (up to 192KB) system data RAM2 accessible over over AXI to be shared with ITCM (64K granularity) */ -#define D1_AXISRAM_BASE D1_AXISRAM1_BASE /*!< Base address of : (up to 320KB) system data RAM1/2 accessible over over AXI */ - -#define D2_AHBSRAM1_BASE (0x30000000UL) /*!< Base address of : (up to 16KB) system data RAM accessible over over AXI->AHB Bridge */ -#define D2_AHBSRAM2_BASE (0x30004000UL) /*!< Base address of : (up to 16KB) system data RAM accessible over over AXI->AHB Bridge */ -#define D2_AHBSRAM_BASE D2_AHBSRAM1_BASE /*!< Base address of : (up to 32KB) system data RAM1/2 accessible over over AXI->AHB Bridge */ - -#define D3_BKPSRAM_BASE (0x38800000UL) /*!< Base address of : Backup SRAM(4 KB) over AXI->AHB Bridge */ -#define D3_SRAM_BASE (0x38000000UL) /*!< Base address of : Backup SRAM(16 KB) over AXI->AHB Bridge */ - -#define PERIPH_BASE (0x40000000UL) /*!< Base address of : AHB/APB Peripherals */ -#define OCTOSPI1_BASE (0x90000000UL) /*!< Base address of : OCTOSPI1 memories accessible over AXI */ -#define OCTOSPI2_BASE (0x70000000UL) /*!< Base address of : OCTOSPI2 memories accessible over AXI */ - -#define FLASH_BANK1_BASE (0x08000000UL) /*!< Base address of : (up to 1 MB) Flash Bank1 accessible over AXI */ -#define FLASH_END (0x080FFFFFUL) /*!< FLASH end address */ - - -/* Legacy define */ -#define FLASH_BASE FLASH_BANK1_BASE - -/*!< Device electronic signature memory map */ -#define UID_BASE (0x1FF1E800UL) /*!< Unique device ID register base address */ -#define FLASHSIZE_BASE (0x1FF1E880UL) /*!< FLASH Size register base address */ - - -/*!< Peripheral memory map */ -#define D2_APB1PERIPH_BASE PERIPH_BASE -#define D2_APB2PERIPH_BASE (PERIPH_BASE + 0x00010000UL) -#define D2_AHB1PERIPH_BASE (PERIPH_BASE + 0x00020000UL) -#define D2_AHB2PERIPH_BASE (PERIPH_BASE + 0x08020000UL) - -#define D1_APB1PERIPH_BASE (PERIPH_BASE + 0x10000000UL) -#define D1_AHB1PERIPH_BASE (PERIPH_BASE + 0x12000000UL) - -#define D3_APB1PERIPH_BASE (PERIPH_BASE + 0x18000000UL) -#define D3_AHB1PERIPH_BASE (PERIPH_BASE + 0x18020000UL) - -/*!< Legacy Peripheral memory map */ -#define APB1PERIPH_BASE PERIPH_BASE -#define APB2PERIPH_BASE (PERIPH_BASE + 0x00010000UL) -#define AHB1PERIPH_BASE (PERIPH_BASE + 0x00020000UL) -#define AHB2PERIPH_BASE (PERIPH_BASE + 0x08000000UL) - - -/*!< D1_AHB1PERIPH peripherals */ - -#define MDMA_BASE (D1_AHB1PERIPH_BASE + 0x0000UL) -#define DMA2D_BASE (D1_AHB1PERIPH_BASE + 0x1000UL) -#define FLASH_R_BASE (D1_AHB1PERIPH_BASE + 0x2000UL) -#define FMC_R_BASE (D1_AHB1PERIPH_BASE + 0x4000UL) -#define OCTOSPI1_R_BASE (D1_AHB1PERIPH_BASE + 0x5000UL) -#define DLYB_OCTOSPI1_BASE (D1_AHB1PERIPH_BASE + 0x6000UL) -#define SDMMC1_BASE (D1_AHB1PERIPH_BASE + 0x7000UL) -#define DLYB_SDMMC1_BASE (D1_AHB1PERIPH_BASE + 0x8000UL) -#define RAMECC1_BASE (D1_AHB1PERIPH_BASE + 0x9000UL) -#define OCTOSPI2_R_BASE (D1_AHB1PERIPH_BASE + 0xA000UL) -#define DLYB_OCTOSPI2_BASE (D1_AHB1PERIPH_BASE + 0xB000UL) -#define OCTOSPIM_BASE (D1_AHB1PERIPH_BASE + 0xB400UL) - -#define OTFDEC1_BASE (D1_AHB1PERIPH_BASE + 0xB800UL) -#define OTFDEC1_REGION1_BASE (OTFDEC1_BASE + 0x20UL) -#define OTFDEC1_REGION2_BASE (OTFDEC1_BASE + 0x50UL) -#define OTFDEC1_REGION3_BASE (OTFDEC1_BASE + 0x80UL) -#define OTFDEC1_REGION4_BASE (OTFDEC1_BASE + 0xB0UL) -#define OTFDEC2_BASE (D1_AHB1PERIPH_BASE + 0xBC00UL) -#define OTFDEC2_REGION1_BASE (OTFDEC2_BASE + 0x20UL) -#define OTFDEC2_REGION2_BASE (OTFDEC2_BASE + 0x50UL) -#define OTFDEC2_REGION3_BASE (OTFDEC2_BASE + 0x80UL) -#define OTFDEC2_REGION4_BASE (OTFDEC2_BASE + 0xB0UL) - -/*!< D2_AHB1PERIPH peripherals */ - -#define DMA1_BASE (D2_AHB1PERIPH_BASE + 0x0000UL) -#define DMA2_BASE (D2_AHB1PERIPH_BASE + 0x0400UL) -#define DMAMUX1_BASE (D2_AHB1PERIPH_BASE + 0x0800UL) -#define ADC1_BASE (D2_AHB1PERIPH_BASE + 0x2000UL) -#define ADC2_BASE (D2_AHB1PERIPH_BASE + 0x2100UL) -#define ADC12_COMMON_BASE (D2_AHB1PERIPH_BASE + 0x2300UL) -#define ETH_BASE (D2_AHB1PERIPH_BASE + 0x8000UL) -#define ETH_MAC_BASE (ETH_BASE) - -/*!< USB registers base address */ -#define USB1_OTG_HS_PERIPH_BASE (0x40040000UL) -#define USB_OTG_GLOBAL_BASE (0x000UL) -#define USB_OTG_DEVICE_BASE (0x800UL) -#define USB_OTG_IN_ENDPOINT_BASE (0x900UL) -#define USB_OTG_OUT_ENDPOINT_BASE (0xB00UL) -#define USB_OTG_EP_REG_SIZE (0x20UL) -#define USB_OTG_HOST_BASE (0x400UL) -#define USB_OTG_HOST_PORT_BASE (0x440UL) -#define USB_OTG_HOST_CHANNEL_BASE (0x500UL) -#define USB_OTG_HOST_CHANNEL_SIZE (0x20UL) -#define USB_OTG_PCGCCTL_BASE (0xE00UL) -#define USB_OTG_FIFO_BASE (0x1000UL) -#define USB_OTG_FIFO_SIZE (0x1000UL) - -/*!< D2_AHB2PERIPH peripherals */ - -#define DCMI_BASE (D2_AHB2PERIPH_BASE + 0x0000UL) -#define PSSI_BASE (D2_AHB2PERIPH_BASE + 0x0400UL) -#define CRYP_BASE (D2_AHB2PERIPH_BASE + 0x1000UL) -#define HASH_BASE (D2_AHB2PERIPH_BASE + 0x1400UL) -#define HASH_DIGEST_BASE (D2_AHB2PERIPH_BASE + 0x1710UL) -#define RNG_BASE (D2_AHB2PERIPH_BASE + 0x1800UL) -#define SDMMC2_BASE (D2_AHB2PERIPH_BASE + 0x2400UL) -#define DLYB_SDMMC2_BASE (D2_AHB2PERIPH_BASE + 0x2800UL) -#define RAMECC2_BASE (D2_AHB2PERIPH_BASE + 0x3000UL) -#define FMAC_BASE (D2_AHB2PERIPH_BASE + 0x4000UL) -#define CORDIC_BASE (D2_AHB2PERIPH_BASE + 0x4400UL) - -/*!< D3_AHB1PERIPH peripherals */ -#define GPIOA_BASE (D3_AHB1PERIPH_BASE + 0x0000UL) -#define GPIOB_BASE (D3_AHB1PERIPH_BASE + 0x0400UL) -#define GPIOC_BASE (D3_AHB1PERIPH_BASE + 0x0800UL) -#define GPIOD_BASE (D3_AHB1PERIPH_BASE + 0x0C00UL) -#define GPIOE_BASE (D3_AHB1PERIPH_BASE + 0x1000UL) -#define GPIOF_BASE (D3_AHB1PERIPH_BASE + 0x1400UL) -#define GPIOG_BASE (D3_AHB1PERIPH_BASE + 0x1800UL) -#define GPIOH_BASE (D3_AHB1PERIPH_BASE + 0x1C00UL) -#define GPIOJ_BASE (D3_AHB1PERIPH_BASE + 0x2400UL) -#define GPIOK_BASE (D3_AHB1PERIPH_BASE + 0x2800UL) -#define RCC_BASE (D3_AHB1PERIPH_BASE + 0x4400UL) -#define PWR_BASE (D3_AHB1PERIPH_BASE + 0x4800UL) -#define CRC_BASE (D3_AHB1PERIPH_BASE + 0x4C00UL) -#define BDMA_BASE (D3_AHB1PERIPH_BASE + 0x5400UL) -#define DMAMUX2_BASE (D3_AHB1PERIPH_BASE + 0x5800UL) -#define ADC3_BASE (D3_AHB1PERIPH_BASE + 0x6000UL) -#define ADC3_COMMON_BASE (D3_AHB1PERIPH_BASE + 0x6300UL) -#define HSEM_BASE (D3_AHB1PERIPH_BASE + 0x6400UL) -#define RAMECC3_BASE (D3_AHB1PERIPH_BASE + 0x7000UL) - -/*!< D1_APB1PERIPH peripherals */ -#define LTDC_BASE (D1_APB1PERIPH_BASE + 0x1000UL) -#define LTDC_Layer1_BASE (LTDC_BASE + 0x84UL) -#define LTDC_Layer2_BASE (LTDC_BASE + 0x104UL) -#define WWDG1_BASE (D1_APB1PERIPH_BASE + 0x3000UL) - -/*!< D2_APB1PERIPH peripherals */ -#define TIM2_BASE (D2_APB1PERIPH_BASE + 0x0000UL) -#define TIM3_BASE (D2_APB1PERIPH_BASE + 0x0400UL) -#define TIM4_BASE (D2_APB1PERIPH_BASE + 0x0800UL) -#define TIM5_BASE (D2_APB1PERIPH_BASE + 0x0C00UL) -#define TIM6_BASE (D2_APB1PERIPH_BASE + 0x1000UL) -#define TIM7_BASE (D2_APB1PERIPH_BASE + 0x1400UL) -#define TIM12_BASE (D2_APB1PERIPH_BASE + 0x1800UL) -#define TIM13_BASE (D2_APB1PERIPH_BASE + 0x1C00UL) -#define TIM14_BASE (D2_APB1PERIPH_BASE + 0x2000UL) -#define LPTIM1_BASE (D2_APB1PERIPH_BASE + 0x2400UL) - - -#define SPI2_BASE (D2_APB1PERIPH_BASE + 0x3800UL) -#define SPI3_BASE (D2_APB1PERIPH_BASE + 0x3C00UL) -#define SPDIFRX_BASE (D2_APB1PERIPH_BASE + 0x4000UL) -#define USART2_BASE (D2_APB1PERIPH_BASE + 0x4400UL) -#define USART3_BASE (D2_APB1PERIPH_BASE + 0x4800UL) -#define UART4_BASE (D2_APB1PERIPH_BASE + 0x4C00UL) -#define UART5_BASE (D2_APB1PERIPH_BASE + 0x5000UL) -#define I2C1_BASE (D2_APB1PERIPH_BASE + 0x5400UL) -#define I2C2_BASE (D2_APB1PERIPH_BASE + 0x5800UL) -#define I2C3_BASE (D2_APB1PERIPH_BASE + 0x5C00UL) -#define I2C5_BASE (D2_APB1PERIPH_BASE + 0x6400UL) -#define CEC_BASE (D2_APB1PERIPH_BASE + 0x6C00UL) -#define DAC1_BASE (D2_APB1PERIPH_BASE + 0x7400UL) -#define UART7_BASE (D2_APB1PERIPH_BASE + 0x7800UL) -#define UART8_BASE (D2_APB1PERIPH_BASE + 0x7C00UL) -#define CRS_BASE (D2_APB1PERIPH_BASE + 0x8400UL) -#define SWPMI1_BASE (D2_APB1PERIPH_BASE + 0x8800UL) -#define OPAMP_BASE (D2_APB1PERIPH_BASE + 0x9000UL) -#define OPAMP1_BASE (D2_APB1PERIPH_BASE + 0x9000UL) -#define OPAMP2_BASE (D2_APB1PERIPH_BASE + 0x9010UL) -#define MDIOS_BASE (D2_APB1PERIPH_BASE + 0x9400UL) -#define FDCAN1_BASE (D2_APB1PERIPH_BASE + 0xA000UL) -#define FDCAN2_BASE (D2_APB1PERIPH_BASE + 0xA400UL) -#define FDCAN_CCU_BASE (D2_APB1PERIPH_BASE + 0xA800UL) -#define SRAMCAN_BASE (D2_APB1PERIPH_BASE + 0xAC00UL) -#define FDCAN3_BASE (D2_APB1PERIPH_BASE + 0xD400UL) -#define TIM23_BASE (D2_APB1PERIPH_BASE + 0xE000UL) -#define TIM24_BASE (D2_APB1PERIPH_BASE + 0xE400UL) - -/*!< D2_APB2PERIPH peripherals */ - -#define TIM1_BASE (D2_APB2PERIPH_BASE + 0x0000UL) -#define TIM8_BASE (D2_APB2PERIPH_BASE + 0x0400UL) -#define USART1_BASE (D2_APB2PERIPH_BASE + 0x1000UL) -#define USART6_BASE (D2_APB2PERIPH_BASE + 0x1400UL) -#define UART9_BASE (D2_APB2PERIPH_BASE + 0x1800UL) -#define USART10_BASE (D2_APB2PERIPH_BASE + 0x1C00UL) -#define SPI1_BASE (D2_APB2PERIPH_BASE + 0x3000UL) -#define SPI4_BASE (D2_APB2PERIPH_BASE + 0x3400UL) -#define TIM15_BASE (D2_APB2PERIPH_BASE + 0x4000UL) -#define TIM16_BASE (D2_APB2PERIPH_BASE + 0x4400UL) -#define TIM17_BASE (D2_APB2PERIPH_BASE + 0x4800UL) -#define SPI5_BASE (D2_APB2PERIPH_BASE + 0x5000UL) -#define SAI1_BASE (D2_APB2PERIPH_BASE + 0x5800UL) -#define SAI1_Block_A_BASE (SAI1_BASE + 0x004UL) -#define SAI1_Block_B_BASE (SAI1_BASE + 0x024UL) -#define DFSDM1_BASE (D2_APB2PERIPH_BASE + 0x7800UL) -#define DFSDM1_Channel0_BASE (DFSDM1_BASE + 0x00UL) -#define DFSDM1_Channel1_BASE (DFSDM1_BASE + 0x20UL) -#define DFSDM1_Channel2_BASE (DFSDM1_BASE + 0x40UL) -#define DFSDM1_Channel3_BASE (DFSDM1_BASE + 0x60UL) -#define DFSDM1_Channel4_BASE (DFSDM1_BASE + 0x80UL) -#define DFSDM1_Channel5_BASE (DFSDM1_BASE + 0xA0UL) -#define DFSDM1_Channel6_BASE (DFSDM1_BASE + 0xC0UL) -#define DFSDM1_Channel7_BASE (DFSDM1_BASE + 0xE0UL) -#define DFSDM1_Filter0_BASE (DFSDM1_BASE + 0x100UL) -#define DFSDM1_Filter1_BASE (DFSDM1_BASE + 0x180UL) -#define DFSDM1_Filter2_BASE (DFSDM1_BASE + 0x200UL) -#define DFSDM1_Filter3_BASE (DFSDM1_BASE + 0x280UL) - - -/*!< D3_APB1PERIPH peripherals */ -#define EXTI_BASE (D3_APB1PERIPH_BASE + 0x0000UL) -#define EXTI_D1_BASE (EXTI_BASE + 0x0080UL) -#define EXTI_D2_BASE (EXTI_BASE + 0x00C0UL) -#define SYSCFG_BASE (D3_APB1PERIPH_BASE + 0x0400UL) -#define LPUART1_BASE (D3_APB1PERIPH_BASE + 0x0C00UL) -#define SPI6_BASE (D3_APB1PERIPH_BASE + 0x1400UL) -#define I2C4_BASE (D3_APB1PERIPH_BASE + 0x1C00UL) -#define LPTIM2_BASE (D3_APB1PERIPH_BASE + 0x2400UL) -#define LPTIM3_BASE (D3_APB1PERIPH_BASE + 0x2800UL) -#define LPTIM4_BASE (D3_APB1PERIPH_BASE + 0x2C00UL) -#define LPTIM5_BASE (D3_APB1PERIPH_BASE + 0x3000UL) -#define COMP12_BASE (D3_APB1PERIPH_BASE + 0x3800UL) -#define COMP1_BASE (COMP12_BASE + 0x0CUL) -#define COMP2_BASE (COMP12_BASE + 0x10UL) -#define VREFBUF_BASE (D3_APB1PERIPH_BASE + 0x3C00UL) -#define RTC_BASE (D3_APB1PERIPH_BASE + 0x4000UL) -#define IWDG1_BASE (D3_APB1PERIPH_BASE + 0x4800UL) - - -#define SAI4_BASE (D3_APB1PERIPH_BASE + 0x5400UL) -#define SAI4_Block_A_BASE (SAI4_BASE + 0x004UL) -#define SAI4_Block_B_BASE (SAI4_BASE + 0x024UL) - -#define DTS_BASE (D3_APB1PERIPH_BASE + 0x6800UL) - - - -#define BDMA_Channel0_BASE (BDMA_BASE + 0x0008UL) -#define BDMA_Channel1_BASE (BDMA_BASE + 0x001CUL) -#define BDMA_Channel2_BASE (BDMA_BASE + 0x0030UL) -#define BDMA_Channel3_BASE (BDMA_BASE + 0x0044UL) -#define BDMA_Channel4_BASE (BDMA_BASE + 0x0058UL) -#define BDMA_Channel5_BASE (BDMA_BASE + 0x006CUL) -#define BDMA_Channel6_BASE (BDMA_BASE + 0x0080UL) -#define BDMA_Channel7_BASE (BDMA_BASE + 0x0094UL) - -#define DMAMUX2_Channel0_BASE (DMAMUX2_BASE) -#define DMAMUX2_Channel1_BASE (DMAMUX2_BASE + 0x0004UL) -#define DMAMUX2_Channel2_BASE (DMAMUX2_BASE + 0x0008UL) -#define DMAMUX2_Channel3_BASE (DMAMUX2_BASE + 0x000CUL) -#define DMAMUX2_Channel4_BASE (DMAMUX2_BASE + 0x0010UL) -#define DMAMUX2_Channel5_BASE (DMAMUX2_BASE + 0x0014UL) -#define DMAMUX2_Channel6_BASE (DMAMUX2_BASE + 0x0018UL) -#define DMAMUX2_Channel7_BASE (DMAMUX2_BASE + 0x001CUL) - -#define DMAMUX2_RequestGenerator0_BASE (DMAMUX2_BASE + 0x0100UL) -#define DMAMUX2_RequestGenerator1_BASE (DMAMUX2_BASE + 0x0104UL) -#define DMAMUX2_RequestGenerator2_BASE (DMAMUX2_BASE + 0x0108UL) -#define DMAMUX2_RequestGenerator3_BASE (DMAMUX2_BASE + 0x010CUL) -#define DMAMUX2_RequestGenerator4_BASE (DMAMUX2_BASE + 0x0110UL) -#define DMAMUX2_RequestGenerator5_BASE (DMAMUX2_BASE + 0x0114UL) -#define DMAMUX2_RequestGenerator6_BASE (DMAMUX2_BASE + 0x0118UL) -#define DMAMUX2_RequestGenerator7_BASE (DMAMUX2_BASE + 0x011CUL) - -#define DMAMUX2_ChannelStatus_BASE (DMAMUX2_BASE + 0x0080UL) -#define DMAMUX2_RequestGenStatus_BASE (DMAMUX2_BASE + 0x0140UL) - -#define DMA1_Stream0_BASE (DMA1_BASE + 0x010UL) -#define DMA1_Stream1_BASE (DMA1_BASE + 0x028UL) -#define DMA1_Stream2_BASE (DMA1_BASE + 0x040UL) -#define DMA1_Stream3_BASE (DMA1_BASE + 0x058UL) -#define DMA1_Stream4_BASE (DMA1_BASE + 0x070UL) -#define DMA1_Stream5_BASE (DMA1_BASE + 0x088UL) -#define DMA1_Stream6_BASE (DMA1_BASE + 0x0A0UL) -#define DMA1_Stream7_BASE (DMA1_BASE + 0x0B8UL) - -#define DMA2_Stream0_BASE (DMA2_BASE + 0x010UL) -#define DMA2_Stream1_BASE (DMA2_BASE + 0x028UL) -#define DMA2_Stream2_BASE (DMA2_BASE + 0x040UL) -#define DMA2_Stream3_BASE (DMA2_BASE + 0x058UL) -#define DMA2_Stream4_BASE (DMA2_BASE + 0x070UL) -#define DMA2_Stream5_BASE (DMA2_BASE + 0x088UL) -#define DMA2_Stream6_BASE (DMA2_BASE + 0x0A0UL) -#define DMA2_Stream7_BASE (DMA2_BASE + 0x0B8UL) - -#define DMAMUX1_Channel0_BASE (DMAMUX1_BASE) -#define DMAMUX1_Channel1_BASE (DMAMUX1_BASE + 0x0004UL) -#define DMAMUX1_Channel2_BASE (DMAMUX1_BASE + 0x0008UL) -#define DMAMUX1_Channel3_BASE (DMAMUX1_BASE + 0x000CUL) -#define DMAMUX1_Channel4_BASE (DMAMUX1_BASE + 0x0010UL) -#define DMAMUX1_Channel5_BASE (DMAMUX1_BASE + 0x0014UL) -#define DMAMUX1_Channel6_BASE (DMAMUX1_BASE + 0x0018UL) -#define DMAMUX1_Channel7_BASE (DMAMUX1_BASE + 0x001CUL) -#define DMAMUX1_Channel8_BASE (DMAMUX1_BASE + 0x0020UL) -#define DMAMUX1_Channel9_BASE (DMAMUX1_BASE + 0x0024UL) -#define DMAMUX1_Channel10_BASE (DMAMUX1_BASE + 0x0028UL) -#define DMAMUX1_Channel11_BASE (DMAMUX1_BASE + 0x002CUL) -#define DMAMUX1_Channel12_BASE (DMAMUX1_BASE + 0x0030UL) -#define DMAMUX1_Channel13_BASE (DMAMUX1_BASE + 0x0034UL) -#define DMAMUX1_Channel14_BASE (DMAMUX1_BASE + 0x0038UL) -#define DMAMUX1_Channel15_BASE (DMAMUX1_BASE + 0x003CUL) - -#define DMAMUX1_RequestGenerator0_BASE (DMAMUX1_BASE + 0x0100UL) -#define DMAMUX1_RequestGenerator1_BASE (DMAMUX1_BASE + 0x0104UL) -#define DMAMUX1_RequestGenerator2_BASE (DMAMUX1_BASE + 0x0108UL) -#define DMAMUX1_RequestGenerator3_BASE (DMAMUX1_BASE + 0x010CUL) -#define DMAMUX1_RequestGenerator4_BASE (DMAMUX1_BASE + 0x0110UL) -#define DMAMUX1_RequestGenerator5_BASE (DMAMUX1_BASE + 0x0114UL) -#define DMAMUX1_RequestGenerator6_BASE (DMAMUX1_BASE + 0x0118UL) -#define DMAMUX1_RequestGenerator7_BASE (DMAMUX1_BASE + 0x011CUL) - -#define DMAMUX1_ChannelStatus_BASE (DMAMUX1_BASE + 0x0080UL) -#define DMAMUX1_RequestGenStatus_BASE (DMAMUX1_BASE + 0x0140UL) - -/*!< FMC Banks registers base address */ -#define FMC_Bank1_R_BASE (FMC_R_BASE + 0x0000UL) -#define FMC_Bank1E_R_BASE (FMC_R_BASE + 0x0104UL) -#define FMC_Bank2_R_BASE (FMC_R_BASE + 0x0060UL) -#define FMC_Bank3_R_BASE (FMC_R_BASE + 0x0080UL) -#define FMC_Bank5_6_R_BASE (FMC_R_BASE + 0x0140UL) - -/* Debug MCU registers base address */ -#define DBGMCU_BASE (0x5C001000UL) - -#define MDMA_Channel0_BASE (MDMA_BASE + 0x00000040UL) -#define MDMA_Channel1_BASE (MDMA_BASE + 0x00000080UL) -#define MDMA_Channel2_BASE (MDMA_BASE + 0x000000C0UL) -#define MDMA_Channel3_BASE (MDMA_BASE + 0x00000100UL) -#define MDMA_Channel4_BASE (MDMA_BASE + 0x00000140UL) -#define MDMA_Channel5_BASE (MDMA_BASE + 0x00000180UL) -#define MDMA_Channel6_BASE (MDMA_BASE + 0x000001C0UL) -#define MDMA_Channel7_BASE (MDMA_BASE + 0x00000200UL) -#define MDMA_Channel8_BASE (MDMA_BASE + 0x00000240UL) -#define MDMA_Channel9_BASE (MDMA_BASE + 0x00000280UL) -#define MDMA_Channel10_BASE (MDMA_BASE + 0x000002C0UL) -#define MDMA_Channel11_BASE (MDMA_BASE + 0x00000300UL) -#define MDMA_Channel12_BASE (MDMA_BASE + 0x00000340UL) -#define MDMA_Channel13_BASE (MDMA_BASE + 0x00000380UL) -#define MDMA_Channel14_BASE (MDMA_BASE + 0x000003C0UL) -#define MDMA_Channel15_BASE (MDMA_BASE + 0x00000400UL) - -#define RAMECC1_Monitor1_BASE (RAMECC1_BASE + 0x20UL) -#define RAMECC1_Monitor2_BASE (RAMECC1_BASE + 0x40UL) -#define RAMECC1_Monitor3_BASE (RAMECC1_BASE + 0x60UL) -#define RAMECC1_Monitor4_BASE (RAMECC1_BASE + 0x80UL) -#define RAMECC1_Monitor5_BASE (RAMECC1_BASE + 0xA0UL) -#define RAMECC1_Monitor6_BASE (RAMECC1_BASE + 0xC0UL) - -#define RAMECC2_Monitor1_BASE (RAMECC2_BASE + 0x20UL) -#define RAMECC2_Monitor2_BASE (RAMECC2_BASE + 0x40UL) -#define RAMECC2_Monitor3_BASE (RAMECC2_BASE + 0x60UL) - -#define RAMECC3_Monitor1_BASE (RAMECC3_BASE + 0x20UL) -#define RAMECC3_Monitor2_BASE (RAMECC3_BASE + 0x40UL) - - - -#define GPV_BASE (PERIPH_BASE + 0x11000000UL) /*!< GPV_BASE (PERIPH_BASE + 0x11000000UL) */ - -/** - * @} - */ - -/** @addtogroup Peripheral_declaration - * @{ - */ -#define TIM2 ((TIM_TypeDef *) TIM2_BASE) -#define TIM3 ((TIM_TypeDef *) TIM3_BASE) -#define TIM4 ((TIM_TypeDef *) TIM4_BASE) -#define TIM5 ((TIM_TypeDef *) TIM5_BASE) -#define TIM6 ((TIM_TypeDef *) TIM6_BASE) -#define TIM7 ((TIM_TypeDef *) TIM7_BASE) -#define TIM13 ((TIM_TypeDef *) TIM13_BASE) -#define TIM14 ((TIM_TypeDef *) TIM14_BASE) -#define VREFBUF ((VREFBUF_TypeDef *) VREFBUF_BASE) -#define RTC ((RTC_TypeDef *) RTC_BASE) -#define WWDG1 ((WWDG_TypeDef *) WWDG1_BASE) - - -#define IWDG1 ((IWDG_TypeDef *) IWDG1_BASE) -#define SPI2 ((SPI_TypeDef *) SPI2_BASE) -#define SPI3 ((SPI_TypeDef *) SPI3_BASE) -#define SPI4 ((SPI_TypeDef *) SPI4_BASE) -#define SPI5 ((SPI_TypeDef *) SPI5_BASE) -#define SPI6 ((SPI_TypeDef *) SPI6_BASE) -#define USART2 ((USART_TypeDef *) USART2_BASE) -#define USART3 ((USART_TypeDef *) USART3_BASE) -#define USART6 ((USART_TypeDef *) USART6_BASE) -#define USART10 ((USART_TypeDef *) USART10_BASE) -#define UART7 ((USART_TypeDef *) UART7_BASE) -#define UART8 ((USART_TypeDef *) UART8_BASE) -#define UART9 ((USART_TypeDef *) UART9_BASE) -#define CRS ((CRS_TypeDef *) CRS_BASE) -#define UART4 ((USART_TypeDef *) UART4_BASE) -#define UART5 ((USART_TypeDef *) UART5_BASE) -#define I2C1 ((I2C_TypeDef *) I2C1_BASE) -#define I2C2 ((I2C_TypeDef *) I2C2_BASE) -#define I2C3 ((I2C_TypeDef *) I2C3_BASE) -#define I2C4 ((I2C_TypeDef *) I2C4_BASE) -#define I2C5 ((I2C_TypeDef *) I2C5_BASE) -#define FDCAN1 ((FDCAN_GlobalTypeDef *) FDCAN1_BASE) -#define FDCAN2 ((FDCAN_GlobalTypeDef *) FDCAN2_BASE) -#define FDCAN_CCU ((FDCAN_ClockCalibrationUnit_TypeDef *) FDCAN_CCU_BASE) -#define FDCAN3 ((FDCAN_GlobalTypeDef *) FDCAN3_BASE) -#define TIM23 ((TIM_TypeDef *) TIM23_BASE) -#define TIM24 ((TIM_TypeDef *) TIM24_BASE) -#define CEC ((CEC_TypeDef *) CEC_BASE) -#define LPTIM1 ((LPTIM_TypeDef *) LPTIM1_BASE) -#define PWR ((PWR_TypeDef *) PWR_BASE) -#define DAC1 ((DAC_TypeDef *) DAC1_BASE) -#define LPUART1 ((USART_TypeDef *) LPUART1_BASE) -#define SWPMI1 ((SWPMI_TypeDef *) SWPMI1_BASE) -#define LPTIM2 ((LPTIM_TypeDef *) LPTIM2_BASE) -#define LPTIM3 ((LPTIM_TypeDef *) LPTIM3_BASE) -#define DTS ((DTS_TypeDef *) DTS_BASE) -#define LPTIM4 ((LPTIM_TypeDef *) LPTIM4_BASE) -#define LPTIM5 ((LPTIM_TypeDef *) LPTIM5_BASE) - -#define SYSCFG ((SYSCFG_TypeDef *) SYSCFG_BASE) -#define COMP12 ((COMPOPT_TypeDef *) COMP12_BASE) -#define COMP1 ((COMP_TypeDef *) COMP1_BASE) -#define COMP2 ((COMP_TypeDef *) COMP2_BASE) -#define COMP12_COMMON ((COMP_Common_TypeDef *) COMP2_BASE) -#define OPAMP ((OPAMP_TypeDef *) OPAMP_BASE) -#define OPAMP1 ((OPAMP_TypeDef *) OPAMP1_BASE) -#define OPAMP2 ((OPAMP_TypeDef *) OPAMP2_BASE) - - -#define EXTI ((EXTI_TypeDef *) EXTI_BASE) -#define EXTI_D1 ((EXTI_Core_TypeDef *) EXTI_D1_BASE) -#define EXTI_D2 ((EXTI_Core_TypeDef *) EXTI_D2_BASE) -#define TIM1 ((TIM_TypeDef *) TIM1_BASE) -#define SPI1 ((SPI_TypeDef *) SPI1_BASE) -#define TIM8 ((TIM_TypeDef *) TIM8_BASE) -#define USART1 ((USART_TypeDef *) USART1_BASE) -#define TIM12 ((TIM_TypeDef *) TIM12_BASE) -#define TIM15 ((TIM_TypeDef *) TIM15_BASE) -#define TIM16 ((TIM_TypeDef *) TIM16_BASE) -#define TIM17 ((TIM_TypeDef *) TIM17_BASE) -#define SAI1 ((SAI_TypeDef *) SAI1_BASE) -#define SAI1_Block_A ((SAI_Block_TypeDef *)SAI1_Block_A_BASE) -#define SAI1_Block_B ((SAI_Block_TypeDef *)SAI1_Block_B_BASE) -#define SAI4 ((SAI_TypeDef *) SAI4_BASE) -#define SAI4_Block_A ((SAI_Block_TypeDef *)SAI4_Block_A_BASE) -#define SAI4_Block_B ((SAI_Block_TypeDef *)SAI4_Block_B_BASE) - -#define SPDIFRX ((SPDIFRX_TypeDef *) SPDIFRX_BASE) -#define DFSDM1_Channel0 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel0_BASE) -#define DFSDM1_Channel1 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel1_BASE) -#define DFSDM1_Channel2 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel2_BASE) -#define DFSDM1_Channel3 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel3_BASE) -#define DFSDM1_Channel4 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel4_BASE) -#define DFSDM1_Channel5 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel5_BASE) -#define DFSDM1_Channel6 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel6_BASE) -#define DFSDM1_Channel7 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel7_BASE) -#define DFSDM1_Filter0 ((DFSDM_Filter_TypeDef *) DFSDM1_Filter0_BASE) -#define DFSDM1_Filter1 ((DFSDM_Filter_TypeDef *) DFSDM1_Filter1_BASE) -#define DFSDM1_Filter2 ((DFSDM_Filter_TypeDef *) DFSDM1_Filter2_BASE) -#define DFSDM1_Filter3 ((DFSDM_Filter_TypeDef *) DFSDM1_Filter3_BASE) -#define DMA2D ((DMA2D_TypeDef *) DMA2D_BASE) -#define DCMI ((DCMI_TypeDef *) DCMI_BASE) -#define PSSI ((PSSI_TypeDef *) PSSI_BASE) -#define RCC ((RCC_TypeDef *) RCC_BASE) -#define FLASH ((FLASH_TypeDef *) FLASH_R_BASE) -#define CRC ((CRC_TypeDef *) CRC_BASE) - -#define GPIOA ((GPIO_TypeDef *) GPIOA_BASE) -#define GPIOB ((GPIO_TypeDef *) GPIOB_BASE) -#define GPIOC ((GPIO_TypeDef *) GPIOC_BASE) -#define GPIOD ((GPIO_TypeDef *) GPIOD_BASE) -#define GPIOE ((GPIO_TypeDef *) GPIOE_BASE) -#define GPIOF ((GPIO_TypeDef *) GPIOF_BASE) -#define GPIOG ((GPIO_TypeDef *) GPIOG_BASE) -#define GPIOH ((GPIO_TypeDef *) GPIOH_BASE) -#define GPIOJ ((GPIO_TypeDef *) GPIOJ_BASE) -#define GPIOK ((GPIO_TypeDef *) GPIOK_BASE) - -#define ADC1 ((ADC_TypeDef *) ADC1_BASE) -#define ADC2 ((ADC_TypeDef *) ADC2_BASE) -#define ADC3 ((ADC_TypeDef *) ADC3_BASE) -#define ADC3_COMMON ((ADC_Common_TypeDef *) ADC3_COMMON_BASE) -#define ADC12_COMMON ((ADC_Common_TypeDef *) ADC12_COMMON_BASE) - -#define CRYP ((CRYP_TypeDef *) CRYP_BASE) -#define HASH ((HASH_TypeDef *) HASH_BASE) -#define HASH_DIGEST ((HASH_DIGEST_TypeDef *) HASH_DIGEST_BASE) -#define RNG ((RNG_TypeDef *) RNG_BASE) -#define SDMMC2 ((SDMMC_TypeDef *) SDMMC2_BASE) -#define DLYB_SDMMC2 ((DLYB_TypeDef *) DLYB_SDMMC2_BASE) -#define FMAC ((FMAC_TypeDef *) FMAC_BASE) -#define CORDIC ((CORDIC_TypeDef *) CORDIC_BASE) - -#define BDMA ((BDMA_TypeDef *) BDMA_BASE) -#define BDMA_Channel0 ((BDMA_Channel_TypeDef *) BDMA_Channel0_BASE) -#define BDMA_Channel1 ((BDMA_Channel_TypeDef *) BDMA_Channel1_BASE) -#define BDMA_Channel2 ((BDMA_Channel_TypeDef *) BDMA_Channel2_BASE) -#define BDMA_Channel3 ((BDMA_Channel_TypeDef *) BDMA_Channel3_BASE) -#define BDMA_Channel4 ((BDMA_Channel_TypeDef *) BDMA_Channel4_BASE) -#define BDMA_Channel5 ((BDMA_Channel_TypeDef *) BDMA_Channel5_BASE) -#define BDMA_Channel6 ((BDMA_Channel_TypeDef *) BDMA_Channel6_BASE) -#define BDMA_Channel7 ((BDMA_Channel_TypeDef *) BDMA_Channel7_BASE) - -#define RAMECC1 ((RAMECC_TypeDef *)RAMECC1_BASE) -#define RAMECC1_Monitor1 ((RAMECC_MonitorTypeDef *)RAMECC1_Monitor1_BASE) -#define RAMECC1_Monitor2 ((RAMECC_MonitorTypeDef *)RAMECC1_Monitor2_BASE) -#define RAMECC1_Monitor3 ((RAMECC_MonitorTypeDef *)RAMECC1_Monitor3_BASE) -#define RAMECC1_Monitor4 ((RAMECC_MonitorTypeDef *)RAMECC1_Monitor4_BASE) -#define RAMECC1_Monitor5 ((RAMECC_MonitorTypeDef *)RAMECC1_Monitor5_BASE) -#define RAMECC1_Monitor6 ((RAMECC_MonitorTypeDef *)RAMECC1_Monitor6_BASE) - -#define RAMECC2 ((RAMECC_TypeDef *)RAMECC2_BASE) -#define RAMECC2_Monitor1 ((RAMECC_MonitorTypeDef *)RAMECC2_Monitor1_BASE) -#define RAMECC2_Monitor2 ((RAMECC_MonitorTypeDef *)RAMECC2_Monitor2_BASE) -#define RAMECC2_Monitor3 ((RAMECC_MonitorTypeDef *)RAMECC2_Monitor3_BASE) - -#define RAMECC3 ((RAMECC_TypeDef *)RAMECC3_BASE) -#define RAMECC3_Monitor1 ((RAMECC_MonitorTypeDef *)RAMECC3_Monitor1_BASE) -#define RAMECC3_Monitor2 ((RAMECC_MonitorTypeDef *)RAMECC3_Monitor2_BASE) - -#define DMAMUX2 ((DMAMUX_Channel_TypeDef *) DMAMUX2_BASE) -#define DMAMUX2_Channel0 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel0_BASE) -#define DMAMUX2_Channel1 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel1_BASE) -#define DMAMUX2_Channel2 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel2_BASE) -#define DMAMUX2_Channel3 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel3_BASE) -#define DMAMUX2_Channel4 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel4_BASE) -#define DMAMUX2_Channel5 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel5_BASE) -#define DMAMUX2_Channel6 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel6_BASE) -#define DMAMUX2_Channel7 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel7_BASE) - - -#define DMAMUX2_RequestGenerator0 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator0_BASE) -#define DMAMUX2_RequestGenerator1 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator1_BASE) -#define DMAMUX2_RequestGenerator2 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator2_BASE) -#define DMAMUX2_RequestGenerator3 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator3_BASE) -#define DMAMUX2_RequestGenerator4 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator4_BASE) -#define DMAMUX2_RequestGenerator5 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator5_BASE) -#define DMAMUX2_RequestGenerator6 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator6_BASE) -#define DMAMUX2_RequestGenerator7 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator7_BASE) - -#define DMAMUX2_ChannelStatus ((DMAMUX_ChannelStatus_TypeDef *) DMAMUX2_ChannelStatus_BASE) -#define DMAMUX2_RequestGenStatus ((DMAMUX_RequestGenStatus_TypeDef *) DMAMUX2_RequestGenStatus_BASE) - -#define DMA2 ((DMA_TypeDef *) DMA2_BASE) -#define DMA2_Stream0 ((DMA_Stream_TypeDef *) DMA2_Stream0_BASE) -#define DMA2_Stream1 ((DMA_Stream_TypeDef *) DMA2_Stream1_BASE) -#define DMA2_Stream2 ((DMA_Stream_TypeDef *) DMA2_Stream2_BASE) -#define DMA2_Stream3 ((DMA_Stream_TypeDef *) DMA2_Stream3_BASE) -#define DMA2_Stream4 ((DMA_Stream_TypeDef *) DMA2_Stream4_BASE) -#define DMA2_Stream5 ((DMA_Stream_TypeDef *) DMA2_Stream5_BASE) -#define DMA2_Stream6 ((DMA_Stream_TypeDef *) DMA2_Stream6_BASE) -#define DMA2_Stream7 ((DMA_Stream_TypeDef *) DMA2_Stream7_BASE) - -#define DMA1 ((DMA_TypeDef *) DMA1_BASE) -#define DMA1_Stream0 ((DMA_Stream_TypeDef *) DMA1_Stream0_BASE) -#define DMA1_Stream1 ((DMA_Stream_TypeDef *) DMA1_Stream1_BASE) -#define DMA1_Stream2 ((DMA_Stream_TypeDef *) DMA1_Stream2_BASE) -#define DMA1_Stream3 ((DMA_Stream_TypeDef *) DMA1_Stream3_BASE) -#define DMA1_Stream4 ((DMA_Stream_TypeDef *) DMA1_Stream4_BASE) -#define DMA1_Stream5 ((DMA_Stream_TypeDef *) DMA1_Stream5_BASE) -#define DMA1_Stream6 ((DMA_Stream_TypeDef *) DMA1_Stream6_BASE) -#define DMA1_Stream7 ((DMA_Stream_TypeDef *) DMA1_Stream7_BASE) - - -#define DMAMUX1 ((DMAMUX_Channel_TypeDef *) DMAMUX1_BASE) -#define DMAMUX1_Channel0 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel0_BASE) -#define DMAMUX1_Channel1 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel1_BASE) -#define DMAMUX1_Channel2 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel2_BASE) -#define DMAMUX1_Channel3 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel3_BASE) -#define DMAMUX1_Channel4 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel4_BASE) -#define DMAMUX1_Channel5 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel5_BASE) -#define DMAMUX1_Channel6 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel6_BASE) -#define DMAMUX1_Channel7 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel7_BASE) -#define DMAMUX1_Channel8 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel8_BASE) -#define DMAMUX1_Channel9 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel9_BASE) -#define DMAMUX1_Channel10 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel10_BASE) -#define DMAMUX1_Channel11 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel11_BASE) -#define DMAMUX1_Channel12 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel12_BASE) -#define DMAMUX1_Channel13 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel13_BASE) -#define DMAMUX1_Channel14 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel14_BASE) -#define DMAMUX1_Channel15 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel15_BASE) - -#define DMAMUX1_RequestGenerator0 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator0_BASE) -#define DMAMUX1_RequestGenerator1 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator1_BASE) -#define DMAMUX1_RequestGenerator2 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator2_BASE) -#define DMAMUX1_RequestGenerator3 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator3_BASE) -#define DMAMUX1_RequestGenerator4 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator4_BASE) -#define DMAMUX1_RequestGenerator5 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator5_BASE) -#define DMAMUX1_RequestGenerator6 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator6_BASE) -#define DMAMUX1_RequestGenerator7 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator7_BASE) - -#define DMAMUX1_ChannelStatus ((DMAMUX_ChannelStatus_TypeDef *) DMAMUX1_ChannelStatus_BASE) -#define DMAMUX1_RequestGenStatus ((DMAMUX_RequestGenStatus_TypeDef *) DMAMUX1_RequestGenStatus_BASE) - - -#define FMC_Bank1_R ((FMC_Bank1_TypeDef *) FMC_Bank1_R_BASE) -#define FMC_Bank1E_R ((FMC_Bank1E_TypeDef *) FMC_Bank1E_R_BASE) -#define FMC_Bank2_R ((FMC_Bank2_TypeDef *) FMC_Bank2_R_BASE) -#define FMC_Bank3_R ((FMC_Bank3_TypeDef *) FMC_Bank3_R_BASE) -#define FMC_Bank5_6_R ((FMC_Bank5_6_TypeDef *) FMC_Bank5_6_R_BASE) - -#define OCTOSPI1 ((OCTOSPI_TypeDef *) OCTOSPI1_R_BASE) -#define DLYB_OCTOSPI1 ((DLYB_TypeDef *) DLYB_OCTOSPI1_BASE) -#define OCTOSPI2 ((OCTOSPI_TypeDef *) OCTOSPI2_R_BASE) -#define DLYB_OCTOSPI2 ((DLYB_TypeDef *) DLYB_OCTOSPI2_BASE) -#define OCTOSPIM ((OCTOSPIM_TypeDef *) OCTOSPIM_BASE) - -#define OTFDEC1 ((OTFDEC_TypeDef *) OTFDEC1_BASE) -#define OTFDEC1_REGION1 ((OTFDEC_Region_TypeDef *) OTFDEC1_REGION1_BASE) -#define OTFDEC1_REGION2 ((OTFDEC_Region_TypeDef *) OTFDEC1_REGION2_BASE) -#define OTFDEC1_REGION3 ((OTFDEC_Region_TypeDef *) OTFDEC1_REGION3_BASE) -#define OTFDEC1_REGION4 ((OTFDEC_Region_TypeDef *) OTFDEC1_REGION4_BASE) - -#define OTFDEC2 ((OTFDEC_TypeDef *) OTFDEC2_BASE) -#define OTFDEC2_REGION1 ((OTFDEC_Region_TypeDef *) OTFDEC2_REGION1_BASE) -#define OTFDEC2_REGION2 ((OTFDEC_Region_TypeDef *) OTFDEC2_REGION2_BASE) -#define OTFDEC2_REGION3 ((OTFDEC_Region_TypeDef *) OTFDEC2_REGION3_BASE) -#define OTFDEC2_REGION4 ((OTFDEC_Region_TypeDef *) OTFDEC2_REGION4_BASE) - -#define SDMMC1 ((SDMMC_TypeDef *) SDMMC1_BASE) -#define DLYB_SDMMC1 ((DLYB_TypeDef *) DLYB_SDMMC1_BASE) - -#define DBGMCU ((DBGMCU_TypeDef *) DBGMCU_BASE) - -#define HSEM ((HSEM_TypeDef *) HSEM_BASE) -#define HSEM_COMMON ((HSEM_Common_TypeDef *) (HSEM_BASE + 0x100UL)) - -#define LTDC ((LTDC_TypeDef *)LTDC_BASE) -#define LTDC_Layer1 ((LTDC_Layer_TypeDef *)LTDC_Layer1_BASE) -#define LTDC_Layer2 ((LTDC_Layer_TypeDef *)LTDC_Layer2_BASE) - -#define MDIOS ((MDIOS_TypeDef *) MDIOS_BASE) - -#define ETH ((ETH_TypeDef *)ETH_BASE) -#define MDMA ((MDMA_TypeDef *)MDMA_BASE) -#define MDMA_Channel0 ((MDMA_Channel_TypeDef *)MDMA_Channel0_BASE) -#define MDMA_Channel1 ((MDMA_Channel_TypeDef *)MDMA_Channel1_BASE) -#define MDMA_Channel2 ((MDMA_Channel_TypeDef *)MDMA_Channel2_BASE) -#define MDMA_Channel3 ((MDMA_Channel_TypeDef *)MDMA_Channel3_BASE) -#define MDMA_Channel4 ((MDMA_Channel_TypeDef *)MDMA_Channel4_BASE) -#define MDMA_Channel5 ((MDMA_Channel_TypeDef *)MDMA_Channel5_BASE) -#define MDMA_Channel6 ((MDMA_Channel_TypeDef *)MDMA_Channel6_BASE) -#define MDMA_Channel7 ((MDMA_Channel_TypeDef *)MDMA_Channel7_BASE) -#define MDMA_Channel8 ((MDMA_Channel_TypeDef *)MDMA_Channel8_BASE) -#define MDMA_Channel9 ((MDMA_Channel_TypeDef *)MDMA_Channel9_BASE) -#define MDMA_Channel10 ((MDMA_Channel_TypeDef *)MDMA_Channel10_BASE) -#define MDMA_Channel11 ((MDMA_Channel_TypeDef *)MDMA_Channel11_BASE) -#define MDMA_Channel12 ((MDMA_Channel_TypeDef *)MDMA_Channel12_BASE) -#define MDMA_Channel13 ((MDMA_Channel_TypeDef *)MDMA_Channel13_BASE) -#define MDMA_Channel14 ((MDMA_Channel_TypeDef *)MDMA_Channel14_BASE) -#define MDMA_Channel15 ((MDMA_Channel_TypeDef *)MDMA_Channel15_BASE) - - -#define USB1_OTG_HS ((USB_OTG_GlobalTypeDef *) USB1_OTG_HS_PERIPH_BASE) - -/* Legacy defines */ -#define USB_OTG_HS USB1_OTG_HS -#define USB_OTG_HS_PERIPH_BASE USB1_OTG_HS_PERIPH_BASE - -#define GPV ((GPV_TypeDef *) GPV_BASE) - -/** - * @} - */ - -/** @addtogroup Exported_constants - * @{ - */ - - /** @addtogroup Peripheral_Registers_Bits_Definition - * @{ - */ - -/******************************************************************************/ -/* Peripheral Registers_Bits_Definition */ -/******************************************************************************/ - -/******************************************************************************/ -/* */ -/* Analog to Digital Converter */ -/* */ -/******************************************************************************/ -/******************************* ADC VERSION ********************************/ -#define ADC_VER_V5_V90 -/******************** Bit definition for ADC_ISR register ********************/ -#define ADC_ISR_ADRDY_Pos (0U) -#define ADC_ISR_ADRDY_Msk (0x1UL << ADC_ISR_ADRDY_Pos) /*!< 0x00000001 */ -#define ADC_ISR_ADRDY ADC_ISR_ADRDY_Msk /*!< ADC Ready (ADRDY) flag */ -#define ADC_ISR_EOSMP_Pos (1U) -#define ADC_ISR_EOSMP_Msk (0x1UL << ADC_ISR_EOSMP_Pos) /*!< 0x00000002 */ -#define ADC_ISR_EOSMP ADC_ISR_EOSMP_Msk /*!< ADC End of Sampling flag */ -#define ADC_ISR_EOC_Pos (2U) -#define ADC_ISR_EOC_Msk (0x1UL << ADC_ISR_EOC_Pos) /*!< 0x00000004 */ -#define ADC_ISR_EOC ADC_ISR_EOC_Msk /*!< ADC End of Regular Conversion flag */ -#define ADC_ISR_EOS_Pos (3U) -#define ADC_ISR_EOS_Msk (0x1UL << ADC_ISR_EOS_Pos) /*!< 0x00000008 */ -#define ADC_ISR_EOS ADC_ISR_EOS_Msk /*!< ADC End of Regular sequence of Conversions flag */ -#define ADC_ISR_OVR_Pos (4U) -#define ADC_ISR_OVR_Msk (0x1UL << ADC_ISR_OVR_Pos) /*!< 0x00000010 */ -#define ADC_ISR_OVR ADC_ISR_OVR_Msk /*!< ADC overrun flag */ -#define ADC_ISR_JEOC_Pos (5U) -#define ADC_ISR_JEOC_Msk (0x1UL << ADC_ISR_JEOC_Pos) /*!< 0x00000020 */ -#define ADC_ISR_JEOC ADC_ISR_JEOC_Msk /*!< ADC End of Injected Conversion flag */ -#define ADC_ISR_JEOS_Pos (6U) -#define ADC_ISR_JEOS_Msk (0x1UL << ADC_ISR_JEOS_Pos) /*!< 0x00000040 */ -#define ADC_ISR_JEOS ADC_ISR_JEOS_Msk /*!< ADC End of Injected sequence of Conversions flag */ -#define ADC_ISR_AWD1_Pos (7U) -#define ADC_ISR_AWD1_Msk (0x1UL << ADC_ISR_AWD1_Pos) /*!< 0x00000080 */ -#define ADC_ISR_AWD1 ADC_ISR_AWD1_Msk /*!< ADC Analog watchdog 1 flag */ -#define ADC_ISR_AWD2_Pos (8U) -#define ADC_ISR_AWD2_Msk (0x1UL << ADC_ISR_AWD2_Pos) /*!< 0x00000100 */ -#define ADC_ISR_AWD2 ADC_ISR_AWD2_Msk /*!< ADC Analog watchdog 2 flag */ -#define ADC_ISR_AWD3_Pos (9U) -#define ADC_ISR_AWD3_Msk (0x1UL << ADC_ISR_AWD3_Pos) /*!< 0x00000200 */ -#define ADC_ISR_AWD3 ADC_ISR_AWD3_Msk /*!< ADC Analog watchdog 3 flag */ -#define ADC_ISR_JQOVF_Pos (10U) -#define ADC_ISR_JQOVF_Msk (0x1UL << ADC_ISR_JQOVF_Pos) /*!< 0x00000400 */ -#define ADC_ISR_JQOVF ADC_ISR_JQOVF_Msk /*!< ADC Injected Context Queue Overflow flag */ -#define ADC_ISR_LDORDY_Pos (12U) -#define ADC_ISR_LDORDY_Msk (0x1UL << ADC_ISR_LDORDY_Pos) /*!< 0x00001000 */ -#define ADC_ISR_LDORDY ADC_ISR_LDORDY_Msk /*!< ADC LDO Ready (LDORDY) flag */ - -/******************** Bit definition for ADC_IER register ********************/ -#define ADC_IER_ADRDYIE_Pos (0U) -#define ADC_IER_ADRDYIE_Msk (0x1UL << ADC_IER_ADRDYIE_Pos) /*!< 0x00000001 */ -#define ADC_IER_ADRDYIE ADC_IER_ADRDYIE_Msk /*!< ADC Ready (ADRDY) interrupt source */ -#define ADC_IER_EOSMPIE_Pos (1U) -#define ADC_IER_EOSMPIE_Msk (0x1UL << ADC_IER_EOSMPIE_Pos) /*!< 0x00000002 */ -#define ADC_IER_EOSMPIE ADC_IER_EOSMPIE_Msk /*!< ADC End of Sampling interrupt source */ -#define ADC_IER_EOCIE_Pos (2U) -#define ADC_IER_EOCIE_Msk (0x1UL << ADC_IER_EOCIE_Pos) /*!< 0x00000004 */ -#define ADC_IER_EOCIE ADC_IER_EOCIE_Msk /*!< ADC End of Regular Conversion interrupt source */ -#define ADC_IER_EOSIE_Pos (3U) -#define ADC_IER_EOSIE_Msk (0x1UL << ADC_IER_EOSIE_Pos) /*!< 0x00000008 */ -#define ADC_IER_EOSIE ADC_IER_EOSIE_Msk /*!< ADC End of Regular sequence of Conversions interrupt source */ -#define ADC_IER_OVRIE_Pos (4U) -#define ADC_IER_OVRIE_Msk (0x1UL << ADC_IER_OVRIE_Pos) /*!< 0x00000010 */ -#define ADC_IER_OVRIE ADC_IER_OVRIE_Msk /*!< ADC overrun interrupt source */ -#define ADC_IER_JEOCIE_Pos (5U) -#define ADC_IER_JEOCIE_Msk (0x1UL << ADC_IER_JEOCIE_Pos) /*!< 0x00000020 */ -#define ADC_IER_JEOCIE ADC_IER_JEOCIE_Msk /*!< ADC End of Injected Conversion interrupt source */ -#define ADC_IER_JEOSIE_Pos (6U) -#define ADC_IER_JEOSIE_Msk (0x1UL << ADC_IER_JEOSIE_Pos) /*!< 0x00000040 */ -#define ADC_IER_JEOSIE ADC_IER_JEOSIE_Msk /*!< ADC End of Injected sequence of Conversions interrupt source */ -#define ADC_IER_AWD1IE_Pos (7U) -#define ADC_IER_AWD1IE_Msk (0x1UL << ADC_IER_AWD1IE_Pos) /*!< 0x00000080 */ -#define ADC_IER_AWD1IE ADC_IER_AWD1IE_Msk /*!< ADC Analog watchdog 1 interrupt source */ -#define ADC_IER_AWD2IE_Pos (8U) -#define ADC_IER_AWD2IE_Msk (0x1UL << ADC_IER_AWD2IE_Pos) /*!< 0x00000100 */ -#define ADC_IER_AWD2IE ADC_IER_AWD2IE_Msk /*!< ADC Analog watchdog 2 interrupt source */ -#define ADC_IER_AWD3IE_Pos (9U) -#define ADC_IER_AWD3IE_Msk (0x1UL << ADC_IER_AWD3IE_Pos) /*!< 0x00000200 */ -#define ADC_IER_AWD3IE ADC_IER_AWD3IE_Msk /*!< ADC Analog watchdog 3 interrupt source */ -#define ADC_IER_JQOVFIE_Pos (10U) -#define ADC_IER_JQOVFIE_Msk (0x1UL << ADC_IER_JQOVFIE_Pos) /*!< 0x00000400 */ -#define ADC_IER_JQOVFIE ADC_IER_JQOVFIE_Msk /*!< ADC Injected Context Queue Overflow interrupt source */ - -/******************** Bit definition for ADC_CR register ********************/ -#define ADC_CR_ADEN_Pos (0U) -#define ADC_CR_ADEN_Msk (0x1UL << ADC_CR_ADEN_Pos) /*!< 0x00000001 */ -#define ADC_CR_ADEN ADC_CR_ADEN_Msk /*!< ADC Enable control */ -#define ADC_CR_ADDIS_Pos (1U) -#define ADC_CR_ADDIS_Msk (0x1UL << ADC_CR_ADDIS_Pos) /*!< 0x00000002 */ -#define ADC_CR_ADDIS ADC_CR_ADDIS_Msk /*!< ADC Disable command */ -#define ADC_CR_ADSTART_Pos (2U) -#define ADC_CR_ADSTART_Msk (0x1UL << ADC_CR_ADSTART_Pos) /*!< 0x00000004 */ -#define ADC_CR_ADSTART ADC_CR_ADSTART_Msk /*!< ADC Start of Regular conversion */ -#define ADC_CR_JADSTART_Pos (3U) -#define ADC_CR_JADSTART_Msk (0x1UL << ADC_CR_JADSTART_Pos) /*!< 0x00000008 */ -#define ADC_CR_JADSTART ADC_CR_JADSTART_Msk /*!< ADC Start of injected conversion */ -#define ADC_CR_ADSTP_Pos (4U) -#define ADC_CR_ADSTP_Msk (0x1UL << ADC_CR_ADSTP_Pos) /*!< 0x00000010 */ -#define ADC_CR_ADSTP ADC_CR_ADSTP_Msk /*!< ADC Stop of Regular conversion */ -#define ADC_CR_JADSTP_Pos (5U) -#define ADC_CR_JADSTP_Msk (0x1UL << ADC_CR_JADSTP_Pos) /*!< 0x00000020 */ -#define ADC_CR_JADSTP ADC_CR_JADSTP_Msk /*!< ADC Stop of injected conversion */ -#define ADC_CR_BOOST_Pos (8U) -#define ADC_CR_BOOST_Msk (0x3UL << ADC_CR_BOOST_Pos) /*!< 0x00000300 */ -#define ADC_CR_BOOST ADC_CR_BOOST_Msk /*!< ADC Boost Mode configuration */ -#define ADC_CR_BOOST_0 (0x1UL << ADC_CR_BOOST_Pos) /*!< 0x00000100 */ -#define ADC_CR_BOOST_1 (0x2UL << ADC_CR_BOOST_Pos) /*!< 0x00000200 */ -#define ADC_CR_ADCALLIN_Pos (16U) -#define ADC_CR_ADCALLIN_Msk (0x1UL << ADC_CR_ADCALLIN_Pos) /*!< 0x00010000 */ -#define ADC_CR_ADCALLIN ADC_CR_ADCALLIN_Msk /*!< ADC Linearity calibration */ -#define ADC_CR_LINCALRDYW1_Pos (22U) -#define ADC_CR_LINCALRDYW1_Msk (0x1UL << ADC_CR_LINCALRDYW1_Pos) /*!< 0x00400000 */ -#define ADC_CR_LINCALRDYW1 ADC_CR_LINCALRDYW1_Msk /*!< ADC Linearity calibration ready Word 1 */ -#define ADC_CR_LINCALRDYW2_Pos (23U) -#define ADC_CR_LINCALRDYW2_Msk (0x1UL << ADC_CR_LINCALRDYW2_Pos) /*!< 0x00800000 */ -#define ADC_CR_LINCALRDYW2 ADC_CR_LINCALRDYW2_Msk /*!< ADC Linearity calibration ready Word 2 */ -#define ADC_CR_LINCALRDYW3_Pos (24U) -#define ADC_CR_LINCALRDYW3_Msk (0x1UL << ADC_CR_LINCALRDYW3_Pos) /*!< 0x01000000 */ -#define ADC_CR_LINCALRDYW3 ADC_CR_LINCALRDYW3_Msk /*!< ADC Linearity calibration ready Word 3 */ -#define ADC_CR_LINCALRDYW4_Pos (25U) -#define ADC_CR_LINCALRDYW4_Msk (0x1UL << ADC_CR_LINCALRDYW4_Pos) /*!< 0x02000000 */ -#define ADC_CR_LINCALRDYW4 ADC_CR_LINCALRDYW4_Msk /*!< ADC Linearity calibration ready Word 4 */ -#define ADC_CR_LINCALRDYW5_Pos (26U) -#define ADC_CR_LINCALRDYW5_Msk (0x1UL << ADC_CR_LINCALRDYW5_Pos) /*!< 0x04000000 */ -#define ADC_CR_LINCALRDYW5 ADC_CR_LINCALRDYW5_Msk /*!< ADC Linearity calibration ready Word 5 */ -#define ADC_CR_LINCALRDYW6_Pos (27U) -#define ADC_CR_LINCALRDYW6_Msk (0x1UL << ADC_CR_LINCALRDYW6_Pos) /*!< 0x08000000 */ -#define ADC_CR_LINCALRDYW6 ADC_CR_LINCALRDYW6_Msk /*!< ADC Linearity calibration ready Word 6 */ -#define ADC_CR_ADVREGEN_Pos (28U) -#define ADC_CR_ADVREGEN_Msk (0x1UL << ADC_CR_ADVREGEN_Pos) /*!< 0x10000000 */ -#define ADC_CR_ADVREGEN ADC_CR_ADVREGEN_Msk /*!< ADC Voltage regulator Enable */ -#define ADC_CR_DEEPPWD_Pos (29U) -#define ADC_CR_DEEPPWD_Msk (0x1UL << ADC_CR_DEEPPWD_Pos) /*!< 0x20000000 */ -#define ADC_CR_DEEPPWD ADC_CR_DEEPPWD_Msk /*!< ADC Deep power down Enable */ -#define ADC_CR_ADCALDIF_Pos (30U) -#define ADC_CR_ADCALDIF_Msk (0x1UL << ADC_CR_ADCALDIF_Pos) /*!< 0x40000000 */ -#define ADC_CR_ADCALDIF ADC_CR_ADCALDIF_Msk /*!< ADC Differential Mode for calibration */ -#define ADC_CR_ADCAL_Pos (31U) -#define ADC_CR_ADCAL_Msk (0x1UL << ADC_CR_ADCAL_Pos) /*!< 0x80000000 */ -#define ADC_CR_ADCAL ADC_CR_ADCAL_Msk /*!< ADC Calibration */ - -/******************** Bit definition for ADC_CFGR register ********************/ -#define ADC_CFGR_DMNGT_Pos (0U) -#define ADC_CFGR_DMNGT_Msk (0x3UL << ADC_CFGR_DMNGT_Pos) /*!< 0x00000003 */ -#define ADC_CFGR_DMNGT ADC_CFGR_DMNGT_Msk /*!< ADC Data Management configuration */ -#define ADC_CFGR_DMNGT_0 (0x1UL << ADC_CFGR_DMNGT_Pos) /*!< 0x00000001 */ -#define ADC_CFGR_DMNGT_1 (0x2UL << ADC_CFGR_DMNGT_Pos) /*!< 0x00000002 */ - -#define ADC_CFGR_RES_Pos (2U) -#define ADC_CFGR_RES_Msk (0x7UL << ADC_CFGR_RES_Pos) /*!< 0x0000001C */ -#define ADC_CFGR_RES ADC_CFGR_RES_Msk /*!< ADC Data resolution */ -#define ADC_CFGR_RES_0 (0x1UL << ADC_CFGR_RES_Pos) /*!< 0x00000004 */ -#define ADC_CFGR_RES_1 (0x2UL << ADC_CFGR_RES_Pos) /*!< 0x00000008 */ -#define ADC_CFGR_RES_2 (0x4UL << ADC_CFGR_RES_Pos) /*!< 0x00000010 */ - -#define ADC_CFGR_EXTSEL_Pos (5U) -#define ADC_CFGR_EXTSEL_Msk (0x1FUL << ADC_CFGR_EXTSEL_Pos) /*!< 0x000003E0 */ -#define ADC_CFGR_EXTSEL ADC_CFGR_EXTSEL_Msk /*!< ADC External trigger selection for regular group */ -#define ADC_CFGR_EXTSEL_0 (0x01UL << ADC_CFGR_EXTSEL_Pos) /*!< 0x00000020 */ -#define ADC_CFGR_EXTSEL_1 (0x02UL << ADC_CFGR_EXTSEL_Pos) /*!< 0x00000040 */ -#define ADC_CFGR_EXTSEL_2 (0x04UL << ADC_CFGR_EXTSEL_Pos) /*!< 0x00000080 */ -#define ADC_CFGR_EXTSEL_3 (0x08UL << ADC_CFGR_EXTSEL_Pos) /*!< 0x00000100 */ -#define ADC_CFGR_EXTSEL_4 (0x10UL << ADC_CFGR_EXTSEL_Pos) /*!< 0x00000200 */ - -#define ADC_CFGR_EXTEN_Pos (10U) -#define ADC_CFGR_EXTEN_Msk (0x3UL << ADC_CFGR_EXTEN_Pos) /*!< 0x00000C00 */ -#define ADC_CFGR_EXTEN ADC_CFGR_EXTEN_Msk /*!< ADC External trigger enable and polarity selection for regular channels */ -#define ADC_CFGR_EXTEN_0 (0x1UL << ADC_CFGR_EXTEN_Pos) /*!< 0x00000400 */ -#define ADC_CFGR_EXTEN_1 (0x2UL << ADC_CFGR_EXTEN_Pos) /*!< 0x00000800 */ - -#define ADC_CFGR_OVRMOD_Pos (12U) -#define ADC_CFGR_OVRMOD_Msk (0x1UL << ADC_CFGR_OVRMOD_Pos) /*!< 0x00001000 */ -#define ADC_CFGR_OVRMOD ADC_CFGR_OVRMOD_Msk /*!< ADC overrun mode */ -#define ADC_CFGR_CONT_Pos (13U) -#define ADC_CFGR_CONT_Msk (0x1UL << ADC_CFGR_CONT_Pos) /*!< 0x00002000 */ -#define ADC_CFGR_CONT ADC_CFGR_CONT_Msk /*!< ADC Single/continuous conversion mode for regular conversion */ -#define ADC_CFGR_AUTDLY_Pos (14U) -#define ADC_CFGR_AUTDLY_Msk (0x1UL << ADC_CFGR_AUTDLY_Pos) /*!< 0x00004000 */ -#define ADC_CFGR_AUTDLY ADC_CFGR_AUTDLY_Msk /*!< ADC Delayed conversion mode */ - -#define ADC_CFGR_DISCEN_Pos (16U) -#define ADC_CFGR_DISCEN_Msk (0x1UL << ADC_CFGR_DISCEN_Pos) /*!< 0x00010000 */ -#define ADC_CFGR_DISCEN ADC_CFGR_DISCEN_Msk /*!< ADC Discontinuous mode for regular channels */ - -#define ADC_CFGR_DISCNUM_Pos (17U) -#define ADC_CFGR_DISCNUM_Msk (0x7UL << ADC_CFGR_DISCNUM_Pos) /*!< 0x000E0000 */ -#define ADC_CFGR_DISCNUM ADC_CFGR_DISCNUM_Msk /*!< ADC Discontinuous mode channel count */ -#define ADC_CFGR_DISCNUM_0 (0x1UL << ADC_CFGR_DISCNUM_Pos) /*!< 0x00020000 */ -#define ADC_CFGR_DISCNUM_1 (0x2UL << ADC_CFGR_DISCNUM_Pos) /*!< 0x00040000 */ -#define ADC_CFGR_DISCNUM_2 (0x4UL << ADC_CFGR_DISCNUM_Pos) /*!< 0x00080000 */ - -#define ADC_CFGR_JDISCEN_Pos (20U) -#define ADC_CFGR_JDISCEN_Msk (0x1UL << ADC_CFGR_JDISCEN_Pos) /*!< 0x00100000 */ -#define ADC_CFGR_JDISCEN ADC_CFGR_JDISCEN_Msk /*!< ADC Discontinuous mode on injected channels */ -#define ADC_CFGR_JQM_Pos (21U) -#define ADC_CFGR_JQM_Msk (0x1UL << ADC_CFGR_JQM_Pos) /*!< 0x00200000 */ -#define ADC_CFGR_JQM ADC_CFGR_JQM_Msk /*!< ADC JSQR Queue mode */ -#define ADC_CFGR_AWD1SGL_Pos (22U) -#define ADC_CFGR_AWD1SGL_Msk (0x1UL << ADC_CFGR_AWD1SGL_Pos) /*!< 0x00400000 */ -#define ADC_CFGR_AWD1SGL ADC_CFGR_AWD1SGL_Msk /*!< Enable the watchdog 1 on a single channel or on all channels */ -#define ADC_CFGR_AWD1EN_Pos (23U) -#define ADC_CFGR_AWD1EN_Msk (0x1UL << ADC_CFGR_AWD1EN_Pos) /*!< 0x00800000 */ -#define ADC_CFGR_AWD1EN ADC_CFGR_AWD1EN_Msk /*!< ADC Analog watchdog 1 enable on regular Channels */ -#define ADC_CFGR_JAWD1EN_Pos (24U) -#define ADC_CFGR_JAWD1EN_Msk (0x1UL << ADC_CFGR_JAWD1EN_Pos) /*!< 0x01000000 */ -#define ADC_CFGR_JAWD1EN ADC_CFGR_JAWD1EN_Msk /*!< ADC Analog watchdog 1 enable on injected Channels */ -#define ADC_CFGR_JAUTO_Pos (25U) -#define ADC_CFGR_JAUTO_Msk (0x1UL << ADC_CFGR_JAUTO_Pos) /*!< 0x02000000 */ -#define ADC_CFGR_JAUTO ADC_CFGR_JAUTO_Msk /*!< ADC Automatic injected group conversion */ - -#define ADC_CFGR_AWD1CH_Pos (26U) -#define ADC_CFGR_AWD1CH_Msk (0x1FUL << ADC_CFGR_AWD1CH_Pos) /*!< 0x7C000000 */ -#define ADC_CFGR_AWD1CH ADC_CFGR_AWD1CH_Msk /*!< ADC Analog watchdog 1 Channel selection */ -#define ADC_CFGR_AWD1CH_0 (0x01UL << ADC_CFGR_AWD1CH_Pos) /*!< 0x04000000 */ -#define ADC_CFGR_AWD1CH_1 (0x02UL << ADC_CFGR_AWD1CH_Pos) /*!< 0x08000000 */ -#define ADC_CFGR_AWD1CH_2 (0x04UL << ADC_CFGR_AWD1CH_Pos) /*!< 0x10000000 */ -#define ADC_CFGR_AWD1CH_3 (0x08UL << ADC_CFGR_AWD1CH_Pos) /*!< 0x20000000 */ -#define ADC_CFGR_AWD1CH_4 (0x10UL << ADC_CFGR_AWD1CH_Pos) /*!< 0x40000000 */ - -#define ADC_CFGR_JQDIS_Pos (31U) -#define ADC_CFGR_JQDIS_Msk (0x1UL << ADC_CFGR_JQDIS_Pos) /*!< 0x80000000 */ -#define ADC_CFGR_JQDIS ADC_CFGR_JQDIS_Msk /*!< ADC Injected queue disable */ - -#define ADC3_CFGR_DMAEN_Pos (0U) -#define ADC3_CFGR_DMAEN_Msk (0x1UL << ADC3_CFGR_DMAEN_Pos) /*!< 0x00000001 */ -#define ADC3_CFGR_DMAEN ADC3_CFGR_DMAEN_Msk /*!< ADC DMA transfer enable */ -#define ADC3_CFGR_DMACFG_Pos (1U) -#define ADC3_CFGR_DMACFG_Msk (0x1UL << ADC3_CFGR_DMACFG_Pos) /*!< 0x00000002 */ -#define ADC3_CFGR_DMACFG ADC3_CFGR_DMACFG_Msk /*!< ADC DMA transfer configuration */ - -#define ADC3_CFGR_RES_Pos (3U) -#define ADC3_CFGR_RES_Msk (0x3UL << ADC3_CFGR_RES_Pos) /*!< 0x00000018 */ -#define ADC3_CFGR_RES ADC3_CFGR_RES_Msk /*!< ADC data resolution */ -#define ADC3_CFGR_RES_0 (0x1UL << ADC3_CFGR_RES_Pos) /*!< 0x00000008 */ -#define ADC3_CFGR_RES_1 (0x2UL << ADC3_CFGR_RES_Pos) /*!< 0x00000010 */ - -#define ADC3_CFGR_ALIGN_Pos (15U) -#define ADC3_CFGR_ALIGN_Msk (0x1UL << ADC3_CFGR_ALIGN_Pos) /*!< 0x00008000 */ -#define ADC3_CFGR_ALIGN ADC3_CFGR_ALIGN_Msk /*!< ADC data alignment */ -/******************** Bit definition for ADC_CFGR2 register ********************/ -#define ADC_CFGR2_ROVSE_Pos (0U) -#define ADC_CFGR2_ROVSE_Msk (0x1UL << ADC_CFGR2_ROVSE_Pos) /*!< 0x00000001 */ -#define ADC_CFGR2_ROVSE ADC_CFGR2_ROVSE_Msk /*!< ADC Regular group oversampler enable */ -#define ADC_CFGR2_JOVSE_Pos (1U) -#define ADC_CFGR2_JOVSE_Msk (0x1UL << ADC_CFGR2_JOVSE_Pos) /*!< 0x00000002 */ -#define ADC_CFGR2_JOVSE ADC_CFGR2_JOVSE_Msk /*!< ADC Injected group oversampler enable */ - -#define ADC_CFGR2_OVSS_Pos (5U) -#define ADC_CFGR2_OVSS_Msk (0xFUL << ADC_CFGR2_OVSS_Pos) /*!< 0x000001E0 */ -#define ADC_CFGR2_OVSS ADC_CFGR2_OVSS_Msk /*!< ADC Regular Oversampling shift */ -#define ADC_CFGR2_OVSS_0 (0x1UL << ADC_CFGR2_OVSS_Pos) /*!< 0x00000020 */ -#define ADC_CFGR2_OVSS_1 (0x2UL << ADC_CFGR2_OVSS_Pos) /*!< 0x00000040 */ -#define ADC_CFGR2_OVSS_2 (0x4UL << ADC_CFGR2_OVSS_Pos) /*!< 0x00000080 */ -#define ADC_CFGR2_OVSS_3 (0x8UL << ADC_CFGR2_OVSS_Pos) /*!< 0x00000100 */ - -#define ADC_CFGR2_TROVS_Pos (9U) -#define ADC_CFGR2_TROVS_Msk (0x1UL << ADC_CFGR2_TROVS_Pos) /*!< 0x00000200 */ -#define ADC_CFGR2_TROVS ADC_CFGR2_TROVS_Msk /*!< ADC Triggered regular Oversampling */ -#define ADC_CFGR2_ROVSM_Pos (10U) -#define ADC_CFGR2_ROVSM_Msk (0x1UL << ADC_CFGR2_ROVSM_Pos) /*!< 0x00000400 */ -#define ADC_CFGR2_ROVSM ADC_CFGR2_ROVSM_Msk /*!< ADC Regular oversampling mode */ - -#define ADC_CFGR2_RSHIFT1_Pos (11U) -#define ADC_CFGR2_RSHIFT1_Msk (0x1UL << ADC_CFGR2_RSHIFT1_Pos) /*!< 0x00000800 */ -#define ADC_CFGR2_RSHIFT1 ADC_CFGR2_RSHIFT1_Msk /*!< ADC Right-shift data after Offset 1 correction */ -#define ADC_CFGR2_RSHIFT2_Pos (12U) -#define ADC_CFGR2_RSHIFT2_Msk (0x1UL << ADC_CFGR2_RSHIFT2_Pos) /*!< 0x00001000 */ -#define ADC_CFGR2_RSHIFT2 ADC_CFGR2_RSHIFT2_Msk /*!< ADC Right-shift data after Offset 2 correction */ -#define ADC_CFGR2_RSHIFT3_Pos (13U) -#define ADC_CFGR2_RSHIFT3_Msk (0x1UL << ADC_CFGR2_RSHIFT3_Pos) /*!< 0x00002000 */ -#define ADC_CFGR2_RSHIFT3 ADC_CFGR2_RSHIFT3_Msk /*!< ADC Right-shift data after Offset 3 correction */ -#define ADC_CFGR2_RSHIFT4_Pos (14U) -#define ADC_CFGR2_RSHIFT4_Msk (0x1UL << ADC_CFGR2_RSHIFT4_Pos) /*!< 0x00004000 */ -#define ADC_CFGR2_RSHIFT4 ADC_CFGR2_RSHIFT4_Msk /*!< ADC Right-shift data after Offset 4 correction */ - -#define ADC_CFGR2_OVSR_Pos (16U) -#define ADC_CFGR2_OVSR_Msk (0x3FFUL << ADC_CFGR2_OVSR_Pos) /*!< 0x03FF0000 */ -#define ADC_CFGR2_OVSR ADC_CFGR2_OVSR_Msk /*!< ADC oversampling Ratio */ -#define ADC_CFGR2_OVSR_0 (0x001UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00010000 */ -#define ADC_CFGR2_OVSR_1 (0x002UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00020000 */ -#define ADC_CFGR2_OVSR_2 (0x004UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00040000 */ -#define ADC_CFGR2_OVSR_3 (0x008UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00080000 */ -#define ADC_CFGR2_OVSR_4 (0x010UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00100000 */ -#define ADC_CFGR2_OVSR_5 (0x020UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00200000 */ -#define ADC_CFGR2_OVSR_6 (0x040UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00400000 */ -#define ADC_CFGR2_OVSR_7 (0x080UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00800000 */ -#define ADC_CFGR2_OVSR_8 (0x100UL << ADC_CFGR2_OVSR_Pos) /*!< 0x01000000 */ -#define ADC_CFGR2_OVSR_9 (0x200UL << ADC_CFGR2_OVSR_Pos) /*!< 0x02000000 */ - -#define ADC_CFGR2_LSHIFT_Pos (28U) -#define ADC_CFGR2_LSHIFT_Msk (0xFUL << ADC_CFGR2_LSHIFT_Pos) /*!< 0xF0000000 */ -#define ADC_CFGR2_LSHIFT ADC_CFGR2_LSHIFT_Msk /*!< ADC Left shift factor */ -#define ADC_CFGR2_LSHIFT_0 (0x1UL << ADC_CFGR2_LSHIFT_Pos) /*!< 0x10000000 */ -#define ADC_CFGR2_LSHIFT_1 (0x2UL << ADC_CFGR2_LSHIFT_Pos) /*!< 0x20000000 */ -#define ADC_CFGR2_LSHIFT_2 (0x4UL << ADC_CFGR2_LSHIFT_Pos) /*!< 0x40000000 */ -#define ADC_CFGR2_LSHIFT_3 (0x8UL << ADC_CFGR2_LSHIFT_Pos) /*!< 0x80000000 */ - -#define ADC3_CFGR2_OVSR_Pos (2U) -#define ADC3_CFGR2_OVSR_Msk (0x7UL << ADC3_CFGR2_OVSR_Pos) /*!< 0x0000001C */ -#define ADC3_CFGR2_OVSR ADC3_CFGR2_OVSR_Msk /*!< ADC oversampling ratio */ -#define ADC3_CFGR2_OVSR_0 (0x1UL << ADC3_CFGR2_OVSR_Pos) /*!< 0x00000004 */ -#define ADC3_CFGR2_OVSR_1 (0x2UL << ADC3_CFGR2_OVSR_Pos) /*!< 0x00000008 */ -#define ADC3_CFGR2_OVSR_2 (0x4UL << ADC3_CFGR2_OVSR_Pos) /*!< 0x00000010 */ - -#define ADC3_CFGR2_SWTRIG_Pos (25U) -#define ADC3_CFGR2_SWTRIG_Msk (0x1UL << ADC3_CFGR2_SWTRIG_Pos) /*!< 0x02000000 */ -#define ADC3_CFGR2_SWTRIG ADC3_CFGR2_SWTRIG_Msk /*!< ADC Software Trigger Bit for Sample time control trigger mode */ -#define ADC3_CFGR2_BULB_Pos (26U) -#define ADC3_CFGR2_BULB_Msk (0x1UL << ADC3_CFGR2_BULB_Pos) /*!< 0x04000000 */ -#define ADC3_CFGR2_BULB ADC3_CFGR2_BULB_Msk /*!< ADC Bulb sampling mode */ -#define ADC3_CFGR2_SMPTRIG_Pos (27U) -#define ADC3_CFGR2_SMPTRIG_Msk (0x1UL << ADC3_CFGR2_SMPTRIG_Pos) /*!< 0x08000000 */ -#define ADC3_CFGR2_SMPTRIG ADC3_CFGR2_SMPTRIG_Msk /*!< ADC Sample Time Control Trigger mode */ -/******************** Bit definition for ADC_SMPR1 register ********************/ -#define ADC_SMPR1_SMP0_Pos (0U) -#define ADC_SMPR1_SMP0_Msk (0x7UL << ADC_SMPR1_SMP0_Pos) /*!< 0x00000007 */ -#define ADC_SMPR1_SMP0 ADC_SMPR1_SMP0_Msk /*!< ADC Channel 0 Sampling time selection */ -#define ADC_SMPR1_SMP0_0 (0x1UL << ADC_SMPR1_SMP0_Pos) /*!< 0x00000001 */ -#define ADC_SMPR1_SMP0_1 (0x2UL << ADC_SMPR1_SMP0_Pos) /*!< 0x00000002 */ -#define ADC_SMPR1_SMP0_2 (0x4UL << ADC_SMPR1_SMP0_Pos) /*!< 0x00000004 */ - -#define ADC_SMPR1_SMP1_Pos (3U) -#define ADC_SMPR1_SMP1_Msk (0x7UL << ADC_SMPR1_SMP1_Pos) /*!< 0x00000038 */ -#define ADC_SMPR1_SMP1 ADC_SMPR1_SMP1_Msk /*!< ADC Channel 1 Sampling time selection */ -#define ADC_SMPR1_SMP1_0 (0x1UL << ADC_SMPR1_SMP1_Pos) /*!< 0x00000008 */ -#define ADC_SMPR1_SMP1_1 (0x2UL << ADC_SMPR1_SMP1_Pos) /*!< 0x00000010 */ -#define ADC_SMPR1_SMP1_2 (0x4UL << ADC_SMPR1_SMP1_Pos) /*!< 0x00000020 */ - -#define ADC_SMPR1_SMP2_Pos (6U) -#define ADC_SMPR1_SMP2_Msk (0x7UL << ADC_SMPR1_SMP2_Pos) /*!< 0x000001C0 */ -#define ADC_SMPR1_SMP2 ADC_SMPR1_SMP2_Msk /*!< ADC Channel 2 Sampling time selection */ -#define ADC_SMPR1_SMP2_0 (0x1UL << ADC_SMPR1_SMP2_Pos) /*!< 0x00000040 */ -#define ADC_SMPR1_SMP2_1 (0x2UL << ADC_SMPR1_SMP2_Pos) /*!< 0x00000080 */ -#define ADC_SMPR1_SMP2_2 (0x4UL << ADC_SMPR1_SMP2_Pos) /*!< 0x00000100 */ - -#define ADC_SMPR1_SMP3_Pos (9U) -#define ADC_SMPR1_SMP3_Msk (0x7UL << ADC_SMPR1_SMP3_Pos) /*!< 0x00000E00 */ -#define ADC_SMPR1_SMP3 ADC_SMPR1_SMP3_Msk /*!< ADC Channel 3 Sampling time selection */ -#define ADC_SMPR1_SMP3_0 (0x1UL << ADC_SMPR1_SMP3_Pos) /*!< 0x00000200 */ -#define ADC_SMPR1_SMP3_1 (0x2UL << ADC_SMPR1_SMP3_Pos) /*!< 0x00000400 */ -#define ADC_SMPR1_SMP3_2 (0x4UL << ADC_SMPR1_SMP3_Pos) /*!< 0x00000800 */ - -#define ADC_SMPR1_SMP4_Pos (12U) -#define ADC_SMPR1_SMP4_Msk (0x7UL << ADC_SMPR1_SMP4_Pos) /*!< 0x00007000 */ -#define ADC_SMPR1_SMP4 ADC_SMPR1_SMP4_Msk /*!< ADC Channel 4 Sampling time selection */ -#define ADC_SMPR1_SMP4_0 (0x1UL << ADC_SMPR1_SMP4_Pos) /*!< 0x00001000 */ -#define ADC_SMPR1_SMP4_1 (0x2UL << ADC_SMPR1_SMP4_Pos) /*!< 0x00002000 */ -#define ADC_SMPR1_SMP4_2 (0x4UL << ADC_SMPR1_SMP4_Pos) /*!< 0x00004000 */ - -#define ADC_SMPR1_SMP5_Pos (15U) -#define ADC_SMPR1_SMP5_Msk (0x7UL << ADC_SMPR1_SMP5_Pos) /*!< 0x00038000 */ -#define ADC_SMPR1_SMP5 ADC_SMPR1_SMP5_Msk /*!< ADC Channel 5 Sampling time selection */ -#define ADC_SMPR1_SMP5_0 (0x1UL << ADC_SMPR1_SMP5_Pos) /*!< 0x00008000 */ -#define ADC_SMPR1_SMP5_1 (0x2UL << ADC_SMPR1_SMP5_Pos) /*!< 0x00010000 */ -#define ADC_SMPR1_SMP5_2 (0x4UL << ADC_SMPR1_SMP5_Pos) /*!< 0x00020000 */ - -#define ADC_SMPR1_SMP6_Pos (18U) -#define ADC_SMPR1_SMP6_Msk (0x7UL << ADC_SMPR1_SMP6_Pos) /*!< 0x001C0000 */ -#define ADC_SMPR1_SMP6 ADC_SMPR1_SMP6_Msk /*!< ADC Channel 6 Sampling time selection */ -#define ADC_SMPR1_SMP6_0 (0x1UL << ADC_SMPR1_SMP6_Pos) /*!< 0x00040000 */ -#define ADC_SMPR1_SMP6_1 (0x2UL << ADC_SMPR1_SMP6_Pos) /*!< 0x00080000 */ -#define ADC_SMPR1_SMP6_2 (0x4UL << ADC_SMPR1_SMP6_Pos) /*!< 0x00100000 */ - -#define ADC_SMPR1_SMP7_Pos (21U) -#define ADC_SMPR1_SMP7_Msk (0x7UL << ADC_SMPR1_SMP7_Pos) /*!< 0x00E00000 */ -#define ADC_SMPR1_SMP7 ADC_SMPR1_SMP7_Msk /*!< ADC Channel 7 Sampling time selection */ -#define ADC_SMPR1_SMP7_0 (0x1UL << ADC_SMPR1_SMP7_Pos) /*!< 0x00200000 */ -#define ADC_SMPR1_SMP7_1 (0x2UL << ADC_SMPR1_SMP7_Pos) /*!< 0x00400000 */ -#define ADC_SMPR1_SMP7_2 (0x4UL << ADC_SMPR1_SMP7_Pos) /*!< 0x00800000 */ - -#define ADC_SMPR1_SMP8_Pos (24U) -#define ADC_SMPR1_SMP8_Msk (0x7UL << ADC_SMPR1_SMP8_Pos) /*!< 0x07000000 */ -#define ADC_SMPR1_SMP8 ADC_SMPR1_SMP8_Msk /*!< ADC Channel 8 Sampling time selection */ -#define ADC_SMPR1_SMP8_0 (0x1UL << ADC_SMPR1_SMP8_Pos) /*!< 0x01000000 */ -#define ADC_SMPR1_SMP8_1 (0x2UL << ADC_SMPR1_SMP8_Pos) /*!< 0x02000000 */ -#define ADC_SMPR1_SMP8_2 (0x4UL << ADC_SMPR1_SMP8_Pos) /*!< 0x04000000 */ - -#define ADC_SMPR1_SMP9_Pos (27U) -#define ADC_SMPR1_SMP9_Msk (0x7UL << ADC_SMPR1_SMP9_Pos) /*!< 0x38000000 */ -#define ADC_SMPR1_SMP9 ADC_SMPR1_SMP9_Msk /*!< ADC Channel 9 Sampling time selection */ -#define ADC_SMPR1_SMP9_0 (0x1UL << ADC_SMPR1_SMP9_Pos) /*!< 0x08000000 */ -#define ADC_SMPR1_SMP9_1 (0x2UL << ADC_SMPR1_SMP9_Pos) /*!< 0x10000000 */ -#define ADC_SMPR1_SMP9_2 (0x4UL << ADC_SMPR1_SMP9_Pos) /*!< 0x20000000 */ - -/******************** Bit definition for ADC_SMPR2 register ********************/ -#define ADC_SMPR2_SMP10_Pos (0U) -#define ADC_SMPR2_SMP10_Msk (0x7UL << ADC_SMPR2_SMP10_Pos) /*!< 0x00000007 */ -#define ADC_SMPR2_SMP10 ADC_SMPR2_SMP10_Msk /*!< ADC Channel 10 Sampling time selection */ -#define ADC_SMPR2_SMP10_0 (0x1UL << ADC_SMPR2_SMP10_Pos) /*!< 0x00000001 */ -#define ADC_SMPR2_SMP10_1 (0x2UL << ADC_SMPR2_SMP10_Pos) /*!< 0x00000002 */ -#define ADC_SMPR2_SMP10_2 (0x4UL << ADC_SMPR2_SMP10_Pos) /*!< 0x00000004 */ - -#define ADC_SMPR2_SMP11_Pos (3U) -#define ADC_SMPR2_SMP11_Msk (0x7UL << ADC_SMPR2_SMP11_Pos) /*!< 0x00000038 */ -#define ADC_SMPR2_SMP11 ADC_SMPR2_SMP11_Msk /*!< ADC Channel 11 Sampling time selection */ -#define ADC_SMPR2_SMP11_0 (0x1UL << ADC_SMPR2_SMP11_Pos) /*!< 0x00000008 */ -#define ADC_SMPR2_SMP11_1 (0x2UL << ADC_SMPR2_SMP11_Pos) /*!< 0x00000010 */ -#define ADC_SMPR2_SMP11_2 (0x4UL << ADC_SMPR2_SMP11_Pos) /*!< 0x00000020 */ - -#define ADC_SMPR2_SMP12_Pos (6U) -#define ADC_SMPR2_SMP12_Msk (0x7UL << ADC_SMPR2_SMP12_Pos) /*!< 0x000001C0 */ -#define ADC_SMPR2_SMP12 ADC_SMPR2_SMP12_Msk /*!< ADC Channel 12 Sampling time selection */ -#define ADC_SMPR2_SMP12_0 (0x1UL << ADC_SMPR2_SMP12_Pos) /*!< 0x00000040 */ -#define ADC_SMPR2_SMP12_1 (0x2UL << ADC_SMPR2_SMP12_Pos) /*!< 0x00000080 */ -#define ADC_SMPR2_SMP12_2 (0x4UL << ADC_SMPR2_SMP12_Pos) /*!< 0x00000100 */ - -#define ADC_SMPR2_SMP13_Pos (9U) -#define ADC_SMPR2_SMP13_Msk (0x7UL << ADC_SMPR2_SMP13_Pos) /*!< 0x00000E00 */ -#define ADC_SMPR2_SMP13 ADC_SMPR2_SMP13_Msk /*!< ADC Channel 13 Sampling time selection */ -#define ADC_SMPR2_SMP13_0 (0x1UL << ADC_SMPR2_SMP13_Pos) /*!< 0x00000200 */ -#define ADC_SMPR2_SMP13_1 (0x2UL << ADC_SMPR2_SMP13_Pos) /*!< 0x00000400 */ -#define ADC_SMPR2_SMP13_2 (0x4UL << ADC_SMPR2_SMP13_Pos) /*!< 0x00000800 */ - -#define ADC_SMPR2_SMP14_Pos (12U) -#define ADC_SMPR2_SMP14_Msk (0x7UL << ADC_SMPR2_SMP14_Pos) /*!< 0x00007000 */ -#define ADC_SMPR2_SMP14 ADC_SMPR2_SMP14_Msk /*!< ADC Channel 14 Sampling time selection */ -#define ADC_SMPR2_SMP14_0 (0x1UL << ADC_SMPR2_SMP14_Pos) /*!< 0x00001000 */ -#define ADC_SMPR2_SMP14_1 (0x2UL << ADC_SMPR2_SMP14_Pos) /*!< 0x00002000 */ -#define ADC_SMPR2_SMP14_2 (0x4UL << ADC_SMPR2_SMP14_Pos) /*!< 0x00004000 */ - -#define ADC_SMPR2_SMP15_Pos (15U) -#define ADC_SMPR2_SMP15_Msk (0x7UL << ADC_SMPR2_SMP15_Pos) /*!< 0x00038000 */ -#define ADC_SMPR2_SMP15 ADC_SMPR2_SMP15_Msk /*!< ADC Channel 15 Sampling time selection */ -#define ADC_SMPR2_SMP15_0 (0x1UL << ADC_SMPR2_SMP15_Pos) /*!< 0x00008000 */ -#define ADC_SMPR2_SMP15_1 (0x2UL << ADC_SMPR2_SMP15_Pos) /*!< 0x00010000 */ -#define ADC_SMPR2_SMP15_2 (0x4UL << ADC_SMPR2_SMP15_Pos) /*!< 0x00020000 */ - -#define ADC_SMPR2_SMP16_Pos (18U) -#define ADC_SMPR2_SMP16_Msk (0x7UL << ADC_SMPR2_SMP16_Pos) /*!< 0x001C0000 */ -#define ADC_SMPR2_SMP16 ADC_SMPR2_SMP16_Msk /*!< ADC Channel 16 Sampling time selection */ -#define ADC_SMPR2_SMP16_0 (0x1UL << ADC_SMPR2_SMP16_Pos) /*!< 0x00040000 */ -#define ADC_SMPR2_SMP16_1 (0x2UL << ADC_SMPR2_SMP16_Pos) /*!< 0x00080000 */ -#define ADC_SMPR2_SMP16_2 (0x4UL << ADC_SMPR2_SMP16_Pos) /*!< 0x00100000 */ - -#define ADC_SMPR2_SMP17_Pos (21U) -#define ADC_SMPR2_SMP17_Msk (0x7UL << ADC_SMPR2_SMP17_Pos) /*!< 0x00E00000 */ -#define ADC_SMPR2_SMP17 ADC_SMPR2_SMP17_Msk /*!< ADC Channel 17 Sampling time selection */ -#define ADC_SMPR2_SMP17_0 (0x1UL << ADC_SMPR2_SMP17_Pos) /*!< 0x00200000 */ -#define ADC_SMPR2_SMP17_1 (0x2UL << ADC_SMPR2_SMP17_Pos) /*!< 0x00400000 */ -#define ADC_SMPR2_SMP17_2 (0x4UL << ADC_SMPR2_SMP17_Pos) /*!< 0x00800000 */ - -#define ADC_SMPR2_SMP18_Pos (24U) -#define ADC_SMPR2_SMP18_Msk (0x7UL << ADC_SMPR2_SMP18_Pos) /*!< 0x07000000 */ -#define ADC_SMPR2_SMP18 ADC_SMPR2_SMP18_Msk /*!< ADC Channel 18 Sampling time selection */ -#define ADC_SMPR2_SMP18_0 (0x1UL << ADC_SMPR2_SMP18_Pos) /*!< 0x01000000 */ -#define ADC_SMPR2_SMP18_1 (0x2UL << ADC_SMPR2_SMP18_Pos) /*!< 0x02000000 */ -#define ADC_SMPR2_SMP18_2 (0x4UL << ADC_SMPR2_SMP18_Pos) /*!< 0x04000000 */ - -#define ADC_SMPR2_SMP19_Pos (27U) -#define ADC_SMPR2_SMP19_Msk (0x7UL << ADC_SMPR2_SMP19_Pos) /*!< 0x38000000 */ -#define ADC_SMPR2_SMP19 ADC_SMPR2_SMP19_Msk /*!< ADC Channel 19 Sampling time selection */ -#define ADC_SMPR2_SMP19_0 (0x1UL << ADC_SMPR2_SMP19_Pos) /*!< 0x08000000 */ -#define ADC_SMPR2_SMP19_1 (0x2UL << ADC_SMPR2_SMP19_Pos) /*!< 0x10000000 */ -#define ADC_SMPR2_SMP19_2 (0x4UL << ADC_SMPR2_SMP19_Pos) /*!< 0x20000000 */ - -/******************** Bit definition for ADC_PCSEL register ********************/ -#define ADC_PCSEL_PCSEL_Pos (0U) -#define ADC_PCSEL_PCSEL_Msk (0xFFFFFUL << ADC_PCSEL_PCSEL_Pos) /*!< 0x000FFFFF */ -#define ADC_PCSEL_PCSEL ADC_PCSEL_PCSEL_Msk /*!< ADC pre channel selection */ -#define ADC_PCSEL_PCSEL_0 (0x00001UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000001 */ -#define ADC_PCSEL_PCSEL_1 (0x00002UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000002 */ -#define ADC_PCSEL_PCSEL_2 (0x00004UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000004 */ -#define ADC_PCSEL_PCSEL_3 (0x00008UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000008 */ -#define ADC_PCSEL_PCSEL_4 (0x00010UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000010 */ -#define ADC_PCSEL_PCSEL_5 (0x00020UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000020 */ -#define ADC_PCSEL_PCSEL_6 (0x00040UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000040 */ -#define ADC_PCSEL_PCSEL_7 (0x00080UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000080 */ -#define ADC_PCSEL_PCSEL_8 (0x00100UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000100 */ -#define ADC_PCSEL_PCSEL_9 (0x00200UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000200 */ -#define ADC_PCSEL_PCSEL_10 (0x00400UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000400 */ -#define ADC_PCSEL_PCSEL_11 (0x00800UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000800 */ -#define ADC_PCSEL_PCSEL_12 (0x01000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00001000 */ -#define ADC_PCSEL_PCSEL_13 (0x02000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00002000 */ -#define ADC_PCSEL_PCSEL_14 (0x04000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00004000 */ -#define ADC_PCSEL_PCSEL_15 (0x08000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00008000 */ -#define ADC_PCSEL_PCSEL_16 (0x10000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00010000 */ -#define ADC_PCSEL_PCSEL_17 (0x20000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00020000 */ -#define ADC_PCSEL_PCSEL_18 (0x40000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00040000 */ -#define ADC_PCSEL_PCSEL_19 (0x80000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00080000 */ - -/***************** Bit definition for ADC_LTR1, 2, 3 registers *****************/ -#define ADC_LTR_LT_Pos (0U) -#define ADC_LTR_LT_Msk (0x3FFFFFFUL << ADC_LTR_LT_Pos) /*!< 0x03FFFFFF */ -#define ADC_LTR_LT ADC_LTR_LT_Msk /*!< ADC Analog watchdog 1, 2 and 3 lower threshold */ - -/***************** Bit definition for ADC_HTR1, 2, 3 registers ****************/ -#define ADC_HTR_HT_Pos (0U) -#define ADC_HTR_HT_Msk (0x3FFFFFFUL << ADC_HTR_HT_Pos) /*!< 0x03FFFFFF */ -#define ADC_HTR_HT ADC_HTR_HT_Msk /*!< ADC Analog watchdog 1,2 and 3 higher threshold */ - -/******************** Bit definition for ADC3_TR1 register *******************/ -#define ADC3_TR1_LT1_Pos (0U) -#define ADC3_TR1_LT1_Msk (0xFFFUL << ADC3_TR1_LT1_Pos) /*!< 0x00000FFF */ -#define ADC3_TR1_LT1 ADC3_TR1_LT1_Msk /*!< ADC analog watchdog 1 threshold low */ - -#define ADC3_TR1_AWDFILT_Pos (12U) -#define ADC3_TR1_AWDFILT_Msk (0x7UL << ADC3_TR1_AWDFILT_Pos) /*!< 0x00007000 */ -#define ADC3_TR1_AWDFILT ADC3_TR1_AWDFILT_Msk /*!< ADC analog watchdog filtering parameter */ -#define ADC3_TR1_AWDFILT_0 (0x1UL << ADC3_TR1_AWDFILT_Pos) /*!< 0x00001000 */ -#define ADC3_TR1_AWDFILT_1 (0x2UL << ADC3_TR1_AWDFILT_Pos) /*!< 0x00002000 */ -#define ADC3_TR1_AWDFILT_2 (0x4UL << ADC3_TR1_AWDFILT_Pos) /*!< 0x00004000 */ - -#define ADC3_TR1_HT1_Pos (16U) -#define ADC3_TR1_HT1_Msk (0xFFFUL << ADC3_TR1_HT1_Pos) /*!< 0x0FFF0000 */ -#define ADC3_TR1_HT1 ADC3_TR1_HT1_Msk /*!< ADC analog watchdog 1 threshold high */ - -/******************** Bit definition for ADC3_TR2 register *******************/ -#define ADC3_TR2_LT2_Pos (0U) -#define ADC3_TR2_LT2_Msk (0xFFUL << ADC3_TR2_LT2_Pos) /*!< 0x000000FF */ -#define ADC3_TR2_LT2 ADC3_TR2_LT2_Msk /*!< ADC analog watchdog 2 threshold low */ - -#define ADC3_TR2_HT2_Pos (16U) -#define ADC3_TR2_HT2_Msk (0xFFUL << ADC3_TR2_HT2_Pos) /*!< 0x00FF0000 */ -#define ADC3_TR2_HT2 ADC3_TR2_HT2_Msk /*!< ADC analog watchdog 2 threshold high */ - -/******************** Bit definition for ADC3_TR3 register *******************/ -#define ADC3_TR3_LT3_Pos (0U) -#define ADC3_TR3_LT3_Msk (0xFFUL << ADC3_TR3_LT3_Pos) /*!< 0x000000FF */ -#define ADC3_TR3_LT3 ADC3_TR3_LT3_Msk /*!< ADC analog watchdog 3 threshold low */ - -#define ADC3_TR3_HT3_Pos (16U) -#define ADC3_TR3_HT3_Msk (0xFFUL << ADC3_TR3_HT3_Pos) /*!< 0x00FF0000 */ -#define ADC3_TR3_HT3 ADC3_TR3_HT3_Msk /*!< ADC analog watchdog 3 threshold high */ - -/******************** Bit definition for ADC_SQR1 register ********************/ -#define ADC_SQR1_L_Pos (0U) -#define ADC_SQR1_L_Msk (0xFUL << ADC_SQR1_L_Pos) /*!< 0x0000000F */ -#define ADC_SQR1_L ADC_SQR1_L_Msk /*!< ADC regular channel sequence length */ -#define ADC_SQR1_L_0 (0x1UL << ADC_SQR1_L_Pos) /*!< 0x00000001 */ -#define ADC_SQR1_L_1 (0x2UL << ADC_SQR1_L_Pos) /*!< 0x00000002 */ -#define ADC_SQR1_L_2 (0x4UL << ADC_SQR1_L_Pos) /*!< 0x00000004 */ -#define ADC_SQR1_L_3 (0x8UL << ADC_SQR1_L_Pos) /*!< 0x00000008 */ - -#define ADC_SQR1_SQ1_Pos (6U) -#define ADC_SQR1_SQ1_Msk (0x1FUL << ADC_SQR1_SQ1_Pos) /*!< 0x000007C0 */ -#define ADC_SQR1_SQ1 ADC_SQR1_SQ1_Msk /*!< ADC 1st conversion in regular sequence */ -#define ADC_SQR1_SQ1_0 (0x01UL << ADC_SQR1_SQ1_Pos) /*!< 0x00000040 */ -#define ADC_SQR1_SQ1_1 (0x02UL << ADC_SQR1_SQ1_Pos) /*!< 0x00000080 */ -#define ADC_SQR1_SQ1_2 (0x04UL << ADC_SQR1_SQ1_Pos) /*!< 0x00000100 */ -#define ADC_SQR1_SQ1_3 (0x08UL << ADC_SQR1_SQ1_Pos) /*!< 0x00000200 */ -#define ADC_SQR1_SQ1_4 (0x10UL << ADC_SQR1_SQ1_Pos) /*!< 0x00000400 */ - -#define ADC_SQR1_SQ2_Pos (12U) -#define ADC_SQR1_SQ2_Msk (0x1FUL << ADC_SQR1_SQ2_Pos) /*!< 0x0001F000 */ -#define ADC_SQR1_SQ2 ADC_SQR1_SQ2_Msk /*!< ADC 2nd conversion in regular sequence */ -#define ADC_SQR1_SQ2_0 (0x01UL << ADC_SQR1_SQ2_Pos) /*!< 0x00001000 */ -#define ADC_SQR1_SQ2_1 (0x02UL << ADC_SQR1_SQ2_Pos) /*!< 0x00002000 */ -#define ADC_SQR1_SQ2_2 (0x04UL << ADC_SQR1_SQ2_Pos) /*!< 0x00004000 */ -#define ADC_SQR1_SQ2_3 (0x08UL << ADC_SQR1_SQ2_Pos) /*!< 0x00008000 */ -#define ADC_SQR1_SQ2_4 (0x10UL << ADC_SQR1_SQ2_Pos) /*!< 0x00010000 */ - -#define ADC_SQR1_SQ3_Pos (18U) -#define ADC_SQR1_SQ3_Msk (0x1FUL << ADC_SQR1_SQ3_Pos) /*!< 0x007C0000 */ -#define ADC_SQR1_SQ3 ADC_SQR1_SQ3_Msk /*!< ADC 3rd conversion in regular sequence */ -#define ADC_SQR1_SQ3_0 (0x01UL << ADC_SQR1_SQ3_Pos) /*!< 0x00040000 */ -#define ADC_SQR1_SQ3_1 (0x02UL << ADC_SQR1_SQ3_Pos) /*!< 0x00080000 */ -#define ADC_SQR1_SQ3_2 (0x04UL << ADC_SQR1_SQ3_Pos) /*!< 0x00100000 */ -#define ADC_SQR1_SQ3_3 (0x08UL << ADC_SQR1_SQ3_Pos) /*!< 0x00200000 */ -#define ADC_SQR1_SQ3_4 (0x10UL << ADC_SQR1_SQ3_Pos) /*!< 0x00400000 */ - -#define ADC_SQR1_SQ4_Pos (24U) -#define ADC_SQR1_SQ4_Msk (0x1FUL << ADC_SQR1_SQ4_Pos) /*!< 0x1F000000 */ -#define ADC_SQR1_SQ4 ADC_SQR1_SQ4_Msk /*!< ADC 4th conversion in regular sequence */ -#define ADC_SQR1_SQ4_0 (0x01UL << ADC_SQR1_SQ4_Pos) /*!< 0x01000000 */ -#define ADC_SQR1_SQ4_1 (0x02UL << ADC_SQR1_SQ4_Pos) /*!< 0x02000000 */ -#define ADC_SQR1_SQ4_2 (0x04UL << ADC_SQR1_SQ4_Pos) /*!< 0x04000000 */ -#define ADC_SQR1_SQ4_3 (0x08UL << ADC_SQR1_SQ4_Pos) /*!< 0x08000000 */ -#define ADC_SQR1_SQ4_4 (0x10UL << ADC_SQR1_SQ4_Pos) /*!< 0x10000000 */ - -/******************** Bit definition for ADC_SQR2 register ********************/ -#define ADC_SQR2_SQ5_Pos (0U) -#define ADC_SQR2_SQ5_Msk (0x1FUL << ADC_SQR2_SQ5_Pos) /*!< 0x0000001F */ -#define ADC_SQR2_SQ5 ADC_SQR2_SQ5_Msk /*!< ADC 5th conversion in regular sequence */ -#define ADC_SQR2_SQ5_0 (0x01UL << ADC_SQR2_SQ5_Pos) /*!< 0x00000001 */ -#define ADC_SQR2_SQ5_1 (0x02UL << ADC_SQR2_SQ5_Pos) /*!< 0x00000002 */ -#define ADC_SQR2_SQ5_2 (0x04UL << ADC_SQR2_SQ5_Pos) /*!< 0x00000004 */ -#define ADC_SQR2_SQ5_3 (0x08UL << ADC_SQR2_SQ5_Pos) /*!< 0x00000008 */ -#define ADC_SQR2_SQ5_4 (0x10UL << ADC_SQR2_SQ5_Pos) /*!< 0x00000010 */ - -#define ADC_SQR2_SQ6_Pos (6U) -#define ADC_SQR2_SQ6_Msk (0x1FUL << ADC_SQR2_SQ6_Pos) /*!< 0x000007C0 */ -#define ADC_SQR2_SQ6 ADC_SQR2_SQ6_Msk /*!< ADC 6th conversion in regular sequence */ -#define ADC_SQR2_SQ6_0 (0x01UL << ADC_SQR2_SQ6_Pos) /*!< 0x00000040 */ -#define ADC_SQR2_SQ6_1 (0x02UL << ADC_SQR2_SQ6_Pos) /*!< 0x00000080 */ -#define ADC_SQR2_SQ6_2 (0x04UL << ADC_SQR2_SQ6_Pos) /*!< 0x00000100 */ -#define ADC_SQR2_SQ6_3 (0x08UL << ADC_SQR2_SQ6_Pos) /*!< 0x00000200 */ -#define ADC_SQR2_SQ6_4 (0x10UL << ADC_SQR2_SQ6_Pos) /*!< 0x00000400 */ - -#define ADC_SQR2_SQ7_Pos (12U) -#define ADC_SQR2_SQ7_Msk (0x1FUL << ADC_SQR2_SQ7_Pos) /*!< 0x0001F000 */ -#define ADC_SQR2_SQ7 ADC_SQR2_SQ7_Msk /*!< ADC 7th conversion in regular sequence */ -#define ADC_SQR2_SQ7_0 (0x01UL << ADC_SQR2_SQ7_Pos) /*!< 0x00001000 */ -#define ADC_SQR2_SQ7_1 (0x02UL << ADC_SQR2_SQ7_Pos) /*!< 0x00002000 */ -#define ADC_SQR2_SQ7_2 (0x04UL << ADC_SQR2_SQ7_Pos) /*!< 0x00004000 */ -#define ADC_SQR2_SQ7_3 (0x08UL << ADC_SQR2_SQ7_Pos) /*!< 0x00008000 */ -#define ADC_SQR2_SQ7_4 (0x10UL << ADC_SQR2_SQ7_Pos) /*!< 0x00010000 */ - -#define ADC_SQR2_SQ8_Pos (18U) -#define ADC_SQR2_SQ8_Msk (0x1FUL << ADC_SQR2_SQ8_Pos) /*!< 0x007C0000 */ -#define ADC_SQR2_SQ8 ADC_SQR2_SQ8_Msk /*!< ADC 8th conversion in regular sequence */ -#define ADC_SQR2_SQ8_0 (0x01UL << ADC_SQR2_SQ8_Pos) /*!< 0x00040000 */ -#define ADC_SQR2_SQ8_1 (0x02UL << ADC_SQR2_SQ8_Pos) /*!< 0x00080000 */ -#define ADC_SQR2_SQ8_2 (0x04UL << ADC_SQR2_SQ8_Pos) /*!< 0x00100000 */ -#define ADC_SQR2_SQ8_3 (0x08UL << ADC_SQR2_SQ8_Pos) /*!< 0x00200000 */ -#define ADC_SQR2_SQ8_4 (0x10UL << ADC_SQR2_SQ8_Pos) /*!< 0x00400000 */ - -#define ADC_SQR2_SQ9_Pos (24U) -#define ADC_SQR2_SQ9_Msk (0x1FUL << ADC_SQR2_SQ9_Pos) /*!< 0x1F000000 */ -#define ADC_SQR2_SQ9 ADC_SQR2_SQ9_Msk /*!< ADC 9th conversion in regular sequence */ -#define ADC_SQR2_SQ9_0 (0x01UL << ADC_SQR2_SQ9_Pos) /*!< 0x01000000 */ -#define ADC_SQR2_SQ9_1 (0x02UL << ADC_SQR2_SQ9_Pos) /*!< 0x02000000 */ -#define ADC_SQR2_SQ9_2 (0x04UL << ADC_SQR2_SQ9_Pos) /*!< 0x04000000 */ -#define ADC_SQR2_SQ9_3 (0x08UL << ADC_SQR2_SQ9_Pos) /*!< 0x08000000 */ -#define ADC_SQR2_SQ9_4 (0x10UL << ADC_SQR2_SQ9_Pos) /*!< 0x10000000 */ - -/******************** Bit definition for ADC_SQR3 register ********************/ -#define ADC_SQR3_SQ10_Pos (0U) -#define ADC_SQR3_SQ10_Msk (0x1FUL << ADC_SQR3_SQ10_Pos) /*!< 0x0000001F */ -#define ADC_SQR3_SQ10 ADC_SQR3_SQ10_Msk /*!< ADC 10th conversion in regular sequence */ -#define ADC_SQR3_SQ10_0 (0x01UL << ADC_SQR3_SQ10_Pos) /*!< 0x00000001 */ -#define ADC_SQR3_SQ10_1 (0x02UL << ADC_SQR3_SQ10_Pos) /*!< 0x00000002 */ -#define ADC_SQR3_SQ10_2 (0x04UL << ADC_SQR3_SQ10_Pos) /*!< 0x00000004 */ -#define ADC_SQR3_SQ10_3 (0x08UL << ADC_SQR3_SQ10_Pos) /*!< 0x00000008 */ -#define ADC_SQR3_SQ10_4 (0x10UL << ADC_SQR3_SQ10_Pos) /*!< 0x00000010 */ - -#define ADC_SQR3_SQ11_Pos (6U) -#define ADC_SQR3_SQ11_Msk (0x1FUL << ADC_SQR3_SQ11_Pos) /*!< 0x000007C0 */ -#define ADC_SQR3_SQ11 ADC_SQR3_SQ11_Msk /*!< ADC 11th conversion in regular sequence */ -#define ADC_SQR3_SQ11_0 (0x01UL << ADC_SQR3_SQ11_Pos) /*!< 0x00000040 */ -#define ADC_SQR3_SQ11_1 (0x02UL << ADC_SQR3_SQ11_Pos) /*!< 0x00000080 */ -#define ADC_SQR3_SQ11_2 (0x04UL << ADC_SQR3_SQ11_Pos) /*!< 0x00000100 */ -#define ADC_SQR3_SQ11_3 (0x08UL << ADC_SQR3_SQ11_Pos) /*!< 0x00000200 */ -#define ADC_SQR3_SQ11_4 (0x10UL << ADC_SQR3_SQ11_Pos) /*!< 0x00000400 */ - -#define ADC_SQR3_SQ12_Pos (12U) -#define ADC_SQR3_SQ12_Msk (0x1FUL << ADC_SQR3_SQ12_Pos) /*!< 0x0001F000 */ -#define ADC_SQR3_SQ12 ADC_SQR3_SQ12_Msk /*!< ADC 12th conversion in regular sequence */ -#define ADC_SQR3_SQ12_0 (0x01UL << ADC_SQR3_SQ12_Pos) /*!< 0x00001000 */ -#define ADC_SQR3_SQ12_1 (0x02UL << ADC_SQR3_SQ12_Pos) /*!< 0x00002000 */ -#define ADC_SQR3_SQ12_2 (0x04UL << ADC_SQR3_SQ12_Pos) /*!< 0x00004000 */ -#define ADC_SQR3_SQ12_3 (0x08UL << ADC_SQR3_SQ12_Pos) /*!< 0x00008000 */ -#define ADC_SQR3_SQ12_4 (0x10UL << ADC_SQR3_SQ12_Pos) /*!< 0x00010000 */ - -#define ADC_SQR3_SQ13_Pos (18U) -#define ADC_SQR3_SQ13_Msk (0x1FUL << ADC_SQR3_SQ13_Pos) /*!< 0x007C0000 */ -#define ADC_SQR3_SQ13 ADC_SQR3_SQ13_Msk /*!< ADC 13th conversion in regular sequence */ -#define ADC_SQR3_SQ13_0 (0x01UL << ADC_SQR3_SQ13_Pos) /*!< 0x00040000 */ -#define ADC_SQR3_SQ13_1 (0x02UL << ADC_SQR3_SQ13_Pos) /*!< 0x00080000 */ -#define ADC_SQR3_SQ13_2 (0x04UL << ADC_SQR3_SQ13_Pos) /*!< 0x00100000 */ -#define ADC_SQR3_SQ13_3 (0x08UL << ADC_SQR3_SQ13_Pos) /*!< 0x00200000 */ -#define ADC_SQR3_SQ13_4 (0x10UL << ADC_SQR3_SQ13_Pos) /*!< 0x00400000 */ - -#define ADC_SQR3_SQ14_Pos (24U) -#define ADC_SQR3_SQ14_Msk (0x1FUL << ADC_SQR3_SQ14_Pos) /*!< 0x1F000000 */ -#define ADC_SQR3_SQ14 ADC_SQR3_SQ14_Msk /*!< ADC 14th conversion in regular sequence */ -#define ADC_SQR3_SQ14_0 (0x01UL << ADC_SQR3_SQ14_Pos) /*!< 0x01000000 */ -#define ADC_SQR3_SQ14_1 (0x02UL << ADC_SQR3_SQ14_Pos) /*!< 0x02000000 */ -#define ADC_SQR3_SQ14_2 (0x04UL << ADC_SQR3_SQ14_Pos) /*!< 0x04000000 */ -#define ADC_SQR3_SQ14_3 (0x08UL << ADC_SQR3_SQ14_Pos) /*!< 0x08000000 */ -#define ADC_SQR3_SQ14_4 (0x10UL << ADC_SQR3_SQ14_Pos) /*!< 0x10000000 */ - -/******************** Bit definition for ADC_SQR4 register ********************/ -#define ADC_SQR4_SQ15_Pos (0U) -#define ADC_SQR4_SQ15_Msk (0x1FUL << ADC_SQR4_SQ15_Pos) /*!< 0x0000001F */ -#define ADC_SQR4_SQ15 ADC_SQR4_SQ15_Msk /*!< ADC 15th conversion in regular sequence */ -#define ADC_SQR4_SQ15_0 (0x01UL << ADC_SQR4_SQ15_Pos) /*!< 0x00000001 */ -#define ADC_SQR4_SQ15_1 (0x02UL << ADC_SQR4_SQ15_Pos) /*!< 0x00000002 */ -#define ADC_SQR4_SQ15_2 (0x04UL << ADC_SQR4_SQ15_Pos) /*!< 0x00000004 */ -#define ADC_SQR4_SQ15_3 (0x08UL << ADC_SQR4_SQ15_Pos) /*!< 0x00000008 */ -#define ADC_SQR4_SQ15_4 (0x10UL << ADC_SQR4_SQ15_Pos) /*!< 0x00000010 */ - -#define ADC_SQR4_SQ16_Pos (6U) -#define ADC_SQR4_SQ16_Msk (0x1FUL << ADC_SQR4_SQ16_Pos) /*!< 0x000007C0 */ -#define ADC_SQR4_SQ16 ADC_SQR4_SQ16_Msk /*!< ADC 16th conversion in regular sequence */ -#define ADC_SQR4_SQ16_0 (0x01UL << ADC_SQR4_SQ16_Pos) /*!< 0x00000040 */ -#define ADC_SQR4_SQ16_1 (0x02UL << ADC_SQR4_SQ16_Pos) /*!< 0x00000080 */ -#define ADC_SQR4_SQ16_2 (0x04UL << ADC_SQR4_SQ16_Pos) /*!< 0x00000100 */ -#define ADC_SQR4_SQ16_3 (0x08UL << ADC_SQR4_SQ16_Pos) /*!< 0x00000200 */ -#define ADC_SQR4_SQ16_4 (0x10UL << ADC_SQR4_SQ16_Pos) /*!< 0x00000400 */ -/******************** Bit definition for ADC_DR register ********************/ -#define ADC_DR_RDATA_Pos (0U) -#define ADC_DR_RDATA_Msk (0xFFFFFFFFUL << ADC_DR_RDATA_Pos) /*!< 0xFFFFFFFF */ -#define ADC_DR_RDATA ADC_DR_RDATA_Msk /*!< ADC regular Data converted */ - -/******************** Bit definition for ADC_JSQR register ********************/ -#define ADC_JSQR_JL_Pos (0U) -#define ADC_JSQR_JL_Msk (0x3UL << ADC_JSQR_JL_Pos) /*!< 0x00000003 */ -#define ADC_JSQR_JL ADC_JSQR_JL_Msk /*!< ADC injected channel sequence length */ -#define ADC_JSQR_JL_0 (0x1UL << ADC_JSQR_JL_Pos) /*!< 0x00000001 */ -#define ADC_JSQR_JL_1 (0x2UL << ADC_JSQR_JL_Pos) /*!< 0x00000002 */ - -#define ADC_JSQR_JEXTSEL_Pos (2U) -#define ADC_JSQR_JEXTSEL_Msk (0x1FUL << ADC_JSQR_JEXTSEL_Pos) /*!< 0x0000007C */ -#define ADC_JSQR_JEXTSEL ADC_JSQR_JEXTSEL_Msk /*!< ADC external trigger selection for injected group */ -#define ADC_JSQR_JEXTSEL_0 (0x01UL << ADC_JSQR_JEXTSEL_Pos) /*!< 0x00000004 */ -#define ADC_JSQR_JEXTSEL_1 (0x02UL << ADC_JSQR_JEXTSEL_Pos) /*!< 0x00000008 */ -#define ADC_JSQR_JEXTSEL_2 (0x04UL << ADC_JSQR_JEXTSEL_Pos) /*!< 0x00000010 */ -#define ADC_JSQR_JEXTSEL_3 (0x08UL << ADC_JSQR_JEXTSEL_Pos) /*!< 0x00000020 */ -#define ADC_JSQR_JEXTSEL_4 (0x10UL << ADC_JSQR_JEXTSEL_Pos) /*!< 0x00000040 */ - -#define ADC_JSQR_JEXTEN_Pos (7U) -#define ADC_JSQR_JEXTEN_Msk (0x3UL << ADC_JSQR_JEXTEN_Pos) /*!< 0x00000180 */ -#define ADC_JSQR_JEXTEN ADC_JSQR_JEXTEN_Msk /*!< ADC external trigger enable and polarity selection for injected channels */ -#define ADC_JSQR_JEXTEN_0 (0x1UL << ADC_JSQR_JEXTEN_Pos) /*!< 0x00000080 */ -#define ADC_JSQR_JEXTEN_1 (0x2UL << ADC_JSQR_JEXTEN_Pos) /*!< 0x00000100 */ - -#define ADC_JSQR_JSQ1_Pos (9U) -#define ADC_JSQR_JSQ1_Msk (0x1FUL << ADC_JSQR_JSQ1_Pos) /*!< 0x00003E00 */ -#define ADC_JSQR_JSQ1 ADC_JSQR_JSQ1_Msk /*!< ADC 1st conversion in injected sequence */ -#define ADC_JSQR_JSQ1_0 (0x01UL << ADC_JSQR_JSQ1_Pos) /*!< 0x00000200 */ -#define ADC_JSQR_JSQ1_1 (0x02UL << ADC_JSQR_JSQ1_Pos) /*!< 0x00000400 */ -#define ADC_JSQR_JSQ1_2 (0x04UL << ADC_JSQR_JSQ1_Pos) /*!< 0x00000800 */ -#define ADC_JSQR_JSQ1_3 (0x08UL << ADC_JSQR_JSQ1_Pos) /*!< 0x00001000 */ -#define ADC_JSQR_JSQ1_4 (0x10UL << ADC_JSQR_JSQ1_Pos) /*!< 0x00002000 */ - -#define ADC_JSQR_JSQ2_Pos (15U) -#define ADC_JSQR_JSQ2_Msk (0x1FUL << ADC_JSQR_JSQ2_Pos) /*!< 0x000F8000 */ -#define ADC_JSQR_JSQ2 ADC_JSQR_JSQ2_Msk /*!< ADC 2nd conversion in injected sequence */ -#define ADC_JSQR_JSQ2_0 (0x01UL << ADC_JSQR_JSQ2_Pos) /*!< 0x00008000 */ -#define ADC_JSQR_JSQ2_1 (0x02UL << ADC_JSQR_JSQ2_Pos) /*!< 0x00010000 */ -#define ADC_JSQR_JSQ2_2 (0x04UL << ADC_JSQR_JSQ2_Pos) /*!< 0x00020000 */ -#define ADC_JSQR_JSQ2_3 (0x08UL << ADC_JSQR_JSQ2_Pos) /*!< 0x00040000 */ -#define ADC_JSQR_JSQ2_4 (0x10UL << ADC_JSQR_JSQ2_Pos) /*!< 0x00080000 */ - -#define ADC_JSQR_JSQ3_Pos (21U) -#define ADC_JSQR_JSQ3_Msk (0x1FUL << ADC_JSQR_JSQ3_Pos) /*!< 0x03E00000 */ -#define ADC_JSQR_JSQ3 ADC_JSQR_JSQ3_Msk /*!< ADC 3rd conversion in injected sequence */ -#define ADC_JSQR_JSQ3_0 (0x01UL << ADC_JSQR_JSQ3_Pos) /*!< 0x00200000 */ -#define ADC_JSQR_JSQ3_1 (0x02UL << ADC_JSQR_JSQ3_Pos) /*!< 0x00400000 */ -#define ADC_JSQR_JSQ3_2 (0x04UL << ADC_JSQR_JSQ3_Pos) /*!< 0x00800000 */ -#define ADC_JSQR_JSQ3_3 (0x08UL << ADC_JSQR_JSQ3_Pos) /*!< 0x01000000 */ -#define ADC_JSQR_JSQ3_4 (0x10UL << ADC_JSQR_JSQ3_Pos) /*!< 0x02000000 */ - -#define ADC_JSQR_JSQ4_Pos (27U) -#define ADC_JSQR_JSQ4_Msk (0x1FUL << ADC_JSQR_JSQ4_Pos) /*!< 0xF8000000 */ -#define ADC_JSQR_JSQ4 ADC_JSQR_JSQ4_Msk /*!< ADC 4th conversion in injected sequence */ -#define ADC_JSQR_JSQ4_0 (0x01UL << ADC_JSQR_JSQ4_Pos) /*!< 0x08000000 */ -#define ADC_JSQR_JSQ4_1 (0x02UL << ADC_JSQR_JSQ4_Pos) /*!< 0x10000000 */ -#define ADC_JSQR_JSQ4_2 (0x04UL << ADC_JSQR_JSQ4_Pos) /*!< 0x20000000 */ -#define ADC_JSQR_JSQ4_3 (0x08UL << ADC_JSQR_JSQ4_Pos) /*!< 0x40000000 */ -#define ADC_JSQR_JSQ4_4 (0x10UL << ADC_JSQR_JSQ4_Pos) /*!< 0x80000000 */ - -/******************** Bit definition for ADC_OFR1 register ********************/ -#define ADC_OFR1_OFFSET1_Pos (0U) -#define ADC_OFR1_OFFSET1_Msk (0x3FFFFFFUL << ADC_OFR1_OFFSET1_Pos) /*!< 0x03FFFFFF */ -#define ADC_OFR1_OFFSET1 ADC_OFR1_OFFSET1_Msk /*!< ADC data offset 1 for channel programmed into bits OFFSET1_CH[4:0] */ -#define ADC_OFR1_OFFSET1_0 (0x0000001UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000001 */ -#define ADC_OFR1_OFFSET1_1 (0x0000002UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000002 */ -#define ADC_OFR1_OFFSET1_2 (0x0000004UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000004 */ -#define ADC_OFR1_OFFSET1_3 (0x0000008UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000008 */ -#define ADC_OFR1_OFFSET1_4 (0x0000010UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000010 */ -#define ADC_OFR1_OFFSET1_5 (0x0000020UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000020 */ -#define ADC_OFR1_OFFSET1_6 (0x0000040UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000040 */ -#define ADC_OFR1_OFFSET1_7 (0x0000080UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000080 */ -#define ADC_OFR1_OFFSET1_8 (0x0000100UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000100 */ -#define ADC_OFR1_OFFSET1_9 (0x0000200UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000200 */ -#define ADC_OFR1_OFFSET1_10 (0x0000400UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000400 */ -#define ADC_OFR1_OFFSET1_11 (0x0000800UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000800 */ -#define ADC_OFR1_OFFSET1_12 (0x0001000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00001000 */ -#define ADC_OFR1_OFFSET1_13 (0x0002000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00002000 */ -#define ADC_OFR1_OFFSET1_14 (0x0004000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00004000 */ -#define ADC_OFR1_OFFSET1_15 (0x0008000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00008000 */ -#define ADC_OFR1_OFFSET1_16 (0x0010000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00010000 */ -#define ADC_OFR1_OFFSET1_17 (0x0020000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00020000 */ -#define ADC_OFR1_OFFSET1_18 (0x0040000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00040000 */ -#define ADC_OFR1_OFFSET1_19 (0x0080000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00080000 */ -#define ADC_OFR1_OFFSET1_20 (0x0100000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00100000 */ -#define ADC_OFR1_OFFSET1_21 (0x0200000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00200000 */ -#define ADC_OFR1_OFFSET1_22 (0x0400000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00400000 */ -#define ADC_OFR1_OFFSET1_23 (0x0800000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00800000 */ -#define ADC_OFR1_OFFSET1_24 (0x1000000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x01000000 */ -#define ADC_OFR1_OFFSET1_25 (0x2000000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x02000000 */ - -#define ADC_OFR1_OFFSET1_CH_Pos (26U) -#define ADC_OFR1_OFFSET1_CH_Msk (0x1FUL << ADC_OFR1_OFFSET1_CH_Pos) /*!< 0x7C000000 */ -#define ADC_OFR1_OFFSET1_CH ADC_OFR1_OFFSET1_CH_Msk /*!< ADC Channel selection for the data offset 1 */ -#define ADC_OFR1_OFFSET1_CH_0 (0x01UL << ADC_OFR1_OFFSET1_CH_Pos) /*!< 0x04000000 */ -#define ADC_OFR1_OFFSET1_CH_1 (0x02UL << ADC_OFR1_OFFSET1_CH_Pos) /*!< 0x08000000 */ -#define ADC_OFR1_OFFSET1_CH_2 (0x04UL << ADC_OFR1_OFFSET1_CH_Pos) /*!< 0x10000000 */ -#define ADC_OFR1_OFFSET1_CH_3 (0x08UL << ADC_OFR1_OFFSET1_CH_Pos) /*!< 0x20000000 */ -#define ADC_OFR1_OFFSET1_CH_4 (0x10UL << ADC_OFR1_OFFSET1_CH_Pos) /*!< 0x40000000 */ - -#define ADC_OFR1_SSATE_Pos (31U) -#define ADC_OFR1_SSATE_Msk (0x1UL << ADC_OFR1_SSATE_Pos) /*!< 0x80000000 */ -#define ADC_OFR1_SSATE ADC_OFR1_SSATE_Msk /*!< ADC Signed saturation Enable */ - -#define ADC3_OFR1_OFFSET1_Pos (0U) -#define ADC3_OFR1_OFFSET1_Msk (0xFFFUL << ADC3_OFR1_OFFSET1_Pos) /*!< 0x00000FFF */ -#define ADC3_OFR1_OFFSET1 ADC3_OFR1_OFFSET1_Msk /*!< ADC data offset 1 for channel programmed into bits OFFSET1_CH[4:0] */ - -#define ADC3_OFR1_OFFSETPOS_Pos (24U) -#define ADC3_OFR1_OFFSETPOS_Msk (0x1UL << ADC3_OFR1_OFFSETPOS_Pos) /*!< 0x01000000 */ -#define ADC3_OFR1_OFFSETPOS ADC3_OFR1_OFFSETPOS_Msk /*!< ADC offset number 1 positive */ -#define ADC3_OFR1_SATEN_Pos (25U) -#define ADC3_OFR1_SATEN_Msk (0x1UL << ADC3_OFR1_SATEN_Pos) /*!< 0x02000000 */ -#define ADC3_OFR1_SATEN ADC3_OFR1_SATEN_Msk /*!< ADC offset number 1 saturation enable */ - -#define ADC3_OFR1_OFFSET1_EN_Pos (31U) -#define ADC3_OFR1_OFFSET1_EN_Msk (0x1UL << ADC3_OFR1_OFFSET1_EN_Pos) /*!< 0x80000000 */ -#define ADC3_OFR1_OFFSET1_EN ADC3_OFR1_OFFSET1_EN_Msk /*!< ADC offset number 1 enable */ - -/******************** Bit definition for ADC_OFR2 register ********************/ -#define ADC_OFR2_OFFSET2_Pos (0U) -#define ADC_OFR2_OFFSET2_Msk (0x3FFFFFFUL << ADC_OFR2_OFFSET2_Pos) /*!< 0x03FFFFFF */ -#define ADC_OFR2_OFFSET2 ADC_OFR2_OFFSET2_Msk /*!< ADC data offset 2 for channel programmed into bits OFFSET2_CH[4:0] */ -#define ADC_OFR2_OFFSET2_0 (0x0000001UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000001 */ -#define ADC_OFR2_OFFSET2_1 (0x0000002UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000002 */ -#define ADC_OFR2_OFFSET2_2 (0x0000004UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000004 */ -#define ADC_OFR2_OFFSET2_3 (0x0000008UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000008 */ -#define ADC_OFR2_OFFSET2_4 (0x0000010UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000010 */ -#define ADC_OFR2_OFFSET2_5 (0x0000020UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000020 */ -#define ADC_OFR2_OFFSET2_6 (0x0000040UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000040 */ -#define ADC_OFR2_OFFSET2_7 (0x0000080UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000080 */ -#define ADC_OFR2_OFFSET2_8 (0x0000100UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000100 */ -#define ADC_OFR2_OFFSET2_9 (0x0000200UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000200 */ -#define ADC_OFR2_OFFSET2_10 (0x0000400UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000400 */ -#define ADC_OFR2_OFFSET2_11 (0x0000800UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000800 */ -#define ADC_OFR2_OFFSET2_12 (0x0001000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00001000 */ -#define ADC_OFR2_OFFSET2_13 (0x0002000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00002000 */ -#define ADC_OFR2_OFFSET2_14 (0x0004000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00004000 */ -#define ADC_OFR2_OFFSET2_15 (0x0008000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00008000 */ -#define ADC_OFR2_OFFSET2_16 (0x0010000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00010000 */ -#define ADC_OFR2_OFFSET2_17 (0x0020000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00020000 */ -#define ADC_OFR2_OFFSET2_18 (0x0040000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00040000 */ -#define ADC_OFR2_OFFSET2_19 (0x0080000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00080000 */ -#define ADC_OFR2_OFFSET2_20 (0x0100000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00100000 */ -#define ADC_OFR2_OFFSET2_21 (0x0200000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00200000 */ -#define ADC_OFR2_OFFSET2_22 (0x0400000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00400000 */ -#define ADC_OFR2_OFFSET2_23 (0x0800000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00800000 */ -#define ADC_OFR2_OFFSET2_24 (0x1000000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x01000000 */ -#define ADC_OFR2_OFFSET2_25 (0x2000000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x02000000 */ - -#define ADC_OFR2_OFFSET2_CH_Pos (26U) -#define ADC_OFR2_OFFSET2_CH_Msk (0x1FUL << ADC_OFR2_OFFSET2_CH_Pos) /*!< 0x7C000000 */ -#define ADC_OFR2_OFFSET2_CH ADC_OFR2_OFFSET2_CH_Msk /*!< ADC Channel selection for the data offset 2 */ -#define ADC_OFR2_OFFSET2_CH_0 (0x01UL << ADC_OFR2_OFFSET2_CH_Pos) /*!< 0x04000000 */ -#define ADC_OFR2_OFFSET2_CH_1 (0x02UL << ADC_OFR2_OFFSET2_CH_Pos) /*!< 0x08000000 */ -#define ADC_OFR2_OFFSET2_CH_2 (0x04UL << ADC_OFR2_OFFSET2_CH_Pos) /*!< 0x10000000 */ -#define ADC_OFR2_OFFSET2_CH_3 (0x08UL << ADC_OFR2_OFFSET2_CH_Pos) /*!< 0x20000000 */ -#define ADC_OFR2_OFFSET2_CH_4 (0x10UL << ADC_OFR2_OFFSET2_CH_Pos) /*!< 0x40000000 */ - -#define ADC_OFR2_SSATE_Pos (31U) -#define ADC_OFR2_SSATE_Msk (0x1UL << ADC_OFR2_SSATE_Pos) /*!< 0x80000000 */ -#define ADC_OFR2_SSATE ADC_OFR2_SSATE_Msk /*!< ADC Signed saturation Enable */ - -#define ADC3_OFR2_OFFSET2_Pos (0U) -#define ADC3_OFR2_OFFSET2_Msk (0xFFFUL << ADC3_OFR2_OFFSET2_Pos) /*!< 0x00000FFF */ -#define ADC3_OFR2_OFFSET2 ADC3_OFR2_OFFSET2_Msk /*!< ADC data offset 2 for channel programmed into bits OFFSET1_CH[4:0] */ - -#define ADC3_OFR2_OFFSETPOS_Pos (24U) -#define ADC3_OFR2_OFFSETPOS_Msk (0x1UL << ADC3_OFR2_OFFSETPOS_Pos) /*!< 0x01000000 */ -#define ADC3_OFR2_OFFSETPOS ADC3_OFR2_OFFSETPOS_Msk /*!< ADC offset number 2 positive */ -#define ADC3_OFR2_SATEN_Pos (25U) -#define ADC3_OFR2_SATEN_Msk (0x1UL << ADC3_OFR2_SATEN_Pos) /*!< 0x02000000 */ -#define ADC3_OFR2_SATEN ADC3_OFR2_SATEN_Msk /*!< ADC offset number 2 saturation enable */ - -#define ADC3_OFR2_OFFSET2_EN_Pos (31U) -#define ADC3_OFR2_OFFSET2_EN_Msk (0x1UL << ADC3_OFR2_OFFSET2_EN_Pos) /*!< 0x80000000 */ -#define ADC3_OFR2_OFFSET2_EN ADC3_OFR2_OFFSET2_EN_Msk /*!< ADC offset number 2 enable */ - -/******************** Bit definition for ADC_OFR3 register ********************/ -#define ADC_OFR3_OFFSET3_Pos (0U) -#define ADC_OFR3_OFFSET3_Msk (0x3FFFFFFUL << ADC_OFR3_OFFSET3_Pos) /*!< 0x03FFFFFF */ -#define ADC_OFR3_OFFSET3 ADC_OFR3_OFFSET3_Msk /*!< ADC data offset 3 for channel programmed into bits OFFSET3_CH[4:0] */ -#define ADC_OFR3_OFFSET3_0 (0x0000001UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000001 */ -#define ADC_OFR3_OFFSET3_1 (0x0000002UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000002 */ -#define ADC_OFR3_OFFSET3_2 (0x0000004UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000004 */ -#define ADC_OFR3_OFFSET3_3 (0x0000008UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000008 */ -#define ADC_OFR3_OFFSET3_4 (0x0000010UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000010 */ -#define ADC_OFR3_OFFSET3_5 (0x0000020UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000020 */ -#define ADC_OFR3_OFFSET3_6 (0x0000040UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000040 */ -#define ADC_OFR3_OFFSET3_7 (0x0000080UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000080 */ -#define ADC_OFR3_OFFSET3_8 (0x0000100UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000100 */ -#define ADC_OFR3_OFFSET3_9 (0x0000200UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000200 */ -#define ADC_OFR3_OFFSET3_10 (0x0000400UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000400 */ -#define ADC_OFR3_OFFSET3_11 (0x0000800UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000800 */ -#define ADC_OFR3_OFFSET3_12 (0x0001000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00001000 */ -#define ADC_OFR3_OFFSET3_13 (0x0002000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00002000 */ -#define ADC_OFR3_OFFSET3_14 (0x0004000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00004000 */ -#define ADC_OFR3_OFFSET3_15 (0x0008000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00008000 */ -#define ADC_OFR3_OFFSET3_16 (0x0010000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00010000 */ -#define ADC_OFR3_OFFSET3_17 (0x0020000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00020000 */ -#define ADC_OFR3_OFFSET3_18 (0x0040000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00040000 */ -#define ADC_OFR3_OFFSET3_19 (0x0080000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00080000 */ -#define ADC_OFR3_OFFSET3_20 (0x0100000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00100000 */ -#define ADC_OFR3_OFFSET3_21 (0x0200000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00200000 */ -#define ADC_OFR3_OFFSET3_22 (0x0400000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00400000 */ -#define ADC_OFR3_OFFSET3_23 (0x0800000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00800000 */ -#define ADC_OFR3_OFFSET3_24 (0x1000000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x01000000 */ -#define ADC_OFR3_OFFSET3_25 (0x2000000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x02000000 */ - -#define ADC_OFR3_OFFSET3_CH_Pos (26U) -#define ADC_OFR3_OFFSET3_CH_Msk (0x1FUL << ADC_OFR3_OFFSET3_CH_Pos) /*!< 0x7C000000 */ -#define ADC_OFR3_OFFSET3_CH ADC_OFR3_OFFSET3_CH_Msk /*!< ADC Channel selection for the data offset 3 */ -#define ADC_OFR3_OFFSET3_CH_0 (0x01UL << ADC_OFR3_OFFSET3_CH_Pos) /*!< 0x04000000 */ -#define ADC_OFR3_OFFSET3_CH_1 (0x02UL << ADC_OFR3_OFFSET3_CH_Pos) /*!< 0x08000000 */ -#define ADC_OFR3_OFFSET3_CH_2 (0x04UL << ADC_OFR3_OFFSET3_CH_Pos) /*!< 0x10000000 */ -#define ADC_OFR3_OFFSET3_CH_3 (0x08UL << ADC_OFR3_OFFSET3_CH_Pos) /*!< 0x20000000 */ -#define ADC_OFR3_OFFSET3_CH_4 (0x10UL << ADC_OFR3_OFFSET3_CH_Pos) /*!< 0x40000000 */ - -#define ADC_OFR3_SSATE_Pos (31U) -#define ADC_OFR3_SSATE_Msk (0x1UL << ADC_OFR3_SSATE_Pos) /*!< 0x80000000 */ -#define ADC_OFR3_SSATE ADC_OFR3_SSATE_Msk /*!< ADC Signed saturation Enable */ - -#define ADC3_OFR3_OFFSET3_Pos (0U) -#define ADC3_OFR3_OFFSET3_Msk (0xFFFUL << ADC3_OFR3_OFFSET3_Pos) /*!< 0x00000FFF */ -#define ADC3_OFR3_OFFSET3 ADC3_OFR3_OFFSET3_Msk /*!< ADC data offset 3 for channel programmed into bits OFFSET1_CH[4:0] */ - -#define ADC3_OFR3_OFFSETPOS_Pos (24U) -#define ADC3_OFR3_OFFSETPOS_Msk (0x1UL << ADC3_OFR3_OFFSETPOS_Pos) /*!< 0x01000000 */ -#define ADC3_OFR3_OFFSETPOS ADC3_OFR3_OFFSETPOS_Msk /*!< ADC offset number 3 positive */ -#define ADC3_OFR3_SATEN_Pos (25U) -#define ADC3_OFR3_SATEN_Msk (0x1UL << ADC3_OFR3_SATEN_Pos) /*!< 0x02000000 */ -#define ADC3_OFR3_SATEN ADC3_OFR3_SATEN_Msk /*!< ADC offset number 3 saturation enable */ - -#define ADC3_OFR3_OFFSET3_EN_Pos (31U) -#define ADC3_OFR3_OFFSET3_EN_Msk (0x1UL << ADC3_OFR3_OFFSET3_EN_Pos) /*!< 0x80000000 */ -#define ADC3_OFR3_OFFSET3_EN ADC3_OFR3_OFFSET3_EN_Msk /*!< ADC offset number 3 enable */ - -/******************** Bit definition for ADC_OFR4 register ********************/ -#define ADC_OFR4_OFFSET4_Pos (0U) -#define ADC_OFR4_OFFSET4_Msk (0x3FFFFFFUL << ADC_OFR4_OFFSET4_Pos) /*!< 0x03FFFFFF */ -#define ADC_OFR4_OFFSET4 ADC_OFR4_OFFSET4_Msk /*!< ADC data offset 4 for channel programmed into bits OFFSET4_CH[4:0] */ -#define ADC_OFR4_OFFSET4_0 (0x0000001UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000001 */ -#define ADC_OFR4_OFFSET4_1 (0x0000002UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000002 */ -#define ADC_OFR4_OFFSET4_2 (0x0000004UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000004 */ -#define ADC_OFR4_OFFSET4_3 (0x0000008UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000008 */ -#define ADC_OFR4_OFFSET4_4 (0x0000010UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000010 */ -#define ADC_OFR4_OFFSET4_5 (0x0000020UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000020 */ -#define ADC_OFR4_OFFSET4_6 (0x0000040UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000040 */ -#define ADC_OFR4_OFFSET4_7 (0x0000080UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000080 */ -#define ADC_OFR4_OFFSET4_8 (0x0000100UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000100 */ -#define ADC_OFR4_OFFSET4_9 (0x0000200UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000200 */ -#define ADC_OFR4_OFFSET4_10 (0x0000400UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000400 */ -#define ADC_OFR4_OFFSET4_11 (0x0000800UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000800 */ -#define ADC_OFR4_OFFSET4_12 (0x0001000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00001000 */ -#define ADC_OFR4_OFFSET4_13 (0x0002000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00002000 */ -#define ADC_OFR4_OFFSET4_14 (0x0004000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00004000 */ -#define ADC_OFR4_OFFSET4_15 (0x0008000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00008000 */ -#define ADC_OFR4_OFFSET4_16 (0x0010000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00010000 */ -#define ADC_OFR4_OFFSET4_17 (0x0020000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00020000 */ -#define ADC_OFR4_OFFSET4_18 (0x0040000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00040000 */ -#define ADC_OFR4_OFFSET4_19 (0x0080000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00080000 */ -#define ADC_OFR4_OFFSET4_20 (0x0100000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00100000 */ -#define ADC_OFR4_OFFSET4_21 (0x0200000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00200000 */ -#define ADC_OFR4_OFFSET4_22 (0x0400000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00400000 */ -#define ADC_OFR4_OFFSET4_23 (0x0800000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00800000 */ -#define ADC_OFR4_OFFSET4_24 (0x1000000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x01000000 */ -#define ADC_OFR4_OFFSET4_25 (0x2000000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x02000000 */ - -#define ADC_OFR4_OFFSET4_CH_Pos (26U) -#define ADC_OFR4_OFFSET4_CH_Msk (0x1FUL << ADC_OFR4_OFFSET4_CH_Pos) /*!< 0x7C000000 */ -#define ADC_OFR4_OFFSET4_CH ADC_OFR4_OFFSET4_CH_Msk /*!< ADC Channel selection for the data offset 4 */ -#define ADC_OFR4_OFFSET4_CH_0 (0x01UL << ADC_OFR4_OFFSET4_CH_Pos) /*!< 0x04000000 */ -#define ADC_OFR4_OFFSET4_CH_1 (0x02UL << ADC_OFR4_OFFSET4_CH_Pos) /*!< 0x08000000 */ -#define ADC_OFR4_OFFSET4_CH_2 (0x04UL << ADC_OFR4_OFFSET4_CH_Pos) /*!< 0x10000000 */ -#define ADC_OFR4_OFFSET4_CH_3 (0x08UL << ADC_OFR4_OFFSET4_CH_Pos) /*!< 0x20000000 */ -#define ADC_OFR4_OFFSET4_CH_4 (0x10UL << ADC_OFR4_OFFSET4_CH_Pos) /*!< 0x40000000 */ - -#define ADC_OFR4_SSATE_Pos (31U) -#define ADC_OFR4_SSATE_Msk (0x1UL << ADC_OFR4_SSATE_Pos) /*!< 0x80000000 */ -#define ADC_OFR4_SSATE ADC_OFR4_SSATE_Msk /*!< ADC Signed saturation Enable */ - -#define ADC3_OFR4_OFFSET4_Pos (0U) -#define ADC3_OFR4_OFFSET4_Msk (0xFFFUL << ADC3_OFR4_OFFSET4_Pos) /*!< 0x00000FFF */ -#define ADC3_OFR4_OFFSET4 ADC3_OFR4_OFFSET4_Msk /*!< ADC data offset 4 for channel programmed into bits OFFSET1_CH[4:0] */ - -#define ADC3_OFR4_OFFSETPOS_Pos (24U) -#define ADC3_OFR4_OFFSETPOS_Msk (0x1UL << ADC3_OFR4_OFFSETPOS_Pos) /*!< 0x01000000 */ -#define ADC3_OFR4_OFFSETPOS ADC3_OFR4_OFFSETPOS_Msk /*!< ADC offset number 4 positive */ -#define ADC3_OFR4_SATEN_Pos (25U) -#define ADC3_OFR4_SATEN_Msk (0x1UL << ADC3_OFR4_SATEN_Pos) /*!< 0x02000000 */ -#define ADC3_OFR4_SATEN ADC3_OFR4_SATEN_Msk /*!< ADC offset number 4 saturation enable */ - -#define ADC3_OFR4_OFFSET4_EN_Pos (31U) -#define ADC3_OFR4_OFFSET4_EN_Msk (0x1UL << ADC3_OFR4_OFFSET4_EN_Pos) /*!< 0x80000000 */ -#define ADC3_OFR4_OFFSET4_EN ADC3_OFR4_OFFSET4_EN_Msk /*!< ADC offset number 4 enable */ - -/******************** Bit definition for ADC_JDR1 register ********************/ -#define ADC_JDR1_JDATA_Pos (0U) -#define ADC_JDR1_JDATA_Msk (0xFFFFFFFFUL << ADC_JDR1_JDATA_Pos) /*!< 0xFFFFFFFF */ -#define ADC_JDR1_JDATA ADC_JDR1_JDATA_Msk /*!< ADC Injected DATA */ -#define ADC_JDR1_JDATA_0 (0x00000001UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000001 */ -#define ADC_JDR1_JDATA_1 (0x00000002UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000002 */ -#define ADC_JDR1_JDATA_2 (0x00000004UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000004 */ -#define ADC_JDR1_JDATA_3 (0x00000008UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000008 */ -#define ADC_JDR1_JDATA_4 (0x00000010UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000010 */ -#define ADC_JDR1_JDATA_5 (0x00000020UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000020 */ -#define ADC_JDR1_JDATA_6 (0x00000040UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000040 */ -#define ADC_JDR1_JDATA_7 (0x00000080UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000080 */ -#define ADC_JDR1_JDATA_8 (0x00000100UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000100 */ -#define ADC_JDR1_JDATA_9 (0x00000200UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000200 */ -#define ADC_JDR1_JDATA_10 (0x00000400UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000400 */ -#define ADC_JDR1_JDATA_11 (0x00000800UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000800 */ -#define ADC_JDR1_JDATA_12 (0x00001000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00001000 */ -#define ADC_JDR1_JDATA_13 (0x00002000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00002000 */ -#define ADC_JDR1_JDATA_14 (0x00004000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00004000 */ -#define ADC_JDR1_JDATA_15 (0x00008000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00008000 */ -#define ADC_JDR1_JDATA_16 (0x00010000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00010000 */ -#define ADC_JDR1_JDATA_17 (0x00020000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00020000 */ -#define ADC_JDR1_JDATA_18 (0x00040000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00040000 */ -#define ADC_JDR1_JDATA_19 (0x00080000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00080000 */ -#define ADC_JDR1_JDATA_20 (0x00100000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00100000 */ -#define ADC_JDR1_JDATA_21 (0x00200000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00200000 */ -#define ADC_JDR1_JDATA_22 (0x00400000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00400000 */ -#define ADC_JDR1_JDATA_23 (0x00800000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00800000 */ -#define ADC_JDR1_JDATA_24 (0x01000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x01000000 */ -#define ADC_JDR1_JDATA_25 (0x02000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x02000000 */ -#define ADC_JDR1_JDATA_26 (0x04000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x04000000 */ -#define ADC_JDR1_JDATA_27 (0x08000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x08000000 */ -#define ADC_JDR1_JDATA_28 (0x10000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x10000000 */ -#define ADC_JDR1_JDATA_29 (0x20000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x20000000 */ -#define ADC_JDR1_JDATA_30 (0x40000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x40000000 */ -#define ADC_JDR1_JDATA_31 (0x80000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x80000000 */ - -/******************** Bit definition for ADC_JDR2 register ********************/ -#define ADC_JDR2_JDATA_Pos (0U) -#define ADC_JDR2_JDATA_Msk (0xFFFFFFFFUL << ADC_JDR2_JDATA_Pos) /*!< 0xFFFFFFFF */ -#define ADC_JDR2_JDATA ADC_JDR2_JDATA_Msk /*!< ADC Injected DATA */ -#define ADC_JDR2_JDATA_0 (0x00000001UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000001 */ -#define ADC_JDR2_JDATA_1 (0x00000002UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000002 */ -#define ADC_JDR2_JDATA_2 (0x00000004UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000004 */ -#define ADC_JDR2_JDATA_3 (0x00000008UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000008 */ -#define ADC_JDR2_JDATA_4 (0x00000010UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000010 */ -#define ADC_JDR2_JDATA_5 (0x00000020UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000020 */ -#define ADC_JDR2_JDATA_6 (0x00000040UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000040 */ -#define ADC_JDR2_JDATA_7 (0x00000080UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000080 */ -#define ADC_JDR2_JDATA_8 (0x00000100UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000100 */ -#define ADC_JDR2_JDATA_9 (0x00000200UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000200 */ -#define ADC_JDR2_JDATA_10 (0x00000400UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000400 */ -#define ADC_JDR2_JDATA_11 (0x00000800UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000800 */ -#define ADC_JDR2_JDATA_12 (0x00001000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00001000 */ -#define ADC_JDR2_JDATA_13 (0x00002000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00002000 */ -#define ADC_JDR2_JDATA_14 (0x00004000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00004000 */ -#define ADC_JDR2_JDATA_15 (0x00008000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00008000 */ -#define ADC_JDR2_JDATA_16 (0x00010000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00010000 */ -#define ADC_JDR2_JDATA_17 (0x00020000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00020000 */ -#define ADC_JDR2_JDATA_18 (0x00040000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00040000 */ -#define ADC_JDR2_JDATA_19 (0x00080000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00080000 */ -#define ADC_JDR2_JDATA_20 (0x00100000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00100000 */ -#define ADC_JDR2_JDATA_21 (0x00200000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00200000 */ -#define ADC_JDR2_JDATA_22 (0x00400000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00400000 */ -#define ADC_JDR2_JDATA_23 (0x00800000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00800000 */ -#define ADC_JDR2_JDATA_24 (0x01000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x01000000 */ -#define ADC_JDR2_JDATA_25 (0x02000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x02000000 */ -#define ADC_JDR2_JDATA_26 (0x04000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x04000000 */ -#define ADC_JDR2_JDATA_27 (0x08000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x08000000 */ -#define ADC_JDR2_JDATA_28 (0x10000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x10000000 */ -#define ADC_JDR2_JDATA_29 (0x20000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x20000000 */ -#define ADC_JDR2_JDATA_30 (0x40000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x40000000 */ -#define ADC_JDR2_JDATA_31 (0x80000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x80000000 */ - -/******************** Bit definition for ADC_JDR3 register ********************/ -#define ADC_JDR3_JDATA_Pos (0U) -#define ADC_JDR3_JDATA_Msk (0xFFFFFFFFUL << ADC_JDR3_JDATA_Pos) /*!< 0xFFFFFFFF */ -#define ADC_JDR3_JDATA ADC_JDR3_JDATA_Msk /*!< ADC Injected DATA */ -#define ADC_JDR3_JDATA_0 (0x00000001UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000001 */ -#define ADC_JDR3_JDATA_1 (0x00000002UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000002 */ -#define ADC_JDR3_JDATA_2 (0x00000004UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000004 */ -#define ADC_JDR3_JDATA_3 (0x00000008UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000008 */ -#define ADC_JDR3_JDATA_4 (0x00000010UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000010 */ -#define ADC_JDR3_JDATA_5 (0x00000020UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000020 */ -#define ADC_JDR3_JDATA_6 (0x00000040UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000040 */ -#define ADC_JDR3_JDATA_7 (0x00000080UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000080 */ -#define ADC_JDR3_JDATA_8 (0x00000100UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000100 */ -#define ADC_JDR3_JDATA_9 (0x00000200UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000200 */ -#define ADC_JDR3_JDATA_10 (0x00000400UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000400 */ -#define ADC_JDR3_JDATA_11 (0x00000800UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000800 */ -#define ADC_JDR3_JDATA_12 (0x00001000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00001000 */ -#define ADC_JDR3_JDATA_13 (0x00002000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00002000 */ -#define ADC_JDR3_JDATA_14 (0x00004000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00004000 */ -#define ADC_JDR3_JDATA_15 (0x00008000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00008000 */ -#define ADC_JDR3_JDATA_16 (0x00010000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00010000 */ -#define ADC_JDR3_JDATA_17 (0x00020000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00020000 */ -#define ADC_JDR3_JDATA_18 (0x00040000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00040000 */ -#define ADC_JDR3_JDATA_19 (0x00080000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00080000 */ -#define ADC_JDR3_JDATA_20 (0x00100000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00100000 */ -#define ADC_JDR3_JDATA_21 (0x00200000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00200000 */ -#define ADC_JDR3_JDATA_22 (0x00400000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00400000 */ -#define ADC_JDR3_JDATA_23 (0x00800000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00800000 */ -#define ADC_JDR3_JDATA_24 (0x01000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x01000000 */ -#define ADC_JDR3_JDATA_25 (0x02000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x02000000 */ -#define ADC_JDR3_JDATA_26 (0x04000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x04000000 */ -#define ADC_JDR3_JDATA_27 (0x08000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x08000000 */ -#define ADC_JDR3_JDATA_28 (0x10000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x10000000 */ -#define ADC_JDR3_JDATA_29 (0x20000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x20000000 */ -#define ADC_JDR3_JDATA_30 (0x40000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x40000000 */ -#define ADC_JDR3_JDATA_31 (0x80000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x80000000 */ - -/******************** Bit definition for ADC_JDR4 register ********************/ -#define ADC_JDR4_JDATA_Pos (0U) -#define ADC_JDR4_JDATA_Msk (0xFFFFFFFFUL << ADC_JDR4_JDATA_Pos) /*!< 0xFFFFFFFF */ -#define ADC_JDR4_JDATA ADC_JDR4_JDATA_Msk /*!< ADC Injected DATA */ -#define ADC_JDR4_JDATA_0 (0x00000001UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000001 */ -#define ADC_JDR4_JDATA_1 (0x00000002UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000002 */ -#define ADC_JDR4_JDATA_2 (0x00000004UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000004 */ -#define ADC_JDR4_JDATA_3 (0x00000008UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000008 */ -#define ADC_JDR4_JDATA_4 (0x00000010UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000010 */ -#define ADC_JDR4_JDATA_5 (0x00000020UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000020 */ -#define ADC_JDR4_JDATA_6 (0x00000040UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000040 */ -#define ADC_JDR4_JDATA_7 (0x00000080UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000080 */ -#define ADC_JDR4_JDATA_8 (0x00000100UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000100 */ -#define ADC_JDR4_JDATA_9 (0x00000200UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000200 */ -#define ADC_JDR4_JDATA_10 (0x00000400UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000400 */ -#define ADC_JDR4_JDATA_11 (0x00000800UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000800 */ -#define ADC_JDR4_JDATA_12 (0x00001000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00001000 */ -#define ADC_JDR4_JDATA_13 (0x00002000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00002000 */ -#define ADC_JDR4_JDATA_14 (0x00004000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00004000 */ -#define ADC_JDR4_JDATA_15 (0x00008000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00008000 */ -#define ADC_JDR4_JDATA_16 (0x00010000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00010000 */ -#define ADC_JDR4_JDATA_17 (0x00020000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00020000 */ -#define ADC_JDR4_JDATA_18 (0x00040000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00040000 */ -#define ADC_JDR4_JDATA_19 (0x00080000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00080000 */ -#define ADC_JDR4_JDATA_20 (0x00100000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00100000 */ -#define ADC_JDR4_JDATA_21 (0x00200000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00200000 */ -#define ADC_JDR4_JDATA_22 (0x00400000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00400000 */ -#define ADC_JDR4_JDATA_23 (0x00800000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00800000 */ -#define ADC_JDR4_JDATA_24 (0x01000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x01000000 */ -#define ADC_JDR4_JDATA_25 (0x02000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x02000000 */ -#define ADC_JDR4_JDATA_26 (0x04000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x04000000 */ -#define ADC_JDR4_JDATA_27 (0x08000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x08000000 */ -#define ADC_JDR4_JDATA_28 (0x10000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x10000000 */ -#define ADC_JDR4_JDATA_29 (0x20000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x20000000 */ -#define ADC_JDR4_JDATA_30 (0x40000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x40000000 */ -#define ADC_JDR4_JDATA_31 (0x80000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x80000000 */ - -/******************** Bit definition for ADC_AWD2CR register ********************/ -#define ADC_AWD2CR_AWD2CH_Pos (0U) -#define ADC_AWD2CR_AWD2CH_Msk (0xFFFFFUL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x000FFFFF */ -#define ADC_AWD2CR_AWD2CH ADC_AWD2CR_AWD2CH_Msk /*!< ADC Analog watchdog 2 channel selection */ -#define ADC_AWD2CR_AWD2CH_0 (0x00001UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000001 */ -#define ADC_AWD2CR_AWD2CH_1 (0x00002UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000002 */ -#define ADC_AWD2CR_AWD2CH_2 (0x00004UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000004 */ -#define ADC_AWD2CR_AWD2CH_3 (0x00008UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000008 */ -#define ADC_AWD2CR_AWD2CH_4 (0x00010UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000010 */ -#define ADC_AWD2CR_AWD2CH_5 (0x00020UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000020 */ -#define ADC_AWD2CR_AWD2CH_6 (0x00040UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000040 */ -#define ADC_AWD2CR_AWD2CH_7 (0x00080UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000080 */ -#define ADC_AWD2CR_AWD2CH_8 (0x00100UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000100 */ -#define ADC_AWD2CR_AWD2CH_9 (0x00200UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000200 */ -#define ADC_AWD2CR_AWD2CH_10 (0x00400UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000400 */ -#define ADC_AWD2CR_AWD2CH_11 (0x00800UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000800 */ -#define ADC_AWD2CR_AWD2CH_12 (0x01000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00001000 */ -#define ADC_AWD2CR_AWD2CH_13 (0x02000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00002000 */ -#define ADC_AWD2CR_AWD2CH_14 (0x04000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00004000 */ -#define ADC_AWD2CR_AWD2CH_15 (0x08000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00008000 */ -#define ADC_AWD2CR_AWD2CH_16 (0x10000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00010000 */ -#define ADC_AWD2CR_AWD2CH_17 (0x20000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00020000 */ -#define ADC_AWD2CR_AWD2CH_18 (0x40000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00040000 */ -#define ADC_AWD2CR_AWD2CH_19 (0x80000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00080000 */ - -/******************** Bit definition for ADC_AWD3CR register ********************/ -#define ADC_AWD3CR_AWD3CH_Pos (0U) -#define ADC_AWD3CR_AWD3CH_Msk (0xFFFFFUL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x000FFFFF */ -#define ADC_AWD3CR_AWD3CH ADC_AWD3CR_AWD3CH_Msk /*!< ADC Analog watchdog 2 channel selection */ -#define ADC_AWD3CR_AWD3CH_0 (0x00001UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000001 */ -#define ADC_AWD3CR_AWD3CH_1 (0x00002UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000002 */ -#define ADC_AWD3CR_AWD3CH_2 (0x00004UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000004 */ -#define ADC_AWD3CR_AWD3CH_3 (0x00008UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000008 */ -#define ADC_AWD3CR_AWD3CH_4 (0x00010UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000010 */ -#define ADC_AWD3CR_AWD3CH_5 (0x00020UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000020 */ -#define ADC_AWD3CR_AWD3CH_6 (0x00040UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000040 */ -#define ADC_AWD3CR_AWD3CH_7 (0x00080UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000080 */ -#define ADC_AWD3CR_AWD3CH_8 (0x00100UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000100 */ -#define ADC_AWD3CR_AWD3CH_9 (0x00200UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000200 */ -#define ADC_AWD3CR_AWD3CH_10 (0x00400UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000400 */ -#define ADC_AWD3CR_AWD3CH_11 (0x00800UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000800 */ -#define ADC_AWD3CR_AWD3CH_12 (0x01000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00001000 */ -#define ADC_AWD3CR_AWD3CH_13 (0x02000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00002000 */ -#define ADC_AWD3CR_AWD3CH_14 (0x04000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00004000 */ -#define ADC_AWD3CR_AWD3CH_15 (0x08000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00008000 */ -#define ADC_AWD3CR_AWD3CH_16 (0x10000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00010000 */ -#define ADC_AWD3CR_AWD3CH_17 (0x20000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00020000 */ -#define ADC_AWD3CR_AWD3CH_18 (0x40000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00040000 */ -#define ADC_AWD3CR_AWD3CH_19 (0x80000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00080000 */ - -/******************** Bit definition for ADC_DIFSEL register ********************/ -#define ADC_DIFSEL_DIFSEL_Pos (0U) -#define ADC_DIFSEL_DIFSEL_Msk (0xFFFFFUL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x000FFFFF */ -#define ADC_DIFSEL_DIFSEL ADC_DIFSEL_DIFSEL_Msk /*!< ADC differential modes for channels 1 to 18 */ -#define ADC_DIFSEL_DIFSEL_0 (0x00001UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000001 */ -#define ADC_DIFSEL_DIFSEL_1 (0x00002UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000002 */ -#define ADC_DIFSEL_DIFSEL_2 (0x00004UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000004 */ -#define ADC_DIFSEL_DIFSEL_3 (0x00008UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000008 */ -#define ADC_DIFSEL_DIFSEL_4 (0x00010UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000010 */ -#define ADC_DIFSEL_DIFSEL_5 (0x00020UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000020 */ -#define ADC_DIFSEL_DIFSEL_6 (0x00040UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000040 */ -#define ADC_DIFSEL_DIFSEL_7 (0x00080UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000080 */ -#define ADC_DIFSEL_DIFSEL_8 (0x00100UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000100 */ -#define ADC_DIFSEL_DIFSEL_9 (0x00200UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000200 */ -#define ADC_DIFSEL_DIFSEL_10 (0x00400UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000400 */ -#define ADC_DIFSEL_DIFSEL_11 (0x00800UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000800 */ -#define ADC_DIFSEL_DIFSEL_12 (0x01000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00001000 */ -#define ADC_DIFSEL_DIFSEL_13 (0x02000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00002000 */ -#define ADC_DIFSEL_DIFSEL_14 (0x04000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00004000 */ -#define ADC_DIFSEL_DIFSEL_15 (0x08000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00008000 */ -#define ADC_DIFSEL_DIFSEL_16 (0x10000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00010000 */ -#define ADC_DIFSEL_DIFSEL_17 (0x20000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00020000 */ -#define ADC_DIFSEL_DIFSEL_18 (0x40000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00040000 */ -#define ADC_DIFSEL_DIFSEL_19 (0x80000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00080000 */ - -/******************** Bit definition for ADC_CALFACT register ********************/ -#define ADC_CALFACT_CALFACT_S_Pos (0U) -#define ADC_CALFACT_CALFACT_S_Msk (0x7FFUL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x000007FF */ -#define ADC_CALFACT_CALFACT_S ADC_CALFACT_CALFACT_S_Msk /*!< ADC calibration factors in single-ended mode */ -#define ADC_CALFACT_CALFACT_S_0 (0x001UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000001 */ -#define ADC_CALFACT_CALFACT_S_1 (0x002UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000002 */ -#define ADC_CALFACT_CALFACT_S_2 (0x004UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000004 */ -#define ADC_CALFACT_CALFACT_S_3 (0x008UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000008 */ -#define ADC_CALFACT_CALFACT_S_4 (0x010UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000010 */ -#define ADC_CALFACT_CALFACT_S_5 (0x020UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000020 */ -#define ADC_CALFACT_CALFACT_S_6 (0x040UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000040 */ -#define ADC_CALFACT_CALFACT_S_7 (0x080UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000080 */ -#define ADC_CALFACT_CALFACT_S_8 (0x100UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000100 */ -#define ADC_CALFACT_CALFACT_S_9 (0x200UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000200 */ -#define ADC_CALFACT_CALFACT_S_10 (0x400UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000400 */ -#define ADC_CALFACT_CALFACT_D_Pos (16U) -#define ADC_CALFACT_CALFACT_D_Msk (0x7FFUL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x07FF0000 */ -#define ADC_CALFACT_CALFACT_D ADC_CALFACT_CALFACT_D_Msk /*!< ADC calibration factors in differential mode */ -#define ADC_CALFACT_CALFACT_D_0 (0x001UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00010000 */ -#define ADC_CALFACT_CALFACT_D_1 (0x002UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00020000 */ -#define ADC_CALFACT_CALFACT_D_2 (0x004UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00040000 */ -#define ADC_CALFACT_CALFACT_D_3 (0x008UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00080000 */ -#define ADC_CALFACT_CALFACT_D_4 (0x010UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00100000 */ -#define ADC_CALFACT_CALFACT_D_5 (0x020UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00200000 */ -#define ADC_CALFACT_CALFACT_D_6 (0x040UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00400000 */ -#define ADC_CALFACT_CALFACT_D_7 (0x080UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00800000 */ -#define ADC_CALFACT_CALFACT_D_8 (0x100UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x01000000 */ -#define ADC_CALFACT_CALFACT_D_9 (0x200UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x02000000 */ -#define ADC_CALFACT_CALFACT_D_10 (0x400UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x04000000 */ - -/******************** Bit definition for ADC_CALFACT2 register ********************/ -#define ADC_CALFACT2_LINCALFACT_Pos (0U) -#define ADC_CALFACT2_LINCALFACT_Msk (0x3FFFFFFFUL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x3FFFFFFF */ -#define ADC_CALFACT2_LINCALFACT ADC_CALFACT2_LINCALFACT_Msk /*!< ADC Linearity calibration factors */ -#define ADC_CALFACT2_LINCALFACT_0 (0x00000001UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000001 */ -#define ADC_CALFACT2_LINCALFACT_1 (0x00000002UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000002 */ -#define ADC_CALFACT2_LINCALFACT_2 (0x00000004UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000004 */ -#define ADC_CALFACT2_LINCALFACT_3 (0x00000008UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000008 */ -#define ADC_CALFACT2_LINCALFACT_4 (0x00000010UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000010 */ -#define ADC_CALFACT2_LINCALFACT_5 (0x00000020UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000020 */ -#define ADC_CALFACT2_LINCALFACT_6 (0x00000040UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000040 */ -#define ADC_CALFACT2_LINCALFACT_7 (0x00000080UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000080 */ -#define ADC_CALFACT2_LINCALFACT_8 (0x00000100UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000100 */ -#define ADC_CALFACT2_LINCALFACT_9 (0x00000200UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000200 */ -#define ADC_CALFACT2_LINCALFACT_10 (0x00000400UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000400 */ -#define ADC_CALFACT2_LINCALFACT_11 (0x00000800UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000800 */ -#define ADC_CALFACT2_LINCALFACT_12 (0x00001000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00001000 */ -#define ADC_CALFACT2_LINCALFACT_13 (0x00002000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00002000 */ -#define ADC_CALFACT2_LINCALFACT_14 (0x00004000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00004000 */ -#define ADC_CALFACT2_LINCALFACT_15 (0x00008000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00008000 */ -#define ADC_CALFACT2_LINCALFACT_16 (0x00010000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00010000 */ -#define ADC_CALFACT2_LINCALFACT_17 (0x00020000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00020000 */ -#define ADC_CALFACT2_LINCALFACT_18 (0x00040000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00040000 */ -#define ADC_CALFACT2_LINCALFACT_19 (0x00080000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00080000 */ -#define ADC_CALFACT2_LINCALFACT_20 (0x00100000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00100000 */ -#define ADC_CALFACT2_LINCALFACT_21 (0x00200000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00200000 */ -#define ADC_CALFACT2_LINCALFACT_22 (0x00400000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00400000 */ -#define ADC_CALFACT2_LINCALFACT_23 (0x00800000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00800000 */ -#define ADC_CALFACT2_LINCALFACT_24 (0x01000000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x01000000 */ -#define ADC_CALFACT2_LINCALFACT_25 (0x02000000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x02000000 */ -#define ADC_CALFACT2_LINCALFACT_26 (0x04000000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x04000000 */ -#define ADC_CALFACT2_LINCALFACT_27 (0x08000000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x08000000 */ -#define ADC_CALFACT2_LINCALFACT_28 (0x10000000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x10000000 */ -#define ADC_CALFACT2_LINCALFACT_29 (0x20000000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x20000000 */ - -/************************* ADC Common registers *****************************/ -/******************** Bit definition for ADC_CSR register ********************/ -#define ADC_CSR_ADRDY_MST_Pos (0U) -#define ADC_CSR_ADRDY_MST_Msk (0x1UL << ADC_CSR_ADRDY_MST_Pos) /*!< 0x00000001 */ -#define ADC_CSR_ADRDY_MST ADC_CSR_ADRDY_MST_Msk /*!< Master ADC ready */ -#define ADC_CSR_EOSMP_MST_Pos (1U) -#define ADC_CSR_EOSMP_MST_Msk (0x1UL << ADC_CSR_EOSMP_MST_Pos) /*!< 0x00000002 */ -#define ADC_CSR_EOSMP_MST ADC_CSR_EOSMP_MST_Msk /*!< End of sampling phase flag of the master ADC */ -#define ADC_CSR_EOC_MST_Pos (2U) -#define ADC_CSR_EOC_MST_Msk (0x1UL << ADC_CSR_EOC_MST_Pos) /*!< 0x00000004 */ -#define ADC_CSR_EOC_MST ADC_CSR_EOC_MST_Msk /*!< End of regular conversion of the master ADC */ -#define ADC_CSR_EOS_MST_Pos (3U) -#define ADC_CSR_EOS_MST_Msk (0x1UL << ADC_CSR_EOS_MST_Pos) /*!< 0x00000008 */ -#define ADC_CSR_EOS_MST ADC_CSR_EOS_MST_Msk /*!< End of regular sequence flag of the master ADC */ -#define ADC_CSR_OVR_MST_Pos (4U) -#define ADC_CSR_OVR_MST_Msk (0x1UL << ADC_CSR_OVR_MST_Pos) /*!< 0x00000010 */ -#define ADC_CSR_OVR_MST ADC_CSR_OVR_MST_Msk /*!< Overrun flag of the master ADC */ -#define ADC_CSR_JEOC_MST_Pos (5U) -#define ADC_CSR_JEOC_MST_Msk (0x1UL << ADC_CSR_JEOC_MST_Pos) /*!< 0x00000020 */ -#define ADC_CSR_JEOC_MST ADC_CSR_JEOC_MST_Msk /*!< End of injected conversion of the master ADC */ -#define ADC_CSR_JEOS_MST_Pos (6U) -#define ADC_CSR_JEOS_MST_Msk (0x1UL << ADC_CSR_JEOS_MST_Pos) /*!< 0x00000040 */ -#define ADC_CSR_JEOS_MST ADC_CSR_JEOS_MST_Msk /*!< End of injected sequence flag of the master ADC */ -#define ADC_CSR_AWD1_MST_Pos (7U) -#define ADC_CSR_AWD1_MST_Msk (0x1UL << ADC_CSR_AWD1_MST_Pos) /*!< 0x00000080 */ -#define ADC_CSR_AWD1_MST ADC_CSR_AWD1_MST_Msk /*!< Analog watchdog 1 flag of the master ADC */ -#define ADC_CSR_AWD2_MST_Pos (8U) -#define ADC_CSR_AWD2_MST_Msk (0x1UL << ADC_CSR_AWD2_MST_Pos) /*!< 0x00000100 */ -#define ADC_CSR_AWD2_MST ADC_CSR_AWD2_MST_Msk /*!< Analog watchdog 2 flag of the master ADC */ -#define ADC_CSR_AWD3_MST_Pos (9U) -#define ADC_CSR_AWD3_MST_Msk (0x1UL << ADC_CSR_AWD3_MST_Pos) /*!< 0x00000200 */ -#define ADC_CSR_AWD3_MST ADC_CSR_AWD3_MST_Msk /*!< Analog watchdog 3 flag of the master ADC */ -#define ADC_CSR_JQOVF_MST_Pos (10U) -#define ADC_CSR_JQOVF_MST_Msk (0x1UL << ADC_CSR_JQOVF_MST_Pos) /*!< 0x00000400 */ -#define ADC_CSR_JQOVF_MST ADC_CSR_JQOVF_MST_Msk /*!< Injected context queue overflow flag of the master ADC */ -#define ADC_CSR_ADRDY_SLV_Pos (16U) -#define ADC_CSR_ADRDY_SLV_Msk (0x1UL << ADC_CSR_ADRDY_SLV_Pos) /*!< 0x00010000 */ -#define ADC_CSR_ADRDY_SLV ADC_CSR_ADRDY_SLV_Msk /*!< Slave ADC ready */ -#define ADC_CSR_EOSMP_SLV_Pos (17U) -#define ADC_CSR_EOSMP_SLV_Msk (0x1UL << ADC_CSR_EOSMP_SLV_Pos) /*!< 0x00020000 */ -#define ADC_CSR_EOSMP_SLV ADC_CSR_EOSMP_SLV_Msk /*!< End of sampling phase flag of the slave ADC */ -#define ADC_CSR_EOC_SLV_Pos (18U) -#define ADC_CSR_EOC_SLV_Msk (0x1UL << ADC_CSR_EOC_SLV_Pos) /*!< 0x00040000 */ -#define ADC_CSR_EOC_SLV ADC_CSR_EOC_SLV_Msk /*!< End of regular conversion of the slave ADC */ -#define ADC_CSR_EOS_SLV_Pos (19U) -#define ADC_CSR_EOS_SLV_Msk (0x1UL << ADC_CSR_EOS_SLV_Pos) /*!< 0x00080000 */ -#define ADC_CSR_EOS_SLV ADC_CSR_EOS_SLV_Msk /*!< End of regular sequence flag of the slave ADC */ -#define ADC_CSR_OVR_SLV_Pos (20U) -#define ADC_CSR_OVR_SLV_Msk (0x1UL << ADC_CSR_OVR_SLV_Pos) /*!< 0x00100000 */ -#define ADC_CSR_OVR_SLV ADC_CSR_OVR_SLV_Msk /*!< Overrun flag of the slave ADC */ -#define ADC_CSR_JEOC_SLV_Pos (21U) -#define ADC_CSR_JEOC_SLV_Msk (0x1UL << ADC_CSR_JEOC_SLV_Pos) /*!< 0x00200000 */ -#define ADC_CSR_JEOC_SLV ADC_CSR_JEOC_SLV_Msk /*!< End of injected conversion of the slave ADC */ -#define ADC_CSR_JEOS_SLV_Pos (22U) -#define ADC_CSR_JEOS_SLV_Msk (0x1UL << ADC_CSR_JEOS_SLV_Pos) /*!< 0x00400000 */ -#define ADC_CSR_JEOS_SLV ADC_CSR_JEOS_SLV_Msk /*!< End of injected sequence flag of the slave ADC */ -#define ADC_CSR_AWD1_SLV_Pos (23U) -#define ADC_CSR_AWD1_SLV_Msk (0x1UL << ADC_CSR_AWD1_SLV_Pos) /*!< 0x00800000 */ -#define ADC_CSR_AWD1_SLV ADC_CSR_AWD1_SLV_Msk /*!< Analog watchdog 1 flag of the slave ADC */ -#define ADC_CSR_AWD2_SLV_Pos (24U) -#define ADC_CSR_AWD2_SLV_Msk (0x1UL << ADC_CSR_AWD2_SLV_Pos) /*!< 0x01000000 */ -#define ADC_CSR_AWD2_SLV ADC_CSR_AWD2_SLV_Msk /*!< Analog watchdog 2 flag of the slave ADC */ -#define ADC_CSR_AWD3_SLV_Pos (25U) -#define ADC_CSR_AWD3_SLV_Msk (0x1UL << ADC_CSR_AWD3_SLV_Pos) /*!< 0x02000000 */ -#define ADC_CSR_AWD3_SLV ADC_CSR_AWD3_SLV_Msk /*!< Analog watchdog 3 flag of the slave ADC */ -#define ADC_CSR_JQOVF_SLV_Pos (26U) -#define ADC_CSR_JQOVF_SLV_Msk (0x1UL << ADC_CSR_JQOVF_SLV_Pos) /*!< 0x04000000 */ -#define ADC_CSR_JQOVF_SLV ADC_CSR_JQOVF_SLV_Msk /*!< Injected context queue overflow flag of the slave ADC */ - -/******************** Bit definition for ADC_CCR register ********************/ -#define ADC_CCR_DUAL_Pos (0U) -#define ADC_CCR_DUAL_Msk (0x1FUL << ADC_CCR_DUAL_Pos) /*!< 0x0000001F */ -#define ADC_CCR_DUAL ADC_CCR_DUAL_Msk /*!< Dual ADC mode selection */ -#define ADC_CCR_DUAL_0 (0x01UL << ADC_CCR_DUAL_Pos) /*!< 0x00000001 */ -#define ADC_CCR_DUAL_1 (0x02UL << ADC_CCR_DUAL_Pos) /*!< 0x00000002 */ -#define ADC_CCR_DUAL_2 (0x04UL << ADC_CCR_DUAL_Pos) /*!< 0x00000004 */ -#define ADC_CCR_DUAL_3 (0x08UL << ADC_CCR_DUAL_Pos) /*!< 0x00000008 */ -#define ADC_CCR_DUAL_4 (0x10UL << ADC_CCR_DUAL_Pos) /*!< 0x00000010 */ - -#define ADC_CCR_DELAY_Pos (8U) -#define ADC_CCR_DELAY_Msk (0xFUL << ADC_CCR_DELAY_Pos) /*!< 0x00000F00 */ -#define ADC_CCR_DELAY ADC_CCR_DELAY_Msk /*!< Delay between 2 sampling phases */ -#define ADC_CCR_DELAY_0 (0x1UL << ADC_CCR_DELAY_Pos) /*!< 0x00000100 */ -#define ADC_CCR_DELAY_1 (0x2UL << ADC_CCR_DELAY_Pos) /*!< 0x00000200 */ -#define ADC_CCR_DELAY_2 (0x4UL << ADC_CCR_DELAY_Pos) /*!< 0x00000400 */ -#define ADC_CCR_DELAY_3 (0x8UL << ADC_CCR_DELAY_Pos) /*!< 0x00000800 */ - - -#define ADC_CCR_DAMDF_Pos (14U) -#define ADC_CCR_DAMDF_Msk (0x3UL << ADC_CCR_DAMDF_Pos) /*!< 0x0000C000 */ -#define ADC_CCR_DAMDF ADC_CCR_DAMDF_Msk /*!< Dual ADC mode Data format */ -#define ADC_CCR_DAMDF_0 (0x1UL << ADC_CCR_DAMDF_Pos) /*!< 0x00004000 */ -#define ADC_CCR_DAMDF_1 (0x2UL << ADC_CCR_DAMDF_Pos) /*!< 0x00008000 */ - -#define ADC_CCR_CKMODE_Pos (16U) -#define ADC_CCR_CKMODE_Msk (0x3UL << ADC_CCR_CKMODE_Pos) /*!< 0x00030000 */ -#define ADC_CCR_CKMODE ADC_CCR_CKMODE_Msk /*!< ADC clock mode */ -#define ADC_CCR_CKMODE_0 (0x1UL << ADC_CCR_CKMODE_Pos) /*!< 0x00010000 */ -#define ADC_CCR_CKMODE_1 (0x2UL << ADC_CCR_CKMODE_Pos) /*!< 0x00020000 */ - -#define ADC_CCR_PRESC_Pos (18U) -#define ADC_CCR_PRESC_Msk (0xFUL << ADC_CCR_PRESC_Pos) /*!< 0x003C0000 */ -#define ADC_CCR_PRESC ADC_CCR_PRESC_Msk /*!< ADC prescaler */ -#define ADC_CCR_PRESC_0 (0x1UL << ADC_CCR_PRESC_Pos) /*!< 0x00040000 */ -#define ADC_CCR_PRESC_1 (0x2UL << ADC_CCR_PRESC_Pos) /*!< 0x00080000 */ -#define ADC_CCR_PRESC_2 (0x4UL << ADC_CCR_PRESC_Pos) /*!< 0x00100000 */ -#define ADC_CCR_PRESC_3 (0x8UL << ADC_CCR_PRESC_Pos) /*!< 0x00200000 */ - -#define ADC_CCR_VREFEN_Pos (22U) -#define ADC_CCR_VREFEN_Msk (0x1UL << ADC_CCR_VREFEN_Pos) /*!< 0x00400000 */ -#define ADC_CCR_VREFEN ADC_CCR_VREFEN_Msk /*!< VREFINT enable */ -#define ADC_CCR_TSEN_Pos (23U) -#define ADC_CCR_TSEN_Msk (0x1UL << ADC_CCR_TSEN_Pos) /*!< 0x00800000 */ -#define ADC_CCR_TSEN ADC_CCR_TSEN_Msk /*!< Temperature sensor enable */ -#define ADC_CCR_VBATEN_Pos (24U) -#define ADC_CCR_VBATEN_Msk (0x1UL << ADC_CCR_VBATEN_Pos) /*!< 0x01000000 */ -#define ADC_CCR_VBATEN ADC_CCR_VBATEN_Msk /*!< VBAT enable */ - -/******************** Bit definition for ADC_CDR register *******************/ -#define ADC_CDR_RDATA_MST_Pos (0U) -#define ADC_CDR_RDATA_MST_Msk (0xFFFFUL << ADC_CDR_RDATA_MST_Pos) /*!< 0x0000FFFF */ -#define ADC_CDR_RDATA_MST ADC_CDR_RDATA_MST_Msk /*!< ADC multimode master group regular conversion data */ - -#define ADC_CDR_RDATA_SLV_Pos (16U) -#define ADC_CDR_RDATA_SLV_Msk (0xFFFFUL << ADC_CDR_RDATA_SLV_Pos) /*!< 0xFFFF0000 */ -#define ADC_CDR_RDATA_SLV ADC_CDR_RDATA_SLV_Msk /*!< ADC multimode slave group regular conversion data */ - -/******************** Bit definition for ADC_CDR2 register ******************/ -#define ADC_CDR2_RDATA_ALT_Pos (0U) -#define ADC_CDR2_RDATA_ALT_Msk (0xFFFFFFFFUL << ADC_CDR2_RDATA_ALT_Pos) /*!< 0xFFFFFFFF */ -#define ADC_CDR2_RDATA_ALT ADC_CDR2_RDATA_ALT_Msk /*!< Regular data of the master/slave alternated ADCs */ - - -/******************************************************************************/ -/* */ -/* VREFBUF */ -/* */ -/******************************************************************************/ -/******************* Bit definition for VREFBUF_CSR register ****************/ -#define VREFBUF_CSR_ENVR_Pos (0U) -#define VREFBUF_CSR_ENVR_Msk (0x1UL << VREFBUF_CSR_ENVR_Pos) /*!< 0x00000001 */ -#define VREFBUF_CSR_ENVR VREFBUF_CSR_ENVR_Msk /*!*/ -#define DAC_CR_CEN1_Pos (14U) -#define DAC_CR_CEN1_Msk (0x1UL << DAC_CR_CEN1_Pos) /*!< 0x00004000 */ -#define DAC_CR_CEN1 DAC_CR_CEN1_Msk /*!*/ - -#define DAC_CR_EN2_Pos (16U) -#define DAC_CR_EN2_Msk (0x1UL << DAC_CR_EN2_Pos) /*!< 0x00010000 */ -#define DAC_CR_EN2 DAC_CR_EN2_Msk /*!*/ -#define DAC_CR_CEN2_Pos (30U) -#define DAC_CR_CEN2_Msk (0x1UL << DAC_CR_CEN2_Pos) /*!< 0x40000000 */ -#define DAC_CR_CEN2 DAC_CR_CEN2_Msk /*!*/ - -/***************** Bit definition for DAC_SWTRIGR register ******************/ -#define DAC_SWTRIGR_SWTRIG1_Pos (0U) -#define DAC_SWTRIGR_SWTRIG1_Msk (0x1UL << DAC_SWTRIGR_SWTRIG1_Pos) /*!< 0x00000001 */ -#define DAC_SWTRIGR_SWTRIG1 DAC_SWTRIGR_SWTRIG1_Msk /*!
© Copyright (c) 2019 STMicroelectronics. - * All rights reserved.
- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/** @addtogroup CMSIS_Device - * @{ - */ - -/** @addtogroup stm32h735xx - * @{ - */ - -#ifndef STM32H735xx_H -#define STM32H735xx_H - -#ifdef __cplusplus - extern "C" { -#endif /* __cplusplus */ - -/** @addtogroup Peripheral_interrupt_number_definition - * @{ - */ - -/** - * @brief STM32H7XX Interrupt Number Definition, according to the selected device - * in @ref Library_configuration_section - */ -typedef enum -{ -/****** Cortex-M Processor Exceptions Numbers *****************************************************************/ - NonMaskableInt_IRQn = -14, /*!< 2 Non Maskable Interrupt */ - HardFault_IRQn = -13, /*!< 4 Cortex-M Memory Management Interrupt */ - MemoryManagement_IRQn = -12, /*!< 4 Cortex-M Memory Management Interrupt */ - BusFault_IRQn = -11, /*!< 5 Cortex-M Bus Fault Interrupt */ - UsageFault_IRQn = -10, /*!< 6 Cortex-M Usage Fault Interrupt */ - SVCall_IRQn = -5, /*!< 11 Cortex-M SV Call Interrupt */ - DebugMonitor_IRQn = -4, /*!< 12 Cortex-M Debug Monitor Interrupt */ - PendSV_IRQn = -2, /*!< 14 Cortex-M Pend SV Interrupt */ - SysTick_IRQn = -1, /*!< 15 Cortex-M System Tick Interrupt */ -/****** STM32 specific Interrupt Numbers **********************************************************************/ - WWDG_IRQn = 0, /*!< Window WatchDog Interrupt ( wwdg1_it, wwdg2_it) */ - PVD_AVD_IRQn = 1, /*!< PVD/AVD through EXTI Line detection Interrupt */ - TAMP_STAMP_IRQn = 2, /*!< Tamper and TimeStamp interrupts through the EXTI line */ - RTC_WKUP_IRQn = 3, /*!< RTC Wakeup interrupt through the EXTI line */ - FLASH_IRQn = 4, /*!< FLASH global Interrupt */ - RCC_IRQn = 5, /*!< RCC global Interrupt */ - EXTI0_IRQn = 6, /*!< EXTI Line0 Interrupt */ - EXTI1_IRQn = 7, /*!< EXTI Line1 Interrupt */ - EXTI2_IRQn = 8, /*!< EXTI Line2 Interrupt */ - EXTI3_IRQn = 9, /*!< EXTI Line3 Interrupt */ - EXTI4_IRQn = 10, /*!< EXTI Line4 Interrupt */ - DMA1_Stream0_IRQn = 11, /*!< DMA1 Stream 0 global Interrupt */ - DMA1_Stream1_IRQn = 12, /*!< DMA1 Stream 1 global Interrupt */ - DMA1_Stream2_IRQn = 13, /*!< DMA1 Stream 2 global Interrupt */ - DMA1_Stream3_IRQn = 14, /*!< DMA1 Stream 3 global Interrupt */ - DMA1_Stream4_IRQn = 15, /*!< DMA1 Stream 4 global Interrupt */ - DMA1_Stream5_IRQn = 16, /*!< DMA1 Stream 5 global Interrupt */ - DMA1_Stream6_IRQn = 17, /*!< DMA1 Stream 6 global Interrupt */ - ADC_IRQn = 18, /*!< ADC1 and ADC2 global Interrupts */ - FDCAN1_IT0_IRQn = 19, /*!< FDCAN1 Interrupt line 0 */ - FDCAN2_IT0_IRQn = 20, /*!< FDCAN2 Interrupt line 0 */ - FDCAN1_IT1_IRQn = 21, /*!< FDCAN1 Interrupt line 1 */ - FDCAN2_IT1_IRQn = 22, /*!< FDCAN2 Interrupt line 1 */ - EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ - TIM1_BRK_IRQn = 24, /*!< TIM1 Break Interrupt */ - TIM1_UP_IRQn = 25, /*!< TIM1 Update Interrupt */ - TIM1_TRG_COM_IRQn = 26, /*!< TIM1 Trigger and Commutation Interrupt */ - TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ - TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ - TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ - TIM4_IRQn = 30, /*!< TIM4 global Interrupt */ - I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ - I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ - I2C2_EV_IRQn = 33, /*!< I2C2 Event Interrupt */ - I2C2_ER_IRQn = 34, /*!< I2C2 Error Interrupt */ - SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ - SPI2_IRQn = 36, /*!< SPI2 global Interrupt */ - USART1_IRQn = 37, /*!< USART1 global Interrupt */ - USART2_IRQn = 38, /*!< USART2 global Interrupt */ - USART3_IRQn = 39, /*!< USART3 global Interrupt */ - EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ - RTC_Alarm_IRQn = 41, /*!< RTC Alarm (A and B) through EXTI Line Interrupt */ - TIM8_BRK_TIM12_IRQn = 43, /*!< TIM8 Break Interrupt and TIM12 global interrupt */ - TIM8_UP_TIM13_IRQn = 44, /*!< TIM8 Update Interrupt and TIM13 global interrupt */ - TIM8_TRG_COM_TIM14_IRQn = 45, /*!< TIM8 Trigger and Commutation Interrupt and TIM14 global interrupt */ - TIM8_CC_IRQn = 46, /*!< TIM8 Capture Compare Interrupt */ - DMA1_Stream7_IRQn = 47, /*!< DMA1 Stream7 Interrupt */ - FMC_IRQn = 48, /*!< FMC global Interrupt */ - SDMMC1_IRQn = 49, /*!< SDMMC1 global Interrupt */ - TIM5_IRQn = 50, /*!< TIM5 global Interrupt */ - SPI3_IRQn = 51, /*!< SPI3 global Interrupt */ - UART4_IRQn = 52, /*!< UART4 global Interrupt */ - UART5_IRQn = 53, /*!< UART5 global Interrupt */ - TIM6_DAC_IRQn = 54, /*!< TIM6 global and DAC1&2 underrun error interrupts */ - TIM7_IRQn = 55, /*!< TIM7 global interrupt */ - DMA2_Stream0_IRQn = 56, /*!< DMA2 Stream 0 global Interrupt */ - DMA2_Stream1_IRQn = 57, /*!< DMA2 Stream 1 global Interrupt */ - DMA2_Stream2_IRQn = 58, /*!< DMA2 Stream 2 global Interrupt */ - DMA2_Stream3_IRQn = 59, /*!< DMA2 Stream 3 global Interrupt */ - DMA2_Stream4_IRQn = 60, /*!< DMA2 Stream 4 global Interrupt */ - ETH_IRQn = 61, /*!< Ethernet global Interrupt */ - ETH_WKUP_IRQn = 62, /*!< Ethernet Wakeup through EXTI line Interrupt */ - FDCAN_CAL_IRQn = 63, /*!< FDCAN Calibration unit Interrupt */ - DMA2_Stream5_IRQn = 68, /*!< DMA2 Stream 5 global interrupt */ - DMA2_Stream6_IRQn = 69, /*!< DMA2 Stream 6 global interrupt */ - DMA2_Stream7_IRQn = 70, /*!< DMA2 Stream 7 global interrupt */ - USART6_IRQn = 71, /*!< USART6 global interrupt */ - I2C3_EV_IRQn = 72, /*!< I2C3 event interrupt */ - I2C3_ER_IRQn = 73, /*!< I2C3 error interrupt */ - OTG_HS_EP1_OUT_IRQn = 74, /*!< USB OTG HS End Point 1 Out global interrupt */ - OTG_HS_EP1_IN_IRQn = 75, /*!< USB OTG HS End Point 1 In global interrupt */ - OTG_HS_WKUP_IRQn = 76, /*!< USB OTG HS Wakeup through EXTI interrupt */ - OTG_HS_IRQn = 77, /*!< USB OTG HS global interrupt */ - DCMI_PSSI_IRQn = 78, /*!< DCMI and PSSI global interrupt */ - CRYP_IRQn = 79, /*!< CRYP crypto global interrupt */ - HASH_RNG_IRQn = 80, /*!< HASH and RNG global interrupt */ - FPU_IRQn = 81, /*!< FPU global interrupt */ - UART7_IRQn = 82, /*!< UART7 global interrupt */ - UART8_IRQn = 83, /*!< UART8 global interrupt */ - SPI4_IRQn = 84, /*!< SPI4 global Interrupt */ - SPI5_IRQn = 85, /*!< SPI5 global Interrupt */ - SPI6_IRQn = 86, /*!< SPI6 global Interrupt */ - SAI1_IRQn = 87, /*!< SAI1 global Interrupt */ - LTDC_IRQn = 88, /*!< LTDC global Interrupt */ - LTDC_ER_IRQn = 89, /*!< LTDC Error global Interrupt */ - DMA2D_IRQn = 90, /*!< DMA2D global Interrupt */ - OCTOSPI1_IRQn = 92, /*!< OCTOSPI1 global interrupt */ - LPTIM1_IRQn = 93, /*!< LP TIM1 interrupt */ - CEC_IRQn = 94, /*!< HDMI-CEC global Interrupt */ - I2C4_EV_IRQn = 95, /*!< I2C4 Event Interrupt */ - I2C4_ER_IRQn = 96, /*!< I2C4 Error Interrupt */ - SPDIF_RX_IRQn = 97, /*!< SPDIF-RX global Interrupt */ - DMAMUX1_OVR_IRQn = 102, /*! - -/** @addtogroup Peripheral_registers_structures - * @{ - */ - -/** - * @brief Analog to Digital Converter - */ - -typedef struct -{ - __IO uint32_t ISR; /*!< ADC Interrupt and Status Register, Address offset: 0x00 */ - __IO uint32_t IER; /*!< ADC Interrupt Enable Register, Address offset: 0x04 */ - __IO uint32_t CR; /*!< ADC control register, Address offset: 0x08 */ - __IO uint32_t CFGR; /*!< ADC Configuration register, Address offset: 0x0C */ - __IO uint32_t CFGR2; /*!< ADC Configuration register 2, Address offset: 0x10 */ - __IO uint32_t SMPR1; /*!< ADC sample time register 1, Address offset: 0x14 */ - __IO uint32_t SMPR2; /*!< ADC sample time register 2, Address offset: 0x18 */ - __IO uint32_t PCSEL_RES0; /*!< Rserved for ADC3, ADC1/2 pre-channel selection, Address offset: 0x1C */ - __IO uint32_t LTR1_TR1; /*!< ADC watchdog Lower threshold register 1, Address offset: 0x20 */ - __IO uint32_t HTR1_TR2; /*!< ADC watchdog higher threshold register 1, Address offset: 0x24 */ - __IO uint32_t RES1_TR3; /*!< Rserved for ADC1/2, ADC3 threshold register, Address offset: 0x28 */ - uint32_t RESERVED2; /*!< Reserved, 0x02C */ - __IO uint32_t SQR1; /*!< ADC regular sequence register 1, Address offset: 0x30 */ - __IO uint32_t SQR2; /*!< ADC regular sequence register 2, Address offset: 0x34 */ - __IO uint32_t SQR3; /*!< ADC regular sequence register 3, Address offset: 0x38 */ - __IO uint32_t SQR4; /*!< ADC regular sequence register 4, Address offset: 0x3C */ - __IO uint32_t DR; /*!< ADC regular data register, Address offset: 0x40 */ - uint32_t RESERVED3; /*!< Reserved, 0x044 */ - uint32_t RESERVED4; /*!< Reserved, 0x048 */ - __IO uint32_t JSQR; /*!< ADC injected sequence register, Address offset: 0x4C */ - uint32_t RESERVED5[4]; /*!< Reserved, 0x050 - 0x05C */ - __IO uint32_t OFR1; /*!< ADC offset register 1, Address offset: 0x60 */ - __IO uint32_t OFR2; /*!< ADC offset register 2, Address offset: 0x64 */ - __IO uint32_t OFR3; /*!< ADC offset register 3, Address offset: 0x68 */ - __IO uint32_t OFR4; /*!< ADC offset register 4, Address offset: 0x6C */ - uint32_t RESERVED6[4]; /*!< Reserved, 0x070 - 0x07C */ - __IO uint32_t JDR1; /*!< ADC injected data register 1, Address offset: 0x80 */ - __IO uint32_t JDR2; /*!< ADC injected data register 2, Address offset: 0x84 */ - __IO uint32_t JDR3; /*!< ADC injected data register 3, Address offset: 0x88 */ - __IO uint32_t JDR4; /*!< ADC injected data register 4, Address offset: 0x8C */ - uint32_t RESERVED7[4]; /*!< Reserved, 0x090 - 0x09C */ - __IO uint32_t AWD2CR; /*!< ADC Analog Watchdog 2 Configuration Register, Address offset: 0xA0 */ - __IO uint32_t AWD3CR; /*!< ADC Analog Watchdog 3 Configuration Register, Address offset: 0xA4 */ - uint32_t RESERVED8; /*!< Reserved, 0x0A8 */ - uint32_t RESERVED9; /*!< Reserved, 0x0AC */ - __IO uint32_t LTR2_DIFSEL; /*!< ADC watchdog Lower threshold register 2, Difsel for ADC3, Address offset: 0xB0 */ - __IO uint32_t HTR2_CALFACT; /*!< ADC watchdog Higher threshold register 2, Calfact for ADC3, Address offset: 0xB4 */ - __IO uint32_t LTR3_RES10; /*!< ADC watchdog Lower threshold register 3, specific ADC1/2, Address offset: 0xB8 */ - __IO uint32_t HTR3_RES11; /*!< ADC watchdog Higher threshold register 3, specific ADC1/2, Address offset: 0xBC */ - __IO uint32_t DIFSEL_RES12; /*!< ADC Differential Mode Selection Register specific ADC1/2, Address offset: 0xC0 */ - __IO uint32_t CALFACT_RES13; /*!< ADC Calibration Factors specific ADC1/2, Address offset: 0xC4 */ - __IO uint32_t CALFACT2_RES14; /*!< ADC Linearity Calibration Factors specific ADC1/2, Address offset: 0xC8 */ -} ADC_TypeDef; - - -typedef struct -{ -__IO uint32_t CSR; /*!< ADC Common status register, Address offset: ADC1/3 base address + 0x300 */ -uint32_t RESERVED; /*!< Reserved, ADC1/3 base address + 0x304 */ -__IO uint32_t CCR; /*!< ADC common control register, Address offset: ADC1/3 base address + 0x308 */ -__IO uint32_t CDR; /*!< ADC common regular data register for dual Address offset: ADC1/3 base address + 0x30C */ -__IO uint32_t CDR2; /*!< ADC common regular data register for 32-bit dual mode Address offset: ADC1/3 base address + 0x310 */ - -} ADC_Common_TypeDef; - - -/** - * @brief VREFBUF - */ - -typedef struct -{ - __IO uint32_t CSR; /*!< VREFBUF control and status register, Address offset: 0x00 */ - __IO uint32_t CCR; /*!< VREFBUF calibration and control register, Address offset: 0x04 */ -} VREFBUF_TypeDef; - - -/** - * @brief FD Controller Area Network - */ - -typedef struct -{ - __IO uint32_t CREL; /*!< FDCAN Core Release register, Address offset: 0x000 */ - __IO uint32_t ENDN; /*!< FDCAN Endian register, Address offset: 0x004 */ - __IO uint32_t RESERVED1; /*!< Reserved, 0x008 */ - __IO uint32_t DBTP; /*!< FDCAN Data Bit Timing & Prescaler register, Address offset: 0x00C */ - __IO uint32_t TEST; /*!< FDCAN Test register, Address offset: 0x010 */ - __IO uint32_t RWD; /*!< FDCAN RAM Watchdog register, Address offset: 0x014 */ - __IO uint32_t CCCR; /*!< FDCAN CC Control register, Address offset: 0x018 */ - __IO uint32_t NBTP; /*!< FDCAN Nominal Bit Timing & Prescaler register, Address offset: 0x01C */ - __IO uint32_t TSCC; /*!< FDCAN Timestamp Counter Configuration register, Address offset: 0x020 */ - __IO uint32_t TSCV; /*!< FDCAN Timestamp Counter Value register, Address offset: 0x024 */ - __IO uint32_t TOCC; /*!< FDCAN Timeout Counter Configuration register, Address offset: 0x028 */ - __IO uint32_t TOCV; /*!< FDCAN Timeout Counter Value register, Address offset: 0x02C */ - __IO uint32_t RESERVED2[4]; /*!< Reserved, 0x030 - 0x03C */ - __IO uint32_t ECR; /*!< FDCAN Error Counter register, Address offset: 0x040 */ - __IO uint32_t PSR; /*!< FDCAN Protocol Status register, Address offset: 0x044 */ - __IO uint32_t TDCR; /*!< FDCAN Transmitter Delay Compensation register, Address offset: 0x048 */ - __IO uint32_t RESERVED3; /*!< Reserved, 0x04C */ - __IO uint32_t IR; /*!< FDCAN Interrupt register, Address offset: 0x050 */ - __IO uint32_t IE; /*!< FDCAN Interrupt Enable register, Address offset: 0x054 */ - __IO uint32_t ILS; /*!< FDCAN Interrupt Line Select register, Address offset: 0x058 */ - __IO uint32_t ILE; /*!< FDCAN Interrupt Line Enable register, Address offset: 0x05C */ - __IO uint32_t RESERVED4[8]; /*!< Reserved, 0x060 - 0x07C */ - __IO uint32_t GFC; /*!< FDCAN Global Filter Configuration register, Address offset: 0x080 */ - __IO uint32_t SIDFC; /*!< FDCAN Standard ID Filter Configuration register, Address offset: 0x084 */ - __IO uint32_t XIDFC; /*!< FDCAN Extended ID Filter Configuration register, Address offset: 0x088 */ - __IO uint32_t RESERVED5; /*!< Reserved, 0x08C */ - __IO uint32_t XIDAM; /*!< FDCAN Extended ID AND Mask register, Address offset: 0x090 */ - __IO uint32_t HPMS; /*!< FDCAN High Priority Message Status register, Address offset: 0x094 */ - __IO uint32_t NDAT1; /*!< FDCAN New Data 1 register, Address offset: 0x098 */ - __IO uint32_t NDAT2; /*!< FDCAN New Data 2 register, Address offset: 0x09C */ - __IO uint32_t RXF0C; /*!< FDCAN Rx FIFO 0 Configuration register, Address offset: 0x0A0 */ - __IO uint32_t RXF0S; /*!< FDCAN Rx FIFO 0 Status register, Address offset: 0x0A4 */ - __IO uint32_t RXF0A; /*!< FDCAN Rx FIFO 0 Acknowledge register, Address offset: 0x0A8 */ - __IO uint32_t RXBC; /*!< FDCAN Rx Buffer Configuration register, Address offset: 0x0AC */ - __IO uint32_t RXF1C; /*!< FDCAN Rx FIFO 1 Configuration register, Address offset: 0x0B0 */ - __IO uint32_t RXF1S; /*!< FDCAN Rx FIFO 1 Status register, Address offset: 0x0B4 */ - __IO uint32_t RXF1A; /*!< FDCAN Rx FIFO 1 Acknowledge register, Address offset: 0x0B8 */ - __IO uint32_t RXESC; /*!< FDCAN Rx Buffer/FIFO Element Size Configuration register, Address offset: 0x0BC */ - __IO uint32_t TXBC; /*!< FDCAN Tx Buffer Configuration register, Address offset: 0x0C0 */ - __IO uint32_t TXFQS; /*!< FDCAN Tx FIFO/Queue Status register, Address offset: 0x0C4 */ - __IO uint32_t TXESC; /*!< FDCAN Tx Buffer Element Size Configuration register, Address offset: 0x0C8 */ - __IO uint32_t TXBRP; /*!< FDCAN Tx Buffer Request Pending register, Address offset: 0x0CC */ - __IO uint32_t TXBAR; /*!< FDCAN Tx Buffer Add Request register, Address offset: 0x0D0 */ - __IO uint32_t TXBCR; /*!< FDCAN Tx Buffer Cancellation Request register, Address offset: 0x0D4 */ - __IO uint32_t TXBTO; /*!< FDCAN Tx Buffer Transmission Occurred register, Address offset: 0x0D8 */ - __IO uint32_t TXBCF; /*!< FDCAN Tx Buffer Cancellation Finished register, Address offset: 0x0DC */ - __IO uint32_t TXBTIE; /*!< FDCAN Tx Buffer Transmission Interrupt Enable register, Address offset: 0x0E0 */ - __IO uint32_t TXBCIE; /*!< FDCAN Tx Buffer Cancellation Finished Interrupt Enable register, Address offset: 0x0E4 */ - __IO uint32_t RESERVED6[2]; /*!< Reserved, 0x0E8 - 0x0EC */ - __IO uint32_t TXEFC; /*!< FDCAN Tx Event FIFO Configuration register, Address offset: 0x0F0 */ - __IO uint32_t TXEFS; /*!< FDCAN Tx Event FIFO Status register, Address offset: 0x0F4 */ - __IO uint32_t TXEFA; /*!< FDCAN Tx Event FIFO Acknowledge register, Address offset: 0x0F8 */ - __IO uint32_t RESERVED7; /*!< Reserved, 0x0FC */ -} FDCAN_GlobalTypeDef; - -/** - * @brief TTFD Controller Area Network - */ - -typedef struct -{ - __IO uint32_t TTTMC; /*!< TT Trigger Memory Configuration register, Address offset: 0x100 */ - __IO uint32_t TTRMC; /*!< TT Reference Message Configuration register, Address offset: 0x104 */ - __IO uint32_t TTOCF; /*!< TT Operation Configuration register, Address offset: 0x108 */ - __IO uint32_t TTMLM; /*!< TT Matrix Limits register, Address offset: 0x10C */ - __IO uint32_t TURCF; /*!< TUR Configuration register, Address offset: 0x110 */ - __IO uint32_t TTOCN; /*!< TT Operation Control register, Address offset: 0x114 */ - __IO uint32_t TTGTP; /*!< TT Global Time Preset register, Address offset: 0x118 */ - __IO uint32_t TTTMK; /*!< TT Time Mark register, Address offset: 0x11C */ - __IO uint32_t TTIR; /*!< TT Interrupt register, Address offset: 0x120 */ - __IO uint32_t TTIE; /*!< TT Interrupt Enable register, Address offset: 0x124 */ - __IO uint32_t TTILS; /*!< TT Interrupt Line Select register, Address offset: 0x128 */ - __IO uint32_t TTOST; /*!< TT Operation Status register, Address offset: 0x12C */ - __IO uint32_t TURNA; /*!< TT TUR Numerator Actual register, Address offset: 0x130 */ - __IO uint32_t TTLGT; /*!< TT Local and Global Time register, Address offset: 0x134 */ - __IO uint32_t TTCTC; /*!< TT Cycle Time and Count register, Address offset: 0x138 */ - __IO uint32_t TTCPT; /*!< TT Capture Time register, Address offset: 0x13C */ - __IO uint32_t TTCSM; /*!< TT Cycle Sync Mark register, Address offset: 0x140 */ - __IO uint32_t RESERVED1[111]; /*!< Reserved, 0x144 - 0x2FC */ - __IO uint32_t TTTS; /*!< TT Trigger Select register, Address offset: 0x300 */ -} TTCAN_TypeDef; - -/** - * @brief FD Controller Area Network - */ - -typedef struct -{ - __IO uint32_t CREL; /*!< Clock Calibration Unit Core Release register, Address offset: 0x00 */ - __IO uint32_t CCFG; /*!< Calibration Configuration register, Address offset: 0x04 */ - __IO uint32_t CSTAT; /*!< Calibration Status register, Address offset: 0x08 */ - __IO uint32_t CWD; /*!< Calibration Watchdog register, Address offset: 0x0C */ - __IO uint32_t IR; /*!< CCU Interrupt register, Address offset: 0x10 */ - __IO uint32_t IE; /*!< CCU Interrupt Enable register, Address offset: 0x14 */ -} FDCAN_ClockCalibrationUnit_TypeDef; - - -/** - * @brief Consumer Electronics Control - */ - -typedef struct -{ - __IO uint32_t CR; /*!< CEC control register, Address offset:0x00 */ - __IO uint32_t CFGR; /*!< CEC configuration register, Address offset:0x04 */ - __IO uint32_t TXDR; /*!< CEC Tx data register , Address offset:0x08 */ - __IO uint32_t RXDR; /*!< CEC Rx Data Register, Address offset:0x0C */ - __IO uint32_t ISR; /*!< CEC Interrupt and Status Register, Address offset:0x10 */ - __IO uint32_t IER; /*!< CEC interrupt enable register, Address offset:0x14 */ -}CEC_TypeDef; - -/** - * @brief COordincate Rotation DIgital Computer - */ -typedef struct -{ - __IO uint32_t CSR; /*!< CORDIC control and status register, Address offset: 0x00 */ - __IO uint32_t WDATA; /*!< CORDIC argument register, Address offset: 0x04 */ - __IO uint32_t RDATA; /*!< CORDIC result register, Address offset: 0x08 */ -} CORDIC_TypeDef; - -/** - * @brief CRC calculation unit - */ - -typedef struct -{ - __IO uint32_t DR; /*!< CRC Data register, Address offset: 0x00 */ - __IO uint32_t IDR; /*!< CRC Independent data register, Address offset: 0x04 */ - __IO uint32_t CR; /*!< CRC Control register, Address offset: 0x08 */ - uint32_t RESERVED2; /*!< Reserved, 0x0C */ - __IO uint32_t INIT; /*!< Initial CRC value register, Address offset: 0x10 */ - __IO uint32_t POL; /*!< CRC polynomial register, Address offset: 0x14 */ -} CRC_TypeDef; - - -/** - * @brief Clock Recovery System - */ -typedef struct -{ -__IO uint32_t CR; /*!< CRS ccontrol register, Address offset: 0x00 */ -__IO uint32_t CFGR; /*!< CRS configuration register, Address offset: 0x04 */ -__IO uint32_t ISR; /*!< CRS interrupt and status register, Address offset: 0x08 */ -__IO uint32_t ICR; /*!< CRS interrupt flag clear register, Address offset: 0x0C */ -} CRS_TypeDef; - - -/** - * @brief Digital to Analog Converter - */ - -typedef struct -{ - __IO uint32_t CR; /*!< DAC control register, Address offset: 0x00 */ - __IO uint32_t SWTRIGR; /*!< DAC software trigger register, Address offset: 0x04 */ - __IO uint32_t DHR12R1; /*!< DAC channel1 12-bit right-aligned data holding register, Address offset: 0x08 */ - __IO uint32_t DHR12L1; /*!< DAC channel1 12-bit left aligned data holding register, Address offset: 0x0C */ - __IO uint32_t DHR8R1; /*!< DAC channel1 8-bit right aligned data holding register, Address offset: 0x10 */ - __IO uint32_t DHR12R2; /*!< DAC channel2 12-bit right aligned data holding register, Address offset: 0x14 */ - __IO uint32_t DHR12L2; /*!< DAC channel2 12-bit left aligned data holding register, Address offset: 0x18 */ - __IO uint32_t DHR8R2; /*!< DAC channel2 8-bit right-aligned data holding register, Address offset: 0x1C */ - __IO uint32_t DHR12RD; /*!< Dual DAC 12-bit right-aligned data holding register, Address offset: 0x20 */ - __IO uint32_t DHR12LD; /*!< DUAL DAC 12-bit left aligned data holding register, Address offset: 0x24 */ - __IO uint32_t DHR8RD; /*!< DUAL DAC 8-bit right aligned data holding register, Address offset: 0x28 */ - __IO uint32_t DOR1; /*!< DAC channel1 data output register, Address offset: 0x2C */ - __IO uint32_t DOR2; /*!< DAC channel2 data output register, Address offset: 0x30 */ - __IO uint32_t SR; /*!< DAC status register, Address offset: 0x34 */ - __IO uint32_t CCR; /*!< DAC calibration control register, Address offset: 0x38 */ - __IO uint32_t MCR; /*!< DAC mode control register, Address offset: 0x3C */ - __IO uint32_t SHSR1; /*!< DAC Sample and Hold sample time register 1, Address offset: 0x40 */ - __IO uint32_t SHSR2; /*!< DAC Sample and Hold sample time register 2, Address offset: 0x44 */ - __IO uint32_t SHHR; /*!< DAC Sample and Hold hold time register, Address offset: 0x48 */ - __IO uint32_t SHRR; /*!< DAC Sample and Hold refresh time register, Address offset: 0x4C */ -} DAC_TypeDef; - -/** - * @brief DFSDM module registers - */ -typedef struct -{ - __IO uint32_t FLTCR1; /*!< DFSDM control register1, Address offset: 0x100 */ - __IO uint32_t FLTCR2; /*!< DFSDM control register2, Address offset: 0x104 */ - __IO uint32_t FLTISR; /*!< DFSDM interrupt and status register, Address offset: 0x108 */ - __IO uint32_t FLTICR; /*!< DFSDM interrupt flag clear register, Address offset: 0x10C */ - __IO uint32_t FLTJCHGR; /*!< DFSDM injected channel group selection register, Address offset: 0x110 */ - __IO uint32_t FLTFCR; /*!< DFSDM filter control register, Address offset: 0x114 */ - __IO uint32_t FLTJDATAR; /*!< DFSDM data register for injected group, Address offset: 0x118 */ - __IO uint32_t FLTRDATAR; /*!< DFSDM data register for regular group, Address offset: 0x11C */ - __IO uint32_t FLTAWHTR; /*!< DFSDM analog watchdog high threshold register, Address offset: 0x120 */ - __IO uint32_t FLTAWLTR; /*!< DFSDM analog watchdog low threshold register, Address offset: 0x124 */ - __IO uint32_t FLTAWSR; /*!< DFSDM analog watchdog status register Address offset: 0x128 */ - __IO uint32_t FLTAWCFR; /*!< DFSDM analog watchdog clear flag register Address offset: 0x12C */ - __IO uint32_t FLTEXMAX; /*!< DFSDM extreme detector maximum register, Address offset: 0x130 */ - __IO uint32_t FLTEXMIN; /*!< DFSDM extreme detector minimum register Address offset: 0x134 */ - __IO uint32_t FLTCNVTIMR; /*!< DFSDM conversion timer, Address offset: 0x138 */ -} DFSDM_Filter_TypeDef; - -/** - * @brief DFSDM channel configuration registers - */ -typedef struct -{ - __IO uint32_t CHCFGR1; /*!< DFSDM channel configuration register1, Address offset: 0x00 */ - __IO uint32_t CHCFGR2; /*!< DFSDM channel configuration register2, Address offset: 0x04 */ - __IO uint32_t CHAWSCDR; /*!< DFSDM channel analog watchdog and - short circuit detector register, Address offset: 0x08 */ - __IO uint32_t CHWDATAR; /*!< DFSDM channel watchdog filter data register, Address offset: 0x0C */ - __IO uint32_t CHDATINR; /*!< DFSDM channel data input register, Address offset: 0x10 */ -} DFSDM_Channel_TypeDef; - -/** - * @brief Debug MCU - */ -typedef struct -{ - __IO uint32_t IDCODE; /*!< MCU device ID code, Address offset: 0x00 */ - __IO uint32_t CR; /*!< Debug MCU configuration register, Address offset: 0x04 */ - uint32_t RESERVED4[11]; /*!< Reserved, Address offset: 0x08 */ - __IO uint32_t APB3FZ1; /*!< Debug MCU APB3FZ1 freeze register, Address offset: 0x34 */ - uint32_t RESERVED5; /*!< Reserved, Address offset: 0x38 */ - __IO uint32_t APB1LFZ1; /*!< Debug MCU APB1LFZ1 freeze register, Address offset: 0x3C */ - uint32_t RESERVED6; /*!< Reserved, Address offset: 0x40 */ - __IO uint32_t APB1HFZ1; /*!< Debug MCU APB1LFZ1 freeze register, Address offset: 0x44 */ - uint32_t RESERVED7; /*!< Reserved, Address offset: 0x48 */ - __IO uint32_t APB2FZ1; /*!< Debug MCU APB2FZ1 freeze register, Address offset: 0x4C */ - uint32_t RESERVED8; /*!< Reserved, Address offset: 0x50 */ - __IO uint32_t APB4FZ1; /*!< Debug MCU APB4FZ1 freeze register, Address offset: 0x54 */ - __IO uint32_t RESERVED9[990]; /*!< Reserved, Address offset: 0x58-0xFCC */ - __IO uint32_t PIDR4; /*!< Debug MCU peripheral identity register 4, Address offset: 0xFD0 */ - __IO uint32_t RESERVED10[3];/*!< Reserved, Address offset: 0xFD4-0xFDC */ - __IO uint32_t PIDR0; /*!< Debug MCU peripheral identity register 0, Address offset: 0xFE0 */ - __IO uint32_t PIDR1; /*!< Debug MCU peripheral identity register 1, Address offset: 0xFE4 */ - __IO uint32_t PIDR2; /*!< Debug MCU peripheral identity register 2, Address offset: 0xFE8 */ - __IO uint32_t PIDR3; /*!< Debug MCU peripheral identity register 3, Address offset: 0xFEC */ - __IO uint32_t CIDR0; /*!< Debug MCU component identity register 0, Address offset: 0xFF0 */ - __IO uint32_t CIDR1; /*!< Debug MCU component identity register 1, Address offset: 0xFF4 */ - __IO uint32_t CIDR2; /*!< Debug MCU component identity register 2, Address offset: 0xFF8 */ - __IO uint32_t CIDR3; /*!< Debug MCU component identity register 3, Address offset: 0xFFC */ -}DBGMCU_TypeDef; -/** - * @brief DCMI - */ - -typedef struct -{ - __IO uint32_t CR; /*!< DCMI control register 1, Address offset: 0x00 */ - __IO uint32_t SR; /*!< DCMI status register, Address offset: 0x04 */ - __IO uint32_t RISR; /*!< DCMI raw interrupt status register, Address offset: 0x08 */ - __IO uint32_t IER; /*!< DCMI interrupt enable register, Address offset: 0x0C */ - __IO uint32_t MISR; /*!< DCMI masked interrupt status register, Address offset: 0x10 */ - __IO uint32_t ICR; /*!< DCMI interrupt clear register, Address offset: 0x14 */ - __IO uint32_t ESCR; /*!< DCMI embedded synchronization code register, Address offset: 0x18 */ - __IO uint32_t ESUR; /*!< DCMI embedded synchronization unmask register, Address offset: 0x1C */ - __IO uint32_t CWSTRTR; /*!< DCMI crop window start, Address offset: 0x20 */ - __IO uint32_t CWSIZER; /*!< DCMI crop window size, Address offset: 0x24 */ - __IO uint32_t DR; /*!< DCMI data register, Address offset: 0x28 */ -} DCMI_TypeDef; - -/** - * @brief PSSI - */ - -typedef struct -{ - __IO uint32_t CR; /*!< PSSI control register 1, Address offset: 0x000 */ - __IO uint32_t SR; /*!< PSSI status register, Address offset: 0x004 */ - __IO uint32_t RIS; /*!< PSSI raw interrupt status register, Address offset: 0x008 */ - __IO uint32_t IER; /*!< PSSI interrupt enable register, Address offset: 0x00C */ - __IO uint32_t MIS; /*!< PSSI masked interrupt status register, Address offset: 0x010 */ - __IO uint32_t ICR; /*!< PSSI interrupt clear register, Address offset: 0x014 */ - __IO uint32_t RESERVED1[4]; /*!< Reserved, 0x018 - 0x024 */ - __IO uint32_t DR; /*!< PSSI data register, Address offset: 0x028 */ - __IO uint32_t RESERVED2[241]; /*!< Reserved, 0x02C - 0x3EC */ - __IO uint32_t HWCFGR; /*!< PSSI IP HW configuration register, Address offset: 0x3F0 */ - __IO uint32_t VERR; /*!< PSSI IP version register, Address offset: 0x3F4 */ - __IO uint32_t IPIDR; /*!< PSSI IP ID register, Address offset: 0x3F8 */ - __IO uint32_t SIDR; /*!< PSSI SIZE ID register, Address offset: 0x3FC */ -} PSSI_TypeDef; - -/** - * @brief DMA Controller - */ - -typedef struct -{ - __IO uint32_t CR; /*!< DMA stream x configuration register */ - __IO uint32_t NDTR; /*!< DMA stream x number of data register */ - __IO uint32_t PAR; /*!< DMA stream x peripheral address register */ - __IO uint32_t M0AR; /*!< DMA stream x memory 0 address register */ - __IO uint32_t M1AR; /*!< DMA stream x memory 1 address register */ - __IO uint32_t FCR; /*!< DMA stream x FIFO control register */ -} DMA_Stream_TypeDef; - -typedef struct -{ - __IO uint32_t LISR; /*!< DMA low interrupt status register, Address offset: 0x00 */ - __IO uint32_t HISR; /*!< DMA high interrupt status register, Address offset: 0x04 */ - __IO uint32_t LIFCR; /*!< DMA low interrupt flag clear register, Address offset: 0x08 */ - __IO uint32_t HIFCR; /*!< DMA high interrupt flag clear register, Address offset: 0x0C */ -} DMA_TypeDef; - -typedef struct -{ - __IO uint32_t CCR; /*!< DMA channel x configuration register */ - __IO uint32_t CNDTR; /*!< DMA channel x number of data register */ - __IO uint32_t CPAR; /*!< DMA channel x peripheral address register */ - __IO uint32_t CM0AR; /*!< DMA channel x memory 0 address register */ - __IO uint32_t CM1AR; /*!< DMA channel x memory 1 address register */ -} BDMA_Channel_TypeDef; - -typedef struct -{ - __IO uint32_t ISR; /*!< DMA interrupt status register, Address offset: 0x00 */ - __IO uint32_t IFCR; /*!< DMA interrupt flag clear register, Address offset: 0x04 */ -} BDMA_TypeDef; - -typedef struct -{ - __IO uint32_t CCR; /*!< DMA Multiplexer Channel x Control Register */ -}DMAMUX_Channel_TypeDef; - -typedef struct -{ - __IO uint32_t CSR; /*!< DMA Channel Status Register */ - __IO uint32_t CFR; /*!< DMA Channel Clear Flag Register */ -}DMAMUX_ChannelStatus_TypeDef; - -typedef struct -{ - __IO uint32_t RGCR; /*!< DMA Request Generator x Control Register */ -}DMAMUX_RequestGen_TypeDef; - -typedef struct -{ - __IO uint32_t RGSR; /*!< DMA Request Generator Status Register */ - __IO uint32_t RGCFR; /*!< DMA Request Generator Clear Flag Register */ -}DMAMUX_RequestGenStatus_TypeDef; - -/** - * @brief MDMA Controller - */ -typedef struct -{ - __IO uint32_t GISR0; /*!< MDMA Global Interrupt/Status Register 0, Address offset: 0x00 */ -}MDMA_TypeDef; - -typedef struct -{ - __IO uint32_t CISR; /*!< MDMA channel x interrupt/status register, Address offset: 0x40 */ - __IO uint32_t CIFCR; /*!< MDMA channel x interrupt flag clear register, Address offset: 0x44 */ - __IO uint32_t CESR; /*!< MDMA Channel x error status register, Address offset: 0x48 */ - __IO uint32_t CCR; /*!< MDMA channel x control register, Address offset: 0x4C */ - __IO uint32_t CTCR; /*!< MDMA channel x Transfer Configuration register, Address offset: 0x50 */ - __IO uint32_t CBNDTR; /*!< MDMA Channel x block number of data register, Address offset: 0x54 */ - __IO uint32_t CSAR; /*!< MDMA channel x source address register, Address offset: 0x58 */ - __IO uint32_t CDAR; /*!< MDMA channel x destination address register, Address offset: 0x5C */ - __IO uint32_t CBRUR; /*!< MDMA channel x Block Repeat address Update register, Address offset: 0x60 */ - __IO uint32_t CLAR; /*!< MDMA channel x Link Address register, Address offset: 0x64 */ - __IO uint32_t CTBR; /*!< MDMA channel x Trigger and Bus selection Register, Address offset: 0x68 */ - uint32_t RESERVED0; /*!< Reserved, 0x6C */ - __IO uint32_t CMAR; /*!< MDMA channel x Mask address register, Address offset: 0x70 */ - __IO uint32_t CMDR; /*!< MDMA channel x Mask Data register, Address offset: 0x74 */ -}MDMA_Channel_TypeDef; - -/** - * @brief DMA2D Controller - */ - -typedef struct -{ - __IO uint32_t CR; /*!< DMA2D Control Register, Address offset: 0x00 */ - __IO uint32_t ISR; /*!< DMA2D Interrupt Status Register, Address offset: 0x04 */ - __IO uint32_t IFCR; /*!< DMA2D Interrupt Flag Clear Register, Address offset: 0x08 */ - __IO uint32_t FGMAR; /*!< DMA2D Foreground Memory Address Register, Address offset: 0x0C */ - __IO uint32_t FGOR; /*!< DMA2D Foreground Offset Register, Address offset: 0x10 */ - __IO uint32_t BGMAR; /*!< DMA2D Background Memory Address Register, Address offset: 0x14 */ - __IO uint32_t BGOR; /*!< DMA2D Background Offset Register, Address offset: 0x18 */ - __IO uint32_t FGPFCCR; /*!< DMA2D Foreground PFC Control Register, Address offset: 0x1C */ - __IO uint32_t FGCOLR; /*!< DMA2D Foreground Color Register, Address offset: 0x20 */ - __IO uint32_t BGPFCCR; /*!< DMA2D Background PFC Control Register, Address offset: 0x24 */ - __IO uint32_t BGCOLR; /*!< DMA2D Background Color Register, Address offset: 0x28 */ - __IO uint32_t FGCMAR; /*!< DMA2D Foreground CLUT Memory Address Register, Address offset: 0x2C */ - __IO uint32_t BGCMAR; /*!< DMA2D Background CLUT Memory Address Register, Address offset: 0x30 */ - __IO uint32_t OPFCCR; /*!< DMA2D Output PFC Control Register, Address offset: 0x34 */ - __IO uint32_t OCOLR; /*!< DMA2D Output Color Register, Address offset: 0x38 */ - __IO uint32_t OMAR; /*!< DMA2D Output Memory Address Register, Address offset: 0x3C */ - __IO uint32_t OOR; /*!< DMA2D Output Offset Register, Address offset: 0x40 */ - __IO uint32_t NLR; /*!< DMA2D Number of Line Register, Address offset: 0x44 */ - __IO uint32_t LWR; /*!< DMA2D Line Watermark Register, Address offset: 0x48 */ - __IO uint32_t AMTCR; /*!< DMA2D AHB Master Timer Configuration Register, Address offset: 0x4C */ - uint32_t RESERVED[236]; /*!< Reserved, 0x50-0x3FF */ - __IO uint32_t FGCLUT[256]; /*!< DMA2D Foreground CLUT, Address offset:400-7FF */ - __IO uint32_t BGCLUT[256]; /*!< DMA2D Background CLUT, Address offset:800-BFF */ -} DMA2D_TypeDef; - - -/** - * @brief Ethernet MAC - */ -typedef struct -{ - __IO uint32_t MACCR; - __IO uint32_t MACECR; - __IO uint32_t MACPFR; - __IO uint32_t MACWTR; - __IO uint32_t MACHT0R; - __IO uint32_t MACHT1R; - uint32_t RESERVED1[14]; - __IO uint32_t MACVTR; - uint32_t RESERVED2; - __IO uint32_t MACVHTR; - uint32_t RESERVED3; - __IO uint32_t MACVIR; - __IO uint32_t MACIVIR; - uint32_t RESERVED4[2]; - __IO uint32_t MACTFCR; - uint32_t RESERVED5[7]; - __IO uint32_t MACRFCR; - uint32_t RESERVED6[7]; - __IO uint32_t MACISR; - __IO uint32_t MACIER; - __IO uint32_t MACRXTXSR; - uint32_t RESERVED7; - __IO uint32_t MACPCSR; - __IO uint32_t MACRWKPFR; - uint32_t RESERVED8[2]; - __IO uint32_t MACLCSR; - __IO uint32_t MACLTCR; - __IO uint32_t MACLETR; - __IO uint32_t MAC1USTCR; - uint32_t RESERVED9[12]; - __IO uint32_t MACVR; - __IO uint32_t MACDR; - uint32_t RESERVED10; - __IO uint32_t MACHWF0R; - __IO uint32_t MACHWF1R; - __IO uint32_t MACHWF2R; - uint32_t RESERVED11[54]; - __IO uint32_t MACMDIOAR; - __IO uint32_t MACMDIODR; - uint32_t RESERVED12[2]; - __IO uint32_t MACARPAR; - uint32_t RESERVED13[59]; - __IO uint32_t MACA0HR; - __IO uint32_t MACA0LR; - __IO uint32_t MACA1HR; - __IO uint32_t MACA1LR; - __IO uint32_t MACA2HR; - __IO uint32_t MACA2LR; - __IO uint32_t MACA3HR; - __IO uint32_t MACA3LR; - uint32_t RESERVED14[248]; - __IO uint32_t MMCCR; - __IO uint32_t MMCRIR; - __IO uint32_t MMCTIR; - __IO uint32_t MMCRIMR; - __IO uint32_t MMCTIMR; - uint32_t RESERVED15[14]; - __IO uint32_t MMCTSCGPR; - __IO uint32_t MMCTMCGPR; - uint32_t RESERVED16[5]; - __IO uint32_t MMCTPCGR; - uint32_t RESERVED17[10]; - __IO uint32_t MMCRCRCEPR; - __IO uint32_t MMCRAEPR; - uint32_t RESERVED18[10]; - __IO uint32_t MMCRUPGR; - uint32_t RESERVED19[9]; - __IO uint32_t MMCTLPIMSTR; - __IO uint32_t MMCTLPITCR; - __IO uint32_t MMCRLPIMSTR; - __IO uint32_t MMCRLPITCR; - uint32_t RESERVED20[65]; - __IO uint32_t MACL3L4C0R; - __IO uint32_t MACL4A0R; - uint32_t RESERVED21[2]; - __IO uint32_t MACL3A0R0R; - __IO uint32_t MACL3A1R0R; - __IO uint32_t MACL3A2R0R; - __IO uint32_t MACL3A3R0R; - uint32_t RESERVED22[4]; - __IO uint32_t MACL3L4C1R; - __IO uint32_t MACL4A1R; - uint32_t RESERVED23[2]; - __IO uint32_t MACL3A0R1R; - __IO uint32_t MACL3A1R1R; - __IO uint32_t MACL3A2R1R; - __IO uint32_t MACL3A3R1R; - uint32_t RESERVED24[108]; - __IO uint32_t MACTSCR; - __IO uint32_t MACSSIR; - __IO uint32_t MACSTSR; - __IO uint32_t MACSTNR; - __IO uint32_t MACSTSUR; - __IO uint32_t MACSTNUR; - __IO uint32_t MACTSAR; - uint32_t RESERVED25; - __IO uint32_t MACTSSR; - uint32_t RESERVED26[3]; - __IO uint32_t MACTTSSNR; - __IO uint32_t MACTTSSSR; - uint32_t RESERVED27[2]; - __IO uint32_t MACACR; - uint32_t RESERVED28; - __IO uint32_t MACATSNR; - __IO uint32_t MACATSSR; - __IO uint32_t MACTSIACR; - __IO uint32_t MACTSEACR; - __IO uint32_t MACTSICNR; - __IO uint32_t MACTSECNR; - uint32_t RESERVED29[4]; - __IO uint32_t MACPPSCR; - uint32_t RESERVED30[3]; - __IO uint32_t MACPPSTTSR; - __IO uint32_t MACPPSTTNR; - __IO uint32_t MACPPSIR; - __IO uint32_t MACPPSWR; - uint32_t RESERVED31[12]; - __IO uint32_t MACPOCR; - __IO uint32_t MACSPI0R; - __IO uint32_t MACSPI1R; - __IO uint32_t MACSPI2R; - __IO uint32_t MACLMIR; - uint32_t RESERVED32[11]; - __IO uint32_t MTLOMR; - uint32_t RESERVED33[7]; - __IO uint32_t MTLISR; - uint32_t RESERVED34[55]; - __IO uint32_t MTLTQOMR; - __IO uint32_t MTLTQUR; - __IO uint32_t MTLTQDR; - uint32_t RESERVED35[8]; - __IO uint32_t MTLQICSR; - __IO uint32_t MTLRQOMR; - __IO uint32_t MTLRQMPOCR; - __IO uint32_t MTLRQDR; - uint32_t RESERVED36[177]; - __IO uint32_t DMAMR; - __IO uint32_t DMASBMR; - __IO uint32_t DMAISR; - __IO uint32_t DMADSR; - uint32_t RESERVED37[60]; - __IO uint32_t DMACCR; - __IO uint32_t DMACTCR; - __IO uint32_t DMACRCR; - uint32_t RESERVED38[2]; - __IO uint32_t DMACTDLAR; - uint32_t RESERVED39; - __IO uint32_t DMACRDLAR; - __IO uint32_t DMACTDTPR; - uint32_t RESERVED40; - __IO uint32_t DMACRDTPR; - __IO uint32_t DMACTDRLR; - __IO uint32_t DMACRDRLR; - __IO uint32_t DMACIER; - __IO uint32_t DMACRIWTR; -__IO uint32_t DMACSFCSR; - uint32_t RESERVED41; - __IO uint32_t DMACCATDR; - uint32_t RESERVED42; - __IO uint32_t DMACCARDR; - uint32_t RESERVED43; - __IO uint32_t DMACCATBR; - uint32_t RESERVED44; - __IO uint32_t DMACCARBR; - __IO uint32_t DMACSR; -uint32_t RESERVED45[2]; -__IO uint32_t DMACMFCR; -}ETH_TypeDef; -/** - * @brief External Interrupt/Event Controller - */ - -typedef struct -{ -__IO uint32_t RTSR1; /*!< EXTI Rising trigger selection register, Address offset: 0x00 */ -__IO uint32_t FTSR1; /*!< EXTI Falling trigger selection register, Address offset: 0x04 */ -__IO uint32_t SWIER1; /*!< EXTI Software interrupt event register, Address offset: 0x08 */ -__IO uint32_t D3PMR1; /*!< EXTI D3 Pending mask register, (same register as to SRDPMR1) Address offset: 0x0C */ -__IO uint32_t D3PCR1L; /*!< EXTI D3 Pending clear selection register low, (same register as to SRDPCR1L) Address offset: 0x10 */ -__IO uint32_t D3PCR1H; /*!< EXTI D3 Pending clear selection register High, (same register as to SRDPCR1H) Address offset: 0x14 */ -uint32_t RESERVED1[2]; /*!< Reserved, 0x18 to 0x1C */ -__IO uint32_t RTSR2; /*!< EXTI Rising trigger selection register, Address offset: 0x20 */ -__IO uint32_t FTSR2; /*!< EXTI Falling trigger selection register, Address offset: 0x24 */ -__IO uint32_t SWIER2; /*!< EXTI Software interrupt event register, Address offset: 0x28 */ -__IO uint32_t D3PMR2; /*!< EXTI D3 Pending mask register, (same register as to SRDPMR2) Address offset: 0x2C */ -__IO uint32_t D3PCR2L; /*!< EXTI D3 Pending clear selection register low, (same register as to SRDPCR2L) Address offset: 0x30 */ -__IO uint32_t D3PCR2H; /*!< EXTI D3 Pending clear selection register High, (same register as to SRDPCR2H) Address offset: 0x34 */ -uint32_t RESERVED2[2]; /*!< Reserved, 0x38 to 0x3C */ -__IO uint32_t RTSR3; /*!< EXTI Rising trigger selection register, Address offset: 0x40 */ -__IO uint32_t FTSR3; /*!< EXTI Falling trigger selection register, Address offset: 0x44 */ -__IO uint32_t SWIER3; /*!< EXTI Software interrupt event register, Address offset: 0x48 */ -__IO uint32_t D3PMR3; /*!< EXTI D3 Pending mask register, (same register as to SRDPMR3) Address offset: 0x4C */ -__IO uint32_t D3PCR3L; /*!< EXTI D3 Pending clear selection register low, (same register as to SRDPCR3L) Address offset: 0x50 */ -__IO uint32_t D3PCR3H; /*!< EXTI D3 Pending clear selection register High, (same register as to SRDPCR3H) Address offset: 0x54 */ -uint32_t RESERVED3[10]; /*!< Reserved, 0x58 to 0x7C */ -__IO uint32_t IMR1; /*!< EXTI Interrupt mask register, Address offset: 0x80 */ -__IO uint32_t EMR1; /*!< EXTI Event mask register, Address offset: 0x84 */ -__IO uint32_t PR1; /*!< EXTI Pending register, Address offset: 0x88 */ -uint32_t RESERVED4; /*!< Reserved, 0x8C */ -__IO uint32_t IMR2; /*!< EXTI Interrupt mask register, Address offset: 0x90 */ -__IO uint32_t EMR2; /*!< EXTI Event mask register, Address offset: 0x94 */ -__IO uint32_t PR2; /*!< EXTI Pending register, Address offset: 0x98 */ -uint32_t RESERVED5; /*!< Reserved, 0x9C */ -__IO uint32_t IMR3; /*!< EXTI Interrupt mask register, Address offset: 0xA0 */ -__IO uint32_t EMR3; /*!< EXTI Event mask register, Address offset: 0xA4 */ -__IO uint32_t PR3; /*!< EXTI Pending register, Address offset: 0xA8 */ -}EXTI_TypeDef; - -/** - * @brief This structure registers corresponds to EXTI_Typdef CPU1/CPU2 registers subset (IMRx, EMRx and PRx), allowing to define EXTI_D1/EXTI_D2 - * with rapid/common access to these IMRx, EMRx, PRx registers for CPU1 and CPU2. - * Note that EXTI_D1 and EXTI_D2 bases addresses are calculated to point to CPUx first register: - * IMR1 in case of EXTI_D1 that is addressing CPU1 (Coretx-M7) - * C2IMR1 in case of EXTI_D2 that is addressing CPU2 (Coretx-M4) - * Note: EXTI_D2 and corresponding C2IMRx, C2EMRx and C2PRx registers are available for Dual Core devices only - */ - -typedef struct -{ -__IO uint32_t IMR1; /*!< EXTI Interrupt mask register, Address offset: 0x00 */ -__IO uint32_t EMR1; /*!< EXTI Event mask register, Address offset: 0x04 */ -__IO uint32_t PR1; /*!< EXTI Pending register, Address offset: 0x08 */ -uint32_t RESERVED1; /*!< Reserved, 0x0C */ -__IO uint32_t IMR2; /*!< EXTI Interrupt mask register, Address offset: 0x10 */ -__IO uint32_t EMR2; /*!< EXTI Event mask register, Address offset: 0x14 */ -__IO uint32_t PR2; /*!< EXTI Pending register, Address offset: 0x18 */ -uint32_t RESERVED2; /*!< Reserved, 0x1C */ -__IO uint32_t IMR3; /*!< EXTI Interrupt mask register, Address offset: 0x20 */ -__IO uint32_t EMR3; /*!< EXTI Event mask register, Address offset: 0x24 */ -__IO uint32_t PR3; /*!< EXTI Pending register, Address offset: 0x28 */ -}EXTI_Core_TypeDef; - - -/** - * @brief FLASH Registers - */ - -typedef struct -{ - __IO uint32_t ACR; /*!< FLASH access control register, Address offset: 0x00 */ - __IO uint32_t KEYR1; /*!< Flash Key Register for bank1, Address offset: 0x04 */ - __IO uint32_t OPTKEYR; /*!< Flash Option Key Register, Address offset: 0x08 */ - __IO uint32_t CR1; /*!< Flash Control Register for bank1, Address offset: 0x0C */ - __IO uint32_t SR1; /*!< Flash Status Register for bank1, Address offset: 0x10 */ - __IO uint32_t CCR1; /*!< Flash Control Register for bank1, Address offset: 0x14 */ - __IO uint32_t OPTCR; /*!< Flash Option Control Register, Address offset: 0x18 */ - __IO uint32_t OPTSR_CUR; /*!< Flash Option Status Current Register, Address offset: 0x1C */ - __IO uint32_t OPTSR_PRG; /*!< Flash Option Status to Program Register, Address offset: 0x20 */ - __IO uint32_t OPTCCR; /*!< Flash Option Clear Control Register, Address offset: 0x24 */ - __IO uint32_t PRAR_CUR1; /*!< Flash Current Protection Address Register for bank1, Address offset: 0x28 */ - __IO uint32_t PRAR_PRG1; /*!< Flash Protection Address to Program Register for bank1, Address offset: 0x2C */ - __IO uint32_t SCAR_CUR1; /*!< Flash Current Secure Address Register for bank1, Address offset: 0x30 */ - __IO uint32_t SCAR_PRG1; /*!< Flash Secure Address to Program Register for bank1, Address offset: 0x34 */ - __IO uint32_t WPSN_CUR1; /*!< Flash Current Write Protection Register on bank1, Address offset: 0x38 */ - __IO uint32_t WPSN_PRG1; /*!< Flash Write Protection to Program Register on bank1, Address offset: 0x3C */ - __IO uint32_t BOOT_CUR; /*!< Flash Current Boot Address for Pelican Core Register, Address offset: 0x40 */ - __IO uint32_t BOOT_PRG; /*!< Flash Boot Address to Program for Pelican Core Register, Address offset: 0x44 */ - uint32_t RESERVED0[2]; /*!< Reserved, 0x48 to 0x4C */ - __IO uint32_t CRCCR1; /*!< Flash CRC Control register For Bank1 Register , Address offset: 0x50 */ - __IO uint32_t CRCSADD1; /*!< Flash CRC Start Address Register for Bank1 , Address offset: 0x54 */ - __IO uint32_t CRCEADD1; /*!< Flash CRC End Address Register for Bank1 , Address offset: 0x58 */ - __IO uint32_t CRCDATA; /*!< Flash CRC Data Register for Bank1 , Address offset: 0x5C */ - __IO uint32_t ECC_FA1; /*!< Flash ECC Fail Address For Bank1 Register , Address offset: 0x60 */ - uint32_t RESERVED[3]; /*!< Reserved, 0x64 to 0x6C */ - __IO uint32_t OPTSR2_CUR; /*!< Flash Option Status Current Register 2, Address offset: 0x70 */ - __IO uint32_t OPTSR2_PRG; /*!< Flash Option Status to Program Register 2, Address offset: 0x74 */ -} FLASH_TypeDef; - -/** - * @brief Filter and Mathematical ACcelerator - */ -typedef struct -{ - __IO uint32_t X1BUFCFG; /*!< FMAC X1 Buffer Configuration register, Address offset: 0x00 */ - __IO uint32_t X2BUFCFG; /*!< FMAC X2 Buffer Configuration register, Address offset: 0x04 */ - __IO uint32_t YBUFCFG; /*!< FMAC Y Buffer Configuration register, Address offset: 0x08 */ - __IO uint32_t PARAM; /*!< FMAC Parameter register, Address offset: 0x0C */ - __IO uint32_t CR; /*!< FMAC Control register, Address offset: 0x10 */ - __IO uint32_t SR; /*!< FMAC Status register, Address offset: 0x14 */ - __IO uint32_t WDATA; /*!< FMAC Write Data register, Address offset: 0x18 */ - __IO uint32_t RDATA; /*!< FMAC Read Data register, Address offset: 0x1C */ -} FMAC_TypeDef; - -/** - * @brief Flexible Memory Controller - */ - -typedef struct -{ - __IO uint32_t BTCR[8]; /*!< NOR/PSRAM chip-select control register(BCR) and chip-select timing register(BTR), Address offset: 0x00-1C */ -} FMC_Bank1_TypeDef; - -/** - * @brief Flexible Memory Controller Bank1E - */ - -typedef struct -{ - __IO uint32_t BWTR[7]; /*!< NOR/PSRAM write timing registers, Address offset: 0x104-0x11C */ -} FMC_Bank1E_TypeDef; - -/** - * @brief Flexible Memory Controller Bank2 - */ - -typedef struct -{ - __IO uint32_t PCR2; /*!< NAND Flash control register 2, Address offset: 0x60 */ - __IO uint32_t SR2; /*!< NAND Flash FIFO status and interrupt register 2, Address offset: 0x64 */ - __IO uint32_t PMEM2; /*!< NAND Flash Common memory space timing register 2, Address offset: 0x68 */ - __IO uint32_t PATT2; /*!< NAND Flash Attribute memory space timing register 2, Address offset: 0x6C */ - uint32_t RESERVED0; /*!< Reserved, 0x70 */ - __IO uint32_t ECCR2; /*!< NAND Flash ECC result registers 2, Address offset: 0x74 */ -} FMC_Bank2_TypeDef; - -/** - * @brief Flexible Memory Controller Bank3 - */ - -typedef struct -{ - __IO uint32_t PCR; /*!< NAND Flash control register 3, Address offset: 0x80 */ - __IO uint32_t SR; /*!< NAND Flash FIFO status and interrupt register 3, Address offset: 0x84 */ - __IO uint32_t PMEM; /*!< NAND Flash Common memory space timing register 3, Address offset: 0x88 */ - __IO uint32_t PATT; /*!< NAND Flash Attribute memory space timing register 3, Address offset: 0x8C */ - uint32_t RESERVED; /*!< Reserved, 0x90 */ - __IO uint32_t ECCR; /*!< NAND Flash ECC result registers 3, Address offset: 0x94 */ -} FMC_Bank3_TypeDef; - -/** - * @brief Flexible Memory Controller Bank5 and 6 - */ - - -typedef struct -{ - __IO uint32_t SDCR[2]; /*!< SDRAM Control registers , Address offset: 0x140-0x144 */ - __IO uint32_t SDTR[2]; /*!< SDRAM Timing registers , Address offset: 0x148-0x14C */ - __IO uint32_t SDCMR; /*!< SDRAM Command Mode register, Address offset: 0x150 */ - __IO uint32_t SDRTR; /*!< SDRAM Refresh Timer register, Address offset: 0x154 */ - __IO uint32_t SDSR; /*!< SDRAM Status register, Address offset: 0x158 */ -} FMC_Bank5_6_TypeDef; - -/** - * @brief General Purpose I/O - */ - -typedef struct -{ - __IO uint32_t MODER; /*!< GPIO port mode register, Address offset: 0x00 */ - __IO uint32_t OTYPER; /*!< GPIO port output type register, Address offset: 0x04 */ - __IO uint32_t OSPEEDR; /*!< GPIO port output speed register, Address offset: 0x08 */ - __IO uint32_t PUPDR; /*!< GPIO port pull-up/pull-down register, Address offset: 0x0C */ - __IO uint32_t IDR; /*!< GPIO port input data register, Address offset: 0x10 */ - __IO uint32_t ODR; /*!< GPIO port output data register, Address offset: 0x14 */ - __IO uint32_t BSRR; /*!< GPIO port bit set/reset, Address offset: 0x18 */ - __IO uint32_t LCKR; /*!< GPIO port configuration lock register, Address offset: 0x1C */ - __IO uint32_t AFR[2]; /*!< GPIO alternate function registers, Address offset: 0x20-0x24 */ -} GPIO_TypeDef; - -/** - * @brief Operational Amplifier (OPAMP) - */ - -typedef struct -{ - __IO uint32_t CSR; /*!< OPAMP control/status register, Address offset: 0x00 */ - __IO uint32_t OTR; /*!< OPAMP offset trimming register for normal mode, Address offset: 0x04 */ - __IO uint32_t HSOTR; /*!< OPAMP offset trimming register for high speed mode, Address offset: 0x08 */ -} OPAMP_TypeDef; - -/** - * @brief System configuration controller - */ - -typedef struct -{ - uint32_t RESERVED1; /*!< Reserved, Address offset: 0x00 */ - __IO uint32_t PMCR; /*!< SYSCFG peripheral mode configuration register, Address offset: 0x04 */ - __IO uint32_t EXTICR[4]; /*!< SYSCFG external interrupt configuration registers, Address offset: 0x08-0x14 */ - __IO uint32_t CFGR; /*!< SYSCFG configuration registers, Address offset: 0x18 */ - uint32_t RESERVED2; /*!< Reserved, Address offset: 0x1C */ - __IO uint32_t CCCSR; /*!< SYSCFG compensation cell control/status register, Address offset: 0x20 */ - __IO uint32_t CCVR; /*!< SYSCFG compensation cell value register, Address offset: 0x24 */ - __IO uint32_t CCCR; /*!< SYSCFG compensation cell code register, Address offset: 0x28 */ - uint32_t RESERVED3; /*!< Reserved, Address offset: 0x2C */ - __IO uint32_t ADC2ALT; /*!< ADC2 internal input alternate connection register, Address offset: 0x30 */ - uint32_t RESERVED4[60]; /*!< Reserved, 0x34-0x120 */ - __IO uint32_t PKGR; /*!< SYSCFG package register, Address offset: 0x124 */ - uint32_t RESERVED5[118]; /*!< Reserved, 0x128-0x2FC */ - __IO uint32_t UR0; /*!< SYSCFG user register 0, Address offset: 0x300 */ - __IO uint32_t UR1; /*!< SYSCFG user register 1, Address offset: 0x304 */ - __IO uint32_t UR2; /*!< SYSCFG user register 2, Address offset: 0x308 */ - __IO uint32_t UR3; /*!< SYSCFG user register 3, Address offset: 0x30C */ - __IO uint32_t UR4; /*!< SYSCFG user register 4, Address offset: 0x310 */ - __IO uint32_t UR5; /*!< SYSCFG user register 5, Address offset: 0x314 */ - __IO uint32_t UR6; /*!< SYSCFG user register 6, Address offset: 0x318 */ - __IO uint32_t UR7; /*!< SYSCFG user register 7, Address offset: 0x31C */ - uint32_t RESERVED6[3]; /*!< Reserved, Address offset: 0x320-0x328 */ - __IO uint32_t UR11; /*!< SYSCFG user register 11, Address offset: 0x32C */ - __IO uint32_t UR12; /*!< SYSCFG user register 12, Address offset: 0x330 */ - __IO uint32_t UR13; /*!< SYSCFG user register 13, Address offset: 0x334 */ - __IO uint32_t UR14; /*!< SYSCFG user register 14, Address offset: 0x338 */ - __IO uint32_t UR15; /*!< SYSCFG user register 15, Address offset: 0x33C */ - __IO uint32_t UR16; /*!< SYSCFG user register 16, Address offset: 0x340 */ - __IO uint32_t UR17; /*!< SYSCFG user register 17, Address offset: 0x344 */ - __IO uint32_t UR18; /*!< SYSCFG user register 18, Address offset: 0x348 */ - -} SYSCFG_TypeDef; - -/** - * @brief Inter-integrated Circuit Interface - */ - -typedef struct -{ - __IO uint32_t CR1; /*!< I2C Control register 1, Address offset: 0x00 */ - __IO uint32_t CR2; /*!< I2C Control register 2, Address offset: 0x04 */ - __IO uint32_t OAR1; /*!< I2C Own address 1 register, Address offset: 0x08 */ - __IO uint32_t OAR2; /*!< I2C Own address 2 register, Address offset: 0x0C */ - __IO uint32_t TIMINGR; /*!< I2C Timing register, Address offset: 0x10 */ - __IO uint32_t TIMEOUTR; /*!< I2C Timeout register, Address offset: 0x14 */ - __IO uint32_t ISR; /*!< I2C Interrupt and status register, Address offset: 0x18 */ - __IO uint32_t ICR; /*!< I2C Interrupt clear register, Address offset: 0x1C */ - __IO uint32_t PECR; /*!< I2C PEC register, Address offset: 0x20 */ - __IO uint32_t RXDR; /*!< I2C Receive data register, Address offset: 0x24 */ - __IO uint32_t TXDR; /*!< I2C Transmit data register, Address offset: 0x28 */ -} I2C_TypeDef; - -/** - * @brief Independent WATCHDOG - */ - -typedef struct -{ - __IO uint32_t KR; /*!< IWDG Key register, Address offset: 0x00 */ - __IO uint32_t PR; /*!< IWDG Prescaler register, Address offset: 0x04 */ - __IO uint32_t RLR; /*!< IWDG Reload register, Address offset: 0x08 */ - __IO uint32_t SR; /*!< IWDG Status register, Address offset: 0x0C */ - __IO uint32_t WINR; /*!< IWDG Window register, Address offset: 0x10 */ -} IWDG_TypeDef; - - -/** - * @brief LCD-TFT Display Controller - */ - -typedef struct -{ - uint32_t RESERVED0[2]; /*!< Reserved, 0x00-0x04 */ - __IO uint32_t SSCR; /*!< LTDC Synchronization Size Configuration Register, Address offset: 0x08 */ - __IO uint32_t BPCR; /*!< LTDC Back Porch Configuration Register, Address offset: 0x0C */ - __IO uint32_t AWCR; /*!< LTDC Active Width Configuration Register, Address offset: 0x10 */ - __IO uint32_t TWCR; /*!< LTDC Total Width Configuration Register, Address offset: 0x14 */ - __IO uint32_t GCR; /*!< LTDC Global Control Register, Address offset: 0x18 */ - uint32_t RESERVED1[2]; /*!< Reserved, 0x1C-0x20 */ - __IO uint32_t SRCR; /*!< LTDC Shadow Reload Configuration Register, Address offset: 0x24 */ - uint32_t RESERVED2[1]; /*!< Reserved, 0x28 */ - __IO uint32_t BCCR; /*!< LTDC Background Color Configuration Register, Address offset: 0x2C */ - uint32_t RESERVED3[1]; /*!< Reserved, 0x30 */ - __IO uint32_t IER; /*!< LTDC Interrupt Enable Register, Address offset: 0x34 */ - __IO uint32_t ISR; /*!< LTDC Interrupt Status Register, Address offset: 0x38 */ - __IO uint32_t ICR; /*!< LTDC Interrupt Clear Register, Address offset: 0x3C */ - __IO uint32_t LIPCR; /*!< LTDC Line Interrupt Position Configuration Register, Address offset: 0x40 */ - __IO uint32_t CPSR; /*!< LTDC Current Position Status Register, Address offset: 0x44 */ - __IO uint32_t CDSR; /*!< LTDC Current Display Status Register, Address offset: 0x48 */ -} LTDC_TypeDef; - -/** - * @brief LCD-TFT Display layer x Controller - */ - -typedef struct -{ - __IO uint32_t CR; /*!< LTDC Layerx Control Register Address offset: 0x84 */ - __IO uint32_t WHPCR; /*!< LTDC Layerx Window Horizontal Position Configuration Register Address offset: 0x88 */ - __IO uint32_t WVPCR; /*!< LTDC Layerx Window Vertical Position Configuration Register Address offset: 0x8C */ - __IO uint32_t CKCR; /*!< LTDC Layerx Color Keying Configuration Register Address offset: 0x90 */ - __IO uint32_t PFCR; /*!< LTDC Layerx Pixel Format Configuration Register Address offset: 0x94 */ - __IO uint32_t CACR; /*!< LTDC Layerx Constant Alpha Configuration Register Address offset: 0x98 */ - __IO uint32_t DCCR; /*!< LTDC Layerx Default Color Configuration Register Address offset: 0x9C */ - __IO uint32_t BFCR; /*!< LTDC Layerx Blending Factors Configuration Register Address offset: 0xA0 */ - uint32_t RESERVED0[2]; /*!< Reserved */ - __IO uint32_t CFBAR; /*!< LTDC Layerx Color Frame Buffer Address Register Address offset: 0xAC */ - __IO uint32_t CFBLR; /*!< LTDC Layerx Color Frame Buffer Length Register Address offset: 0xB0 */ - __IO uint32_t CFBLNR; /*!< LTDC Layerx ColorFrame Buffer Line Number Register Address offset: 0xB4 */ - uint32_t RESERVED1[3]; /*!< Reserved */ - __IO uint32_t CLUTWR; /*!< LTDC Layerx CLUT Write Register Address offset: 0x144 */ - -} LTDC_Layer_TypeDef; - -/** - * @brief Power Control - */ - -typedef struct -{ - __IO uint32_t CR1; /*!< PWR power control register 1, Address offset: 0x00 */ - __IO uint32_t CSR1; /*!< PWR power control status register 1, Address offset: 0x04 */ - __IO uint32_t CR2; /*!< PWR power control register 2, Address offset: 0x08 */ - __IO uint32_t CR3; /*!< PWR power control register 3, Address offset: 0x0C */ - __IO uint32_t CPUCR; /*!< PWR CPU control register, Address offset: 0x10 */ - uint32_t RESERVED0; /*!< Reserved, Address offset: 0x14 */ - __IO uint32_t D3CR; /*!< PWR D3 domain control register, Address offset: 0x18 */ - uint32_t RESERVED1; /*!< Reserved, Address offset: 0x1C */ - __IO uint32_t WKUPCR; /*!< PWR wakeup clear register, Address offset: 0x20 */ - __IO uint32_t WKUPFR; /*!< PWR wakeup flag register, Address offset: 0x24 */ - __IO uint32_t WKUPEPR; /*!< PWR wakeup enable and polarity register, Address offset: 0x28 */ -} PWR_TypeDef; - -/** - * @brief Reset and Clock Control - */ - -typedef struct -{ - __IO uint32_t CR; /*!< RCC clock control register, Address offset: 0x00 */ - __IO uint32_t HSICFGR; /*!< HSI Clock Calibration Register, Address offset: 0x04 */ - __IO uint32_t CRRCR; /*!< Clock Recovery RC Register, Address offset: 0x08 */ - __IO uint32_t CSICFGR; /*!< CSI Clock Calibration Register, Address offset: 0x0C */ - __IO uint32_t CFGR; /*!< RCC clock configuration register, Address offset: 0x10 */ - uint32_t RESERVED1; /*!< Reserved, Address offset: 0x14 */ - __IO uint32_t D1CFGR; /*!< RCC Domain 1 configuration register, Address offset: 0x18 */ - __IO uint32_t D2CFGR; /*!< RCC Domain 2 configuration register, Address offset: 0x1C */ - __IO uint32_t D3CFGR; /*!< RCC Domain 3 configuration register, Address offset: 0x20 */ - uint32_t RESERVED2; /*!< Reserved, Address offset: 0x24 */ - __IO uint32_t PLLCKSELR; /*!< RCC PLLs Clock Source Selection Register, Address offset: 0x28 */ - __IO uint32_t PLLCFGR; /*!< RCC PLLs Configuration Register, Address offset: 0x2C */ - __IO uint32_t PLL1DIVR; /*!< RCC PLL1 Dividers Configuration Register, Address offset: 0x30 */ - __IO uint32_t PLL1FRACR; /*!< RCC PLL1 Fractional Divider Configuration Register, Address offset: 0x34 */ - __IO uint32_t PLL2DIVR; /*!< RCC PLL2 Dividers Configuration Register, Address offset: 0x38 */ - __IO uint32_t PLL2FRACR; /*!< RCC PLL2 Fractional Divider Configuration Register, Address offset: 0x3C */ - __IO uint32_t PLL3DIVR; /*!< RCC PLL3 Dividers Configuration Register, Address offset: 0x40 */ - __IO uint32_t PLL3FRACR; /*!< RCC PLL3 Fractional Divider Configuration Register, Address offset: 0x44 */ - uint32_t RESERVED3; /*!< Reserved, Address offset: 0x48 */ - __IO uint32_t D1CCIPR; /*!< RCC Domain 1 Kernel Clock Configuration Register Address offset: 0x4C */ - __IO uint32_t D2CCIP1R; /*!< RCC Domain 2 Kernel Clock Configuration Register Address offset: 0x50 */ - __IO uint32_t D2CCIP2R; /*!< RCC Domain 2 Kernel Clock Configuration Register Address offset: 0x54 */ - __IO uint32_t D3CCIPR; /*!< RCC Domain 3 Kernel Clock Configuration Register Address offset: 0x58 */ - uint32_t RESERVED4; /*!< Reserved, Address offset: 0x5C */ - __IO uint32_t CIER; /*!< RCC Clock Source Interrupt Enable Register Address offset: 0x60 */ - __IO uint32_t CIFR; /*!< RCC Clock Source Interrupt Flag Register Address offset: 0x64 */ - __IO uint32_t CICR; /*!< RCC Clock Source Interrupt Clear Register Address offset: 0x68 */ - uint32_t RESERVED5; /*!< Reserved, Address offset: 0x6C */ - __IO uint32_t BDCR; /*!< RCC Vswitch Backup Domain Control Register, Address offset: 0x70 */ - __IO uint32_t CSR; /*!< RCC clock control & status register, Address offset: 0x74 */ - uint32_t RESERVED6; /*!< Reserved, Address offset: 0x78 */ - __IO uint32_t AHB3RSTR; /*!< RCC AHB3 peripheral reset register, Address offset: 0x7C */ - __IO uint32_t AHB1RSTR; /*!< RCC AHB1 peripheral reset register, Address offset: 0x80 */ - __IO uint32_t AHB2RSTR; /*!< RCC AHB2 peripheral reset register, Address offset: 0x84 */ - __IO uint32_t AHB4RSTR; /*!< RCC AHB4 peripheral reset register, Address offset: 0x88 */ - __IO uint32_t APB3RSTR; /*!< RCC APB3 peripheral reset register, Address offset: 0x8C */ - __IO uint32_t APB1LRSTR; /*!< RCC APB1 peripheral reset Low Word register, Address offset: 0x90 */ - __IO uint32_t APB1HRSTR; /*!< RCC APB1 peripheral reset High Word register, Address offset: 0x94 */ - __IO uint32_t APB2RSTR; /*!< RCC APB2 peripheral reset register, Address offset: 0x98 */ - __IO uint32_t APB4RSTR; /*!< RCC APB4 peripheral reset register, Address offset: 0x9C */ - __IO uint32_t GCR; /*!< RCC RCC Global Control Register, Address offset: 0xA0 */ - uint32_t RESERVED8; /*!< Reserved, Address offset: 0xA4 */ - __IO uint32_t D3AMR; /*!< RCC Domain 3 Autonomous Mode Register, Address offset: 0xA8 */ - uint32_t RESERVED11[9]; /*!< Reserved, 0xAC-0xCC Address offset: 0xAC */ - __IO uint32_t RSR; /*!< RCC Reset status register, Address offset: 0xD0 */ - __IO uint32_t AHB3ENR; /*!< RCC AHB3 peripheral clock register, Address offset: 0xD4 */ - __IO uint32_t AHB1ENR; /*!< RCC AHB1 peripheral clock register, Address offset: 0xD8 */ - __IO uint32_t AHB2ENR; /*!< RCC AHB2 peripheral clock register, Address offset: 0xDC */ - __IO uint32_t AHB4ENR; /*!< RCC AHB4 peripheral clock register, Address offset: 0xE0 */ - __IO uint32_t APB3ENR; /*!< RCC APB3 peripheral clock register, Address offset: 0xE4 */ - __IO uint32_t APB1LENR; /*!< RCC APB1 peripheral clock Low Word register, Address offset: 0xE8 */ - __IO uint32_t APB1HENR; /*!< RCC APB1 peripheral clock High Word register, Address offset: 0xEC */ - __IO uint32_t APB2ENR; /*!< RCC APB2 peripheral clock register, Address offset: 0xF0 */ - __IO uint32_t APB4ENR; /*!< RCC APB4 peripheral clock register, Address offset: 0xF4 */ - uint32_t RESERVED12; /*!< Reserved, Address offset: 0xF8 */ - __IO uint32_t AHB3LPENR; /*!< RCC AHB3 peripheral sleep clock register, Address offset: 0xFC */ - __IO uint32_t AHB1LPENR; /*!< RCC AHB1 peripheral sleep clock register, Address offset: 0x100 */ - __IO uint32_t AHB2LPENR; /*!< RCC AHB2 peripheral sleep clock register, Address offset: 0x104 */ - __IO uint32_t AHB4LPENR; /*!< RCC AHB4 peripheral sleep clock register, Address offset: 0x108 */ - __IO uint32_t APB3LPENR; /*!< RCC APB3 peripheral sleep clock register, Address offset: 0x10C */ - __IO uint32_t APB1LLPENR; /*!< RCC APB1 peripheral sleep clock Low Word register, Address offset: 0x110 */ - __IO uint32_t APB1HLPENR; /*!< RCC APB1 peripheral sleep clock High Word register, Address offset: 0x114 */ - __IO uint32_t APB2LPENR; /*!< RCC APB2 peripheral sleep clock register, Address offset: 0x118 */ - __IO uint32_t APB4LPENR; /*!< RCC APB4 peripheral sleep clock register, Address offset: 0x11C */ - uint32_t RESERVED13[4]; /*!< Reserved, 0x120-0x12C Address offset: 0x120 */ - -} RCC_TypeDef; - - -/** - * @brief Real-Time Clock - */ -typedef struct -{ - __IO uint32_t TR; /*!< RTC time register, Address offset: 0x00 */ - __IO uint32_t DR; /*!< RTC date register, Address offset: 0x04 */ - __IO uint32_t CR; /*!< RTC control register, Address offset: 0x08 */ - __IO uint32_t ISR; /*!< RTC initialization and status register, Address offset: 0x0C */ - __IO uint32_t PRER; /*!< RTC prescaler register, Address offset: 0x10 */ - __IO uint32_t WUTR; /*!< RTC wakeup timer register, Address offset: 0x14 */ - uint32_t RESERVED; /*!< Reserved, Address offset: 0x18 */ - __IO uint32_t ALRMAR; /*!< RTC alarm A register, Address offset: 0x1C */ - __IO uint32_t ALRMBR; /*!< RTC alarm B register, Address offset: 0x20 */ - __IO uint32_t WPR; /*!< RTC write protection register, Address offset: 0x24 */ - __IO uint32_t SSR; /*!< RTC sub second register, Address offset: 0x28 */ - __IO uint32_t SHIFTR; /*!< RTC shift control register, Address offset: 0x2C */ - __IO uint32_t TSTR; /*!< RTC time stamp time register, Address offset: 0x30 */ - __IO uint32_t TSDR; /*!< RTC time stamp date register, Address offset: 0x34 */ - __IO uint32_t TSSSR; /*!< RTC time-stamp sub second register, Address offset: 0x38 */ - __IO uint32_t CALR; /*!< RTC calibration register, Address offset: 0x3C */ - __IO uint32_t TAMPCR; /*!< RTC tamper configuration register, Address offset: 0x40 */ - __IO uint32_t ALRMASSR; /*!< RTC alarm A sub second register, Address offset: 0x44 */ - __IO uint32_t ALRMBSSR; /*!< RTC alarm B sub second register, Address offset: 0x48 */ - __IO uint32_t OR; /*!< RTC option register, Address offset: 0x4C */ - __IO uint32_t BKP0R; /*!< RTC backup register 0, Address offset: 0x50 */ - __IO uint32_t BKP1R; /*!< RTC backup register 1, Address offset: 0x54 */ - __IO uint32_t BKP2R; /*!< RTC backup register 2, Address offset: 0x58 */ - __IO uint32_t BKP3R; /*!< RTC backup register 3, Address offset: 0x5C */ - __IO uint32_t BKP4R; /*!< RTC backup register 4, Address offset: 0x60 */ - __IO uint32_t BKP5R; /*!< RTC backup register 5, Address offset: 0x64 */ - __IO uint32_t BKP6R; /*!< RTC backup register 6, Address offset: 0x68 */ - __IO uint32_t BKP7R; /*!< RTC backup register 7, Address offset: 0x6C */ - __IO uint32_t BKP8R; /*!< RTC backup register 8, Address offset: 0x70 */ - __IO uint32_t BKP9R; /*!< RTC backup register 9, Address offset: 0x74 */ - __IO uint32_t BKP10R; /*!< RTC backup register 10, Address offset: 0x78 */ - __IO uint32_t BKP11R; /*!< RTC backup register 11, Address offset: 0x7C */ - __IO uint32_t BKP12R; /*!< RTC backup register 12, Address offset: 0x80 */ - __IO uint32_t BKP13R; /*!< RTC backup register 13, Address offset: 0x84 */ - __IO uint32_t BKP14R; /*!< RTC backup register 14, Address offset: 0x88 */ - __IO uint32_t BKP15R; /*!< RTC backup register 15, Address offset: 0x8C */ - __IO uint32_t BKP16R; /*!< RTC backup register 16, Address offset: 0x90 */ - __IO uint32_t BKP17R; /*!< RTC backup register 17, Address offset: 0x94 */ - __IO uint32_t BKP18R; /*!< RTC backup register 18, Address offset: 0x98 */ - __IO uint32_t BKP19R; /*!< RTC backup register 19, Address offset: 0x9C */ - __IO uint32_t BKP20R; /*!< RTC backup register 20, Address offset: 0xA0 */ - __IO uint32_t BKP21R; /*!< RTC backup register 21, Address offset: 0xA4 */ - __IO uint32_t BKP22R; /*!< RTC backup register 22, Address offset: 0xA8 */ - __IO uint32_t BKP23R; /*!< RTC backup register 23, Address offset: 0xAC */ - __IO uint32_t BKP24R; /*!< RTC backup register 24, Address offset: 0xB0 */ - __IO uint32_t BKP25R; /*!< RTC backup register 25, Address offset: 0xB4 */ - __IO uint32_t BKP26R; /*!< RTC backup register 26, Address offset: 0xB8 */ - __IO uint32_t BKP27R; /*!< RTC backup register 27, Address offset: 0xBC */ - __IO uint32_t BKP28R; /*!< RTC backup register 28, Address offset: 0xC0 */ - __IO uint32_t BKP29R; /*!< RTC backup register 29, Address offset: 0xC4 */ - __IO uint32_t BKP30R; /*!< RTC backup register 30, Address offset: 0xC8 */ - __IO uint32_t BKP31R; /*!< RTC backup register 31, Address offset: 0xCC */ -} RTC_TypeDef; - -/** - * @brief Serial Audio Interface - */ - -typedef struct -{ - __IO uint32_t GCR; /*!< SAI global configuration register, Address offset: 0x00 */ - uint32_t RESERVED0[16]; /*!< Reserved, 0x04 - 0x43 */ - __IO uint32_t PDMCR; /*!< SAI PDM control register, Address offset: 0x44 */ - __IO uint32_t PDMDLY; /*!< SAI PDM delay register, Address offset: 0x48 */ -} SAI_TypeDef; - -typedef struct -{ - __IO uint32_t CR1; /*!< SAI block x configuration register 1, Address offset: 0x04 */ - __IO uint32_t CR2; /*!< SAI block x configuration register 2, Address offset: 0x08 */ - __IO uint32_t FRCR; /*!< SAI block x frame configuration register, Address offset: 0x0C */ - __IO uint32_t SLOTR; /*!< SAI block x slot register, Address offset: 0x10 */ - __IO uint32_t IMR; /*!< SAI block x interrupt mask register, Address offset: 0x14 */ - __IO uint32_t SR; /*!< SAI block x status register, Address offset: 0x18 */ - __IO uint32_t CLRFR; /*!< SAI block x clear flag register, Address offset: 0x1C */ - __IO uint32_t DR; /*!< SAI block x data register, Address offset: 0x20 */ -} SAI_Block_TypeDef; - -/** - * @brief SPDIF-RX Interface - */ - -typedef struct -{ - __IO uint32_t CR; /*!< Control register, Address offset: 0x00 */ - __IO uint32_t IMR; /*!< Interrupt mask register, Address offset: 0x04 */ - __IO uint32_t SR; /*!< Status register, Address offset: 0x08 */ - __IO uint32_t IFCR; /*!< Interrupt Flag Clear register, Address offset: 0x0C */ - __IO uint32_t DR; /*!< Data input register, Address offset: 0x10 */ - __IO uint32_t CSR; /*!< Channel Status register, Address offset: 0x14 */ - __IO uint32_t DIR; /*!< Debug Information register, Address offset: 0x18 */ - uint32_t RESERVED2; /*!< Reserved, 0x1A */ -} SPDIFRX_TypeDef; - - -/** - * @brief Secure digital input/output Interface - */ - -typedef struct -{ - __IO uint32_t POWER; /*!< SDMMC power control register, Address offset: 0x00 */ - __IO uint32_t CLKCR; /*!< SDMMC clock control register, Address offset: 0x04 */ - __IO uint32_t ARG; /*!< SDMMC argument register, Address offset: 0x08 */ - __IO uint32_t CMD; /*!< SDMMC command register, Address offset: 0x0C */ - __I uint32_t RESPCMD; /*!< SDMMC command response register, Address offset: 0x10 */ - __I uint32_t RESP1; /*!< SDMMC response 1 register, Address offset: 0x14 */ - __I uint32_t RESP2; /*!< SDMMC response 2 register, Address offset: 0x18 */ - __I uint32_t RESP3; /*!< SDMMC response 3 register, Address offset: 0x1C */ - __I uint32_t RESP4; /*!< SDMMC response 4 register, Address offset: 0x20 */ - __IO uint32_t DTIMER; /*!< SDMMC data timer register, Address offset: 0x24 */ - __IO uint32_t DLEN; /*!< SDMMC data length register, Address offset: 0x28 */ - __IO uint32_t DCTRL; /*!< SDMMC data control register, Address offset: 0x2C */ - __I uint32_t DCOUNT; /*!< SDMMC data counter register, Address offset: 0x30 */ - __I uint32_t STA; /*!< SDMMC status register, Address offset: 0x34 */ - __IO uint32_t ICR; /*!< SDMMC interrupt clear register, Address offset: 0x38 */ - __IO uint32_t MASK; /*!< SDMMC mask register, Address offset: 0x3C */ - __IO uint32_t ACKTIME; /*!< SDMMC Acknowledgement timer register, Address offset: 0x40 */ - uint32_t RESERVED0[3]; /*!< Reserved, 0x44 - 0x4C - 0x4C */ - __IO uint32_t IDMACTRL; /*!< SDMMC DMA control register, Address offset: 0x50 */ - __IO uint32_t IDMABSIZE; /*!< SDMMC DMA buffer size register, Address offset: 0x54 */ - __IO uint32_t IDMABASE0; /*!< SDMMC DMA buffer 0 base address register, Address offset: 0x58 */ - __IO uint32_t IDMABASE1; /*!< SDMMC DMA buffer 1 base address register, Address offset: 0x5C */ - uint32_t RESERVED1[8]; /*!< Reserved, 0x60-0x7C */ - __IO uint32_t FIFO; /*!< SDMMC data FIFO register, Address offset: 0x80 */ - uint32_t RESERVED2[222]; /*!< Reserved, 0x84-0x3F8 */ - __IO uint32_t IPVR; /*!< SDMMC data FIFO register, Address offset: 0x3FC */ -} SDMMC_TypeDef; - - -/** - * @brief Delay Block DLYB - */ - -typedef struct -{ - __IO uint32_t CR; /*!< DELAY BLOCK control register, Address offset: 0x00 */ - __IO uint32_t CFGR; /*!< DELAY BLOCK configuration register, Address offset: 0x04 */ -} DLYB_TypeDef; - -/** - * @brief HW Semaphore HSEM - */ - -typedef struct -{ - __IO uint32_t R[32]; /*!< 2-step write lock and read back registers, Address offset: 00h-7Ch */ - __IO uint32_t RLR[32]; /*!< 1-step read lock registers, Address offset: 80h-FCh */ - __IO uint32_t C1IER; /*!< HSEM Interrupt enable register , Address offset: 100h */ - __IO uint32_t C1ICR; /*!< HSEM Interrupt clear register , Address offset: 104h */ - __IO uint32_t C1ISR; /*!< HSEM Interrupt Status register , Address offset: 108h */ - __IO uint32_t C1MISR; /*!< HSEM Interrupt Masked Status register , Address offset: 10Ch */ - uint32_t Reserved[12]; /* Reserved Address offset: 110h-13Ch */ - __IO uint32_t CR; /*!< HSEM Semaphore clear register , Address offset: 140h */ - __IO uint32_t KEYR; /*!< HSEM Semaphore clear key register , Address offset: 144h */ - -} HSEM_TypeDef; - -typedef struct -{ - __IO uint32_t IER; /*!< HSEM interrupt enable register , Address offset: 0h */ - __IO uint32_t ICR; /*!< HSEM interrupt clear register , Address offset: 4h */ - __IO uint32_t ISR; /*!< HSEM interrupt status register , Address offset: 8h */ - __IO uint32_t MISR; /*!< HSEM masked interrupt status register , Address offset: Ch */ -} HSEM_Common_TypeDef; - -/** - * @brief Serial Peripheral Interface - */ - -typedef struct -{ - __IO uint32_t CR1; /*!< SPI/I2S Control register 1, Address offset: 0x00 */ - __IO uint32_t CR2; /*!< SPI Control register 2, Address offset: 0x04 */ - __IO uint32_t CFG1; /*!< SPI Configuration register 1, Address offset: 0x08 */ - __IO uint32_t CFG2; /*!< SPI Configuration register 2, Address offset: 0x0C */ - __IO uint32_t IER; /*!< SPI/I2S Interrupt Enable register, Address offset: 0x10 */ - __IO uint32_t SR; /*!< SPI/I2S Status register, Address offset: 0x14 */ - __IO uint32_t IFCR; /*!< SPI/I2S Interrupt/Status flags clear register, Address offset: 0x18 */ - uint32_t RESERVED0; /*!< Reserved, 0x1C */ - __IO uint32_t TXDR; /*!< SPI/I2S Transmit data register, Address offset: 0x20 */ - uint32_t RESERVED1[3]; /*!< Reserved, 0x24-0x2C */ - __IO uint32_t RXDR; /*!< SPI/I2S Receive data register, Address offset: 0x30 */ - uint32_t RESERVED2[3]; /*!< Reserved, 0x34-0x3C */ - __IO uint32_t CRCPOLY; /*!< SPI CRC Polynomial register, Address offset: 0x40 */ - __IO uint32_t TXCRC; /*!< SPI Transmitter CRC register, Address offset: 0x44 */ - __IO uint32_t RXCRC; /*!< SPI Receiver CRC register, Address offset: 0x48 */ - __IO uint32_t UDRDR; /*!< SPI Underrun data register, Address offset: 0x4C */ - __IO uint32_t I2SCFGR; /*!< I2S Configuration register, Address offset: 0x50 */ - -} SPI_TypeDef; - -/** - * @brief DTS - */ -typedef struct -{ - __IO uint32_t CFGR1; /*!< DTS configuration register, Address offset: 0x00 */ - uint32_t RESERVED0; /*!< Reserved, Address offset: 0x04 */ - __IO uint32_t T0VALR1; /*!< DTS T0 Value register, Address offset: 0x08 */ - uint32_t RESERVED1; /*!< Reserved, Address offset: 0x0C */ - __IO uint32_t RAMPVALR; /*!< DTS Ramp value register, Address offset: 0x10 */ - __IO uint32_t ITR1; /*!< DTS Interrupt threshold register, Address offset: 0x14 */ - uint32_t RESERVED2; /*!< Reserved, Address offset: 0x18 */ - __IO uint32_t DR; /*!< DTS data register, Address offset: 0x1C */ - __IO uint32_t SR; /*!< DTS status register Address offset: 0x20 */ - __IO uint32_t ITENR; /*!< DTS Interrupt enable register, Address offset: 0x24 */ - __IO uint32_t ICIFR; /*!< DTS Clear Interrupt flag register, Address offset: 0x28 */ - __IO uint32_t OR; /*!< DTS option register 1, Address offset: 0x2C */ -} -DTS_TypeDef; - -/** - * @brief TIM - */ - -typedef struct -{ - __IO uint32_t CR1; /*!< TIM control register 1, Address offset: 0x00 */ - __IO uint32_t CR2; /*!< TIM control register 2, Address offset: 0x04 */ - __IO uint32_t SMCR; /*!< TIM slave mode control register, Address offset: 0x08 */ - __IO uint32_t DIER; /*!< TIM DMA/interrupt enable register, Address offset: 0x0C */ - __IO uint32_t SR; /*!< TIM status register, Address offset: 0x10 */ - __IO uint32_t EGR; /*!< TIM event generation register, Address offset: 0x14 */ - __IO uint32_t CCMR1; /*!< TIM capture/compare mode register 1, Address offset: 0x18 */ - __IO uint32_t CCMR2; /*!< TIM capture/compare mode register 2, Address offset: 0x1C */ - __IO uint32_t CCER; /*!< TIM capture/compare enable register, Address offset: 0x20 */ - __IO uint32_t CNT; /*!< TIM counter register, Address offset: 0x24 */ - __IO uint32_t PSC; /*!< TIM prescaler, Address offset: 0x28 */ - __IO uint32_t ARR; /*!< TIM auto-reload register, Address offset: 0x2C */ - __IO uint32_t RCR; /*!< TIM repetition counter register, Address offset: 0x30 */ - __IO uint32_t CCR1; /*!< TIM capture/compare register 1, Address offset: 0x34 */ - __IO uint32_t CCR2; /*!< TIM capture/compare register 2, Address offset: 0x38 */ - __IO uint32_t CCR3; /*!< TIM capture/compare register 3, Address offset: 0x3C */ - __IO uint32_t CCR4; /*!< TIM capture/compare register 4, Address offset: 0x40 */ - __IO uint32_t BDTR; /*!< TIM break and dead-time register, Address offset: 0x44 */ - __IO uint32_t DCR; /*!< TIM DMA control register, Address offset: 0x48 */ - __IO uint32_t DMAR; /*!< TIM DMA address for full transfer, Address offset: 0x4C */ - uint32_t RESERVED1; /*!< Reserved, 0x50 */ - __IO uint32_t CCMR3; /*!< TIM capture/compare mode register 3, Address offset: 0x54 */ - __IO uint32_t CCR5; /*!< TIM capture/compare register5, Address offset: 0x58 */ - __IO uint32_t CCR6; /*!< TIM capture/compare register6, Address offset: 0x5C */ - __IO uint32_t AF1; /*!< TIM alternate function option register 1, Address offset: 0x60 */ - __IO uint32_t AF2; /*!< TIM alternate function option register 2, Address offset: 0x64 */ - __IO uint32_t TISEL; /*!< TIM Input Selection register, Address offset: 0x68 */ -} TIM_TypeDef; - -/** - * @brief LPTIMIMER - */ -typedef struct -{ - __IO uint32_t ISR; /*!< LPTIM Interrupt and Status register, Address offset: 0x00 */ - __IO uint32_t ICR; /*!< LPTIM Interrupt Clear register, Address offset: 0x04 */ - __IO uint32_t IER; /*!< LPTIM Interrupt Enable register, Address offset: 0x08 */ - __IO uint32_t CFGR; /*!< LPTIM Configuration register, Address offset: 0x0C */ - __IO uint32_t CR; /*!< LPTIM Control register, Address offset: 0x10 */ - __IO uint32_t CMP; /*!< LPTIM Compare register, Address offset: 0x14 */ - __IO uint32_t ARR; /*!< LPTIM Autoreload register, Address offset: 0x18 */ - __IO uint32_t CNT; /*!< LPTIM Counter register, Address offset: 0x1C */ - uint32_t RESERVED1; /*!< Reserved, 0x20 */ - __IO uint32_t CFGR2; /*!< LPTIM Configuration register, Address offset: 0x24 */ -} LPTIM_TypeDef; - -/** - * @brief Comparator - */ -typedef struct -{ - __IO uint32_t SR; /*!< Comparator status register, Address offset: 0x00 */ - __IO uint32_t ICFR; /*!< Comparator interrupt clear flag register, Address offset: 0x04 */ - __IO uint32_t OR; /*!< Comparator option register, Address offset: 0x08 */ -} COMPOPT_TypeDef; - -typedef struct -{ - __IO uint32_t CFGR; /*!< Comparator configuration register , Address offset: 0x00 */ -} COMP_TypeDef; - -typedef struct -{ - __IO uint32_t CFGR; /*!< COMP control and status register, used for bits common to several COMP instances, Address offset: 0x00 */ -} COMP_Common_TypeDef; -/** - * @brief Universal Synchronous Asynchronous Receiver Transmitter - */ - -typedef struct -{ - __IO uint32_t CR1; /*!< USART Control register 1, Address offset: 0x00 */ - __IO uint32_t CR2; /*!< USART Control register 2, Address offset: 0x04 */ - __IO uint32_t CR3; /*!< USART Control register 3, Address offset: 0x08 */ - __IO uint32_t BRR; /*!< USART Baud rate register, Address offset: 0x0C */ - __IO uint32_t GTPR; /*!< USART Guard time and prescaler register, Address offset: 0x10 */ - __IO uint32_t RTOR; /*!< USART Receiver Time Out register, Address offset: 0x14 */ - __IO uint32_t RQR; /*!< USART Request register, Address offset: 0x18 */ - __IO uint32_t ISR; /*!< USART Interrupt and status register, Address offset: 0x1C */ - __IO uint32_t ICR; /*!< USART Interrupt flag Clear register, Address offset: 0x20 */ - __IO uint32_t RDR; /*!< USART Receive Data register, Address offset: 0x24 */ - __IO uint32_t TDR; /*!< USART Transmit Data register, Address offset: 0x28 */ - __IO uint32_t PRESC; /*!< USART clock Prescaler register, Address offset: 0x2C */ -} USART_TypeDef; - -/** - * @brief Single Wire Protocol Master Interface SPWMI - */ -typedef struct -{ - __IO uint32_t CR; /*!< SWPMI Configuration/Control register, Address offset: 0x00 */ - __IO uint32_t BRR; /*!< SWPMI bitrate register, Address offset: 0x04 */ - uint32_t RESERVED1; /*!< Reserved, 0x08 */ - __IO uint32_t ISR; /*!< SWPMI Interrupt and Status register, Address offset: 0x0C */ - __IO uint32_t ICR; /*!< SWPMI Interrupt Flag Clear register, Address offset: 0x10 */ - __IO uint32_t IER; /*!< SWPMI Interrupt Enable register, Address offset: 0x14 */ - __IO uint32_t RFL; /*!< SWPMI Receive Frame Length register, Address offset: 0x18 */ - __IO uint32_t TDR; /*!< SWPMI Transmit data register, Address offset: 0x1C */ - __IO uint32_t RDR; /*!< SWPMI Receive data register, Address offset: 0x20 */ - __IO uint32_t OR; /*!< SWPMI Option register, Address offset: 0x24 */ -} SWPMI_TypeDef; - -/** - * @brief Window WATCHDOG - */ - -typedef struct -{ - __IO uint32_t CR; /*!< WWDG Control register, Address offset: 0x00 */ - __IO uint32_t CFR; /*!< WWDG Configuration register, Address offset: 0x04 */ - __IO uint32_t SR; /*!< WWDG Status register, Address offset: 0x08 */ -} WWDG_TypeDef; - - -/** - * @brief RAM_ECC_Specific_Registers - */ -typedef struct -{ - __IO uint32_t CR; /*!< RAMECC monitor configuration register */ - __IO uint32_t SR; /*!< RAMECC monitor status register */ - __IO uint32_t FAR; /*!< RAMECC monitor failing address register */ - __IO uint32_t FDRL; /*!< RAMECC monitor failing data low register */ - __IO uint32_t FDRH; /*!< RAMECC monitor failing data high register */ - __IO uint32_t FECR; /*!< RAMECC monitor failing ECC error code register */ -} RAMECC_MonitorTypeDef; - -typedef struct -{ - __IO uint32_t IER; /*!< RAMECC interrupt enable register */ -} RAMECC_TypeDef; -/** - * @} - */ - - -/** - * @brief Crypto Processor - */ - -typedef struct -{ - __IO uint32_t CR; /*!< CRYP control register, Address offset: 0x00 */ - __IO uint32_t SR; /*!< CRYP status register, Address offset: 0x04 */ - __IO uint32_t DIN; /*!< CRYP data input register, Address offset: 0x08 */ - __IO uint32_t DOUT; /*!< CRYP data output register, Address offset: 0x0C */ - __IO uint32_t DMACR; /*!< CRYP DMA control register, Address offset: 0x10 */ - __IO uint32_t IMSCR; /*!< CRYP interrupt mask set/clear register, Address offset: 0x14 */ - __IO uint32_t RISR; /*!< CRYP raw interrupt status register, Address offset: 0x18 */ - __IO uint32_t MISR; /*!< CRYP masked interrupt status register, Address offset: 0x1C */ - __IO uint32_t K0LR; /*!< CRYP key left register 0, Address offset: 0x20 */ - __IO uint32_t K0RR; /*!< CRYP key right register 0, Address offset: 0x24 */ - __IO uint32_t K1LR; /*!< CRYP key left register 1, Address offset: 0x28 */ - __IO uint32_t K1RR; /*!< CRYP key right register 1, Address offset: 0x2C */ - __IO uint32_t K2LR; /*!< CRYP key left register 2, Address offset: 0x30 */ - __IO uint32_t K2RR; /*!< CRYP key right register 2, Address offset: 0x34 */ - __IO uint32_t K3LR; /*!< CRYP key left register 3, Address offset: 0x38 */ - __IO uint32_t K3RR; /*!< CRYP key right register 3, Address offset: 0x3C */ - __IO uint32_t IV0LR; /*!< CRYP initialization vector left-word register 0, Address offset: 0x40 */ - __IO uint32_t IV0RR; /*!< CRYP initialization vector right-word register 0, Address offset: 0x44 */ - __IO uint32_t IV1LR; /*!< CRYP initialization vector left-word register 1, Address offset: 0x48 */ - __IO uint32_t IV1RR; /*!< CRYP initialization vector right-word register 1, Address offset: 0x4C */ - __IO uint32_t CSGCMCCM0R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 0, Address offset: 0x50 */ - __IO uint32_t CSGCMCCM1R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 1, Address offset: 0x54 */ - __IO uint32_t CSGCMCCM2R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 2, Address offset: 0x58 */ - __IO uint32_t CSGCMCCM3R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 3, Address offset: 0x5C */ - __IO uint32_t CSGCMCCM4R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 4, Address offset: 0x60 */ - __IO uint32_t CSGCMCCM5R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 5, Address offset: 0x64 */ - __IO uint32_t CSGCMCCM6R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 6, Address offset: 0x68 */ - __IO uint32_t CSGCMCCM7R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 7, Address offset: 0x6C */ - __IO uint32_t CSGCM0R; /*!< CRYP GCM/GMAC context swap register 0, Address offset: 0x70 */ - __IO uint32_t CSGCM1R; /*!< CRYP GCM/GMAC context swap register 1, Address offset: 0x74 */ - __IO uint32_t CSGCM2R; /*!< CRYP GCM/GMAC context swap register 2, Address offset: 0x78 */ - __IO uint32_t CSGCM3R; /*!< CRYP GCM/GMAC context swap register 3, Address offset: 0x7C */ - __IO uint32_t CSGCM4R; /*!< CRYP GCM/GMAC context swap register 4, Address offset: 0x80 */ - __IO uint32_t CSGCM5R; /*!< CRYP GCM/GMAC context swap register 5, Address offset: 0x84 */ - __IO uint32_t CSGCM6R; /*!< CRYP GCM/GMAC context swap register 6, Address offset: 0x88 */ - __IO uint32_t CSGCM7R; /*!< CRYP GCM/GMAC context swap register 7, Address offset: 0x8C */ -} CRYP_TypeDef; - -/** - * @brief HASH - */ - -typedef struct -{ - __IO uint32_t CR; /*!< HASH control register, Address offset: 0x00 */ - __IO uint32_t DIN; /*!< HASH data input register, Address offset: 0x04 */ - __IO uint32_t STR; /*!< HASH start register, Address offset: 0x08 */ - __IO uint32_t HR[5]; /*!< HASH digest registers, Address offset: 0x0C-0x1C */ - __IO uint32_t IMR; /*!< HASH interrupt enable register, Address offset: 0x20 */ - __IO uint32_t SR; /*!< HASH status register, Address offset: 0x24 */ - uint32_t RESERVED[52]; /*!< Reserved, 0x28-0xF4 */ - __IO uint32_t CSR[54]; /*!< HASH context swap registers, Address offset: 0x0F8-0x1CC */ -} HASH_TypeDef; - -/** - * @brief HASH_DIGEST - */ - -typedef struct -{ - __IO uint32_t HR[8]; /*!< HASH digest registers, Address offset: 0x310-0x32C */ -} HASH_DIGEST_TypeDef; - - -/** - * @brief RNG - */ - -typedef struct -{ - __IO uint32_t CR; /*!< RNG control register, Address offset: 0x00 */ - __IO uint32_t SR; /*!< RNG status register, Address offset: 0x04 */ - __IO uint32_t DR; /*!< RNG data register, Address offset: 0x08 */ - uint32_t RESERVED; - __IO uint32_t HTCR; /*!< RNG health test configuration register, Address offset: 0x10 */ -} RNG_TypeDef; - -/** - * @brief MDIOS - */ - -typedef struct -{ - __IO uint32_t CR; - __IO uint32_t WRFR; - __IO uint32_t CWRFR; - __IO uint32_t RDFR; - __IO uint32_t CRDFR; - __IO uint32_t SR; - __IO uint32_t CLRFR; - uint32_t RESERVED[57]; - __IO uint32_t DINR0; - __IO uint32_t DINR1; - __IO uint32_t DINR2; - __IO uint32_t DINR3; - __IO uint32_t DINR4; - __IO uint32_t DINR5; - __IO uint32_t DINR6; - __IO uint32_t DINR7; - __IO uint32_t DINR8; - __IO uint32_t DINR9; - __IO uint32_t DINR10; - __IO uint32_t DINR11; - __IO uint32_t DINR12; - __IO uint32_t DINR13; - __IO uint32_t DINR14; - __IO uint32_t DINR15; - __IO uint32_t DINR16; - __IO uint32_t DINR17; - __IO uint32_t DINR18; - __IO uint32_t DINR19; - __IO uint32_t DINR20; - __IO uint32_t DINR21; - __IO uint32_t DINR22; - __IO uint32_t DINR23; - __IO uint32_t DINR24; - __IO uint32_t DINR25; - __IO uint32_t DINR26; - __IO uint32_t DINR27; - __IO uint32_t DINR28; - __IO uint32_t DINR29; - __IO uint32_t DINR30; - __IO uint32_t DINR31; - __IO uint32_t DOUTR0; - __IO uint32_t DOUTR1; - __IO uint32_t DOUTR2; - __IO uint32_t DOUTR3; - __IO uint32_t DOUTR4; - __IO uint32_t DOUTR5; - __IO uint32_t DOUTR6; - __IO uint32_t DOUTR7; - __IO uint32_t DOUTR8; - __IO uint32_t DOUTR9; - __IO uint32_t DOUTR10; - __IO uint32_t DOUTR11; - __IO uint32_t DOUTR12; - __IO uint32_t DOUTR13; - __IO uint32_t DOUTR14; - __IO uint32_t DOUTR15; - __IO uint32_t DOUTR16; - __IO uint32_t DOUTR17; - __IO uint32_t DOUTR18; - __IO uint32_t DOUTR19; - __IO uint32_t DOUTR20; - __IO uint32_t DOUTR21; - __IO uint32_t DOUTR22; - __IO uint32_t DOUTR23; - __IO uint32_t DOUTR24; - __IO uint32_t DOUTR25; - __IO uint32_t DOUTR26; - __IO uint32_t DOUTR27; - __IO uint32_t DOUTR28; - __IO uint32_t DOUTR29; - __IO uint32_t DOUTR30; - __IO uint32_t DOUTR31; -} MDIOS_TypeDef; - - -/** - * @brief USB_OTG_Core_Registers - */ -typedef struct -{ - __IO uint32_t GOTGCTL; /*!< USB_OTG Control and Status Register 000h */ - __IO uint32_t GOTGINT; /*!< USB_OTG Interrupt Register 004h */ - __IO uint32_t GAHBCFG; /*!< Core AHB Configuration Register 008h */ - __IO uint32_t GUSBCFG; /*!< Core USB Configuration Register 00Ch */ - __IO uint32_t GRSTCTL; /*!< Core Reset Register 010h */ - __IO uint32_t GINTSTS; /*!< Core Interrupt Register 014h */ - __IO uint32_t GINTMSK; /*!< Core Interrupt Mask Register 018h */ - __IO uint32_t GRXSTSR; /*!< Receive Sts Q Read Register 01Ch */ - __IO uint32_t GRXSTSP; /*!< Receive Sts Q Read & POP Register 020h */ - __IO uint32_t GRXFSIZ; /*!< Receive FIFO Size Register 024h */ - __IO uint32_t DIEPTXF0_HNPTXFSIZ; /*!< EP0 / Non Periodic Tx FIFO Size Register 028h */ - __IO uint32_t HNPTXSTS; /*!< Non Periodic Tx FIFO/Queue Sts reg 02Ch */ - uint32_t Reserved30[2]; /*!< Reserved 030h */ - __IO uint32_t GCCFG; /*!< General Purpose IO Register 038h */ - __IO uint32_t CID; /*!< User ID Register 03Ch */ - __IO uint32_t GSNPSID; /* USB_OTG core ID 040h*/ - __IO uint32_t GHWCFG1; /* User HW config1 044h*/ - __IO uint32_t GHWCFG2; /* User HW config2 048h*/ - __IO uint32_t GHWCFG3; /*!< User HW config3 04Ch */ - uint32_t Reserved6; /*!< Reserved 050h */ - __IO uint32_t GLPMCFG; /*!< LPM Register 054h */ - __IO uint32_t GPWRDN; /*!< Power Down Register 058h */ - __IO uint32_t GDFIFOCFG; /*!< DFIFO Software Config Register 05Ch */ - __IO uint32_t GADPCTL; /*!< ADP Timer, Control and Status Register 60Ch */ - uint32_t Reserved43[39]; /*!< Reserved 058h-0FFh */ - __IO uint32_t HPTXFSIZ; /*!< Host Periodic Tx FIFO Size Reg 100h */ - __IO uint32_t DIEPTXF[0x0F]; /*!< dev Periodic Transmit FIFO */ -} USB_OTG_GlobalTypeDef; - - -/** - * @brief USB_OTG_device_Registers - */ -typedef struct -{ - __IO uint32_t DCFG; /*!< dev Configuration Register 800h */ - __IO uint32_t DCTL; /*!< dev Control Register 804h */ - __IO uint32_t DSTS; /*!< dev Status Register (RO) 808h */ - uint32_t Reserved0C; /*!< Reserved 80Ch */ - __IO uint32_t DIEPMSK; /*!< dev IN Endpoint Mask 810h */ - __IO uint32_t DOEPMSK; /*!< dev OUT Endpoint Mask 814h */ - __IO uint32_t DAINT; /*!< dev All Endpoints Itr Reg 818h */ - __IO uint32_t DAINTMSK; /*!< dev All Endpoints Itr Mask 81Ch */ - uint32_t Reserved20; /*!< Reserved 820h */ - uint32_t Reserved9; /*!< Reserved 824h */ - __IO uint32_t DVBUSDIS; /*!< dev VBUS discharge Register 828h */ - __IO uint32_t DVBUSPULSE; /*!< dev VBUS Pulse Register 82Ch */ - __IO uint32_t DTHRCTL; /*!< dev threshold 830h */ - __IO uint32_t DIEPEMPMSK; /*!< dev empty msk 834h */ - __IO uint32_t DEACHINT; /*!< dedicated EP interrupt 838h */ - __IO uint32_t DEACHMSK; /*!< dedicated EP msk 83Ch */ - uint32_t Reserved40; /*!< dedicated EP mask 840h */ - __IO uint32_t DINEP1MSK; /*!< dedicated EP mask 844h */ - uint32_t Reserved44[15]; /*!< Reserved 844-87Ch */ - __IO uint32_t DOUTEP1MSK; /*!< dedicated EP msk 884h */ -} USB_OTG_DeviceTypeDef; - - -/** - * @brief USB_OTG_IN_Endpoint-Specific_Register - */ -typedef struct -{ - __IO uint32_t DIEPCTL; /*!< dev IN Endpoint Control Reg 900h + (ep_num * 20h) + 00h */ - uint32_t Reserved04; /*!< Reserved 900h + (ep_num * 20h) + 04h */ - __IO uint32_t DIEPINT; /*!< dev IN Endpoint Itr Reg 900h + (ep_num * 20h) + 08h */ - uint32_t Reserved0C; /*!< Reserved 900h + (ep_num * 20h) + 0Ch */ - __IO uint32_t DIEPTSIZ; /*!< IN Endpoint Txfer Size 900h + (ep_num * 20h) + 10h */ - __IO uint32_t DIEPDMA; /*!< IN Endpoint DMA Address Reg 900h + (ep_num * 20h) + 14h */ - __IO uint32_t DTXFSTS; /*!< IN Endpoint Tx FIFO Status Reg 900h + (ep_num * 20h) + 18h */ - uint32_t Reserved18; /*!< Reserved 900h+(ep_num*20h)+1Ch-900h+ (ep_num * 20h) + 1Ch */ -} USB_OTG_INEndpointTypeDef; - - -/** - * @brief USB_OTG_OUT_Endpoint-Specific_Registers - */ -typedef struct -{ - __IO uint32_t DOEPCTL; /*!< dev OUT Endpoint Control Reg B00h + (ep_num * 20h) + 00h */ - uint32_t Reserved04; /*!< Reserved B00h + (ep_num * 20h) + 04h */ - __IO uint32_t DOEPINT; /*!< dev OUT Endpoint Itr Reg B00h + (ep_num * 20h) + 08h */ - uint32_t Reserved0C; /*!< Reserved B00h + (ep_num * 20h) + 0Ch */ - __IO uint32_t DOEPTSIZ; /*!< dev OUT Endpoint Txfer Size B00h + (ep_num * 20h) + 10h */ - __IO uint32_t DOEPDMA; /*!< dev OUT Endpoint DMA Address B00h + (ep_num * 20h) + 14h */ - uint32_t Reserved18[2]; /*!< Reserved B00h + (ep_num * 20h) + 18h - B00h + (ep_num * 20h) + 1Ch */ -} USB_OTG_OUTEndpointTypeDef; - - -/** - * @brief USB_OTG_Host_Mode_Register_Structures - */ -typedef struct -{ - __IO uint32_t HCFG; /*!< Host Configuration Register 400h */ - __IO uint32_t HFIR; /*!< Host Frame Interval Register 404h */ - __IO uint32_t HFNUM; /*!< Host Frame Nbr/Frame Remaining 408h */ - uint32_t Reserved40C; /*!< Reserved 40Ch */ - __IO uint32_t HPTXSTS; /*!< Host Periodic Tx FIFO/ Queue Status 410h */ - __IO uint32_t HAINT; /*!< Host All Channels Interrupt Register 414h */ - __IO uint32_t HAINTMSK; /*!< Host All Channels Interrupt Mask 418h */ -} USB_OTG_HostTypeDef; - -/** - * @brief USB_OTG_Host_Channel_Specific_Registers - */ -typedef struct -{ - __IO uint32_t HCCHAR; /*!< Host Channel Characteristics Register 500h */ - __IO uint32_t HCSPLT; /*!< Host Channel Split Control Register 504h */ - __IO uint32_t HCINT; /*!< Host Channel Interrupt Register 508h */ - __IO uint32_t HCINTMSK; /*!< Host Channel Interrupt Mask Register 50Ch */ - __IO uint32_t HCTSIZ; /*!< Host Channel Transfer Size Register 510h */ - __IO uint32_t HCDMA; /*!< Host Channel DMA Address Register 514h */ - uint32_t Reserved[2]; /*!< Reserved */ -} USB_OTG_HostChannelTypeDef; -/** - * @} - */ - -/** - * @brief OCTO Serial Peripheral Interface - */ - -typedef struct -{ - __IO uint32_t CR; /*!< OCTOSPI Control register, Address offset: 0x000 */ - uint32_t RESERVED; /*!< Reserved, Address offset: 0x004 */ - __IO uint32_t DCR1; /*!< OCTOSPI Device Configuration register 1, Address offset: 0x008 */ - __IO uint32_t DCR2; /*!< OCTOSPI Device Configuration register 2, Address offset: 0x00C */ - __IO uint32_t DCR3; /*!< OCTOSPI Device Configuration register 3, Address offset: 0x010 */ - __IO uint32_t DCR4; /*!< OCTOSPI Device Configuration register 4, Address offset: 0x014 */ - uint32_t RESERVED1[2]; /*!< Reserved, Address offset: 0x018-0x01C */ - __IO uint32_t SR; /*!< OCTOSPI Status register, Address offset: 0x020 */ - __IO uint32_t FCR; /*!< OCTOSPI Flag Clear register, Address offset: 0x024 */ - uint32_t RESERVED2[6]; /*!< Reserved, Address offset: 0x028-0x03C */ - __IO uint32_t DLR; /*!< OCTOSPI Data Length register, Address offset: 0x040 */ - uint32_t RESERVED3; /*!< Reserved, Address offset: 0x044 */ - __IO uint32_t AR; /*!< OCTOSPI Address register, Address offset: 0x048 */ - uint32_t RESERVED4; /*!< Reserved, Address offset: 0x04C */ - __IO uint32_t DR; /*!< OCTOSPI Data register, Address offset: 0x050 */ - uint32_t RESERVED5[11]; /*!< Reserved, Address offset: 0x054-0x07C */ - __IO uint32_t PSMKR; /*!< OCTOSPI Polling Status Mask register, Address offset: 0x080 */ - uint32_t RESERVED6; /*!< Reserved, Address offset: 0x084 */ - __IO uint32_t PSMAR; /*!< OCTOSPI Polling Status Match register, Address offset: 0x088 */ - uint32_t RESERVED7; /*!< Reserved, Address offset: 0x08C */ - __IO uint32_t PIR; /*!< OCTOSPI Polling Interval register, Address offset: 0x090 */ - uint32_t RESERVED8[27]; /*!< Reserved, Address offset: 0x094-0x0FC */ - __IO uint32_t CCR; /*!< OCTOSPI Communication Configuration register, Address offset: 0x100 */ - uint32_t RESERVED9; /*!< Reserved, Address offset: 0x104 */ - __IO uint32_t TCR; /*!< OCTOSPI Timing Configuration register, Address offset: 0x108 */ - uint32_t RESERVED10; /*!< Reserved, Address offset: 0x10C */ - __IO uint32_t IR; /*!< OCTOSPI Instruction register, Address offset: 0x110 */ - uint32_t RESERVED11[3]; /*!< Reserved, Address offset: 0x114-0x11C */ - __IO uint32_t ABR; /*!< OCTOSPI Alternate Bytes register, Address offset: 0x120 */ - uint32_t RESERVED12[3]; /*!< Reserved, Address offset: 0x124-0x12C */ - __IO uint32_t LPTR; /*!< OCTOSPI Low Power Timeout register, Address offset: 0x130 */ - uint32_t RESERVED13[3]; /*!< Reserved, Address offset: 0x134-0x13C */ - __IO uint32_t WPCCR; /*!< OCTOSPI Wrap Communication Configuration register, Address offset: 0x140 */ - uint32_t RESERVED14; /*!< Reserved, Address offset: 0x144 */ - __IO uint32_t WPTCR; /*!< OCTOSPI Wrap Timing Configuration register, Address offset: 0x148 */ - uint32_t RESERVED15; /*!< Reserved, Address offset: 0x14C */ - __IO uint32_t WPIR; /*!< OCTOSPI Wrap Instruction register, Address offset: 0x150 */ - uint32_t RESERVED16[3]; /*!< Reserved, Address offset: 0x154-0x15C */ - __IO uint32_t WPABR; /*!< OCTOSPI Wrap Alternate Bytes register, Address offset: 0x160 */ - uint32_t RESERVED17[7]; /*!< Reserved, Address offset: 0x164-0x17C */ - __IO uint32_t WCCR; /*!< OCTOSPI Write Communication Configuration register, Address offset: 0x180 */ - uint32_t RESERVED18; /*!< Reserved, Address offset: 0x184 */ - __IO uint32_t WTCR; /*!< OCTOSPI Write Timing Configuration register, Address offset: 0x188 */ - uint32_t RESERVED19; /*!< Reserved, Address offset: 0x18C */ - __IO uint32_t WIR; /*!< OCTOSPI Write Instruction register, Address offset: 0x190 */ - uint32_t RESERVED20[3]; /*!< Reserved, Address offset: 0x194-0x19C */ - __IO uint32_t WABR; /*!< OCTOSPI Write Alternate Bytes register, Address offset: 0x1A0 */ - uint32_t RESERVED21[23]; /*!< Reserved, Address offset: 0x1A4-0x1FC */ - __IO uint32_t HLCR; /*!< OCTOSPI Hyperbus Latency Configuration register, Address offset: 0x200 */ - uint32_t RESERVED22[122]; /*!< Reserved, Address offset: 0x204-0x3EC */ - __IO uint32_t HWCFGR; /*!< OCTOSPI HW Configuration register, Address offset: 0x3F0 */ - __IO uint32_t VER; /*!< OCTOSPI Version register, Address offset: 0x3F4 */ - __IO uint32_t ID; /*!< OCTOSPI Identification register, Address offset: 0x3F8 */ - __IO uint32_t MID; /*!< OCTOPSI HW Magic ID register, Address offset: 0x3FC */ -} OCTOSPI_TypeDef; - -/** - * @} - */ -/** - * @brief OCTO Serial Peripheral Interface IO Manager - */ - -typedef struct -{ - __IO uint32_t CR; /*!< OCTOSPI IO Manager Control register, Address offset: 0x00 */ - __IO uint32_t PCR[3]; /*!< OCTOSPI IO Manager Port[1:3] Configuration register, Address offset: 0x04-0x20 */ -} OCTOSPIM_TypeDef; - -/** - * @} - */ - -/** - * @brief OTFD register - */ -typedef struct -{ - __IO uint32_t REG_CONFIGR; - __IO uint32_t REG_START_ADDR; - __IO uint32_t REG_END_ADDR; - __IO uint32_t REG_NONCER0; - __IO uint32_t REG_NONCER1; - __IO uint32_t REG_KEYR0; - __IO uint32_t REG_KEYR1; - __IO uint32_t REG_KEYR2; - __IO uint32_t REG_KEYR3; -} OTFDEC_Region_TypeDef; - -typedef struct -{ - __IO uint32_t CR; - uint32_t RESERVED1[191]; - __IO uint32_t ISR; - __IO uint32_t ICR; - __IO uint32_t IER; - uint32_t RESERVED2[56]; - __IO uint32_t HWCFGR2; - __IO uint32_t HWCFGR1; - __IO uint32_t VERR; - __IO uint32_t IPIDR; - __IO uint32_t SIDR; -} OTFDEC_TypeDef; -/** - * @} - */ - -/** - * @brief Global Programmer View - */ - -typedef struct -{ - uint32_t RESERVED0[2036]; /*!< Reserved, Address offset: 0x00-0x1FCC */ - __IO uint32_t AXI_PERIPH_ID_4; /*!< AXI interconnect - peripheral ID4 register, Address offset: 0x1FD0 */ - uint32_t AXI_PERIPH_ID_5; /*!< Reserved, Address offset: 0x1FD4 */ - uint32_t AXI_PERIPH_ID_6; /*!< Reserved, Address offset: 0x1FD8 */ - uint32_t AXI_PERIPH_ID_7; /*!< Reserved, Address offset: 0x1FDC */ - __IO uint32_t AXI_PERIPH_ID_0; /*!< AXI interconnect - peripheral ID0 register, Address offset: 0x1FE0 */ - __IO uint32_t AXI_PERIPH_ID_1; /*!< AXI interconnect - peripheral ID1 register, Address offset: 0x1FE4 */ - __IO uint32_t AXI_PERIPH_ID_2; /*!< AXI interconnect - peripheral ID2 register, Address offset: 0x1FE8 */ - __IO uint32_t AXI_PERIPH_ID_3; /*!< AXI interconnect - peripheral ID3 register, Address offset: 0x1FEC */ - __IO uint32_t AXI_COMP_ID_0; /*!< AXI interconnect - component ID0 register, Address offset: 0x1FF0 */ - __IO uint32_t AXI_COMP_ID_1; /*!< AXI interconnect - component ID1 register, Address offset: 0x1FF4 */ - __IO uint32_t AXI_COMP_ID_2; /*!< AXI interconnect - component ID2 register, Address offset: 0x1FF8 */ - __IO uint32_t AXI_COMP_ID_3; /*!< AXI interconnect - component ID3 register, Address offset: 0x1FFC */ - uint32_t RESERVED1[2]; /*!< Reserved, Address offset: 0x2000-0x2004 */ - __IO uint32_t AXI_TARG1_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 1 bus matrix issuing functionality register, Address offset: 0x2008 */ - uint32_t RESERVED2[6]; /*!< Reserved, Address offset: 0x200C-0x2020 */ - __IO uint32_t AXI_TARG1_FN_MOD2; /*!< AXI interconnect - TARG 1 bus matrix functionality 2 register, Address offset: 0x2024 */ - uint32_t RESERVED3; /*!< Reserved, Address offset: 0x2028 */ - __IO uint32_t AXI_TARG1_FN_MOD_LB; /*!< AXI interconnect - TARG 1 long burst functionality modification register, Address offset: 0x202C */ - uint32_t RESERVED4[54]; /*!< Reserved, Address offset: 0x2030-0x2104 */ - __IO uint32_t AXI_TARG1_FN_MOD; /*!< AXI interconnect - TARG 1 issuing functionality modification register, Address offset: 0x2108 */ - uint32_t RESERVED5[959]; /*!< Reserved, Address offset: 0x210C-0x3004 */ - __IO uint32_t AXI_TARG2_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 2 bus matrix issuing functionality register, Address offset: 0x3008 */ - uint32_t RESERVED6[6]; /*!< Reserved, Address offset: 0x300C-0x3020 */ - __IO uint32_t AXI_TARG2_FN_MOD2; /*!< AXI interconnect - TARG 2 bus matrix functionality 2 register, Address offset: 0x3024 */ - uint32_t RESERVED7; /*!< Reserved, Address offset: 0x3028 */ - __IO uint32_t AXI_TARG2_FN_MOD_LB; /*!< AXI interconnect - TARG 2 long burst functionality modification register, Address offset: 0x302C */ - uint32_t RESERVED8[54]; /*!< Reserved, Address offset: 0x3030-0x3104 */ - __IO uint32_t AXI_TARG2_FN_MOD; /*!< AXI interconnect - TARG 2 issuing functionality modification register, Address offset: 0x3108 */ - uint32_t RESERVED9[959]; /*!< Reserved, Address offset: 0x310C-0x4004 */ - __IO uint32_t AXI_TARG3_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 3 bus matrix issuing functionality register, Address offset: 0x4008 */ - uint32_t RESERVED10[1023]; /*!< Reserved, Address offset: 0x400C-0x5004 */ - __IO uint32_t AXI_TARG4_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 4 bus matrix issuing functionality register, Address offset: 0x5008 */ - uint32_t RESERVED11[1023]; /*!< Reserved, Address offset: 0x500C-0x6004 */ - __IO uint32_t AXI_TARG5_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 5 bus matrix issuing functionality register, Address offset: 0x6008 */ - uint32_t RESERVED12[1023]; /*!< Reserved, Address offset: 0x600C-0x7004 */ - __IO uint32_t AXI_TARG6_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 6 bus matrix issuing functionality register, Address offset: 0x7008 */ - uint32_t RESERVED13[1023]; /*!< Reserved, Address offset: 0x700C-0x8004 */ - __IO uint32_t AXI_TARG7_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 7 bus matrix issuing functionality register, Address offset: 0x8008 */ - uint32_t RESERVED14[6]; /*!< Reserved, Address offset: 0x800C-0x8020 */ - __IO uint32_t AXI_TARG7_FN_MOD2; /*!< AXI interconnect - TARG 7 bus matrix functionality 2 register, Address offset: 0x8024 */ - uint32_t RESERVED15; /*!< Reserved, Address offset: 0x8028 */ - __IO uint32_t AXI_TARG7_FN_MOD_LB; /*!< AXI interconnect - TARG 7 long burst functionality modification register, Address offset: 0x802C */ - uint32_t RESERVED16[54]; /*!< Reserved, Address offset: 0x8030-0x8104 */ - __IO uint32_t AXI_TARG7_FN_MOD; /*!< AXI interconnect - TARG 7 issuing functionality modification register, Address offset: 0x8108 */ - uint32_t RESERVED17[959]; /*!< Reserved, Address offset: 0x810C-0x9004 */ - __IO uint32_t AXI_TARG8_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 8 bus matrix issuing functionality register, Address offset: 0x9008 */ - uint32_t RESERVED117[6]; /*!< Reserved, Address offset: 0x900C-0x9020 */ - __IO uint32_t AXI_TARG8_FN_MOD2; /*!< AXI interconnect - TARG 8 bus matrix functionality 2 register, Address offset: 0x9024 */ - uint32_t RESERVED118[56]; /*!< Reserved, Address offset: 0x9028-0x9104 */ - __IO uint32_t AXI_TARG8_FN_MOD; /*!< AXI interconnect - TARG 8 issuing functionality modification register, Address offset: 0x9108 */ - uint32_t RESERVED119[58310]; /*!< Reserved, Address offset: 0x910C-0x42020 */ - __IO uint32_t AXI_INI1_FN_MOD2; /*!< AXI interconnect - INI 1 functionality modification 2 register, Address offset: 0x42024 */ - __IO uint32_t AXI_INI1_FN_MOD_AHB; /*!< AXI interconnect - INI 1 AHB functionality modification register, Address offset: 0x42028 */ - uint32_t RESERVED18[53]; /*!< Reserved, Address offset: 0x4202C-0x420FC */ - __IO uint32_t AXI_INI1_READ_QOS; /*!< AXI interconnect - INI 1 read QoS register, Address offset: 0x42100 */ - __IO uint32_t AXI_INI1_WRITE_QOS; /*!< AXI interconnect - INI 1 write QoS register, Address offset: 0x42104 */ - __IO uint32_t AXI_INI1_FN_MOD; /*!< AXI interconnect - INI 1 issuing functionality modification register, Address offset: 0x42108 */ - uint32_t RESERVED19[1021]; /*!< Reserved, Address offset: 0x4210C-0x430FC */ - __IO uint32_t AXI_INI2_READ_QOS; /*!< AXI interconnect - INI 2 read QoS register, Address offset: 0x43100 */ - __IO uint32_t AXI_INI2_WRITE_QOS; /*!< AXI interconnect - INI 2 write QoS register, Address offset: 0x43104 */ - __IO uint32_t AXI_INI2_FN_MOD; /*!< AXI interconnect - INI 2 issuing functionality modification register, Address offset: 0x43108 */ - uint32_t RESERVED20[966]; /*!< Reserved, Address offset: 0x4310C-0x44020 */ - __IO uint32_t AXI_INI3_FN_MOD2; /*!< AXI interconnect - INI 3 functionality modification 2 register, Address offset: 0x44024 */ - __IO uint32_t AXI_INI3_FN_MOD_AHB; /*!< AXI interconnect - INI 3 AHB functionality modification register, Address offset: 0x44028 */ - uint32_t RESERVED21[53]; /*!< Reserved, Address offset: 0x4402C-0x440FC */ - __IO uint32_t AXI_INI3_READ_QOS; /*!< AXI interconnect - INI 3 read QoS register, Address offset: 0x44100 */ - __IO uint32_t AXI_INI3_WRITE_QOS; /*!< AXI interconnect - INI 3 write QoS register, Address offset: 0x44104 */ - __IO uint32_t AXI_INI3_FN_MOD; /*!< AXI interconnect - INI 3 issuing functionality modification register, Address offset: 0x44108 */ - uint32_t RESERVED22[1021]; /*!< Reserved, Address offset: 0x4410C-0x450FC */ - __IO uint32_t AXI_INI4_READ_QOS; /*!< AXI interconnect - INI 4 read QoS register, Address offset: 0x45100 */ - __IO uint32_t AXI_INI4_WRITE_QOS; /*!< AXI interconnect - INI 4 write QoS register, Address offset: 0x45104 */ - __IO uint32_t AXI_INI4_FN_MOD; /*!< AXI interconnect - INI 4 issuing functionality modification register, Address offset: 0x45108 */ - uint32_t RESERVED23[1021]; /*!< Reserved, Address offset: 0x4510C-0x460FC */ - __IO uint32_t AXI_INI5_READ_QOS; /*!< AXI interconnect - INI 5 read QoS register, Address offset: 0x46100 */ - __IO uint32_t AXI_INI5_WRITE_QOS; /*!< AXI interconnect - INI 5 write QoS register, Address offset: 0x46104 */ - __IO uint32_t AXI_INI5_FN_MOD; /*!< AXI interconnect - INI 5 issuing functionality modification register, Address offset: 0x46108 */ - uint32_t RESERVED24[1021]; /*!< Reserved, Address offset: 0x4610C-0x470FC */ - __IO uint32_t AXI_INI6_READ_QOS; /*!< AXI interconnect - INI 6 read QoS register, Address offset: 0x47100 */ - __IO uint32_t AXI_INI6_WRITE_QOS; /*!< AXI interconnect - INI 6 write QoS register, Address offset: 0x47104 */ - __IO uint32_t AXI_INI6_FN_MOD; /*!< AXI interconnect - INI 6 issuing functionality modification register, Address offset: 0x47108 */ - -} GPV_TypeDef; - -/** @addtogroup Peripheral_memory_map - * @{ - */ -#define D1_ITCMRAM_BASE (0x00000000UL) /*!< Base address of : 64KB RAM reserved for CPU execution/instruction accessible over ITCM */ -#define D1_ITCMICP_BASE (0x00100000UL) /*!< Base address of : (up to 128KB) embedded Test FLASH memory accessible over ITCM */ -#define D1_DTCMRAM_BASE (0x20000000UL) /*!< Base address of : 128KB system data RAM accessible over DTCM */ -#define D1_AXIFLASH_BASE (0x08000000UL) /*!< Base address of : (up to 1 MB) embedded FLASH memory accessible over AXI */ -#define D1_AXIICP_BASE (0x1FF00000UL) /*!< Base address of : (up to 128KB) embedded Test FLASH memory accessible over AXI */ -#define D1_AXISRAM1_BASE (0x24000000UL) /*!< Base address of : (up to 128KB) system data RAM1 accessible over over AXI */ -#define D1_AXISRAM2_BASE (0x24020000UL) /*!< Base address of : (up to 192KB) system data RAM2 accessible over over AXI to be shared with ITCM (64K granularity) */ -#define D1_AXISRAM_BASE D1_AXISRAM1_BASE /*!< Base address of : (up to 320KB) system data RAM1/2 accessible over over AXI */ - -#define D2_AHBSRAM1_BASE (0x30000000UL) /*!< Base address of : (up to 16KB) system data RAM accessible over over AXI->AHB Bridge */ -#define D2_AHBSRAM2_BASE (0x30004000UL) /*!< Base address of : (up to 16KB) system data RAM accessible over over AXI->AHB Bridge */ -#define D2_AHBSRAM_BASE D2_AHBSRAM1_BASE /*!< Base address of : (up to 32KB) system data RAM1/2 accessible over over AXI->AHB Bridge */ - -#define D3_BKPSRAM_BASE (0x38800000UL) /*!< Base address of : Backup SRAM(4 KB) over AXI->AHB Bridge */ -#define D3_SRAM_BASE (0x38000000UL) /*!< Base address of : Backup SRAM(16 KB) over AXI->AHB Bridge */ - -#define PERIPH_BASE (0x40000000UL) /*!< Base address of : AHB/APB Peripherals */ -#define OCTOSPI1_BASE (0x90000000UL) /*!< Base address of : OCTOSPI1 memories accessible over AXI */ -#define OCTOSPI2_BASE (0x70000000UL) /*!< Base address of : OCTOSPI2 memories accessible over AXI */ - -#define FLASH_BANK1_BASE (0x08000000UL) /*!< Base address of : (up to 1 MB) Flash Bank1 accessible over AXI */ -#define FLASH_END (0x080FFFFFUL) /*!< FLASH end address */ - - -/* Legacy define */ -#define FLASH_BASE FLASH_BANK1_BASE - -/*!< Device electronic signature memory map */ -#define UID_BASE (0x1FF1E800UL) /*!< Unique device ID register base address */ -#define FLASHSIZE_BASE (0x1FF1E880UL) /*!< FLASH Size register base address */ - - -/*!< Peripheral memory map */ -#define D2_APB1PERIPH_BASE PERIPH_BASE -#define D2_APB2PERIPH_BASE (PERIPH_BASE + 0x00010000UL) -#define D2_AHB1PERIPH_BASE (PERIPH_BASE + 0x00020000UL) -#define D2_AHB2PERIPH_BASE (PERIPH_BASE + 0x08020000UL) - -#define D1_APB1PERIPH_BASE (PERIPH_BASE + 0x10000000UL) -#define D1_AHB1PERIPH_BASE (PERIPH_BASE + 0x12000000UL) - -#define D3_APB1PERIPH_BASE (PERIPH_BASE + 0x18000000UL) -#define D3_AHB1PERIPH_BASE (PERIPH_BASE + 0x18020000UL) - -/*!< Legacy Peripheral memory map */ -#define APB1PERIPH_BASE PERIPH_BASE -#define APB2PERIPH_BASE (PERIPH_BASE + 0x00010000UL) -#define AHB1PERIPH_BASE (PERIPH_BASE + 0x00020000UL) -#define AHB2PERIPH_BASE (PERIPH_BASE + 0x08000000UL) - - -/*!< D1_AHB1PERIPH peripherals */ - -#define MDMA_BASE (D1_AHB1PERIPH_BASE + 0x0000UL) -#define DMA2D_BASE (D1_AHB1PERIPH_BASE + 0x1000UL) -#define FLASH_R_BASE (D1_AHB1PERIPH_BASE + 0x2000UL) -#define FMC_R_BASE (D1_AHB1PERIPH_BASE + 0x4000UL) -#define OCTOSPI1_R_BASE (D1_AHB1PERIPH_BASE + 0x5000UL) -#define DLYB_OCTOSPI1_BASE (D1_AHB1PERIPH_BASE + 0x6000UL) -#define SDMMC1_BASE (D1_AHB1PERIPH_BASE + 0x7000UL) -#define DLYB_SDMMC1_BASE (D1_AHB1PERIPH_BASE + 0x8000UL) -#define RAMECC1_BASE (D1_AHB1PERIPH_BASE + 0x9000UL) -#define OCTOSPI2_R_BASE (D1_AHB1PERIPH_BASE + 0xA000UL) -#define DLYB_OCTOSPI2_BASE (D1_AHB1PERIPH_BASE + 0xB000UL) -#define OCTOSPIM_BASE (D1_AHB1PERIPH_BASE + 0xB400UL) - -#define OTFDEC1_BASE (D1_AHB1PERIPH_BASE + 0xB800UL) -#define OTFDEC1_REGION1_BASE (OTFDEC1_BASE + 0x20UL) -#define OTFDEC1_REGION2_BASE (OTFDEC1_BASE + 0x50UL) -#define OTFDEC1_REGION3_BASE (OTFDEC1_BASE + 0x80UL) -#define OTFDEC1_REGION4_BASE (OTFDEC1_BASE + 0xB0UL) -#define OTFDEC2_BASE (D1_AHB1PERIPH_BASE + 0xBC00UL) -#define OTFDEC2_REGION1_BASE (OTFDEC2_BASE + 0x20UL) -#define OTFDEC2_REGION2_BASE (OTFDEC2_BASE + 0x50UL) -#define OTFDEC2_REGION3_BASE (OTFDEC2_BASE + 0x80UL) -#define OTFDEC2_REGION4_BASE (OTFDEC2_BASE + 0xB0UL) - -/*!< D2_AHB1PERIPH peripherals */ - -#define DMA1_BASE (D2_AHB1PERIPH_BASE + 0x0000UL) -#define DMA2_BASE (D2_AHB1PERIPH_BASE + 0x0400UL) -#define DMAMUX1_BASE (D2_AHB1PERIPH_BASE + 0x0800UL) -#define ADC1_BASE (D2_AHB1PERIPH_BASE + 0x2000UL) -#define ADC2_BASE (D2_AHB1PERIPH_BASE + 0x2100UL) -#define ADC12_COMMON_BASE (D2_AHB1PERIPH_BASE + 0x2300UL) -#define ETH_BASE (D2_AHB1PERIPH_BASE + 0x8000UL) -#define ETH_MAC_BASE (ETH_BASE) - -/*!< USB registers base address */ -#define USB1_OTG_HS_PERIPH_BASE (0x40040000UL) -#define USB_OTG_GLOBAL_BASE (0x000UL) -#define USB_OTG_DEVICE_BASE (0x800UL) -#define USB_OTG_IN_ENDPOINT_BASE (0x900UL) -#define USB_OTG_OUT_ENDPOINT_BASE (0xB00UL) -#define USB_OTG_EP_REG_SIZE (0x20UL) -#define USB_OTG_HOST_BASE (0x400UL) -#define USB_OTG_HOST_PORT_BASE (0x440UL) -#define USB_OTG_HOST_CHANNEL_BASE (0x500UL) -#define USB_OTG_HOST_CHANNEL_SIZE (0x20UL) -#define USB_OTG_PCGCCTL_BASE (0xE00UL) -#define USB_OTG_FIFO_BASE (0x1000UL) -#define USB_OTG_FIFO_SIZE (0x1000UL) - -/*!< D2_AHB2PERIPH peripherals */ - -#define DCMI_BASE (D2_AHB2PERIPH_BASE + 0x0000UL) -#define PSSI_BASE (D2_AHB2PERIPH_BASE + 0x0400UL) -#define CRYP_BASE (D2_AHB2PERIPH_BASE + 0x1000UL) -#define HASH_BASE (D2_AHB2PERIPH_BASE + 0x1400UL) -#define HASH_DIGEST_BASE (D2_AHB2PERIPH_BASE + 0x1710UL) -#define RNG_BASE (D2_AHB2PERIPH_BASE + 0x1800UL) -#define SDMMC2_BASE (D2_AHB2PERIPH_BASE + 0x2400UL) -#define DLYB_SDMMC2_BASE (D2_AHB2PERIPH_BASE + 0x2800UL) -#define RAMECC2_BASE (D2_AHB2PERIPH_BASE + 0x3000UL) -#define FMAC_BASE (D2_AHB2PERIPH_BASE + 0x4000UL) -#define CORDIC_BASE (D2_AHB2PERIPH_BASE + 0x4400UL) - -/*!< D3_AHB1PERIPH peripherals */ -#define GPIOA_BASE (D3_AHB1PERIPH_BASE + 0x0000UL) -#define GPIOB_BASE (D3_AHB1PERIPH_BASE + 0x0400UL) -#define GPIOC_BASE (D3_AHB1PERIPH_BASE + 0x0800UL) -#define GPIOD_BASE (D3_AHB1PERIPH_BASE + 0x0C00UL) -#define GPIOE_BASE (D3_AHB1PERIPH_BASE + 0x1000UL) -#define GPIOF_BASE (D3_AHB1PERIPH_BASE + 0x1400UL) -#define GPIOG_BASE (D3_AHB1PERIPH_BASE + 0x1800UL) -#define GPIOH_BASE (D3_AHB1PERIPH_BASE + 0x1C00UL) -#define GPIOJ_BASE (D3_AHB1PERIPH_BASE + 0x2400UL) -#define GPIOK_BASE (D3_AHB1PERIPH_BASE + 0x2800UL) -#define RCC_BASE (D3_AHB1PERIPH_BASE + 0x4400UL) -#define PWR_BASE (D3_AHB1PERIPH_BASE + 0x4800UL) -#define CRC_BASE (D3_AHB1PERIPH_BASE + 0x4C00UL) -#define BDMA_BASE (D3_AHB1PERIPH_BASE + 0x5400UL) -#define DMAMUX2_BASE (D3_AHB1PERIPH_BASE + 0x5800UL) -#define ADC3_BASE (D3_AHB1PERIPH_BASE + 0x6000UL) -#define ADC3_COMMON_BASE (D3_AHB1PERIPH_BASE + 0x6300UL) -#define HSEM_BASE (D3_AHB1PERIPH_BASE + 0x6400UL) -#define RAMECC3_BASE (D3_AHB1PERIPH_BASE + 0x7000UL) - -/*!< D1_APB1PERIPH peripherals */ -#define LTDC_BASE (D1_APB1PERIPH_BASE + 0x1000UL) -#define LTDC_Layer1_BASE (LTDC_BASE + 0x84UL) -#define LTDC_Layer2_BASE (LTDC_BASE + 0x104UL) -#define WWDG1_BASE (D1_APB1PERIPH_BASE + 0x3000UL) - -/*!< D2_APB1PERIPH peripherals */ -#define TIM2_BASE (D2_APB1PERIPH_BASE + 0x0000UL) -#define TIM3_BASE (D2_APB1PERIPH_BASE + 0x0400UL) -#define TIM4_BASE (D2_APB1PERIPH_BASE + 0x0800UL) -#define TIM5_BASE (D2_APB1PERIPH_BASE + 0x0C00UL) -#define TIM6_BASE (D2_APB1PERIPH_BASE + 0x1000UL) -#define TIM7_BASE (D2_APB1PERIPH_BASE + 0x1400UL) -#define TIM12_BASE (D2_APB1PERIPH_BASE + 0x1800UL) -#define TIM13_BASE (D2_APB1PERIPH_BASE + 0x1C00UL) -#define TIM14_BASE (D2_APB1PERIPH_BASE + 0x2000UL) -#define LPTIM1_BASE (D2_APB1PERIPH_BASE + 0x2400UL) - - -#define SPI2_BASE (D2_APB1PERIPH_BASE + 0x3800UL) -#define SPI3_BASE (D2_APB1PERIPH_BASE + 0x3C00UL) -#define SPDIFRX_BASE (D2_APB1PERIPH_BASE + 0x4000UL) -#define USART2_BASE (D2_APB1PERIPH_BASE + 0x4400UL) -#define USART3_BASE (D2_APB1PERIPH_BASE + 0x4800UL) -#define UART4_BASE (D2_APB1PERIPH_BASE + 0x4C00UL) -#define UART5_BASE (D2_APB1PERIPH_BASE + 0x5000UL) -#define I2C1_BASE (D2_APB1PERIPH_BASE + 0x5400UL) -#define I2C2_BASE (D2_APB1PERIPH_BASE + 0x5800UL) -#define I2C3_BASE (D2_APB1PERIPH_BASE + 0x5C00UL) -#define I2C5_BASE (D2_APB1PERIPH_BASE + 0x6400UL) -#define CEC_BASE (D2_APB1PERIPH_BASE + 0x6C00UL) -#define DAC1_BASE (D2_APB1PERIPH_BASE + 0x7400UL) -#define UART7_BASE (D2_APB1PERIPH_BASE + 0x7800UL) -#define UART8_BASE (D2_APB1PERIPH_BASE + 0x7C00UL) -#define CRS_BASE (D2_APB1PERIPH_BASE + 0x8400UL) -#define SWPMI1_BASE (D2_APB1PERIPH_BASE + 0x8800UL) -#define OPAMP_BASE (D2_APB1PERIPH_BASE + 0x9000UL) -#define OPAMP1_BASE (D2_APB1PERIPH_BASE + 0x9000UL) -#define OPAMP2_BASE (D2_APB1PERIPH_BASE + 0x9010UL) -#define MDIOS_BASE (D2_APB1PERIPH_BASE + 0x9400UL) -#define FDCAN1_BASE (D2_APB1PERIPH_BASE + 0xA000UL) -#define FDCAN2_BASE (D2_APB1PERIPH_BASE + 0xA400UL) -#define FDCAN_CCU_BASE (D2_APB1PERIPH_BASE + 0xA800UL) -#define SRAMCAN_BASE (D2_APB1PERIPH_BASE + 0xAC00UL) -#define FDCAN3_BASE (D2_APB1PERIPH_BASE + 0xD400UL) -#define TIM23_BASE (D2_APB1PERIPH_BASE + 0xE000UL) -#define TIM24_BASE (D2_APB1PERIPH_BASE + 0xE400UL) - -/*!< D2_APB2PERIPH peripherals */ - -#define TIM1_BASE (D2_APB2PERIPH_BASE + 0x0000UL) -#define TIM8_BASE (D2_APB2PERIPH_BASE + 0x0400UL) -#define USART1_BASE (D2_APB2PERIPH_BASE + 0x1000UL) -#define USART6_BASE (D2_APB2PERIPH_BASE + 0x1400UL) -#define UART9_BASE (D2_APB2PERIPH_BASE + 0x1800UL) -#define USART10_BASE (D2_APB2PERIPH_BASE + 0x1C00UL) -#define SPI1_BASE (D2_APB2PERIPH_BASE + 0x3000UL) -#define SPI4_BASE (D2_APB2PERIPH_BASE + 0x3400UL) -#define TIM15_BASE (D2_APB2PERIPH_BASE + 0x4000UL) -#define TIM16_BASE (D2_APB2PERIPH_BASE + 0x4400UL) -#define TIM17_BASE (D2_APB2PERIPH_BASE + 0x4800UL) -#define SPI5_BASE (D2_APB2PERIPH_BASE + 0x5000UL) -#define SAI1_BASE (D2_APB2PERIPH_BASE + 0x5800UL) -#define SAI1_Block_A_BASE (SAI1_BASE + 0x004UL) -#define SAI1_Block_B_BASE (SAI1_BASE + 0x024UL) -#define DFSDM1_BASE (D2_APB2PERIPH_BASE + 0x7800UL) -#define DFSDM1_Channel0_BASE (DFSDM1_BASE + 0x00UL) -#define DFSDM1_Channel1_BASE (DFSDM1_BASE + 0x20UL) -#define DFSDM1_Channel2_BASE (DFSDM1_BASE + 0x40UL) -#define DFSDM1_Channel3_BASE (DFSDM1_BASE + 0x60UL) -#define DFSDM1_Channel4_BASE (DFSDM1_BASE + 0x80UL) -#define DFSDM1_Channel5_BASE (DFSDM1_BASE + 0xA0UL) -#define DFSDM1_Channel6_BASE (DFSDM1_BASE + 0xC0UL) -#define DFSDM1_Channel7_BASE (DFSDM1_BASE + 0xE0UL) -#define DFSDM1_Filter0_BASE (DFSDM1_BASE + 0x100UL) -#define DFSDM1_Filter1_BASE (DFSDM1_BASE + 0x180UL) -#define DFSDM1_Filter2_BASE (DFSDM1_BASE + 0x200UL) -#define DFSDM1_Filter3_BASE (DFSDM1_BASE + 0x280UL) - - -/*!< D3_APB1PERIPH peripherals */ -#define EXTI_BASE (D3_APB1PERIPH_BASE + 0x0000UL) -#define EXTI_D1_BASE (EXTI_BASE + 0x0080UL) -#define EXTI_D2_BASE (EXTI_BASE + 0x00C0UL) -#define SYSCFG_BASE (D3_APB1PERIPH_BASE + 0x0400UL) -#define LPUART1_BASE (D3_APB1PERIPH_BASE + 0x0C00UL) -#define SPI6_BASE (D3_APB1PERIPH_BASE + 0x1400UL) -#define I2C4_BASE (D3_APB1PERIPH_BASE + 0x1C00UL) -#define LPTIM2_BASE (D3_APB1PERIPH_BASE + 0x2400UL) -#define LPTIM3_BASE (D3_APB1PERIPH_BASE + 0x2800UL) -#define LPTIM4_BASE (D3_APB1PERIPH_BASE + 0x2C00UL) -#define LPTIM5_BASE (D3_APB1PERIPH_BASE + 0x3000UL) -#define COMP12_BASE (D3_APB1PERIPH_BASE + 0x3800UL) -#define COMP1_BASE (COMP12_BASE + 0x0CUL) -#define COMP2_BASE (COMP12_BASE + 0x10UL) -#define VREFBUF_BASE (D3_APB1PERIPH_BASE + 0x3C00UL) -#define RTC_BASE (D3_APB1PERIPH_BASE + 0x4000UL) -#define IWDG1_BASE (D3_APB1PERIPH_BASE + 0x4800UL) - - -#define SAI4_BASE (D3_APB1PERIPH_BASE + 0x5400UL) -#define SAI4_Block_A_BASE (SAI4_BASE + 0x004UL) -#define SAI4_Block_B_BASE (SAI4_BASE + 0x024UL) - -#define DTS_BASE (D3_APB1PERIPH_BASE + 0x6800UL) - - - -#define BDMA_Channel0_BASE (BDMA_BASE + 0x0008UL) -#define BDMA_Channel1_BASE (BDMA_BASE + 0x001CUL) -#define BDMA_Channel2_BASE (BDMA_BASE + 0x0030UL) -#define BDMA_Channel3_BASE (BDMA_BASE + 0x0044UL) -#define BDMA_Channel4_BASE (BDMA_BASE + 0x0058UL) -#define BDMA_Channel5_BASE (BDMA_BASE + 0x006CUL) -#define BDMA_Channel6_BASE (BDMA_BASE + 0x0080UL) -#define BDMA_Channel7_BASE (BDMA_BASE + 0x0094UL) - -#define DMAMUX2_Channel0_BASE (DMAMUX2_BASE) -#define DMAMUX2_Channel1_BASE (DMAMUX2_BASE + 0x0004UL) -#define DMAMUX2_Channel2_BASE (DMAMUX2_BASE + 0x0008UL) -#define DMAMUX2_Channel3_BASE (DMAMUX2_BASE + 0x000CUL) -#define DMAMUX2_Channel4_BASE (DMAMUX2_BASE + 0x0010UL) -#define DMAMUX2_Channel5_BASE (DMAMUX2_BASE + 0x0014UL) -#define DMAMUX2_Channel6_BASE (DMAMUX2_BASE + 0x0018UL) -#define DMAMUX2_Channel7_BASE (DMAMUX2_BASE + 0x001CUL) - -#define DMAMUX2_RequestGenerator0_BASE (DMAMUX2_BASE + 0x0100UL) -#define DMAMUX2_RequestGenerator1_BASE (DMAMUX2_BASE + 0x0104UL) -#define DMAMUX2_RequestGenerator2_BASE (DMAMUX2_BASE + 0x0108UL) -#define DMAMUX2_RequestGenerator3_BASE (DMAMUX2_BASE + 0x010CUL) -#define DMAMUX2_RequestGenerator4_BASE (DMAMUX2_BASE + 0x0110UL) -#define DMAMUX2_RequestGenerator5_BASE (DMAMUX2_BASE + 0x0114UL) -#define DMAMUX2_RequestGenerator6_BASE (DMAMUX2_BASE + 0x0118UL) -#define DMAMUX2_RequestGenerator7_BASE (DMAMUX2_BASE + 0x011CUL) - -#define DMAMUX2_ChannelStatus_BASE (DMAMUX2_BASE + 0x0080UL) -#define DMAMUX2_RequestGenStatus_BASE (DMAMUX2_BASE + 0x0140UL) - -#define DMA1_Stream0_BASE (DMA1_BASE + 0x010UL) -#define DMA1_Stream1_BASE (DMA1_BASE + 0x028UL) -#define DMA1_Stream2_BASE (DMA1_BASE + 0x040UL) -#define DMA1_Stream3_BASE (DMA1_BASE + 0x058UL) -#define DMA1_Stream4_BASE (DMA1_BASE + 0x070UL) -#define DMA1_Stream5_BASE (DMA1_BASE + 0x088UL) -#define DMA1_Stream6_BASE (DMA1_BASE + 0x0A0UL) -#define DMA1_Stream7_BASE (DMA1_BASE + 0x0B8UL) - -#define DMA2_Stream0_BASE (DMA2_BASE + 0x010UL) -#define DMA2_Stream1_BASE (DMA2_BASE + 0x028UL) -#define DMA2_Stream2_BASE (DMA2_BASE + 0x040UL) -#define DMA2_Stream3_BASE (DMA2_BASE + 0x058UL) -#define DMA2_Stream4_BASE (DMA2_BASE + 0x070UL) -#define DMA2_Stream5_BASE (DMA2_BASE + 0x088UL) -#define DMA2_Stream6_BASE (DMA2_BASE + 0x0A0UL) -#define DMA2_Stream7_BASE (DMA2_BASE + 0x0B8UL) - -#define DMAMUX1_Channel0_BASE (DMAMUX1_BASE) -#define DMAMUX1_Channel1_BASE (DMAMUX1_BASE + 0x0004UL) -#define DMAMUX1_Channel2_BASE (DMAMUX1_BASE + 0x0008UL) -#define DMAMUX1_Channel3_BASE (DMAMUX1_BASE + 0x000CUL) -#define DMAMUX1_Channel4_BASE (DMAMUX1_BASE + 0x0010UL) -#define DMAMUX1_Channel5_BASE (DMAMUX1_BASE + 0x0014UL) -#define DMAMUX1_Channel6_BASE (DMAMUX1_BASE + 0x0018UL) -#define DMAMUX1_Channel7_BASE (DMAMUX1_BASE + 0x001CUL) -#define DMAMUX1_Channel8_BASE (DMAMUX1_BASE + 0x0020UL) -#define DMAMUX1_Channel9_BASE (DMAMUX1_BASE + 0x0024UL) -#define DMAMUX1_Channel10_BASE (DMAMUX1_BASE + 0x0028UL) -#define DMAMUX1_Channel11_BASE (DMAMUX1_BASE + 0x002CUL) -#define DMAMUX1_Channel12_BASE (DMAMUX1_BASE + 0x0030UL) -#define DMAMUX1_Channel13_BASE (DMAMUX1_BASE + 0x0034UL) -#define DMAMUX1_Channel14_BASE (DMAMUX1_BASE + 0x0038UL) -#define DMAMUX1_Channel15_BASE (DMAMUX1_BASE + 0x003CUL) - -#define DMAMUX1_RequestGenerator0_BASE (DMAMUX1_BASE + 0x0100UL) -#define DMAMUX1_RequestGenerator1_BASE (DMAMUX1_BASE + 0x0104UL) -#define DMAMUX1_RequestGenerator2_BASE (DMAMUX1_BASE + 0x0108UL) -#define DMAMUX1_RequestGenerator3_BASE (DMAMUX1_BASE + 0x010CUL) -#define DMAMUX1_RequestGenerator4_BASE (DMAMUX1_BASE + 0x0110UL) -#define DMAMUX1_RequestGenerator5_BASE (DMAMUX1_BASE + 0x0114UL) -#define DMAMUX1_RequestGenerator6_BASE (DMAMUX1_BASE + 0x0118UL) -#define DMAMUX1_RequestGenerator7_BASE (DMAMUX1_BASE + 0x011CUL) - -#define DMAMUX1_ChannelStatus_BASE (DMAMUX1_BASE + 0x0080UL) -#define DMAMUX1_RequestGenStatus_BASE (DMAMUX1_BASE + 0x0140UL) - -/*!< FMC Banks registers base address */ -#define FMC_Bank1_R_BASE (FMC_R_BASE + 0x0000UL) -#define FMC_Bank1E_R_BASE (FMC_R_BASE + 0x0104UL) -#define FMC_Bank2_R_BASE (FMC_R_BASE + 0x0060UL) -#define FMC_Bank3_R_BASE (FMC_R_BASE + 0x0080UL) -#define FMC_Bank5_6_R_BASE (FMC_R_BASE + 0x0140UL) - -/* Debug MCU registers base address */ -#define DBGMCU_BASE (0x5C001000UL) - -#define MDMA_Channel0_BASE (MDMA_BASE + 0x00000040UL) -#define MDMA_Channel1_BASE (MDMA_BASE + 0x00000080UL) -#define MDMA_Channel2_BASE (MDMA_BASE + 0x000000C0UL) -#define MDMA_Channel3_BASE (MDMA_BASE + 0x00000100UL) -#define MDMA_Channel4_BASE (MDMA_BASE + 0x00000140UL) -#define MDMA_Channel5_BASE (MDMA_BASE + 0x00000180UL) -#define MDMA_Channel6_BASE (MDMA_BASE + 0x000001C0UL) -#define MDMA_Channel7_BASE (MDMA_BASE + 0x00000200UL) -#define MDMA_Channel8_BASE (MDMA_BASE + 0x00000240UL) -#define MDMA_Channel9_BASE (MDMA_BASE + 0x00000280UL) -#define MDMA_Channel10_BASE (MDMA_BASE + 0x000002C0UL) -#define MDMA_Channel11_BASE (MDMA_BASE + 0x00000300UL) -#define MDMA_Channel12_BASE (MDMA_BASE + 0x00000340UL) -#define MDMA_Channel13_BASE (MDMA_BASE + 0x00000380UL) -#define MDMA_Channel14_BASE (MDMA_BASE + 0x000003C0UL) -#define MDMA_Channel15_BASE (MDMA_BASE + 0x00000400UL) - -#define RAMECC1_Monitor1_BASE (RAMECC1_BASE + 0x20UL) -#define RAMECC1_Monitor2_BASE (RAMECC1_BASE + 0x40UL) -#define RAMECC1_Monitor3_BASE (RAMECC1_BASE + 0x60UL) -#define RAMECC1_Monitor4_BASE (RAMECC1_BASE + 0x80UL) -#define RAMECC1_Monitor5_BASE (RAMECC1_BASE + 0xA0UL) -#define RAMECC1_Monitor6_BASE (RAMECC1_BASE + 0xC0UL) - -#define RAMECC2_Monitor1_BASE (RAMECC2_BASE + 0x20UL) -#define RAMECC2_Monitor2_BASE (RAMECC2_BASE + 0x40UL) -#define RAMECC2_Monitor3_BASE (RAMECC2_BASE + 0x60UL) - -#define RAMECC3_Monitor1_BASE (RAMECC3_BASE + 0x20UL) -#define RAMECC3_Monitor2_BASE (RAMECC3_BASE + 0x40UL) - - - -#define GPV_BASE (PERIPH_BASE + 0x11000000UL) /*!< GPV_BASE (PERIPH_BASE + 0x11000000UL) */ - -/** - * @} - */ - -/** @addtogroup Peripheral_declaration - * @{ - */ -#define TIM2 ((TIM_TypeDef *) TIM2_BASE) -#define TIM3 ((TIM_TypeDef *) TIM3_BASE) -#define TIM4 ((TIM_TypeDef *) TIM4_BASE) -#define TIM5 ((TIM_TypeDef *) TIM5_BASE) -#define TIM6 ((TIM_TypeDef *) TIM6_BASE) -#define TIM7 ((TIM_TypeDef *) TIM7_BASE) -#define TIM13 ((TIM_TypeDef *) TIM13_BASE) -#define TIM14 ((TIM_TypeDef *) TIM14_BASE) -#define VREFBUF ((VREFBUF_TypeDef *) VREFBUF_BASE) -#define RTC ((RTC_TypeDef *) RTC_BASE) -#define WWDG1 ((WWDG_TypeDef *) WWDG1_BASE) - - -#define IWDG1 ((IWDG_TypeDef *) IWDG1_BASE) -#define SPI2 ((SPI_TypeDef *) SPI2_BASE) -#define SPI3 ((SPI_TypeDef *) SPI3_BASE) -#define SPI4 ((SPI_TypeDef *) SPI4_BASE) -#define SPI5 ((SPI_TypeDef *) SPI5_BASE) -#define SPI6 ((SPI_TypeDef *) SPI6_BASE) -#define USART2 ((USART_TypeDef *) USART2_BASE) -#define USART3 ((USART_TypeDef *) USART3_BASE) -#define USART6 ((USART_TypeDef *) USART6_BASE) -#define USART10 ((USART_TypeDef *) USART10_BASE) -#define UART7 ((USART_TypeDef *) UART7_BASE) -#define UART8 ((USART_TypeDef *) UART8_BASE) -#define UART9 ((USART_TypeDef *) UART9_BASE) -#define CRS ((CRS_TypeDef *) CRS_BASE) -#define UART4 ((USART_TypeDef *) UART4_BASE) -#define UART5 ((USART_TypeDef *) UART5_BASE) -#define I2C1 ((I2C_TypeDef *) I2C1_BASE) -#define I2C2 ((I2C_TypeDef *) I2C2_BASE) -#define I2C3 ((I2C_TypeDef *) I2C3_BASE) -#define I2C4 ((I2C_TypeDef *) I2C4_BASE) -#define I2C5 ((I2C_TypeDef *) I2C5_BASE) -#define FDCAN1 ((FDCAN_GlobalTypeDef *) FDCAN1_BASE) -#define FDCAN2 ((FDCAN_GlobalTypeDef *) FDCAN2_BASE) -#define FDCAN_CCU ((FDCAN_ClockCalibrationUnit_TypeDef *) FDCAN_CCU_BASE) -#define FDCAN3 ((FDCAN_GlobalTypeDef *) FDCAN3_BASE) -#define TIM23 ((TIM_TypeDef *) TIM23_BASE) -#define TIM24 ((TIM_TypeDef *) TIM24_BASE) -#define CEC ((CEC_TypeDef *) CEC_BASE) -#define LPTIM1 ((LPTIM_TypeDef *) LPTIM1_BASE) -#define PWR ((PWR_TypeDef *) PWR_BASE) -#define DAC1 ((DAC_TypeDef *) DAC1_BASE) -#define LPUART1 ((USART_TypeDef *) LPUART1_BASE) -#define SWPMI1 ((SWPMI_TypeDef *) SWPMI1_BASE) -#define LPTIM2 ((LPTIM_TypeDef *) LPTIM2_BASE) -#define LPTIM3 ((LPTIM_TypeDef *) LPTIM3_BASE) -#define DTS ((DTS_TypeDef *) DTS_BASE) -#define LPTIM4 ((LPTIM_TypeDef *) LPTIM4_BASE) -#define LPTIM5 ((LPTIM_TypeDef *) LPTIM5_BASE) - -#define SYSCFG ((SYSCFG_TypeDef *) SYSCFG_BASE) -#define COMP12 ((COMPOPT_TypeDef *) COMP12_BASE) -#define COMP1 ((COMP_TypeDef *) COMP1_BASE) -#define COMP2 ((COMP_TypeDef *) COMP2_BASE) -#define COMP12_COMMON ((COMP_Common_TypeDef *) COMP2_BASE) -#define OPAMP ((OPAMP_TypeDef *) OPAMP_BASE) -#define OPAMP1 ((OPAMP_TypeDef *) OPAMP1_BASE) -#define OPAMP2 ((OPAMP_TypeDef *) OPAMP2_BASE) - - -#define EXTI ((EXTI_TypeDef *) EXTI_BASE) -#define EXTI_D1 ((EXTI_Core_TypeDef *) EXTI_D1_BASE) -#define EXTI_D2 ((EXTI_Core_TypeDef *) EXTI_D2_BASE) -#define TIM1 ((TIM_TypeDef *) TIM1_BASE) -#define SPI1 ((SPI_TypeDef *) SPI1_BASE) -#define TIM8 ((TIM_TypeDef *) TIM8_BASE) -#define USART1 ((USART_TypeDef *) USART1_BASE) -#define TIM12 ((TIM_TypeDef *) TIM12_BASE) -#define TIM15 ((TIM_TypeDef *) TIM15_BASE) -#define TIM16 ((TIM_TypeDef *) TIM16_BASE) -#define TIM17 ((TIM_TypeDef *) TIM17_BASE) -#define SAI1 ((SAI_TypeDef *) SAI1_BASE) -#define SAI1_Block_A ((SAI_Block_TypeDef *)SAI1_Block_A_BASE) -#define SAI1_Block_B ((SAI_Block_TypeDef *)SAI1_Block_B_BASE) -#define SAI4 ((SAI_TypeDef *) SAI4_BASE) -#define SAI4_Block_A ((SAI_Block_TypeDef *)SAI4_Block_A_BASE) -#define SAI4_Block_B ((SAI_Block_TypeDef *)SAI4_Block_B_BASE) - -#define SPDIFRX ((SPDIFRX_TypeDef *) SPDIFRX_BASE) -#define DFSDM1_Channel0 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel0_BASE) -#define DFSDM1_Channel1 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel1_BASE) -#define DFSDM1_Channel2 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel2_BASE) -#define DFSDM1_Channel3 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel3_BASE) -#define DFSDM1_Channel4 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel4_BASE) -#define DFSDM1_Channel5 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel5_BASE) -#define DFSDM1_Channel6 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel6_BASE) -#define DFSDM1_Channel7 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel7_BASE) -#define DFSDM1_Filter0 ((DFSDM_Filter_TypeDef *) DFSDM1_Filter0_BASE) -#define DFSDM1_Filter1 ((DFSDM_Filter_TypeDef *) DFSDM1_Filter1_BASE) -#define DFSDM1_Filter2 ((DFSDM_Filter_TypeDef *) DFSDM1_Filter2_BASE) -#define DFSDM1_Filter3 ((DFSDM_Filter_TypeDef *) DFSDM1_Filter3_BASE) -#define DMA2D ((DMA2D_TypeDef *) DMA2D_BASE) -#define DCMI ((DCMI_TypeDef *) DCMI_BASE) -#define PSSI ((PSSI_TypeDef *) PSSI_BASE) -#define RCC ((RCC_TypeDef *) RCC_BASE) -#define FLASH ((FLASH_TypeDef *) FLASH_R_BASE) -#define CRC ((CRC_TypeDef *) CRC_BASE) - -#define GPIOA ((GPIO_TypeDef *) GPIOA_BASE) -#define GPIOB ((GPIO_TypeDef *) GPIOB_BASE) -#define GPIOC ((GPIO_TypeDef *) GPIOC_BASE) -#define GPIOD ((GPIO_TypeDef *) GPIOD_BASE) -#define GPIOE ((GPIO_TypeDef *) GPIOE_BASE) -#define GPIOF ((GPIO_TypeDef *) GPIOF_BASE) -#define GPIOG ((GPIO_TypeDef *) GPIOG_BASE) -#define GPIOH ((GPIO_TypeDef *) GPIOH_BASE) -#define GPIOJ ((GPIO_TypeDef *) GPIOJ_BASE) -#define GPIOK ((GPIO_TypeDef *) GPIOK_BASE) - -#define ADC1 ((ADC_TypeDef *) ADC1_BASE) -#define ADC2 ((ADC_TypeDef *) ADC2_BASE) -#define ADC3 ((ADC_TypeDef *) ADC3_BASE) -#define ADC3_COMMON ((ADC_Common_TypeDef *) ADC3_COMMON_BASE) -#define ADC12_COMMON ((ADC_Common_TypeDef *) ADC12_COMMON_BASE) - -#define CRYP ((CRYP_TypeDef *) CRYP_BASE) -#define HASH ((HASH_TypeDef *) HASH_BASE) -#define HASH_DIGEST ((HASH_DIGEST_TypeDef *) HASH_DIGEST_BASE) -#define RNG ((RNG_TypeDef *) RNG_BASE) -#define SDMMC2 ((SDMMC_TypeDef *) SDMMC2_BASE) -#define DLYB_SDMMC2 ((DLYB_TypeDef *) DLYB_SDMMC2_BASE) -#define FMAC ((FMAC_TypeDef *) FMAC_BASE) -#define CORDIC ((CORDIC_TypeDef *) CORDIC_BASE) - -#define BDMA ((BDMA_TypeDef *) BDMA_BASE) -#define BDMA_Channel0 ((BDMA_Channel_TypeDef *) BDMA_Channel0_BASE) -#define BDMA_Channel1 ((BDMA_Channel_TypeDef *) BDMA_Channel1_BASE) -#define BDMA_Channel2 ((BDMA_Channel_TypeDef *) BDMA_Channel2_BASE) -#define BDMA_Channel3 ((BDMA_Channel_TypeDef *) BDMA_Channel3_BASE) -#define BDMA_Channel4 ((BDMA_Channel_TypeDef *) BDMA_Channel4_BASE) -#define BDMA_Channel5 ((BDMA_Channel_TypeDef *) BDMA_Channel5_BASE) -#define BDMA_Channel6 ((BDMA_Channel_TypeDef *) BDMA_Channel6_BASE) -#define BDMA_Channel7 ((BDMA_Channel_TypeDef *) BDMA_Channel7_BASE) - -#define RAMECC1 ((RAMECC_TypeDef *)RAMECC1_BASE) -#define RAMECC1_Monitor1 ((RAMECC_MonitorTypeDef *)RAMECC1_Monitor1_BASE) -#define RAMECC1_Monitor2 ((RAMECC_MonitorTypeDef *)RAMECC1_Monitor2_BASE) -#define RAMECC1_Monitor3 ((RAMECC_MonitorTypeDef *)RAMECC1_Monitor3_BASE) -#define RAMECC1_Monitor4 ((RAMECC_MonitorTypeDef *)RAMECC1_Monitor4_BASE) -#define RAMECC1_Monitor5 ((RAMECC_MonitorTypeDef *)RAMECC1_Monitor5_BASE) -#define RAMECC1_Monitor6 ((RAMECC_MonitorTypeDef *)RAMECC1_Monitor6_BASE) - -#define RAMECC2 ((RAMECC_TypeDef *)RAMECC2_BASE) -#define RAMECC2_Monitor1 ((RAMECC_MonitorTypeDef *)RAMECC2_Monitor1_BASE) -#define RAMECC2_Monitor2 ((RAMECC_MonitorTypeDef *)RAMECC2_Monitor2_BASE) -#define RAMECC2_Monitor3 ((RAMECC_MonitorTypeDef *)RAMECC2_Monitor3_BASE) - -#define RAMECC3 ((RAMECC_TypeDef *)RAMECC3_BASE) -#define RAMECC3_Monitor1 ((RAMECC_MonitorTypeDef *)RAMECC3_Monitor1_BASE) -#define RAMECC3_Monitor2 ((RAMECC_MonitorTypeDef *)RAMECC3_Monitor2_BASE) - -#define DMAMUX2 ((DMAMUX_Channel_TypeDef *) DMAMUX2_BASE) -#define DMAMUX2_Channel0 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel0_BASE) -#define DMAMUX2_Channel1 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel1_BASE) -#define DMAMUX2_Channel2 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel2_BASE) -#define DMAMUX2_Channel3 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel3_BASE) -#define DMAMUX2_Channel4 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel4_BASE) -#define DMAMUX2_Channel5 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel5_BASE) -#define DMAMUX2_Channel6 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel6_BASE) -#define DMAMUX2_Channel7 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel7_BASE) - - -#define DMAMUX2_RequestGenerator0 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator0_BASE) -#define DMAMUX2_RequestGenerator1 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator1_BASE) -#define DMAMUX2_RequestGenerator2 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator2_BASE) -#define DMAMUX2_RequestGenerator3 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator3_BASE) -#define DMAMUX2_RequestGenerator4 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator4_BASE) -#define DMAMUX2_RequestGenerator5 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator5_BASE) -#define DMAMUX2_RequestGenerator6 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator6_BASE) -#define DMAMUX2_RequestGenerator7 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator7_BASE) - -#define DMAMUX2_ChannelStatus ((DMAMUX_ChannelStatus_TypeDef *) DMAMUX2_ChannelStatus_BASE) -#define DMAMUX2_RequestGenStatus ((DMAMUX_RequestGenStatus_TypeDef *) DMAMUX2_RequestGenStatus_BASE) - -#define DMA2 ((DMA_TypeDef *) DMA2_BASE) -#define DMA2_Stream0 ((DMA_Stream_TypeDef *) DMA2_Stream0_BASE) -#define DMA2_Stream1 ((DMA_Stream_TypeDef *) DMA2_Stream1_BASE) -#define DMA2_Stream2 ((DMA_Stream_TypeDef *) DMA2_Stream2_BASE) -#define DMA2_Stream3 ((DMA_Stream_TypeDef *) DMA2_Stream3_BASE) -#define DMA2_Stream4 ((DMA_Stream_TypeDef *) DMA2_Stream4_BASE) -#define DMA2_Stream5 ((DMA_Stream_TypeDef *) DMA2_Stream5_BASE) -#define DMA2_Stream6 ((DMA_Stream_TypeDef *) DMA2_Stream6_BASE) -#define DMA2_Stream7 ((DMA_Stream_TypeDef *) DMA2_Stream7_BASE) - -#define DMA1 ((DMA_TypeDef *) DMA1_BASE) -#define DMA1_Stream0 ((DMA_Stream_TypeDef *) DMA1_Stream0_BASE) -#define DMA1_Stream1 ((DMA_Stream_TypeDef *) DMA1_Stream1_BASE) -#define DMA1_Stream2 ((DMA_Stream_TypeDef *) DMA1_Stream2_BASE) -#define DMA1_Stream3 ((DMA_Stream_TypeDef *) DMA1_Stream3_BASE) -#define DMA1_Stream4 ((DMA_Stream_TypeDef *) DMA1_Stream4_BASE) -#define DMA1_Stream5 ((DMA_Stream_TypeDef *) DMA1_Stream5_BASE) -#define DMA1_Stream6 ((DMA_Stream_TypeDef *) DMA1_Stream6_BASE) -#define DMA1_Stream7 ((DMA_Stream_TypeDef *) DMA1_Stream7_BASE) - - -#define DMAMUX1 ((DMAMUX_Channel_TypeDef *) DMAMUX1_BASE) -#define DMAMUX1_Channel0 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel0_BASE) -#define DMAMUX1_Channel1 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel1_BASE) -#define DMAMUX1_Channel2 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel2_BASE) -#define DMAMUX1_Channel3 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel3_BASE) -#define DMAMUX1_Channel4 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel4_BASE) -#define DMAMUX1_Channel5 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel5_BASE) -#define DMAMUX1_Channel6 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel6_BASE) -#define DMAMUX1_Channel7 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel7_BASE) -#define DMAMUX1_Channel8 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel8_BASE) -#define DMAMUX1_Channel9 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel9_BASE) -#define DMAMUX1_Channel10 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel10_BASE) -#define DMAMUX1_Channel11 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel11_BASE) -#define DMAMUX1_Channel12 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel12_BASE) -#define DMAMUX1_Channel13 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel13_BASE) -#define DMAMUX1_Channel14 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel14_BASE) -#define DMAMUX1_Channel15 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel15_BASE) - -#define DMAMUX1_RequestGenerator0 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator0_BASE) -#define DMAMUX1_RequestGenerator1 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator1_BASE) -#define DMAMUX1_RequestGenerator2 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator2_BASE) -#define DMAMUX1_RequestGenerator3 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator3_BASE) -#define DMAMUX1_RequestGenerator4 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator4_BASE) -#define DMAMUX1_RequestGenerator5 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator5_BASE) -#define DMAMUX1_RequestGenerator6 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator6_BASE) -#define DMAMUX1_RequestGenerator7 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator7_BASE) - -#define DMAMUX1_ChannelStatus ((DMAMUX_ChannelStatus_TypeDef *) DMAMUX1_ChannelStatus_BASE) -#define DMAMUX1_RequestGenStatus ((DMAMUX_RequestGenStatus_TypeDef *) DMAMUX1_RequestGenStatus_BASE) - - -#define FMC_Bank1_R ((FMC_Bank1_TypeDef *) FMC_Bank1_R_BASE) -#define FMC_Bank1E_R ((FMC_Bank1E_TypeDef *) FMC_Bank1E_R_BASE) -#define FMC_Bank2_R ((FMC_Bank2_TypeDef *) FMC_Bank2_R_BASE) -#define FMC_Bank3_R ((FMC_Bank3_TypeDef *) FMC_Bank3_R_BASE) -#define FMC_Bank5_6_R ((FMC_Bank5_6_TypeDef *) FMC_Bank5_6_R_BASE) - -#define OCTOSPI1 ((OCTOSPI_TypeDef *) OCTOSPI1_R_BASE) -#define DLYB_OCTOSPI1 ((DLYB_TypeDef *) DLYB_OCTOSPI1_BASE) -#define OCTOSPI2 ((OCTOSPI_TypeDef *) OCTOSPI2_R_BASE) -#define DLYB_OCTOSPI2 ((DLYB_TypeDef *) DLYB_OCTOSPI2_BASE) -#define OCTOSPIM ((OCTOSPIM_TypeDef *) OCTOSPIM_BASE) - -#define OTFDEC1 ((OTFDEC_TypeDef *) OTFDEC1_BASE) -#define OTFDEC1_REGION1 ((OTFDEC_Region_TypeDef *) OTFDEC1_REGION1_BASE) -#define OTFDEC1_REGION2 ((OTFDEC_Region_TypeDef *) OTFDEC1_REGION2_BASE) -#define OTFDEC1_REGION3 ((OTFDEC_Region_TypeDef *) OTFDEC1_REGION3_BASE) -#define OTFDEC1_REGION4 ((OTFDEC_Region_TypeDef *) OTFDEC1_REGION4_BASE) - -#define OTFDEC2 ((OTFDEC_TypeDef *) OTFDEC2_BASE) -#define OTFDEC2_REGION1 ((OTFDEC_Region_TypeDef *) OTFDEC2_REGION1_BASE) -#define OTFDEC2_REGION2 ((OTFDEC_Region_TypeDef *) OTFDEC2_REGION2_BASE) -#define OTFDEC2_REGION3 ((OTFDEC_Region_TypeDef *) OTFDEC2_REGION3_BASE) -#define OTFDEC2_REGION4 ((OTFDEC_Region_TypeDef *) OTFDEC2_REGION4_BASE) - -#define SDMMC1 ((SDMMC_TypeDef *) SDMMC1_BASE) -#define DLYB_SDMMC1 ((DLYB_TypeDef *) DLYB_SDMMC1_BASE) - -#define DBGMCU ((DBGMCU_TypeDef *) DBGMCU_BASE) - -#define HSEM ((HSEM_TypeDef *) HSEM_BASE) -#define HSEM_COMMON ((HSEM_Common_TypeDef *) (HSEM_BASE + 0x100UL)) - -#define LTDC ((LTDC_TypeDef *)LTDC_BASE) -#define LTDC_Layer1 ((LTDC_Layer_TypeDef *)LTDC_Layer1_BASE) -#define LTDC_Layer2 ((LTDC_Layer_TypeDef *)LTDC_Layer2_BASE) - -#define MDIOS ((MDIOS_TypeDef *) MDIOS_BASE) - -#define ETH ((ETH_TypeDef *)ETH_BASE) -#define MDMA ((MDMA_TypeDef *)MDMA_BASE) -#define MDMA_Channel0 ((MDMA_Channel_TypeDef *)MDMA_Channel0_BASE) -#define MDMA_Channel1 ((MDMA_Channel_TypeDef *)MDMA_Channel1_BASE) -#define MDMA_Channel2 ((MDMA_Channel_TypeDef *)MDMA_Channel2_BASE) -#define MDMA_Channel3 ((MDMA_Channel_TypeDef *)MDMA_Channel3_BASE) -#define MDMA_Channel4 ((MDMA_Channel_TypeDef *)MDMA_Channel4_BASE) -#define MDMA_Channel5 ((MDMA_Channel_TypeDef *)MDMA_Channel5_BASE) -#define MDMA_Channel6 ((MDMA_Channel_TypeDef *)MDMA_Channel6_BASE) -#define MDMA_Channel7 ((MDMA_Channel_TypeDef *)MDMA_Channel7_BASE) -#define MDMA_Channel8 ((MDMA_Channel_TypeDef *)MDMA_Channel8_BASE) -#define MDMA_Channel9 ((MDMA_Channel_TypeDef *)MDMA_Channel9_BASE) -#define MDMA_Channel10 ((MDMA_Channel_TypeDef *)MDMA_Channel10_BASE) -#define MDMA_Channel11 ((MDMA_Channel_TypeDef *)MDMA_Channel11_BASE) -#define MDMA_Channel12 ((MDMA_Channel_TypeDef *)MDMA_Channel12_BASE) -#define MDMA_Channel13 ((MDMA_Channel_TypeDef *)MDMA_Channel13_BASE) -#define MDMA_Channel14 ((MDMA_Channel_TypeDef *)MDMA_Channel14_BASE) -#define MDMA_Channel15 ((MDMA_Channel_TypeDef *)MDMA_Channel15_BASE) - - -#define USB1_OTG_HS ((USB_OTG_GlobalTypeDef *) USB1_OTG_HS_PERIPH_BASE) - -/* Legacy defines */ -#define USB_OTG_HS USB1_OTG_HS -#define USB_OTG_HS_PERIPH_BASE USB1_OTG_HS_PERIPH_BASE - -#define GPV ((GPV_TypeDef *) GPV_BASE) - -/** - * @} - */ - -/** @addtogroup Exported_constants - * @{ - */ - - /** @addtogroup Peripheral_Registers_Bits_Definition - * @{ - */ - -/******************************************************************************/ -/* Peripheral Registers_Bits_Definition */ -/******************************************************************************/ - -/******************************************************************************/ -/* */ -/* Analog to Digital Converter */ -/* */ -/******************************************************************************/ -/******************************* ADC VERSION ********************************/ -#define ADC_VER_V5_V90 -/******************** Bit definition for ADC_ISR register ********************/ -#define ADC_ISR_ADRDY_Pos (0U) -#define ADC_ISR_ADRDY_Msk (0x1UL << ADC_ISR_ADRDY_Pos) /*!< 0x00000001 */ -#define ADC_ISR_ADRDY ADC_ISR_ADRDY_Msk /*!< ADC Ready (ADRDY) flag */ -#define ADC_ISR_EOSMP_Pos (1U) -#define ADC_ISR_EOSMP_Msk (0x1UL << ADC_ISR_EOSMP_Pos) /*!< 0x00000002 */ -#define ADC_ISR_EOSMP ADC_ISR_EOSMP_Msk /*!< ADC End of Sampling flag */ -#define ADC_ISR_EOC_Pos (2U) -#define ADC_ISR_EOC_Msk (0x1UL << ADC_ISR_EOC_Pos) /*!< 0x00000004 */ -#define ADC_ISR_EOC ADC_ISR_EOC_Msk /*!< ADC End of Regular Conversion flag */ -#define ADC_ISR_EOS_Pos (3U) -#define ADC_ISR_EOS_Msk (0x1UL << ADC_ISR_EOS_Pos) /*!< 0x00000008 */ -#define ADC_ISR_EOS ADC_ISR_EOS_Msk /*!< ADC End of Regular sequence of Conversions flag */ -#define ADC_ISR_OVR_Pos (4U) -#define ADC_ISR_OVR_Msk (0x1UL << ADC_ISR_OVR_Pos) /*!< 0x00000010 */ -#define ADC_ISR_OVR ADC_ISR_OVR_Msk /*!< ADC overrun flag */ -#define ADC_ISR_JEOC_Pos (5U) -#define ADC_ISR_JEOC_Msk (0x1UL << ADC_ISR_JEOC_Pos) /*!< 0x00000020 */ -#define ADC_ISR_JEOC ADC_ISR_JEOC_Msk /*!< ADC End of Injected Conversion flag */ -#define ADC_ISR_JEOS_Pos (6U) -#define ADC_ISR_JEOS_Msk (0x1UL << ADC_ISR_JEOS_Pos) /*!< 0x00000040 */ -#define ADC_ISR_JEOS ADC_ISR_JEOS_Msk /*!< ADC End of Injected sequence of Conversions flag */ -#define ADC_ISR_AWD1_Pos (7U) -#define ADC_ISR_AWD1_Msk (0x1UL << ADC_ISR_AWD1_Pos) /*!< 0x00000080 */ -#define ADC_ISR_AWD1 ADC_ISR_AWD1_Msk /*!< ADC Analog watchdog 1 flag */ -#define ADC_ISR_AWD2_Pos (8U) -#define ADC_ISR_AWD2_Msk (0x1UL << ADC_ISR_AWD2_Pos) /*!< 0x00000100 */ -#define ADC_ISR_AWD2 ADC_ISR_AWD2_Msk /*!< ADC Analog watchdog 2 flag */ -#define ADC_ISR_AWD3_Pos (9U) -#define ADC_ISR_AWD3_Msk (0x1UL << ADC_ISR_AWD3_Pos) /*!< 0x00000200 */ -#define ADC_ISR_AWD3 ADC_ISR_AWD3_Msk /*!< ADC Analog watchdog 3 flag */ -#define ADC_ISR_JQOVF_Pos (10U) -#define ADC_ISR_JQOVF_Msk (0x1UL << ADC_ISR_JQOVF_Pos) /*!< 0x00000400 */ -#define ADC_ISR_JQOVF ADC_ISR_JQOVF_Msk /*!< ADC Injected Context Queue Overflow flag */ -#define ADC_ISR_LDORDY_Pos (12U) -#define ADC_ISR_LDORDY_Msk (0x1UL << ADC_ISR_LDORDY_Pos) /*!< 0x00001000 */ -#define ADC_ISR_LDORDY ADC_ISR_LDORDY_Msk /*!< ADC LDO Ready (LDORDY) flag */ - -/******************** Bit definition for ADC_IER register ********************/ -#define ADC_IER_ADRDYIE_Pos (0U) -#define ADC_IER_ADRDYIE_Msk (0x1UL << ADC_IER_ADRDYIE_Pos) /*!< 0x00000001 */ -#define ADC_IER_ADRDYIE ADC_IER_ADRDYIE_Msk /*!< ADC Ready (ADRDY) interrupt source */ -#define ADC_IER_EOSMPIE_Pos (1U) -#define ADC_IER_EOSMPIE_Msk (0x1UL << ADC_IER_EOSMPIE_Pos) /*!< 0x00000002 */ -#define ADC_IER_EOSMPIE ADC_IER_EOSMPIE_Msk /*!< ADC End of Sampling interrupt source */ -#define ADC_IER_EOCIE_Pos (2U) -#define ADC_IER_EOCIE_Msk (0x1UL << ADC_IER_EOCIE_Pos) /*!< 0x00000004 */ -#define ADC_IER_EOCIE ADC_IER_EOCIE_Msk /*!< ADC End of Regular Conversion interrupt source */ -#define ADC_IER_EOSIE_Pos (3U) -#define ADC_IER_EOSIE_Msk (0x1UL << ADC_IER_EOSIE_Pos) /*!< 0x00000008 */ -#define ADC_IER_EOSIE ADC_IER_EOSIE_Msk /*!< ADC End of Regular sequence of Conversions interrupt source */ -#define ADC_IER_OVRIE_Pos (4U) -#define ADC_IER_OVRIE_Msk (0x1UL << ADC_IER_OVRIE_Pos) /*!< 0x00000010 */ -#define ADC_IER_OVRIE ADC_IER_OVRIE_Msk /*!< ADC overrun interrupt source */ -#define ADC_IER_JEOCIE_Pos (5U) -#define ADC_IER_JEOCIE_Msk (0x1UL << ADC_IER_JEOCIE_Pos) /*!< 0x00000020 */ -#define ADC_IER_JEOCIE ADC_IER_JEOCIE_Msk /*!< ADC End of Injected Conversion interrupt source */ -#define ADC_IER_JEOSIE_Pos (6U) -#define ADC_IER_JEOSIE_Msk (0x1UL << ADC_IER_JEOSIE_Pos) /*!< 0x00000040 */ -#define ADC_IER_JEOSIE ADC_IER_JEOSIE_Msk /*!< ADC End of Injected sequence of Conversions interrupt source */ -#define ADC_IER_AWD1IE_Pos (7U) -#define ADC_IER_AWD1IE_Msk (0x1UL << ADC_IER_AWD1IE_Pos) /*!< 0x00000080 */ -#define ADC_IER_AWD1IE ADC_IER_AWD1IE_Msk /*!< ADC Analog watchdog 1 interrupt source */ -#define ADC_IER_AWD2IE_Pos (8U) -#define ADC_IER_AWD2IE_Msk (0x1UL << ADC_IER_AWD2IE_Pos) /*!< 0x00000100 */ -#define ADC_IER_AWD2IE ADC_IER_AWD2IE_Msk /*!< ADC Analog watchdog 2 interrupt source */ -#define ADC_IER_AWD3IE_Pos (9U) -#define ADC_IER_AWD3IE_Msk (0x1UL << ADC_IER_AWD3IE_Pos) /*!< 0x00000200 */ -#define ADC_IER_AWD3IE ADC_IER_AWD3IE_Msk /*!< ADC Analog watchdog 3 interrupt source */ -#define ADC_IER_JQOVFIE_Pos (10U) -#define ADC_IER_JQOVFIE_Msk (0x1UL << ADC_IER_JQOVFIE_Pos) /*!< 0x00000400 */ -#define ADC_IER_JQOVFIE ADC_IER_JQOVFIE_Msk /*!< ADC Injected Context Queue Overflow interrupt source */ - -/******************** Bit definition for ADC_CR register ********************/ -#define ADC_CR_ADEN_Pos (0U) -#define ADC_CR_ADEN_Msk (0x1UL << ADC_CR_ADEN_Pos) /*!< 0x00000001 */ -#define ADC_CR_ADEN ADC_CR_ADEN_Msk /*!< ADC Enable control */ -#define ADC_CR_ADDIS_Pos (1U) -#define ADC_CR_ADDIS_Msk (0x1UL << ADC_CR_ADDIS_Pos) /*!< 0x00000002 */ -#define ADC_CR_ADDIS ADC_CR_ADDIS_Msk /*!< ADC Disable command */ -#define ADC_CR_ADSTART_Pos (2U) -#define ADC_CR_ADSTART_Msk (0x1UL << ADC_CR_ADSTART_Pos) /*!< 0x00000004 */ -#define ADC_CR_ADSTART ADC_CR_ADSTART_Msk /*!< ADC Start of Regular conversion */ -#define ADC_CR_JADSTART_Pos (3U) -#define ADC_CR_JADSTART_Msk (0x1UL << ADC_CR_JADSTART_Pos) /*!< 0x00000008 */ -#define ADC_CR_JADSTART ADC_CR_JADSTART_Msk /*!< ADC Start of injected conversion */ -#define ADC_CR_ADSTP_Pos (4U) -#define ADC_CR_ADSTP_Msk (0x1UL << ADC_CR_ADSTP_Pos) /*!< 0x00000010 */ -#define ADC_CR_ADSTP ADC_CR_ADSTP_Msk /*!< ADC Stop of Regular conversion */ -#define ADC_CR_JADSTP_Pos (5U) -#define ADC_CR_JADSTP_Msk (0x1UL << ADC_CR_JADSTP_Pos) /*!< 0x00000020 */ -#define ADC_CR_JADSTP ADC_CR_JADSTP_Msk /*!< ADC Stop of injected conversion */ -#define ADC_CR_BOOST_Pos (8U) -#define ADC_CR_BOOST_Msk (0x3UL << ADC_CR_BOOST_Pos) /*!< 0x00000300 */ -#define ADC_CR_BOOST ADC_CR_BOOST_Msk /*!< ADC Boost Mode configuration */ -#define ADC_CR_BOOST_0 (0x1UL << ADC_CR_BOOST_Pos) /*!< 0x00000100 */ -#define ADC_CR_BOOST_1 (0x2UL << ADC_CR_BOOST_Pos) /*!< 0x00000200 */ -#define ADC_CR_ADCALLIN_Pos (16U) -#define ADC_CR_ADCALLIN_Msk (0x1UL << ADC_CR_ADCALLIN_Pos) /*!< 0x00010000 */ -#define ADC_CR_ADCALLIN ADC_CR_ADCALLIN_Msk /*!< ADC Linearity calibration */ -#define ADC_CR_LINCALRDYW1_Pos (22U) -#define ADC_CR_LINCALRDYW1_Msk (0x1UL << ADC_CR_LINCALRDYW1_Pos) /*!< 0x00400000 */ -#define ADC_CR_LINCALRDYW1 ADC_CR_LINCALRDYW1_Msk /*!< ADC Linearity calibration ready Word 1 */ -#define ADC_CR_LINCALRDYW2_Pos (23U) -#define ADC_CR_LINCALRDYW2_Msk (0x1UL << ADC_CR_LINCALRDYW2_Pos) /*!< 0x00800000 */ -#define ADC_CR_LINCALRDYW2 ADC_CR_LINCALRDYW2_Msk /*!< ADC Linearity calibration ready Word 2 */ -#define ADC_CR_LINCALRDYW3_Pos (24U) -#define ADC_CR_LINCALRDYW3_Msk (0x1UL << ADC_CR_LINCALRDYW3_Pos) /*!< 0x01000000 */ -#define ADC_CR_LINCALRDYW3 ADC_CR_LINCALRDYW3_Msk /*!< ADC Linearity calibration ready Word 3 */ -#define ADC_CR_LINCALRDYW4_Pos (25U) -#define ADC_CR_LINCALRDYW4_Msk (0x1UL << ADC_CR_LINCALRDYW4_Pos) /*!< 0x02000000 */ -#define ADC_CR_LINCALRDYW4 ADC_CR_LINCALRDYW4_Msk /*!< ADC Linearity calibration ready Word 4 */ -#define ADC_CR_LINCALRDYW5_Pos (26U) -#define ADC_CR_LINCALRDYW5_Msk (0x1UL << ADC_CR_LINCALRDYW5_Pos) /*!< 0x04000000 */ -#define ADC_CR_LINCALRDYW5 ADC_CR_LINCALRDYW5_Msk /*!< ADC Linearity calibration ready Word 5 */ -#define ADC_CR_LINCALRDYW6_Pos (27U) -#define ADC_CR_LINCALRDYW6_Msk (0x1UL << ADC_CR_LINCALRDYW6_Pos) /*!< 0x08000000 */ -#define ADC_CR_LINCALRDYW6 ADC_CR_LINCALRDYW6_Msk /*!< ADC Linearity calibration ready Word 6 */ -#define ADC_CR_ADVREGEN_Pos (28U) -#define ADC_CR_ADVREGEN_Msk (0x1UL << ADC_CR_ADVREGEN_Pos) /*!< 0x10000000 */ -#define ADC_CR_ADVREGEN ADC_CR_ADVREGEN_Msk /*!< ADC Voltage regulator Enable */ -#define ADC_CR_DEEPPWD_Pos (29U) -#define ADC_CR_DEEPPWD_Msk (0x1UL << ADC_CR_DEEPPWD_Pos) /*!< 0x20000000 */ -#define ADC_CR_DEEPPWD ADC_CR_DEEPPWD_Msk /*!< ADC Deep power down Enable */ -#define ADC_CR_ADCALDIF_Pos (30U) -#define ADC_CR_ADCALDIF_Msk (0x1UL << ADC_CR_ADCALDIF_Pos) /*!< 0x40000000 */ -#define ADC_CR_ADCALDIF ADC_CR_ADCALDIF_Msk /*!< ADC Differential Mode for calibration */ -#define ADC_CR_ADCAL_Pos (31U) -#define ADC_CR_ADCAL_Msk (0x1UL << ADC_CR_ADCAL_Pos) /*!< 0x80000000 */ -#define ADC_CR_ADCAL ADC_CR_ADCAL_Msk /*!< ADC Calibration */ - -/******************** Bit definition for ADC_CFGR register ********************/ -#define ADC_CFGR_DMNGT_Pos (0U) -#define ADC_CFGR_DMNGT_Msk (0x3UL << ADC_CFGR_DMNGT_Pos) /*!< 0x00000003 */ -#define ADC_CFGR_DMNGT ADC_CFGR_DMNGT_Msk /*!< ADC Data Management configuration */ -#define ADC_CFGR_DMNGT_0 (0x1UL << ADC_CFGR_DMNGT_Pos) /*!< 0x00000001 */ -#define ADC_CFGR_DMNGT_1 (0x2UL << ADC_CFGR_DMNGT_Pos) /*!< 0x00000002 */ - -#define ADC_CFGR_RES_Pos (2U) -#define ADC_CFGR_RES_Msk (0x7UL << ADC_CFGR_RES_Pos) /*!< 0x0000001C */ -#define ADC_CFGR_RES ADC_CFGR_RES_Msk /*!< ADC Data resolution */ -#define ADC_CFGR_RES_0 (0x1UL << ADC_CFGR_RES_Pos) /*!< 0x00000004 */ -#define ADC_CFGR_RES_1 (0x2UL << ADC_CFGR_RES_Pos) /*!< 0x00000008 */ -#define ADC_CFGR_RES_2 (0x4UL << ADC_CFGR_RES_Pos) /*!< 0x00000010 */ - -#define ADC_CFGR_EXTSEL_Pos (5U) -#define ADC_CFGR_EXTSEL_Msk (0x1FUL << ADC_CFGR_EXTSEL_Pos) /*!< 0x000003E0 */ -#define ADC_CFGR_EXTSEL ADC_CFGR_EXTSEL_Msk /*!< ADC External trigger selection for regular group */ -#define ADC_CFGR_EXTSEL_0 (0x01UL << ADC_CFGR_EXTSEL_Pos) /*!< 0x00000020 */ -#define ADC_CFGR_EXTSEL_1 (0x02UL << ADC_CFGR_EXTSEL_Pos) /*!< 0x00000040 */ -#define ADC_CFGR_EXTSEL_2 (0x04UL << ADC_CFGR_EXTSEL_Pos) /*!< 0x00000080 */ -#define ADC_CFGR_EXTSEL_3 (0x08UL << ADC_CFGR_EXTSEL_Pos) /*!< 0x00000100 */ -#define ADC_CFGR_EXTSEL_4 (0x10UL << ADC_CFGR_EXTSEL_Pos) /*!< 0x00000200 */ - -#define ADC_CFGR_EXTEN_Pos (10U) -#define ADC_CFGR_EXTEN_Msk (0x3UL << ADC_CFGR_EXTEN_Pos) /*!< 0x00000C00 */ -#define ADC_CFGR_EXTEN ADC_CFGR_EXTEN_Msk /*!< ADC External trigger enable and polarity selection for regular channels */ -#define ADC_CFGR_EXTEN_0 (0x1UL << ADC_CFGR_EXTEN_Pos) /*!< 0x00000400 */ -#define ADC_CFGR_EXTEN_1 (0x2UL << ADC_CFGR_EXTEN_Pos) /*!< 0x00000800 */ - -#define ADC_CFGR_OVRMOD_Pos (12U) -#define ADC_CFGR_OVRMOD_Msk (0x1UL << ADC_CFGR_OVRMOD_Pos) /*!< 0x00001000 */ -#define ADC_CFGR_OVRMOD ADC_CFGR_OVRMOD_Msk /*!< ADC overrun mode */ -#define ADC_CFGR_CONT_Pos (13U) -#define ADC_CFGR_CONT_Msk (0x1UL << ADC_CFGR_CONT_Pos) /*!< 0x00002000 */ -#define ADC_CFGR_CONT ADC_CFGR_CONT_Msk /*!< ADC Single/continuous conversion mode for regular conversion */ -#define ADC_CFGR_AUTDLY_Pos (14U) -#define ADC_CFGR_AUTDLY_Msk (0x1UL << ADC_CFGR_AUTDLY_Pos) /*!< 0x00004000 */ -#define ADC_CFGR_AUTDLY ADC_CFGR_AUTDLY_Msk /*!< ADC Delayed conversion mode */ - -#define ADC_CFGR_DISCEN_Pos (16U) -#define ADC_CFGR_DISCEN_Msk (0x1UL << ADC_CFGR_DISCEN_Pos) /*!< 0x00010000 */ -#define ADC_CFGR_DISCEN ADC_CFGR_DISCEN_Msk /*!< ADC Discontinuous mode for regular channels */ - -#define ADC_CFGR_DISCNUM_Pos (17U) -#define ADC_CFGR_DISCNUM_Msk (0x7UL << ADC_CFGR_DISCNUM_Pos) /*!< 0x000E0000 */ -#define ADC_CFGR_DISCNUM ADC_CFGR_DISCNUM_Msk /*!< ADC Discontinuous mode channel count */ -#define ADC_CFGR_DISCNUM_0 (0x1UL << ADC_CFGR_DISCNUM_Pos) /*!< 0x00020000 */ -#define ADC_CFGR_DISCNUM_1 (0x2UL << ADC_CFGR_DISCNUM_Pos) /*!< 0x00040000 */ -#define ADC_CFGR_DISCNUM_2 (0x4UL << ADC_CFGR_DISCNUM_Pos) /*!< 0x00080000 */ - -#define ADC_CFGR_JDISCEN_Pos (20U) -#define ADC_CFGR_JDISCEN_Msk (0x1UL << ADC_CFGR_JDISCEN_Pos) /*!< 0x00100000 */ -#define ADC_CFGR_JDISCEN ADC_CFGR_JDISCEN_Msk /*!< ADC Discontinuous mode on injected channels */ -#define ADC_CFGR_JQM_Pos (21U) -#define ADC_CFGR_JQM_Msk (0x1UL << ADC_CFGR_JQM_Pos) /*!< 0x00200000 */ -#define ADC_CFGR_JQM ADC_CFGR_JQM_Msk /*!< ADC JSQR Queue mode */ -#define ADC_CFGR_AWD1SGL_Pos (22U) -#define ADC_CFGR_AWD1SGL_Msk (0x1UL << ADC_CFGR_AWD1SGL_Pos) /*!< 0x00400000 */ -#define ADC_CFGR_AWD1SGL ADC_CFGR_AWD1SGL_Msk /*!< Enable the watchdog 1 on a single channel or on all channels */ -#define ADC_CFGR_AWD1EN_Pos (23U) -#define ADC_CFGR_AWD1EN_Msk (0x1UL << ADC_CFGR_AWD1EN_Pos) /*!< 0x00800000 */ -#define ADC_CFGR_AWD1EN ADC_CFGR_AWD1EN_Msk /*!< ADC Analog watchdog 1 enable on regular Channels */ -#define ADC_CFGR_JAWD1EN_Pos (24U) -#define ADC_CFGR_JAWD1EN_Msk (0x1UL << ADC_CFGR_JAWD1EN_Pos) /*!< 0x01000000 */ -#define ADC_CFGR_JAWD1EN ADC_CFGR_JAWD1EN_Msk /*!< ADC Analog watchdog 1 enable on injected Channels */ -#define ADC_CFGR_JAUTO_Pos (25U) -#define ADC_CFGR_JAUTO_Msk (0x1UL << ADC_CFGR_JAUTO_Pos) /*!< 0x02000000 */ -#define ADC_CFGR_JAUTO ADC_CFGR_JAUTO_Msk /*!< ADC Automatic injected group conversion */ - -#define ADC_CFGR_AWD1CH_Pos (26U) -#define ADC_CFGR_AWD1CH_Msk (0x1FUL << ADC_CFGR_AWD1CH_Pos) /*!< 0x7C000000 */ -#define ADC_CFGR_AWD1CH ADC_CFGR_AWD1CH_Msk /*!< ADC Analog watchdog 1 Channel selection */ -#define ADC_CFGR_AWD1CH_0 (0x01UL << ADC_CFGR_AWD1CH_Pos) /*!< 0x04000000 */ -#define ADC_CFGR_AWD1CH_1 (0x02UL << ADC_CFGR_AWD1CH_Pos) /*!< 0x08000000 */ -#define ADC_CFGR_AWD1CH_2 (0x04UL << ADC_CFGR_AWD1CH_Pos) /*!< 0x10000000 */ -#define ADC_CFGR_AWD1CH_3 (0x08UL << ADC_CFGR_AWD1CH_Pos) /*!< 0x20000000 */ -#define ADC_CFGR_AWD1CH_4 (0x10UL << ADC_CFGR_AWD1CH_Pos) /*!< 0x40000000 */ - -#define ADC_CFGR_JQDIS_Pos (31U) -#define ADC_CFGR_JQDIS_Msk (0x1UL << ADC_CFGR_JQDIS_Pos) /*!< 0x80000000 */ -#define ADC_CFGR_JQDIS ADC_CFGR_JQDIS_Msk /*!< ADC Injected queue disable */ - -#define ADC3_CFGR_DMAEN_Pos (0U) -#define ADC3_CFGR_DMAEN_Msk (0x1UL << ADC3_CFGR_DMAEN_Pos) /*!< 0x00000001 */ -#define ADC3_CFGR_DMAEN ADC3_CFGR_DMAEN_Msk /*!< ADC DMA transfer enable */ -#define ADC3_CFGR_DMACFG_Pos (1U) -#define ADC3_CFGR_DMACFG_Msk (0x1UL << ADC3_CFGR_DMACFG_Pos) /*!< 0x00000002 */ -#define ADC3_CFGR_DMACFG ADC3_CFGR_DMACFG_Msk /*!< ADC DMA transfer configuration */ - -#define ADC3_CFGR_RES_Pos (3U) -#define ADC3_CFGR_RES_Msk (0x3UL << ADC3_CFGR_RES_Pos) /*!< 0x00000018 */ -#define ADC3_CFGR_RES ADC3_CFGR_RES_Msk /*!< ADC data resolution */ -#define ADC3_CFGR_RES_0 (0x1UL << ADC3_CFGR_RES_Pos) /*!< 0x00000008 */ -#define ADC3_CFGR_RES_1 (0x2UL << ADC3_CFGR_RES_Pos) /*!< 0x00000010 */ - -#define ADC3_CFGR_ALIGN_Pos (15U) -#define ADC3_CFGR_ALIGN_Msk (0x1UL << ADC3_CFGR_ALIGN_Pos) /*!< 0x00008000 */ -#define ADC3_CFGR_ALIGN ADC3_CFGR_ALIGN_Msk /*!< ADC data alignment */ -/******************** Bit definition for ADC_CFGR2 register ********************/ -#define ADC_CFGR2_ROVSE_Pos (0U) -#define ADC_CFGR2_ROVSE_Msk (0x1UL << ADC_CFGR2_ROVSE_Pos) /*!< 0x00000001 */ -#define ADC_CFGR2_ROVSE ADC_CFGR2_ROVSE_Msk /*!< ADC Regular group oversampler enable */ -#define ADC_CFGR2_JOVSE_Pos (1U) -#define ADC_CFGR2_JOVSE_Msk (0x1UL << ADC_CFGR2_JOVSE_Pos) /*!< 0x00000002 */ -#define ADC_CFGR2_JOVSE ADC_CFGR2_JOVSE_Msk /*!< ADC Injected group oversampler enable */ - -#define ADC_CFGR2_OVSS_Pos (5U) -#define ADC_CFGR2_OVSS_Msk (0xFUL << ADC_CFGR2_OVSS_Pos) /*!< 0x000001E0 */ -#define ADC_CFGR2_OVSS ADC_CFGR2_OVSS_Msk /*!< ADC Regular Oversampling shift */ -#define ADC_CFGR2_OVSS_0 (0x1UL << ADC_CFGR2_OVSS_Pos) /*!< 0x00000020 */ -#define ADC_CFGR2_OVSS_1 (0x2UL << ADC_CFGR2_OVSS_Pos) /*!< 0x00000040 */ -#define ADC_CFGR2_OVSS_2 (0x4UL << ADC_CFGR2_OVSS_Pos) /*!< 0x00000080 */ -#define ADC_CFGR2_OVSS_3 (0x8UL << ADC_CFGR2_OVSS_Pos) /*!< 0x00000100 */ - -#define ADC_CFGR2_TROVS_Pos (9U) -#define ADC_CFGR2_TROVS_Msk (0x1UL << ADC_CFGR2_TROVS_Pos) /*!< 0x00000200 */ -#define ADC_CFGR2_TROVS ADC_CFGR2_TROVS_Msk /*!< ADC Triggered regular Oversampling */ -#define ADC_CFGR2_ROVSM_Pos (10U) -#define ADC_CFGR2_ROVSM_Msk (0x1UL << ADC_CFGR2_ROVSM_Pos) /*!< 0x00000400 */ -#define ADC_CFGR2_ROVSM ADC_CFGR2_ROVSM_Msk /*!< ADC Regular oversampling mode */ - -#define ADC_CFGR2_RSHIFT1_Pos (11U) -#define ADC_CFGR2_RSHIFT1_Msk (0x1UL << ADC_CFGR2_RSHIFT1_Pos) /*!< 0x00000800 */ -#define ADC_CFGR2_RSHIFT1 ADC_CFGR2_RSHIFT1_Msk /*!< ADC Right-shift data after Offset 1 correction */ -#define ADC_CFGR2_RSHIFT2_Pos (12U) -#define ADC_CFGR2_RSHIFT2_Msk (0x1UL << ADC_CFGR2_RSHIFT2_Pos) /*!< 0x00001000 */ -#define ADC_CFGR2_RSHIFT2 ADC_CFGR2_RSHIFT2_Msk /*!< ADC Right-shift data after Offset 2 correction */ -#define ADC_CFGR2_RSHIFT3_Pos (13U) -#define ADC_CFGR2_RSHIFT3_Msk (0x1UL << ADC_CFGR2_RSHIFT3_Pos) /*!< 0x00002000 */ -#define ADC_CFGR2_RSHIFT3 ADC_CFGR2_RSHIFT3_Msk /*!< ADC Right-shift data after Offset 3 correction */ -#define ADC_CFGR2_RSHIFT4_Pos (14U) -#define ADC_CFGR2_RSHIFT4_Msk (0x1UL << ADC_CFGR2_RSHIFT4_Pos) /*!< 0x00004000 */ -#define ADC_CFGR2_RSHIFT4 ADC_CFGR2_RSHIFT4_Msk /*!< ADC Right-shift data after Offset 4 correction */ - -#define ADC_CFGR2_OVSR_Pos (16U) -#define ADC_CFGR2_OVSR_Msk (0x3FFUL << ADC_CFGR2_OVSR_Pos) /*!< 0x03FF0000 */ -#define ADC_CFGR2_OVSR ADC_CFGR2_OVSR_Msk /*!< ADC oversampling Ratio */ -#define ADC_CFGR2_OVSR_0 (0x001UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00010000 */ -#define ADC_CFGR2_OVSR_1 (0x002UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00020000 */ -#define ADC_CFGR2_OVSR_2 (0x004UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00040000 */ -#define ADC_CFGR2_OVSR_3 (0x008UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00080000 */ -#define ADC_CFGR2_OVSR_4 (0x010UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00100000 */ -#define ADC_CFGR2_OVSR_5 (0x020UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00200000 */ -#define ADC_CFGR2_OVSR_6 (0x040UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00400000 */ -#define ADC_CFGR2_OVSR_7 (0x080UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00800000 */ -#define ADC_CFGR2_OVSR_8 (0x100UL << ADC_CFGR2_OVSR_Pos) /*!< 0x01000000 */ -#define ADC_CFGR2_OVSR_9 (0x200UL << ADC_CFGR2_OVSR_Pos) /*!< 0x02000000 */ - -#define ADC_CFGR2_LSHIFT_Pos (28U) -#define ADC_CFGR2_LSHIFT_Msk (0xFUL << ADC_CFGR2_LSHIFT_Pos) /*!< 0xF0000000 */ -#define ADC_CFGR2_LSHIFT ADC_CFGR2_LSHIFT_Msk /*!< ADC Left shift factor */ -#define ADC_CFGR2_LSHIFT_0 (0x1UL << ADC_CFGR2_LSHIFT_Pos) /*!< 0x10000000 */ -#define ADC_CFGR2_LSHIFT_1 (0x2UL << ADC_CFGR2_LSHIFT_Pos) /*!< 0x20000000 */ -#define ADC_CFGR2_LSHIFT_2 (0x4UL << ADC_CFGR2_LSHIFT_Pos) /*!< 0x40000000 */ -#define ADC_CFGR2_LSHIFT_3 (0x8UL << ADC_CFGR2_LSHIFT_Pos) /*!< 0x80000000 */ - -#define ADC3_CFGR2_OVSR_Pos (2U) -#define ADC3_CFGR2_OVSR_Msk (0x7UL << ADC3_CFGR2_OVSR_Pos) /*!< 0x0000001C */ -#define ADC3_CFGR2_OVSR ADC3_CFGR2_OVSR_Msk /*!< ADC oversampling ratio */ -#define ADC3_CFGR2_OVSR_0 (0x1UL << ADC3_CFGR2_OVSR_Pos) /*!< 0x00000004 */ -#define ADC3_CFGR2_OVSR_1 (0x2UL << ADC3_CFGR2_OVSR_Pos) /*!< 0x00000008 */ -#define ADC3_CFGR2_OVSR_2 (0x4UL << ADC3_CFGR2_OVSR_Pos) /*!< 0x00000010 */ - -#define ADC3_CFGR2_SWTRIG_Pos (25U) -#define ADC3_CFGR2_SWTRIG_Msk (0x1UL << ADC3_CFGR2_SWTRIG_Pos) /*!< 0x02000000 */ -#define ADC3_CFGR2_SWTRIG ADC3_CFGR2_SWTRIG_Msk /*!< ADC Software Trigger Bit for Sample time control trigger mode */ -#define ADC3_CFGR2_BULB_Pos (26U) -#define ADC3_CFGR2_BULB_Msk (0x1UL << ADC3_CFGR2_BULB_Pos) /*!< 0x04000000 */ -#define ADC3_CFGR2_BULB ADC3_CFGR2_BULB_Msk /*!< ADC Bulb sampling mode */ -#define ADC3_CFGR2_SMPTRIG_Pos (27U) -#define ADC3_CFGR2_SMPTRIG_Msk (0x1UL << ADC3_CFGR2_SMPTRIG_Pos) /*!< 0x08000000 */ -#define ADC3_CFGR2_SMPTRIG ADC3_CFGR2_SMPTRIG_Msk /*!< ADC Sample Time Control Trigger mode */ -/******************** Bit definition for ADC_SMPR1 register ********************/ -#define ADC_SMPR1_SMP0_Pos (0U) -#define ADC_SMPR1_SMP0_Msk (0x7UL << ADC_SMPR1_SMP0_Pos) /*!< 0x00000007 */ -#define ADC_SMPR1_SMP0 ADC_SMPR1_SMP0_Msk /*!< ADC Channel 0 Sampling time selection */ -#define ADC_SMPR1_SMP0_0 (0x1UL << ADC_SMPR1_SMP0_Pos) /*!< 0x00000001 */ -#define ADC_SMPR1_SMP0_1 (0x2UL << ADC_SMPR1_SMP0_Pos) /*!< 0x00000002 */ -#define ADC_SMPR1_SMP0_2 (0x4UL << ADC_SMPR1_SMP0_Pos) /*!< 0x00000004 */ - -#define ADC_SMPR1_SMP1_Pos (3U) -#define ADC_SMPR1_SMP1_Msk (0x7UL << ADC_SMPR1_SMP1_Pos) /*!< 0x00000038 */ -#define ADC_SMPR1_SMP1 ADC_SMPR1_SMP1_Msk /*!< ADC Channel 1 Sampling time selection */ -#define ADC_SMPR1_SMP1_0 (0x1UL << ADC_SMPR1_SMP1_Pos) /*!< 0x00000008 */ -#define ADC_SMPR1_SMP1_1 (0x2UL << ADC_SMPR1_SMP1_Pos) /*!< 0x00000010 */ -#define ADC_SMPR1_SMP1_2 (0x4UL << ADC_SMPR1_SMP1_Pos) /*!< 0x00000020 */ - -#define ADC_SMPR1_SMP2_Pos (6U) -#define ADC_SMPR1_SMP2_Msk (0x7UL << ADC_SMPR1_SMP2_Pos) /*!< 0x000001C0 */ -#define ADC_SMPR1_SMP2 ADC_SMPR1_SMP2_Msk /*!< ADC Channel 2 Sampling time selection */ -#define ADC_SMPR1_SMP2_0 (0x1UL << ADC_SMPR1_SMP2_Pos) /*!< 0x00000040 */ -#define ADC_SMPR1_SMP2_1 (0x2UL << ADC_SMPR1_SMP2_Pos) /*!< 0x00000080 */ -#define ADC_SMPR1_SMP2_2 (0x4UL << ADC_SMPR1_SMP2_Pos) /*!< 0x00000100 */ - -#define ADC_SMPR1_SMP3_Pos (9U) -#define ADC_SMPR1_SMP3_Msk (0x7UL << ADC_SMPR1_SMP3_Pos) /*!< 0x00000E00 */ -#define ADC_SMPR1_SMP3 ADC_SMPR1_SMP3_Msk /*!< ADC Channel 3 Sampling time selection */ -#define ADC_SMPR1_SMP3_0 (0x1UL << ADC_SMPR1_SMP3_Pos) /*!< 0x00000200 */ -#define ADC_SMPR1_SMP3_1 (0x2UL << ADC_SMPR1_SMP3_Pos) /*!< 0x00000400 */ -#define ADC_SMPR1_SMP3_2 (0x4UL << ADC_SMPR1_SMP3_Pos) /*!< 0x00000800 */ - -#define ADC_SMPR1_SMP4_Pos (12U) -#define ADC_SMPR1_SMP4_Msk (0x7UL << ADC_SMPR1_SMP4_Pos) /*!< 0x00007000 */ -#define ADC_SMPR1_SMP4 ADC_SMPR1_SMP4_Msk /*!< ADC Channel 4 Sampling time selection */ -#define ADC_SMPR1_SMP4_0 (0x1UL << ADC_SMPR1_SMP4_Pos) /*!< 0x00001000 */ -#define ADC_SMPR1_SMP4_1 (0x2UL << ADC_SMPR1_SMP4_Pos) /*!< 0x00002000 */ -#define ADC_SMPR1_SMP4_2 (0x4UL << ADC_SMPR1_SMP4_Pos) /*!< 0x00004000 */ - -#define ADC_SMPR1_SMP5_Pos (15U) -#define ADC_SMPR1_SMP5_Msk (0x7UL << ADC_SMPR1_SMP5_Pos) /*!< 0x00038000 */ -#define ADC_SMPR1_SMP5 ADC_SMPR1_SMP5_Msk /*!< ADC Channel 5 Sampling time selection */ -#define ADC_SMPR1_SMP5_0 (0x1UL << ADC_SMPR1_SMP5_Pos) /*!< 0x00008000 */ -#define ADC_SMPR1_SMP5_1 (0x2UL << ADC_SMPR1_SMP5_Pos) /*!< 0x00010000 */ -#define ADC_SMPR1_SMP5_2 (0x4UL << ADC_SMPR1_SMP5_Pos) /*!< 0x00020000 */ - -#define ADC_SMPR1_SMP6_Pos (18U) -#define ADC_SMPR1_SMP6_Msk (0x7UL << ADC_SMPR1_SMP6_Pos) /*!< 0x001C0000 */ -#define ADC_SMPR1_SMP6 ADC_SMPR1_SMP6_Msk /*!< ADC Channel 6 Sampling time selection */ -#define ADC_SMPR1_SMP6_0 (0x1UL << ADC_SMPR1_SMP6_Pos) /*!< 0x00040000 */ -#define ADC_SMPR1_SMP6_1 (0x2UL << ADC_SMPR1_SMP6_Pos) /*!< 0x00080000 */ -#define ADC_SMPR1_SMP6_2 (0x4UL << ADC_SMPR1_SMP6_Pos) /*!< 0x00100000 */ - -#define ADC_SMPR1_SMP7_Pos (21U) -#define ADC_SMPR1_SMP7_Msk (0x7UL << ADC_SMPR1_SMP7_Pos) /*!< 0x00E00000 */ -#define ADC_SMPR1_SMP7 ADC_SMPR1_SMP7_Msk /*!< ADC Channel 7 Sampling time selection */ -#define ADC_SMPR1_SMP7_0 (0x1UL << ADC_SMPR1_SMP7_Pos) /*!< 0x00200000 */ -#define ADC_SMPR1_SMP7_1 (0x2UL << ADC_SMPR1_SMP7_Pos) /*!< 0x00400000 */ -#define ADC_SMPR1_SMP7_2 (0x4UL << ADC_SMPR1_SMP7_Pos) /*!< 0x00800000 */ - -#define ADC_SMPR1_SMP8_Pos (24U) -#define ADC_SMPR1_SMP8_Msk (0x7UL << ADC_SMPR1_SMP8_Pos) /*!< 0x07000000 */ -#define ADC_SMPR1_SMP8 ADC_SMPR1_SMP8_Msk /*!< ADC Channel 8 Sampling time selection */ -#define ADC_SMPR1_SMP8_0 (0x1UL << ADC_SMPR1_SMP8_Pos) /*!< 0x01000000 */ -#define ADC_SMPR1_SMP8_1 (0x2UL << ADC_SMPR1_SMP8_Pos) /*!< 0x02000000 */ -#define ADC_SMPR1_SMP8_2 (0x4UL << ADC_SMPR1_SMP8_Pos) /*!< 0x04000000 */ - -#define ADC_SMPR1_SMP9_Pos (27U) -#define ADC_SMPR1_SMP9_Msk (0x7UL << ADC_SMPR1_SMP9_Pos) /*!< 0x38000000 */ -#define ADC_SMPR1_SMP9 ADC_SMPR1_SMP9_Msk /*!< ADC Channel 9 Sampling time selection */ -#define ADC_SMPR1_SMP9_0 (0x1UL << ADC_SMPR1_SMP9_Pos) /*!< 0x08000000 */ -#define ADC_SMPR1_SMP9_1 (0x2UL << ADC_SMPR1_SMP9_Pos) /*!< 0x10000000 */ -#define ADC_SMPR1_SMP9_2 (0x4UL << ADC_SMPR1_SMP9_Pos) /*!< 0x20000000 */ - -/******************** Bit definition for ADC_SMPR2 register ********************/ -#define ADC_SMPR2_SMP10_Pos (0U) -#define ADC_SMPR2_SMP10_Msk (0x7UL << ADC_SMPR2_SMP10_Pos) /*!< 0x00000007 */ -#define ADC_SMPR2_SMP10 ADC_SMPR2_SMP10_Msk /*!< ADC Channel 10 Sampling time selection */ -#define ADC_SMPR2_SMP10_0 (0x1UL << ADC_SMPR2_SMP10_Pos) /*!< 0x00000001 */ -#define ADC_SMPR2_SMP10_1 (0x2UL << ADC_SMPR2_SMP10_Pos) /*!< 0x00000002 */ -#define ADC_SMPR2_SMP10_2 (0x4UL << ADC_SMPR2_SMP10_Pos) /*!< 0x00000004 */ - -#define ADC_SMPR2_SMP11_Pos (3U) -#define ADC_SMPR2_SMP11_Msk (0x7UL << ADC_SMPR2_SMP11_Pos) /*!< 0x00000038 */ -#define ADC_SMPR2_SMP11 ADC_SMPR2_SMP11_Msk /*!< ADC Channel 11 Sampling time selection */ -#define ADC_SMPR2_SMP11_0 (0x1UL << ADC_SMPR2_SMP11_Pos) /*!< 0x00000008 */ -#define ADC_SMPR2_SMP11_1 (0x2UL << ADC_SMPR2_SMP11_Pos) /*!< 0x00000010 */ -#define ADC_SMPR2_SMP11_2 (0x4UL << ADC_SMPR2_SMP11_Pos) /*!< 0x00000020 */ - -#define ADC_SMPR2_SMP12_Pos (6U) -#define ADC_SMPR2_SMP12_Msk (0x7UL << ADC_SMPR2_SMP12_Pos) /*!< 0x000001C0 */ -#define ADC_SMPR2_SMP12 ADC_SMPR2_SMP12_Msk /*!< ADC Channel 12 Sampling time selection */ -#define ADC_SMPR2_SMP12_0 (0x1UL << ADC_SMPR2_SMP12_Pos) /*!< 0x00000040 */ -#define ADC_SMPR2_SMP12_1 (0x2UL << ADC_SMPR2_SMP12_Pos) /*!< 0x00000080 */ -#define ADC_SMPR2_SMP12_2 (0x4UL << ADC_SMPR2_SMP12_Pos) /*!< 0x00000100 */ - -#define ADC_SMPR2_SMP13_Pos (9U) -#define ADC_SMPR2_SMP13_Msk (0x7UL << ADC_SMPR2_SMP13_Pos) /*!< 0x00000E00 */ -#define ADC_SMPR2_SMP13 ADC_SMPR2_SMP13_Msk /*!< ADC Channel 13 Sampling time selection */ -#define ADC_SMPR2_SMP13_0 (0x1UL << ADC_SMPR2_SMP13_Pos) /*!< 0x00000200 */ -#define ADC_SMPR2_SMP13_1 (0x2UL << ADC_SMPR2_SMP13_Pos) /*!< 0x00000400 */ -#define ADC_SMPR2_SMP13_2 (0x4UL << ADC_SMPR2_SMP13_Pos) /*!< 0x00000800 */ - -#define ADC_SMPR2_SMP14_Pos (12U) -#define ADC_SMPR2_SMP14_Msk (0x7UL << ADC_SMPR2_SMP14_Pos) /*!< 0x00007000 */ -#define ADC_SMPR2_SMP14 ADC_SMPR2_SMP14_Msk /*!< ADC Channel 14 Sampling time selection */ -#define ADC_SMPR2_SMP14_0 (0x1UL << ADC_SMPR2_SMP14_Pos) /*!< 0x00001000 */ -#define ADC_SMPR2_SMP14_1 (0x2UL << ADC_SMPR2_SMP14_Pos) /*!< 0x00002000 */ -#define ADC_SMPR2_SMP14_2 (0x4UL << ADC_SMPR2_SMP14_Pos) /*!< 0x00004000 */ - -#define ADC_SMPR2_SMP15_Pos (15U) -#define ADC_SMPR2_SMP15_Msk (0x7UL << ADC_SMPR2_SMP15_Pos) /*!< 0x00038000 */ -#define ADC_SMPR2_SMP15 ADC_SMPR2_SMP15_Msk /*!< ADC Channel 15 Sampling time selection */ -#define ADC_SMPR2_SMP15_0 (0x1UL << ADC_SMPR2_SMP15_Pos) /*!< 0x00008000 */ -#define ADC_SMPR2_SMP15_1 (0x2UL << ADC_SMPR2_SMP15_Pos) /*!< 0x00010000 */ -#define ADC_SMPR2_SMP15_2 (0x4UL << ADC_SMPR2_SMP15_Pos) /*!< 0x00020000 */ - -#define ADC_SMPR2_SMP16_Pos (18U) -#define ADC_SMPR2_SMP16_Msk (0x7UL << ADC_SMPR2_SMP16_Pos) /*!< 0x001C0000 */ -#define ADC_SMPR2_SMP16 ADC_SMPR2_SMP16_Msk /*!< ADC Channel 16 Sampling time selection */ -#define ADC_SMPR2_SMP16_0 (0x1UL << ADC_SMPR2_SMP16_Pos) /*!< 0x00040000 */ -#define ADC_SMPR2_SMP16_1 (0x2UL << ADC_SMPR2_SMP16_Pos) /*!< 0x00080000 */ -#define ADC_SMPR2_SMP16_2 (0x4UL << ADC_SMPR2_SMP16_Pos) /*!< 0x00100000 */ - -#define ADC_SMPR2_SMP17_Pos (21U) -#define ADC_SMPR2_SMP17_Msk (0x7UL << ADC_SMPR2_SMP17_Pos) /*!< 0x00E00000 */ -#define ADC_SMPR2_SMP17 ADC_SMPR2_SMP17_Msk /*!< ADC Channel 17 Sampling time selection */ -#define ADC_SMPR2_SMP17_0 (0x1UL << ADC_SMPR2_SMP17_Pos) /*!< 0x00200000 */ -#define ADC_SMPR2_SMP17_1 (0x2UL << ADC_SMPR2_SMP17_Pos) /*!< 0x00400000 */ -#define ADC_SMPR2_SMP17_2 (0x4UL << ADC_SMPR2_SMP17_Pos) /*!< 0x00800000 */ - -#define ADC_SMPR2_SMP18_Pos (24U) -#define ADC_SMPR2_SMP18_Msk (0x7UL << ADC_SMPR2_SMP18_Pos) /*!< 0x07000000 */ -#define ADC_SMPR2_SMP18 ADC_SMPR2_SMP18_Msk /*!< ADC Channel 18 Sampling time selection */ -#define ADC_SMPR2_SMP18_0 (0x1UL << ADC_SMPR2_SMP18_Pos) /*!< 0x01000000 */ -#define ADC_SMPR2_SMP18_1 (0x2UL << ADC_SMPR2_SMP18_Pos) /*!< 0x02000000 */ -#define ADC_SMPR2_SMP18_2 (0x4UL << ADC_SMPR2_SMP18_Pos) /*!< 0x04000000 */ - -#define ADC_SMPR2_SMP19_Pos (27U) -#define ADC_SMPR2_SMP19_Msk (0x7UL << ADC_SMPR2_SMP19_Pos) /*!< 0x38000000 */ -#define ADC_SMPR2_SMP19 ADC_SMPR2_SMP19_Msk /*!< ADC Channel 19 Sampling time selection */ -#define ADC_SMPR2_SMP19_0 (0x1UL << ADC_SMPR2_SMP19_Pos) /*!< 0x08000000 */ -#define ADC_SMPR2_SMP19_1 (0x2UL << ADC_SMPR2_SMP19_Pos) /*!< 0x10000000 */ -#define ADC_SMPR2_SMP19_2 (0x4UL << ADC_SMPR2_SMP19_Pos) /*!< 0x20000000 */ - -/******************** Bit definition for ADC_PCSEL register ********************/ -#define ADC_PCSEL_PCSEL_Pos (0U) -#define ADC_PCSEL_PCSEL_Msk (0xFFFFFUL << ADC_PCSEL_PCSEL_Pos) /*!< 0x000FFFFF */ -#define ADC_PCSEL_PCSEL ADC_PCSEL_PCSEL_Msk /*!< ADC pre channel selection */ -#define ADC_PCSEL_PCSEL_0 (0x00001UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000001 */ -#define ADC_PCSEL_PCSEL_1 (0x00002UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000002 */ -#define ADC_PCSEL_PCSEL_2 (0x00004UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000004 */ -#define ADC_PCSEL_PCSEL_3 (0x00008UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000008 */ -#define ADC_PCSEL_PCSEL_4 (0x00010UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000010 */ -#define ADC_PCSEL_PCSEL_5 (0x00020UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000020 */ -#define ADC_PCSEL_PCSEL_6 (0x00040UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000040 */ -#define ADC_PCSEL_PCSEL_7 (0x00080UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000080 */ -#define ADC_PCSEL_PCSEL_8 (0x00100UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000100 */ -#define ADC_PCSEL_PCSEL_9 (0x00200UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000200 */ -#define ADC_PCSEL_PCSEL_10 (0x00400UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000400 */ -#define ADC_PCSEL_PCSEL_11 (0x00800UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000800 */ -#define ADC_PCSEL_PCSEL_12 (0x01000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00001000 */ -#define ADC_PCSEL_PCSEL_13 (0x02000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00002000 */ -#define ADC_PCSEL_PCSEL_14 (0x04000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00004000 */ -#define ADC_PCSEL_PCSEL_15 (0x08000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00008000 */ -#define ADC_PCSEL_PCSEL_16 (0x10000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00010000 */ -#define ADC_PCSEL_PCSEL_17 (0x20000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00020000 */ -#define ADC_PCSEL_PCSEL_18 (0x40000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00040000 */ -#define ADC_PCSEL_PCSEL_19 (0x80000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00080000 */ - -/***************** Bit definition for ADC_LTR1, 2, 3 registers *****************/ -#define ADC_LTR_LT_Pos (0U) -#define ADC_LTR_LT_Msk (0x3FFFFFFUL << ADC_LTR_LT_Pos) /*!< 0x03FFFFFF */ -#define ADC_LTR_LT ADC_LTR_LT_Msk /*!< ADC Analog watchdog 1, 2 and 3 lower threshold */ - -/***************** Bit definition for ADC_HTR1, 2, 3 registers ****************/ -#define ADC_HTR_HT_Pos (0U) -#define ADC_HTR_HT_Msk (0x3FFFFFFUL << ADC_HTR_HT_Pos) /*!< 0x03FFFFFF */ -#define ADC_HTR_HT ADC_HTR_HT_Msk /*!< ADC Analog watchdog 1,2 and 3 higher threshold */ - -/******************** Bit definition for ADC3_TR1 register *******************/ -#define ADC3_TR1_LT1_Pos (0U) -#define ADC3_TR1_LT1_Msk (0xFFFUL << ADC3_TR1_LT1_Pos) /*!< 0x00000FFF */ -#define ADC3_TR1_LT1 ADC3_TR1_LT1_Msk /*!< ADC analog watchdog 1 threshold low */ - -#define ADC3_TR1_AWDFILT_Pos (12U) -#define ADC3_TR1_AWDFILT_Msk (0x7UL << ADC3_TR1_AWDFILT_Pos) /*!< 0x00007000 */ -#define ADC3_TR1_AWDFILT ADC3_TR1_AWDFILT_Msk /*!< ADC analog watchdog filtering parameter */ -#define ADC3_TR1_AWDFILT_0 (0x1UL << ADC3_TR1_AWDFILT_Pos) /*!< 0x00001000 */ -#define ADC3_TR1_AWDFILT_1 (0x2UL << ADC3_TR1_AWDFILT_Pos) /*!< 0x00002000 */ -#define ADC3_TR1_AWDFILT_2 (0x4UL << ADC3_TR1_AWDFILT_Pos) /*!< 0x00004000 */ - -#define ADC3_TR1_HT1_Pos (16U) -#define ADC3_TR1_HT1_Msk (0xFFFUL << ADC3_TR1_HT1_Pos) /*!< 0x0FFF0000 */ -#define ADC3_TR1_HT1 ADC3_TR1_HT1_Msk /*!< ADC analog watchdog 1 threshold high */ - -/******************** Bit definition for ADC3_TR2 register *******************/ -#define ADC3_TR2_LT2_Pos (0U) -#define ADC3_TR2_LT2_Msk (0xFFUL << ADC3_TR2_LT2_Pos) /*!< 0x000000FF */ -#define ADC3_TR2_LT2 ADC3_TR2_LT2_Msk /*!< ADC analog watchdog 2 threshold low */ - -#define ADC3_TR2_HT2_Pos (16U) -#define ADC3_TR2_HT2_Msk (0xFFUL << ADC3_TR2_HT2_Pos) /*!< 0x00FF0000 */ -#define ADC3_TR2_HT2 ADC3_TR2_HT2_Msk /*!< ADC analog watchdog 2 threshold high */ - -/******************** Bit definition for ADC3_TR3 register *******************/ -#define ADC3_TR3_LT3_Pos (0U) -#define ADC3_TR3_LT3_Msk (0xFFUL << ADC3_TR3_LT3_Pos) /*!< 0x000000FF */ -#define ADC3_TR3_LT3 ADC3_TR3_LT3_Msk /*!< ADC analog watchdog 3 threshold low */ - -#define ADC3_TR3_HT3_Pos (16U) -#define ADC3_TR3_HT3_Msk (0xFFUL << ADC3_TR3_HT3_Pos) /*!< 0x00FF0000 */ -#define ADC3_TR3_HT3 ADC3_TR3_HT3_Msk /*!< ADC analog watchdog 3 threshold high */ - -/******************** Bit definition for ADC_SQR1 register ********************/ -#define ADC_SQR1_L_Pos (0U) -#define ADC_SQR1_L_Msk (0xFUL << ADC_SQR1_L_Pos) /*!< 0x0000000F */ -#define ADC_SQR1_L ADC_SQR1_L_Msk /*!< ADC regular channel sequence length */ -#define ADC_SQR1_L_0 (0x1UL << ADC_SQR1_L_Pos) /*!< 0x00000001 */ -#define ADC_SQR1_L_1 (0x2UL << ADC_SQR1_L_Pos) /*!< 0x00000002 */ -#define ADC_SQR1_L_2 (0x4UL << ADC_SQR1_L_Pos) /*!< 0x00000004 */ -#define ADC_SQR1_L_3 (0x8UL << ADC_SQR1_L_Pos) /*!< 0x00000008 */ - -#define ADC_SQR1_SQ1_Pos (6U) -#define ADC_SQR1_SQ1_Msk (0x1FUL << ADC_SQR1_SQ1_Pos) /*!< 0x000007C0 */ -#define ADC_SQR1_SQ1 ADC_SQR1_SQ1_Msk /*!< ADC 1st conversion in regular sequence */ -#define ADC_SQR1_SQ1_0 (0x01UL << ADC_SQR1_SQ1_Pos) /*!< 0x00000040 */ -#define ADC_SQR1_SQ1_1 (0x02UL << ADC_SQR1_SQ1_Pos) /*!< 0x00000080 */ -#define ADC_SQR1_SQ1_2 (0x04UL << ADC_SQR1_SQ1_Pos) /*!< 0x00000100 */ -#define ADC_SQR1_SQ1_3 (0x08UL << ADC_SQR1_SQ1_Pos) /*!< 0x00000200 */ -#define ADC_SQR1_SQ1_4 (0x10UL << ADC_SQR1_SQ1_Pos) /*!< 0x00000400 */ - -#define ADC_SQR1_SQ2_Pos (12U) -#define ADC_SQR1_SQ2_Msk (0x1FUL << ADC_SQR1_SQ2_Pos) /*!< 0x0001F000 */ -#define ADC_SQR1_SQ2 ADC_SQR1_SQ2_Msk /*!< ADC 2nd conversion in regular sequence */ -#define ADC_SQR1_SQ2_0 (0x01UL << ADC_SQR1_SQ2_Pos) /*!< 0x00001000 */ -#define ADC_SQR1_SQ2_1 (0x02UL << ADC_SQR1_SQ2_Pos) /*!< 0x00002000 */ -#define ADC_SQR1_SQ2_2 (0x04UL << ADC_SQR1_SQ2_Pos) /*!< 0x00004000 */ -#define ADC_SQR1_SQ2_3 (0x08UL << ADC_SQR1_SQ2_Pos) /*!< 0x00008000 */ -#define ADC_SQR1_SQ2_4 (0x10UL << ADC_SQR1_SQ2_Pos) /*!< 0x00010000 */ - -#define ADC_SQR1_SQ3_Pos (18U) -#define ADC_SQR1_SQ3_Msk (0x1FUL << ADC_SQR1_SQ3_Pos) /*!< 0x007C0000 */ -#define ADC_SQR1_SQ3 ADC_SQR1_SQ3_Msk /*!< ADC 3rd conversion in regular sequence */ -#define ADC_SQR1_SQ3_0 (0x01UL << ADC_SQR1_SQ3_Pos) /*!< 0x00040000 */ -#define ADC_SQR1_SQ3_1 (0x02UL << ADC_SQR1_SQ3_Pos) /*!< 0x00080000 */ -#define ADC_SQR1_SQ3_2 (0x04UL << ADC_SQR1_SQ3_Pos) /*!< 0x00100000 */ -#define ADC_SQR1_SQ3_3 (0x08UL << ADC_SQR1_SQ3_Pos) /*!< 0x00200000 */ -#define ADC_SQR1_SQ3_4 (0x10UL << ADC_SQR1_SQ3_Pos) /*!< 0x00400000 */ - -#define ADC_SQR1_SQ4_Pos (24U) -#define ADC_SQR1_SQ4_Msk (0x1FUL << ADC_SQR1_SQ4_Pos) /*!< 0x1F000000 */ -#define ADC_SQR1_SQ4 ADC_SQR1_SQ4_Msk /*!< ADC 4th conversion in regular sequence */ -#define ADC_SQR1_SQ4_0 (0x01UL << ADC_SQR1_SQ4_Pos) /*!< 0x01000000 */ -#define ADC_SQR1_SQ4_1 (0x02UL << ADC_SQR1_SQ4_Pos) /*!< 0x02000000 */ -#define ADC_SQR1_SQ4_2 (0x04UL << ADC_SQR1_SQ4_Pos) /*!< 0x04000000 */ -#define ADC_SQR1_SQ4_3 (0x08UL << ADC_SQR1_SQ4_Pos) /*!< 0x08000000 */ -#define ADC_SQR1_SQ4_4 (0x10UL << ADC_SQR1_SQ4_Pos) /*!< 0x10000000 */ - -/******************** Bit definition for ADC_SQR2 register ********************/ -#define ADC_SQR2_SQ5_Pos (0U) -#define ADC_SQR2_SQ5_Msk (0x1FUL << ADC_SQR2_SQ5_Pos) /*!< 0x0000001F */ -#define ADC_SQR2_SQ5 ADC_SQR2_SQ5_Msk /*!< ADC 5th conversion in regular sequence */ -#define ADC_SQR2_SQ5_0 (0x01UL << ADC_SQR2_SQ5_Pos) /*!< 0x00000001 */ -#define ADC_SQR2_SQ5_1 (0x02UL << ADC_SQR2_SQ5_Pos) /*!< 0x00000002 */ -#define ADC_SQR2_SQ5_2 (0x04UL << ADC_SQR2_SQ5_Pos) /*!< 0x00000004 */ -#define ADC_SQR2_SQ5_3 (0x08UL << ADC_SQR2_SQ5_Pos) /*!< 0x00000008 */ -#define ADC_SQR2_SQ5_4 (0x10UL << ADC_SQR2_SQ5_Pos) /*!< 0x00000010 */ - -#define ADC_SQR2_SQ6_Pos (6U) -#define ADC_SQR2_SQ6_Msk (0x1FUL << ADC_SQR2_SQ6_Pos) /*!< 0x000007C0 */ -#define ADC_SQR2_SQ6 ADC_SQR2_SQ6_Msk /*!< ADC 6th conversion in regular sequence */ -#define ADC_SQR2_SQ6_0 (0x01UL << ADC_SQR2_SQ6_Pos) /*!< 0x00000040 */ -#define ADC_SQR2_SQ6_1 (0x02UL << ADC_SQR2_SQ6_Pos) /*!< 0x00000080 */ -#define ADC_SQR2_SQ6_2 (0x04UL << ADC_SQR2_SQ6_Pos) /*!< 0x00000100 */ -#define ADC_SQR2_SQ6_3 (0x08UL << ADC_SQR2_SQ6_Pos) /*!< 0x00000200 */ -#define ADC_SQR2_SQ6_4 (0x10UL << ADC_SQR2_SQ6_Pos) /*!< 0x00000400 */ - -#define ADC_SQR2_SQ7_Pos (12U) -#define ADC_SQR2_SQ7_Msk (0x1FUL << ADC_SQR2_SQ7_Pos) /*!< 0x0001F000 */ -#define ADC_SQR2_SQ7 ADC_SQR2_SQ7_Msk /*!< ADC 7th conversion in regular sequence */ -#define ADC_SQR2_SQ7_0 (0x01UL << ADC_SQR2_SQ7_Pos) /*!< 0x00001000 */ -#define ADC_SQR2_SQ7_1 (0x02UL << ADC_SQR2_SQ7_Pos) /*!< 0x00002000 */ -#define ADC_SQR2_SQ7_2 (0x04UL << ADC_SQR2_SQ7_Pos) /*!< 0x00004000 */ -#define ADC_SQR2_SQ7_3 (0x08UL << ADC_SQR2_SQ7_Pos) /*!< 0x00008000 */ -#define ADC_SQR2_SQ7_4 (0x10UL << ADC_SQR2_SQ7_Pos) /*!< 0x00010000 */ - -#define ADC_SQR2_SQ8_Pos (18U) -#define ADC_SQR2_SQ8_Msk (0x1FUL << ADC_SQR2_SQ8_Pos) /*!< 0x007C0000 */ -#define ADC_SQR2_SQ8 ADC_SQR2_SQ8_Msk /*!< ADC 8th conversion in regular sequence */ -#define ADC_SQR2_SQ8_0 (0x01UL << ADC_SQR2_SQ8_Pos) /*!< 0x00040000 */ -#define ADC_SQR2_SQ8_1 (0x02UL << ADC_SQR2_SQ8_Pos) /*!< 0x00080000 */ -#define ADC_SQR2_SQ8_2 (0x04UL << ADC_SQR2_SQ8_Pos) /*!< 0x00100000 */ -#define ADC_SQR2_SQ8_3 (0x08UL << ADC_SQR2_SQ8_Pos) /*!< 0x00200000 */ -#define ADC_SQR2_SQ8_4 (0x10UL << ADC_SQR2_SQ8_Pos) /*!< 0x00400000 */ - -#define ADC_SQR2_SQ9_Pos (24U) -#define ADC_SQR2_SQ9_Msk (0x1FUL << ADC_SQR2_SQ9_Pos) /*!< 0x1F000000 */ -#define ADC_SQR2_SQ9 ADC_SQR2_SQ9_Msk /*!< ADC 9th conversion in regular sequence */ -#define ADC_SQR2_SQ9_0 (0x01UL << ADC_SQR2_SQ9_Pos) /*!< 0x01000000 */ -#define ADC_SQR2_SQ9_1 (0x02UL << ADC_SQR2_SQ9_Pos) /*!< 0x02000000 */ -#define ADC_SQR2_SQ9_2 (0x04UL << ADC_SQR2_SQ9_Pos) /*!< 0x04000000 */ -#define ADC_SQR2_SQ9_3 (0x08UL << ADC_SQR2_SQ9_Pos) /*!< 0x08000000 */ -#define ADC_SQR2_SQ9_4 (0x10UL << ADC_SQR2_SQ9_Pos) /*!< 0x10000000 */ - -/******************** Bit definition for ADC_SQR3 register ********************/ -#define ADC_SQR3_SQ10_Pos (0U) -#define ADC_SQR3_SQ10_Msk (0x1FUL << ADC_SQR3_SQ10_Pos) /*!< 0x0000001F */ -#define ADC_SQR3_SQ10 ADC_SQR3_SQ10_Msk /*!< ADC 10th conversion in regular sequence */ -#define ADC_SQR3_SQ10_0 (0x01UL << ADC_SQR3_SQ10_Pos) /*!< 0x00000001 */ -#define ADC_SQR3_SQ10_1 (0x02UL << ADC_SQR3_SQ10_Pos) /*!< 0x00000002 */ -#define ADC_SQR3_SQ10_2 (0x04UL << ADC_SQR3_SQ10_Pos) /*!< 0x00000004 */ -#define ADC_SQR3_SQ10_3 (0x08UL << ADC_SQR3_SQ10_Pos) /*!< 0x00000008 */ -#define ADC_SQR3_SQ10_4 (0x10UL << ADC_SQR3_SQ10_Pos) /*!< 0x00000010 */ - -#define ADC_SQR3_SQ11_Pos (6U) -#define ADC_SQR3_SQ11_Msk (0x1FUL << ADC_SQR3_SQ11_Pos) /*!< 0x000007C0 */ -#define ADC_SQR3_SQ11 ADC_SQR3_SQ11_Msk /*!< ADC 11th conversion in regular sequence */ -#define ADC_SQR3_SQ11_0 (0x01UL << ADC_SQR3_SQ11_Pos) /*!< 0x00000040 */ -#define ADC_SQR3_SQ11_1 (0x02UL << ADC_SQR3_SQ11_Pos) /*!< 0x00000080 */ -#define ADC_SQR3_SQ11_2 (0x04UL << ADC_SQR3_SQ11_Pos) /*!< 0x00000100 */ -#define ADC_SQR3_SQ11_3 (0x08UL << ADC_SQR3_SQ11_Pos) /*!< 0x00000200 */ -#define ADC_SQR3_SQ11_4 (0x10UL << ADC_SQR3_SQ11_Pos) /*!< 0x00000400 */ - -#define ADC_SQR3_SQ12_Pos (12U) -#define ADC_SQR3_SQ12_Msk (0x1FUL << ADC_SQR3_SQ12_Pos) /*!< 0x0001F000 */ -#define ADC_SQR3_SQ12 ADC_SQR3_SQ12_Msk /*!< ADC 12th conversion in regular sequence */ -#define ADC_SQR3_SQ12_0 (0x01UL << ADC_SQR3_SQ12_Pos) /*!< 0x00001000 */ -#define ADC_SQR3_SQ12_1 (0x02UL << ADC_SQR3_SQ12_Pos) /*!< 0x00002000 */ -#define ADC_SQR3_SQ12_2 (0x04UL << ADC_SQR3_SQ12_Pos) /*!< 0x00004000 */ -#define ADC_SQR3_SQ12_3 (0x08UL << ADC_SQR3_SQ12_Pos) /*!< 0x00008000 */ -#define ADC_SQR3_SQ12_4 (0x10UL << ADC_SQR3_SQ12_Pos) /*!< 0x00010000 */ - -#define ADC_SQR3_SQ13_Pos (18U) -#define ADC_SQR3_SQ13_Msk (0x1FUL << ADC_SQR3_SQ13_Pos) /*!< 0x007C0000 */ -#define ADC_SQR3_SQ13 ADC_SQR3_SQ13_Msk /*!< ADC 13th conversion in regular sequence */ -#define ADC_SQR3_SQ13_0 (0x01UL << ADC_SQR3_SQ13_Pos) /*!< 0x00040000 */ -#define ADC_SQR3_SQ13_1 (0x02UL << ADC_SQR3_SQ13_Pos) /*!< 0x00080000 */ -#define ADC_SQR3_SQ13_2 (0x04UL << ADC_SQR3_SQ13_Pos) /*!< 0x00100000 */ -#define ADC_SQR3_SQ13_3 (0x08UL << ADC_SQR3_SQ13_Pos) /*!< 0x00200000 */ -#define ADC_SQR3_SQ13_4 (0x10UL << ADC_SQR3_SQ13_Pos) /*!< 0x00400000 */ - -#define ADC_SQR3_SQ14_Pos (24U) -#define ADC_SQR3_SQ14_Msk (0x1FUL << ADC_SQR3_SQ14_Pos) /*!< 0x1F000000 */ -#define ADC_SQR3_SQ14 ADC_SQR3_SQ14_Msk /*!< ADC 14th conversion in regular sequence */ -#define ADC_SQR3_SQ14_0 (0x01UL << ADC_SQR3_SQ14_Pos) /*!< 0x01000000 */ -#define ADC_SQR3_SQ14_1 (0x02UL << ADC_SQR3_SQ14_Pos) /*!< 0x02000000 */ -#define ADC_SQR3_SQ14_2 (0x04UL << ADC_SQR3_SQ14_Pos) /*!< 0x04000000 */ -#define ADC_SQR3_SQ14_3 (0x08UL << ADC_SQR3_SQ14_Pos) /*!< 0x08000000 */ -#define ADC_SQR3_SQ14_4 (0x10UL << ADC_SQR3_SQ14_Pos) /*!< 0x10000000 */ - -/******************** Bit definition for ADC_SQR4 register ********************/ -#define ADC_SQR4_SQ15_Pos (0U) -#define ADC_SQR4_SQ15_Msk (0x1FUL << ADC_SQR4_SQ15_Pos) /*!< 0x0000001F */ -#define ADC_SQR4_SQ15 ADC_SQR4_SQ15_Msk /*!< ADC 15th conversion in regular sequence */ -#define ADC_SQR4_SQ15_0 (0x01UL << ADC_SQR4_SQ15_Pos) /*!< 0x00000001 */ -#define ADC_SQR4_SQ15_1 (0x02UL << ADC_SQR4_SQ15_Pos) /*!< 0x00000002 */ -#define ADC_SQR4_SQ15_2 (0x04UL << ADC_SQR4_SQ15_Pos) /*!< 0x00000004 */ -#define ADC_SQR4_SQ15_3 (0x08UL << ADC_SQR4_SQ15_Pos) /*!< 0x00000008 */ -#define ADC_SQR4_SQ15_4 (0x10UL << ADC_SQR4_SQ15_Pos) /*!< 0x00000010 */ - -#define ADC_SQR4_SQ16_Pos (6U) -#define ADC_SQR4_SQ16_Msk (0x1FUL << ADC_SQR4_SQ16_Pos) /*!< 0x000007C0 */ -#define ADC_SQR4_SQ16 ADC_SQR4_SQ16_Msk /*!< ADC 16th conversion in regular sequence */ -#define ADC_SQR4_SQ16_0 (0x01UL << ADC_SQR4_SQ16_Pos) /*!< 0x00000040 */ -#define ADC_SQR4_SQ16_1 (0x02UL << ADC_SQR4_SQ16_Pos) /*!< 0x00000080 */ -#define ADC_SQR4_SQ16_2 (0x04UL << ADC_SQR4_SQ16_Pos) /*!< 0x00000100 */ -#define ADC_SQR4_SQ16_3 (0x08UL << ADC_SQR4_SQ16_Pos) /*!< 0x00000200 */ -#define ADC_SQR4_SQ16_4 (0x10UL << ADC_SQR4_SQ16_Pos) /*!< 0x00000400 */ -/******************** Bit definition for ADC_DR register ********************/ -#define ADC_DR_RDATA_Pos (0U) -#define ADC_DR_RDATA_Msk (0xFFFFFFFFUL << ADC_DR_RDATA_Pos) /*!< 0xFFFFFFFF */ -#define ADC_DR_RDATA ADC_DR_RDATA_Msk /*!< ADC regular Data converted */ - -/******************** Bit definition for ADC_JSQR register ********************/ -#define ADC_JSQR_JL_Pos (0U) -#define ADC_JSQR_JL_Msk (0x3UL << ADC_JSQR_JL_Pos) /*!< 0x00000003 */ -#define ADC_JSQR_JL ADC_JSQR_JL_Msk /*!< ADC injected channel sequence length */ -#define ADC_JSQR_JL_0 (0x1UL << ADC_JSQR_JL_Pos) /*!< 0x00000001 */ -#define ADC_JSQR_JL_1 (0x2UL << ADC_JSQR_JL_Pos) /*!< 0x00000002 */ - -#define ADC_JSQR_JEXTSEL_Pos (2U) -#define ADC_JSQR_JEXTSEL_Msk (0x1FUL << ADC_JSQR_JEXTSEL_Pos) /*!< 0x0000007C */ -#define ADC_JSQR_JEXTSEL ADC_JSQR_JEXTSEL_Msk /*!< ADC external trigger selection for injected group */ -#define ADC_JSQR_JEXTSEL_0 (0x01UL << ADC_JSQR_JEXTSEL_Pos) /*!< 0x00000004 */ -#define ADC_JSQR_JEXTSEL_1 (0x02UL << ADC_JSQR_JEXTSEL_Pos) /*!< 0x00000008 */ -#define ADC_JSQR_JEXTSEL_2 (0x04UL << ADC_JSQR_JEXTSEL_Pos) /*!< 0x00000010 */ -#define ADC_JSQR_JEXTSEL_3 (0x08UL << ADC_JSQR_JEXTSEL_Pos) /*!< 0x00000020 */ -#define ADC_JSQR_JEXTSEL_4 (0x10UL << ADC_JSQR_JEXTSEL_Pos) /*!< 0x00000040 */ - -#define ADC_JSQR_JEXTEN_Pos (7U) -#define ADC_JSQR_JEXTEN_Msk (0x3UL << ADC_JSQR_JEXTEN_Pos) /*!< 0x00000180 */ -#define ADC_JSQR_JEXTEN ADC_JSQR_JEXTEN_Msk /*!< ADC external trigger enable and polarity selection for injected channels */ -#define ADC_JSQR_JEXTEN_0 (0x1UL << ADC_JSQR_JEXTEN_Pos) /*!< 0x00000080 */ -#define ADC_JSQR_JEXTEN_1 (0x2UL << ADC_JSQR_JEXTEN_Pos) /*!< 0x00000100 */ - -#define ADC_JSQR_JSQ1_Pos (9U) -#define ADC_JSQR_JSQ1_Msk (0x1FUL << ADC_JSQR_JSQ1_Pos) /*!< 0x00003E00 */ -#define ADC_JSQR_JSQ1 ADC_JSQR_JSQ1_Msk /*!< ADC 1st conversion in injected sequence */ -#define ADC_JSQR_JSQ1_0 (0x01UL << ADC_JSQR_JSQ1_Pos) /*!< 0x00000200 */ -#define ADC_JSQR_JSQ1_1 (0x02UL << ADC_JSQR_JSQ1_Pos) /*!< 0x00000400 */ -#define ADC_JSQR_JSQ1_2 (0x04UL << ADC_JSQR_JSQ1_Pos) /*!< 0x00000800 */ -#define ADC_JSQR_JSQ1_3 (0x08UL << ADC_JSQR_JSQ1_Pos) /*!< 0x00001000 */ -#define ADC_JSQR_JSQ1_4 (0x10UL << ADC_JSQR_JSQ1_Pos) /*!< 0x00002000 */ - -#define ADC_JSQR_JSQ2_Pos (15U) -#define ADC_JSQR_JSQ2_Msk (0x1FUL << ADC_JSQR_JSQ2_Pos) /*!< 0x000F8000 */ -#define ADC_JSQR_JSQ2 ADC_JSQR_JSQ2_Msk /*!< ADC 2nd conversion in injected sequence */ -#define ADC_JSQR_JSQ2_0 (0x01UL << ADC_JSQR_JSQ2_Pos) /*!< 0x00008000 */ -#define ADC_JSQR_JSQ2_1 (0x02UL << ADC_JSQR_JSQ2_Pos) /*!< 0x00010000 */ -#define ADC_JSQR_JSQ2_2 (0x04UL << ADC_JSQR_JSQ2_Pos) /*!< 0x00020000 */ -#define ADC_JSQR_JSQ2_3 (0x08UL << ADC_JSQR_JSQ2_Pos) /*!< 0x00040000 */ -#define ADC_JSQR_JSQ2_4 (0x10UL << ADC_JSQR_JSQ2_Pos) /*!< 0x00080000 */ - -#define ADC_JSQR_JSQ3_Pos (21U) -#define ADC_JSQR_JSQ3_Msk (0x1FUL << ADC_JSQR_JSQ3_Pos) /*!< 0x03E00000 */ -#define ADC_JSQR_JSQ3 ADC_JSQR_JSQ3_Msk /*!< ADC 3rd conversion in injected sequence */ -#define ADC_JSQR_JSQ3_0 (0x01UL << ADC_JSQR_JSQ3_Pos) /*!< 0x00200000 */ -#define ADC_JSQR_JSQ3_1 (0x02UL << ADC_JSQR_JSQ3_Pos) /*!< 0x00400000 */ -#define ADC_JSQR_JSQ3_2 (0x04UL << ADC_JSQR_JSQ3_Pos) /*!< 0x00800000 */ -#define ADC_JSQR_JSQ3_3 (0x08UL << ADC_JSQR_JSQ3_Pos) /*!< 0x01000000 */ -#define ADC_JSQR_JSQ3_4 (0x10UL << ADC_JSQR_JSQ3_Pos) /*!< 0x02000000 */ - -#define ADC_JSQR_JSQ4_Pos (27U) -#define ADC_JSQR_JSQ4_Msk (0x1FUL << ADC_JSQR_JSQ4_Pos) /*!< 0xF8000000 */ -#define ADC_JSQR_JSQ4 ADC_JSQR_JSQ4_Msk /*!< ADC 4th conversion in injected sequence */ -#define ADC_JSQR_JSQ4_0 (0x01UL << ADC_JSQR_JSQ4_Pos) /*!< 0x08000000 */ -#define ADC_JSQR_JSQ4_1 (0x02UL << ADC_JSQR_JSQ4_Pos) /*!< 0x10000000 */ -#define ADC_JSQR_JSQ4_2 (0x04UL << ADC_JSQR_JSQ4_Pos) /*!< 0x20000000 */ -#define ADC_JSQR_JSQ4_3 (0x08UL << ADC_JSQR_JSQ4_Pos) /*!< 0x40000000 */ -#define ADC_JSQR_JSQ4_4 (0x10UL << ADC_JSQR_JSQ4_Pos) /*!< 0x80000000 */ - -/******************** Bit definition for ADC_OFR1 register ********************/ -#define ADC_OFR1_OFFSET1_Pos (0U) -#define ADC_OFR1_OFFSET1_Msk (0x3FFFFFFUL << ADC_OFR1_OFFSET1_Pos) /*!< 0x03FFFFFF */ -#define ADC_OFR1_OFFSET1 ADC_OFR1_OFFSET1_Msk /*!< ADC data offset 1 for channel programmed into bits OFFSET1_CH[4:0] */ -#define ADC_OFR1_OFFSET1_0 (0x0000001UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000001 */ -#define ADC_OFR1_OFFSET1_1 (0x0000002UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000002 */ -#define ADC_OFR1_OFFSET1_2 (0x0000004UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000004 */ -#define ADC_OFR1_OFFSET1_3 (0x0000008UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000008 */ -#define ADC_OFR1_OFFSET1_4 (0x0000010UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000010 */ -#define ADC_OFR1_OFFSET1_5 (0x0000020UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000020 */ -#define ADC_OFR1_OFFSET1_6 (0x0000040UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000040 */ -#define ADC_OFR1_OFFSET1_7 (0x0000080UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000080 */ -#define ADC_OFR1_OFFSET1_8 (0x0000100UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000100 */ -#define ADC_OFR1_OFFSET1_9 (0x0000200UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000200 */ -#define ADC_OFR1_OFFSET1_10 (0x0000400UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000400 */ -#define ADC_OFR1_OFFSET1_11 (0x0000800UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000800 */ -#define ADC_OFR1_OFFSET1_12 (0x0001000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00001000 */ -#define ADC_OFR1_OFFSET1_13 (0x0002000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00002000 */ -#define ADC_OFR1_OFFSET1_14 (0x0004000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00004000 */ -#define ADC_OFR1_OFFSET1_15 (0x0008000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00008000 */ -#define ADC_OFR1_OFFSET1_16 (0x0010000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00010000 */ -#define ADC_OFR1_OFFSET1_17 (0x0020000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00020000 */ -#define ADC_OFR1_OFFSET1_18 (0x0040000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00040000 */ -#define ADC_OFR1_OFFSET1_19 (0x0080000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00080000 */ -#define ADC_OFR1_OFFSET1_20 (0x0100000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00100000 */ -#define ADC_OFR1_OFFSET1_21 (0x0200000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00200000 */ -#define ADC_OFR1_OFFSET1_22 (0x0400000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00400000 */ -#define ADC_OFR1_OFFSET1_23 (0x0800000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00800000 */ -#define ADC_OFR1_OFFSET1_24 (0x1000000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x01000000 */ -#define ADC_OFR1_OFFSET1_25 (0x2000000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x02000000 */ - -#define ADC_OFR1_OFFSET1_CH_Pos (26U) -#define ADC_OFR1_OFFSET1_CH_Msk (0x1FUL << ADC_OFR1_OFFSET1_CH_Pos) /*!< 0x7C000000 */ -#define ADC_OFR1_OFFSET1_CH ADC_OFR1_OFFSET1_CH_Msk /*!< ADC Channel selection for the data offset 1 */ -#define ADC_OFR1_OFFSET1_CH_0 (0x01UL << ADC_OFR1_OFFSET1_CH_Pos) /*!< 0x04000000 */ -#define ADC_OFR1_OFFSET1_CH_1 (0x02UL << ADC_OFR1_OFFSET1_CH_Pos) /*!< 0x08000000 */ -#define ADC_OFR1_OFFSET1_CH_2 (0x04UL << ADC_OFR1_OFFSET1_CH_Pos) /*!< 0x10000000 */ -#define ADC_OFR1_OFFSET1_CH_3 (0x08UL << ADC_OFR1_OFFSET1_CH_Pos) /*!< 0x20000000 */ -#define ADC_OFR1_OFFSET1_CH_4 (0x10UL << ADC_OFR1_OFFSET1_CH_Pos) /*!< 0x40000000 */ - -#define ADC_OFR1_SSATE_Pos (31U) -#define ADC_OFR1_SSATE_Msk (0x1UL << ADC_OFR1_SSATE_Pos) /*!< 0x80000000 */ -#define ADC_OFR1_SSATE ADC_OFR1_SSATE_Msk /*!< ADC Signed saturation Enable */ - -#define ADC3_OFR1_OFFSET1_Pos (0U) -#define ADC3_OFR1_OFFSET1_Msk (0xFFFUL << ADC3_OFR1_OFFSET1_Pos) /*!< 0x00000FFF */ -#define ADC3_OFR1_OFFSET1 ADC3_OFR1_OFFSET1_Msk /*!< ADC data offset 1 for channel programmed into bits OFFSET1_CH[4:0] */ - -#define ADC3_OFR1_OFFSETPOS_Pos (24U) -#define ADC3_OFR1_OFFSETPOS_Msk (0x1UL << ADC3_OFR1_OFFSETPOS_Pos) /*!< 0x01000000 */ -#define ADC3_OFR1_OFFSETPOS ADC3_OFR1_OFFSETPOS_Msk /*!< ADC offset number 1 positive */ -#define ADC3_OFR1_SATEN_Pos (25U) -#define ADC3_OFR1_SATEN_Msk (0x1UL << ADC3_OFR1_SATEN_Pos) /*!< 0x02000000 */ -#define ADC3_OFR1_SATEN ADC3_OFR1_SATEN_Msk /*!< ADC offset number 1 saturation enable */ - -#define ADC3_OFR1_OFFSET1_EN_Pos (31U) -#define ADC3_OFR1_OFFSET1_EN_Msk (0x1UL << ADC3_OFR1_OFFSET1_EN_Pos) /*!< 0x80000000 */ -#define ADC3_OFR1_OFFSET1_EN ADC3_OFR1_OFFSET1_EN_Msk /*!< ADC offset number 1 enable */ - -/******************** Bit definition for ADC_OFR2 register ********************/ -#define ADC_OFR2_OFFSET2_Pos (0U) -#define ADC_OFR2_OFFSET2_Msk (0x3FFFFFFUL << ADC_OFR2_OFFSET2_Pos) /*!< 0x03FFFFFF */ -#define ADC_OFR2_OFFSET2 ADC_OFR2_OFFSET2_Msk /*!< ADC data offset 2 for channel programmed into bits OFFSET2_CH[4:0] */ -#define ADC_OFR2_OFFSET2_0 (0x0000001UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000001 */ -#define ADC_OFR2_OFFSET2_1 (0x0000002UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000002 */ -#define ADC_OFR2_OFFSET2_2 (0x0000004UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000004 */ -#define ADC_OFR2_OFFSET2_3 (0x0000008UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000008 */ -#define ADC_OFR2_OFFSET2_4 (0x0000010UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000010 */ -#define ADC_OFR2_OFFSET2_5 (0x0000020UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000020 */ -#define ADC_OFR2_OFFSET2_6 (0x0000040UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000040 */ -#define ADC_OFR2_OFFSET2_7 (0x0000080UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000080 */ -#define ADC_OFR2_OFFSET2_8 (0x0000100UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000100 */ -#define ADC_OFR2_OFFSET2_9 (0x0000200UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000200 */ -#define ADC_OFR2_OFFSET2_10 (0x0000400UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000400 */ -#define ADC_OFR2_OFFSET2_11 (0x0000800UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000800 */ -#define ADC_OFR2_OFFSET2_12 (0x0001000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00001000 */ -#define ADC_OFR2_OFFSET2_13 (0x0002000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00002000 */ -#define ADC_OFR2_OFFSET2_14 (0x0004000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00004000 */ -#define ADC_OFR2_OFFSET2_15 (0x0008000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00008000 */ -#define ADC_OFR2_OFFSET2_16 (0x0010000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00010000 */ -#define ADC_OFR2_OFFSET2_17 (0x0020000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00020000 */ -#define ADC_OFR2_OFFSET2_18 (0x0040000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00040000 */ -#define ADC_OFR2_OFFSET2_19 (0x0080000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00080000 */ -#define ADC_OFR2_OFFSET2_20 (0x0100000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00100000 */ -#define ADC_OFR2_OFFSET2_21 (0x0200000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00200000 */ -#define ADC_OFR2_OFFSET2_22 (0x0400000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00400000 */ -#define ADC_OFR2_OFFSET2_23 (0x0800000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00800000 */ -#define ADC_OFR2_OFFSET2_24 (0x1000000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x01000000 */ -#define ADC_OFR2_OFFSET2_25 (0x2000000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x02000000 */ - -#define ADC_OFR2_OFFSET2_CH_Pos (26U) -#define ADC_OFR2_OFFSET2_CH_Msk (0x1FUL << ADC_OFR2_OFFSET2_CH_Pos) /*!< 0x7C000000 */ -#define ADC_OFR2_OFFSET2_CH ADC_OFR2_OFFSET2_CH_Msk /*!< ADC Channel selection for the data offset 2 */ -#define ADC_OFR2_OFFSET2_CH_0 (0x01UL << ADC_OFR2_OFFSET2_CH_Pos) /*!< 0x04000000 */ -#define ADC_OFR2_OFFSET2_CH_1 (0x02UL << ADC_OFR2_OFFSET2_CH_Pos) /*!< 0x08000000 */ -#define ADC_OFR2_OFFSET2_CH_2 (0x04UL << ADC_OFR2_OFFSET2_CH_Pos) /*!< 0x10000000 */ -#define ADC_OFR2_OFFSET2_CH_3 (0x08UL << ADC_OFR2_OFFSET2_CH_Pos) /*!< 0x20000000 */ -#define ADC_OFR2_OFFSET2_CH_4 (0x10UL << ADC_OFR2_OFFSET2_CH_Pos) /*!< 0x40000000 */ - -#define ADC_OFR2_SSATE_Pos (31U) -#define ADC_OFR2_SSATE_Msk (0x1UL << ADC_OFR2_SSATE_Pos) /*!< 0x80000000 */ -#define ADC_OFR2_SSATE ADC_OFR2_SSATE_Msk /*!< ADC Signed saturation Enable */ - -#define ADC3_OFR2_OFFSET2_Pos (0U) -#define ADC3_OFR2_OFFSET2_Msk (0xFFFUL << ADC3_OFR2_OFFSET2_Pos) /*!< 0x00000FFF */ -#define ADC3_OFR2_OFFSET2 ADC3_OFR2_OFFSET2_Msk /*!< ADC data offset 2 for channel programmed into bits OFFSET1_CH[4:0] */ - -#define ADC3_OFR2_OFFSETPOS_Pos (24U) -#define ADC3_OFR2_OFFSETPOS_Msk (0x1UL << ADC3_OFR2_OFFSETPOS_Pos) /*!< 0x01000000 */ -#define ADC3_OFR2_OFFSETPOS ADC3_OFR2_OFFSETPOS_Msk /*!< ADC offset number 2 positive */ -#define ADC3_OFR2_SATEN_Pos (25U) -#define ADC3_OFR2_SATEN_Msk (0x1UL << ADC3_OFR2_SATEN_Pos) /*!< 0x02000000 */ -#define ADC3_OFR2_SATEN ADC3_OFR2_SATEN_Msk /*!< ADC offset number 2 saturation enable */ - -#define ADC3_OFR2_OFFSET2_EN_Pos (31U) -#define ADC3_OFR2_OFFSET2_EN_Msk (0x1UL << ADC3_OFR2_OFFSET2_EN_Pos) /*!< 0x80000000 */ -#define ADC3_OFR2_OFFSET2_EN ADC3_OFR2_OFFSET2_EN_Msk /*!< ADC offset number 2 enable */ - -/******************** Bit definition for ADC_OFR3 register ********************/ -#define ADC_OFR3_OFFSET3_Pos (0U) -#define ADC_OFR3_OFFSET3_Msk (0x3FFFFFFUL << ADC_OFR3_OFFSET3_Pos) /*!< 0x03FFFFFF */ -#define ADC_OFR3_OFFSET3 ADC_OFR3_OFFSET3_Msk /*!< ADC data offset 3 for channel programmed into bits OFFSET3_CH[4:0] */ -#define ADC_OFR3_OFFSET3_0 (0x0000001UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000001 */ -#define ADC_OFR3_OFFSET3_1 (0x0000002UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000002 */ -#define ADC_OFR3_OFFSET3_2 (0x0000004UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000004 */ -#define ADC_OFR3_OFFSET3_3 (0x0000008UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000008 */ -#define ADC_OFR3_OFFSET3_4 (0x0000010UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000010 */ -#define ADC_OFR3_OFFSET3_5 (0x0000020UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000020 */ -#define ADC_OFR3_OFFSET3_6 (0x0000040UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000040 */ -#define ADC_OFR3_OFFSET3_7 (0x0000080UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000080 */ -#define ADC_OFR3_OFFSET3_8 (0x0000100UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000100 */ -#define ADC_OFR3_OFFSET3_9 (0x0000200UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000200 */ -#define ADC_OFR3_OFFSET3_10 (0x0000400UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000400 */ -#define ADC_OFR3_OFFSET3_11 (0x0000800UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000800 */ -#define ADC_OFR3_OFFSET3_12 (0x0001000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00001000 */ -#define ADC_OFR3_OFFSET3_13 (0x0002000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00002000 */ -#define ADC_OFR3_OFFSET3_14 (0x0004000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00004000 */ -#define ADC_OFR3_OFFSET3_15 (0x0008000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00008000 */ -#define ADC_OFR3_OFFSET3_16 (0x0010000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00010000 */ -#define ADC_OFR3_OFFSET3_17 (0x0020000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00020000 */ -#define ADC_OFR3_OFFSET3_18 (0x0040000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00040000 */ -#define ADC_OFR3_OFFSET3_19 (0x0080000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00080000 */ -#define ADC_OFR3_OFFSET3_20 (0x0100000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00100000 */ -#define ADC_OFR3_OFFSET3_21 (0x0200000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00200000 */ -#define ADC_OFR3_OFFSET3_22 (0x0400000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00400000 */ -#define ADC_OFR3_OFFSET3_23 (0x0800000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00800000 */ -#define ADC_OFR3_OFFSET3_24 (0x1000000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x01000000 */ -#define ADC_OFR3_OFFSET3_25 (0x2000000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x02000000 */ - -#define ADC_OFR3_OFFSET3_CH_Pos (26U) -#define ADC_OFR3_OFFSET3_CH_Msk (0x1FUL << ADC_OFR3_OFFSET3_CH_Pos) /*!< 0x7C000000 */ -#define ADC_OFR3_OFFSET3_CH ADC_OFR3_OFFSET3_CH_Msk /*!< ADC Channel selection for the data offset 3 */ -#define ADC_OFR3_OFFSET3_CH_0 (0x01UL << ADC_OFR3_OFFSET3_CH_Pos) /*!< 0x04000000 */ -#define ADC_OFR3_OFFSET3_CH_1 (0x02UL << ADC_OFR3_OFFSET3_CH_Pos) /*!< 0x08000000 */ -#define ADC_OFR3_OFFSET3_CH_2 (0x04UL << ADC_OFR3_OFFSET3_CH_Pos) /*!< 0x10000000 */ -#define ADC_OFR3_OFFSET3_CH_3 (0x08UL << ADC_OFR3_OFFSET3_CH_Pos) /*!< 0x20000000 */ -#define ADC_OFR3_OFFSET3_CH_4 (0x10UL << ADC_OFR3_OFFSET3_CH_Pos) /*!< 0x40000000 */ - -#define ADC_OFR3_SSATE_Pos (31U) -#define ADC_OFR3_SSATE_Msk (0x1UL << ADC_OFR3_SSATE_Pos) /*!< 0x80000000 */ -#define ADC_OFR3_SSATE ADC_OFR3_SSATE_Msk /*!< ADC Signed saturation Enable */ - -#define ADC3_OFR3_OFFSET3_Pos (0U) -#define ADC3_OFR3_OFFSET3_Msk (0xFFFUL << ADC3_OFR3_OFFSET3_Pos) /*!< 0x00000FFF */ -#define ADC3_OFR3_OFFSET3 ADC3_OFR3_OFFSET3_Msk /*!< ADC data offset 3 for channel programmed into bits OFFSET1_CH[4:0] */ - -#define ADC3_OFR3_OFFSETPOS_Pos (24U) -#define ADC3_OFR3_OFFSETPOS_Msk (0x1UL << ADC3_OFR3_OFFSETPOS_Pos) /*!< 0x01000000 */ -#define ADC3_OFR3_OFFSETPOS ADC3_OFR3_OFFSETPOS_Msk /*!< ADC offset number 3 positive */ -#define ADC3_OFR3_SATEN_Pos (25U) -#define ADC3_OFR3_SATEN_Msk (0x1UL << ADC3_OFR3_SATEN_Pos) /*!< 0x02000000 */ -#define ADC3_OFR3_SATEN ADC3_OFR3_SATEN_Msk /*!< ADC offset number 3 saturation enable */ - -#define ADC3_OFR3_OFFSET3_EN_Pos (31U) -#define ADC3_OFR3_OFFSET3_EN_Msk (0x1UL << ADC3_OFR3_OFFSET3_EN_Pos) /*!< 0x80000000 */ -#define ADC3_OFR3_OFFSET3_EN ADC3_OFR3_OFFSET3_EN_Msk /*!< ADC offset number 3 enable */ - -/******************** Bit definition for ADC_OFR4 register ********************/ -#define ADC_OFR4_OFFSET4_Pos (0U) -#define ADC_OFR4_OFFSET4_Msk (0x3FFFFFFUL << ADC_OFR4_OFFSET4_Pos) /*!< 0x03FFFFFF */ -#define ADC_OFR4_OFFSET4 ADC_OFR4_OFFSET4_Msk /*!< ADC data offset 4 for channel programmed into bits OFFSET4_CH[4:0] */ -#define ADC_OFR4_OFFSET4_0 (0x0000001UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000001 */ -#define ADC_OFR4_OFFSET4_1 (0x0000002UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000002 */ -#define ADC_OFR4_OFFSET4_2 (0x0000004UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000004 */ -#define ADC_OFR4_OFFSET4_3 (0x0000008UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000008 */ -#define ADC_OFR4_OFFSET4_4 (0x0000010UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000010 */ -#define ADC_OFR4_OFFSET4_5 (0x0000020UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000020 */ -#define ADC_OFR4_OFFSET4_6 (0x0000040UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000040 */ -#define ADC_OFR4_OFFSET4_7 (0x0000080UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000080 */ -#define ADC_OFR4_OFFSET4_8 (0x0000100UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000100 */ -#define ADC_OFR4_OFFSET4_9 (0x0000200UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000200 */ -#define ADC_OFR4_OFFSET4_10 (0x0000400UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000400 */ -#define ADC_OFR4_OFFSET4_11 (0x0000800UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000800 */ -#define ADC_OFR4_OFFSET4_12 (0x0001000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00001000 */ -#define ADC_OFR4_OFFSET4_13 (0x0002000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00002000 */ -#define ADC_OFR4_OFFSET4_14 (0x0004000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00004000 */ -#define ADC_OFR4_OFFSET4_15 (0x0008000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00008000 */ -#define ADC_OFR4_OFFSET4_16 (0x0010000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00010000 */ -#define ADC_OFR4_OFFSET4_17 (0x0020000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00020000 */ -#define ADC_OFR4_OFFSET4_18 (0x0040000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00040000 */ -#define ADC_OFR4_OFFSET4_19 (0x0080000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00080000 */ -#define ADC_OFR4_OFFSET4_20 (0x0100000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00100000 */ -#define ADC_OFR4_OFFSET4_21 (0x0200000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00200000 */ -#define ADC_OFR4_OFFSET4_22 (0x0400000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00400000 */ -#define ADC_OFR4_OFFSET4_23 (0x0800000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00800000 */ -#define ADC_OFR4_OFFSET4_24 (0x1000000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x01000000 */ -#define ADC_OFR4_OFFSET4_25 (0x2000000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x02000000 */ - -#define ADC_OFR4_OFFSET4_CH_Pos (26U) -#define ADC_OFR4_OFFSET4_CH_Msk (0x1FUL << ADC_OFR4_OFFSET4_CH_Pos) /*!< 0x7C000000 */ -#define ADC_OFR4_OFFSET4_CH ADC_OFR4_OFFSET4_CH_Msk /*!< ADC Channel selection for the data offset 4 */ -#define ADC_OFR4_OFFSET4_CH_0 (0x01UL << ADC_OFR4_OFFSET4_CH_Pos) /*!< 0x04000000 */ -#define ADC_OFR4_OFFSET4_CH_1 (0x02UL << ADC_OFR4_OFFSET4_CH_Pos) /*!< 0x08000000 */ -#define ADC_OFR4_OFFSET4_CH_2 (0x04UL << ADC_OFR4_OFFSET4_CH_Pos) /*!< 0x10000000 */ -#define ADC_OFR4_OFFSET4_CH_3 (0x08UL << ADC_OFR4_OFFSET4_CH_Pos) /*!< 0x20000000 */ -#define ADC_OFR4_OFFSET4_CH_4 (0x10UL << ADC_OFR4_OFFSET4_CH_Pos) /*!< 0x40000000 */ - -#define ADC_OFR4_SSATE_Pos (31U) -#define ADC_OFR4_SSATE_Msk (0x1UL << ADC_OFR4_SSATE_Pos) /*!< 0x80000000 */ -#define ADC_OFR4_SSATE ADC_OFR4_SSATE_Msk /*!< ADC Signed saturation Enable */ - -#define ADC3_OFR4_OFFSET4_Pos (0U) -#define ADC3_OFR4_OFFSET4_Msk (0xFFFUL << ADC3_OFR4_OFFSET4_Pos) /*!< 0x00000FFF */ -#define ADC3_OFR4_OFFSET4 ADC3_OFR4_OFFSET4_Msk /*!< ADC data offset 4 for channel programmed into bits OFFSET1_CH[4:0] */ - -#define ADC3_OFR4_OFFSETPOS_Pos (24U) -#define ADC3_OFR4_OFFSETPOS_Msk (0x1UL << ADC3_OFR4_OFFSETPOS_Pos) /*!< 0x01000000 */ -#define ADC3_OFR4_OFFSETPOS ADC3_OFR4_OFFSETPOS_Msk /*!< ADC offset number 4 positive */ -#define ADC3_OFR4_SATEN_Pos (25U) -#define ADC3_OFR4_SATEN_Msk (0x1UL << ADC3_OFR4_SATEN_Pos) /*!< 0x02000000 */ -#define ADC3_OFR4_SATEN ADC3_OFR4_SATEN_Msk /*!< ADC offset number 4 saturation enable */ - -#define ADC3_OFR4_OFFSET4_EN_Pos (31U) -#define ADC3_OFR4_OFFSET4_EN_Msk (0x1UL << ADC3_OFR4_OFFSET4_EN_Pos) /*!< 0x80000000 */ -#define ADC3_OFR4_OFFSET4_EN ADC3_OFR4_OFFSET4_EN_Msk /*!< ADC offset number 4 enable */ - -/******************** Bit definition for ADC_JDR1 register ********************/ -#define ADC_JDR1_JDATA_Pos (0U) -#define ADC_JDR1_JDATA_Msk (0xFFFFFFFFUL << ADC_JDR1_JDATA_Pos) /*!< 0xFFFFFFFF */ -#define ADC_JDR1_JDATA ADC_JDR1_JDATA_Msk /*!< ADC Injected DATA */ -#define ADC_JDR1_JDATA_0 (0x00000001UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000001 */ -#define ADC_JDR1_JDATA_1 (0x00000002UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000002 */ -#define ADC_JDR1_JDATA_2 (0x00000004UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000004 */ -#define ADC_JDR1_JDATA_3 (0x00000008UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000008 */ -#define ADC_JDR1_JDATA_4 (0x00000010UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000010 */ -#define ADC_JDR1_JDATA_5 (0x00000020UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000020 */ -#define ADC_JDR1_JDATA_6 (0x00000040UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000040 */ -#define ADC_JDR1_JDATA_7 (0x00000080UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000080 */ -#define ADC_JDR1_JDATA_8 (0x00000100UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000100 */ -#define ADC_JDR1_JDATA_9 (0x00000200UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000200 */ -#define ADC_JDR1_JDATA_10 (0x00000400UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000400 */ -#define ADC_JDR1_JDATA_11 (0x00000800UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000800 */ -#define ADC_JDR1_JDATA_12 (0x00001000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00001000 */ -#define ADC_JDR1_JDATA_13 (0x00002000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00002000 */ -#define ADC_JDR1_JDATA_14 (0x00004000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00004000 */ -#define ADC_JDR1_JDATA_15 (0x00008000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00008000 */ -#define ADC_JDR1_JDATA_16 (0x00010000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00010000 */ -#define ADC_JDR1_JDATA_17 (0x00020000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00020000 */ -#define ADC_JDR1_JDATA_18 (0x00040000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00040000 */ -#define ADC_JDR1_JDATA_19 (0x00080000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00080000 */ -#define ADC_JDR1_JDATA_20 (0x00100000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00100000 */ -#define ADC_JDR1_JDATA_21 (0x00200000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00200000 */ -#define ADC_JDR1_JDATA_22 (0x00400000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00400000 */ -#define ADC_JDR1_JDATA_23 (0x00800000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00800000 */ -#define ADC_JDR1_JDATA_24 (0x01000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x01000000 */ -#define ADC_JDR1_JDATA_25 (0x02000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x02000000 */ -#define ADC_JDR1_JDATA_26 (0x04000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x04000000 */ -#define ADC_JDR1_JDATA_27 (0x08000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x08000000 */ -#define ADC_JDR1_JDATA_28 (0x10000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x10000000 */ -#define ADC_JDR1_JDATA_29 (0x20000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x20000000 */ -#define ADC_JDR1_JDATA_30 (0x40000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x40000000 */ -#define ADC_JDR1_JDATA_31 (0x80000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x80000000 */ - -/******************** Bit definition for ADC_JDR2 register ********************/ -#define ADC_JDR2_JDATA_Pos (0U) -#define ADC_JDR2_JDATA_Msk (0xFFFFFFFFUL << ADC_JDR2_JDATA_Pos) /*!< 0xFFFFFFFF */ -#define ADC_JDR2_JDATA ADC_JDR2_JDATA_Msk /*!< ADC Injected DATA */ -#define ADC_JDR2_JDATA_0 (0x00000001UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000001 */ -#define ADC_JDR2_JDATA_1 (0x00000002UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000002 */ -#define ADC_JDR2_JDATA_2 (0x00000004UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000004 */ -#define ADC_JDR2_JDATA_3 (0x00000008UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000008 */ -#define ADC_JDR2_JDATA_4 (0x00000010UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000010 */ -#define ADC_JDR2_JDATA_5 (0x00000020UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000020 */ -#define ADC_JDR2_JDATA_6 (0x00000040UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000040 */ -#define ADC_JDR2_JDATA_7 (0x00000080UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000080 */ -#define ADC_JDR2_JDATA_8 (0x00000100UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000100 */ -#define ADC_JDR2_JDATA_9 (0x00000200UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000200 */ -#define ADC_JDR2_JDATA_10 (0x00000400UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000400 */ -#define ADC_JDR2_JDATA_11 (0x00000800UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000800 */ -#define ADC_JDR2_JDATA_12 (0x00001000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00001000 */ -#define ADC_JDR2_JDATA_13 (0x00002000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00002000 */ -#define ADC_JDR2_JDATA_14 (0x00004000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00004000 */ -#define ADC_JDR2_JDATA_15 (0x00008000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00008000 */ -#define ADC_JDR2_JDATA_16 (0x00010000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00010000 */ -#define ADC_JDR2_JDATA_17 (0x00020000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00020000 */ -#define ADC_JDR2_JDATA_18 (0x00040000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00040000 */ -#define ADC_JDR2_JDATA_19 (0x00080000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00080000 */ -#define ADC_JDR2_JDATA_20 (0x00100000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00100000 */ -#define ADC_JDR2_JDATA_21 (0x00200000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00200000 */ -#define ADC_JDR2_JDATA_22 (0x00400000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00400000 */ -#define ADC_JDR2_JDATA_23 (0x00800000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00800000 */ -#define ADC_JDR2_JDATA_24 (0x01000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x01000000 */ -#define ADC_JDR2_JDATA_25 (0x02000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x02000000 */ -#define ADC_JDR2_JDATA_26 (0x04000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x04000000 */ -#define ADC_JDR2_JDATA_27 (0x08000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x08000000 */ -#define ADC_JDR2_JDATA_28 (0x10000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x10000000 */ -#define ADC_JDR2_JDATA_29 (0x20000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x20000000 */ -#define ADC_JDR2_JDATA_30 (0x40000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x40000000 */ -#define ADC_JDR2_JDATA_31 (0x80000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x80000000 */ - -/******************** Bit definition for ADC_JDR3 register ********************/ -#define ADC_JDR3_JDATA_Pos (0U) -#define ADC_JDR3_JDATA_Msk (0xFFFFFFFFUL << ADC_JDR3_JDATA_Pos) /*!< 0xFFFFFFFF */ -#define ADC_JDR3_JDATA ADC_JDR3_JDATA_Msk /*!< ADC Injected DATA */ -#define ADC_JDR3_JDATA_0 (0x00000001UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000001 */ -#define ADC_JDR3_JDATA_1 (0x00000002UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000002 */ -#define ADC_JDR3_JDATA_2 (0x00000004UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000004 */ -#define ADC_JDR3_JDATA_3 (0x00000008UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000008 */ -#define ADC_JDR3_JDATA_4 (0x00000010UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000010 */ -#define ADC_JDR3_JDATA_5 (0x00000020UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000020 */ -#define ADC_JDR3_JDATA_6 (0x00000040UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000040 */ -#define ADC_JDR3_JDATA_7 (0x00000080UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000080 */ -#define ADC_JDR3_JDATA_8 (0x00000100UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000100 */ -#define ADC_JDR3_JDATA_9 (0x00000200UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000200 */ -#define ADC_JDR3_JDATA_10 (0x00000400UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000400 */ -#define ADC_JDR3_JDATA_11 (0x00000800UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000800 */ -#define ADC_JDR3_JDATA_12 (0x00001000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00001000 */ -#define ADC_JDR3_JDATA_13 (0x00002000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00002000 */ -#define ADC_JDR3_JDATA_14 (0x00004000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00004000 */ -#define ADC_JDR3_JDATA_15 (0x00008000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00008000 */ -#define ADC_JDR3_JDATA_16 (0x00010000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00010000 */ -#define ADC_JDR3_JDATA_17 (0x00020000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00020000 */ -#define ADC_JDR3_JDATA_18 (0x00040000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00040000 */ -#define ADC_JDR3_JDATA_19 (0x00080000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00080000 */ -#define ADC_JDR3_JDATA_20 (0x00100000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00100000 */ -#define ADC_JDR3_JDATA_21 (0x00200000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00200000 */ -#define ADC_JDR3_JDATA_22 (0x00400000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00400000 */ -#define ADC_JDR3_JDATA_23 (0x00800000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00800000 */ -#define ADC_JDR3_JDATA_24 (0x01000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x01000000 */ -#define ADC_JDR3_JDATA_25 (0x02000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x02000000 */ -#define ADC_JDR3_JDATA_26 (0x04000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x04000000 */ -#define ADC_JDR3_JDATA_27 (0x08000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x08000000 */ -#define ADC_JDR3_JDATA_28 (0x10000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x10000000 */ -#define ADC_JDR3_JDATA_29 (0x20000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x20000000 */ -#define ADC_JDR3_JDATA_30 (0x40000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x40000000 */ -#define ADC_JDR3_JDATA_31 (0x80000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x80000000 */ - -/******************** Bit definition for ADC_JDR4 register ********************/ -#define ADC_JDR4_JDATA_Pos (0U) -#define ADC_JDR4_JDATA_Msk (0xFFFFFFFFUL << ADC_JDR4_JDATA_Pos) /*!< 0xFFFFFFFF */ -#define ADC_JDR4_JDATA ADC_JDR4_JDATA_Msk /*!< ADC Injected DATA */ -#define ADC_JDR4_JDATA_0 (0x00000001UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000001 */ -#define ADC_JDR4_JDATA_1 (0x00000002UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000002 */ -#define ADC_JDR4_JDATA_2 (0x00000004UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000004 */ -#define ADC_JDR4_JDATA_3 (0x00000008UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000008 */ -#define ADC_JDR4_JDATA_4 (0x00000010UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000010 */ -#define ADC_JDR4_JDATA_5 (0x00000020UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000020 */ -#define ADC_JDR4_JDATA_6 (0x00000040UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000040 */ -#define ADC_JDR4_JDATA_7 (0x00000080UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000080 */ -#define ADC_JDR4_JDATA_8 (0x00000100UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000100 */ -#define ADC_JDR4_JDATA_9 (0x00000200UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000200 */ -#define ADC_JDR4_JDATA_10 (0x00000400UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000400 */ -#define ADC_JDR4_JDATA_11 (0x00000800UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000800 */ -#define ADC_JDR4_JDATA_12 (0x00001000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00001000 */ -#define ADC_JDR4_JDATA_13 (0x00002000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00002000 */ -#define ADC_JDR4_JDATA_14 (0x00004000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00004000 */ -#define ADC_JDR4_JDATA_15 (0x00008000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00008000 */ -#define ADC_JDR4_JDATA_16 (0x00010000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00010000 */ -#define ADC_JDR4_JDATA_17 (0x00020000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00020000 */ -#define ADC_JDR4_JDATA_18 (0x00040000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00040000 */ -#define ADC_JDR4_JDATA_19 (0x00080000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00080000 */ -#define ADC_JDR4_JDATA_20 (0x00100000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00100000 */ -#define ADC_JDR4_JDATA_21 (0x00200000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00200000 */ -#define ADC_JDR4_JDATA_22 (0x00400000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00400000 */ -#define ADC_JDR4_JDATA_23 (0x00800000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00800000 */ -#define ADC_JDR4_JDATA_24 (0x01000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x01000000 */ -#define ADC_JDR4_JDATA_25 (0x02000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x02000000 */ -#define ADC_JDR4_JDATA_26 (0x04000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x04000000 */ -#define ADC_JDR4_JDATA_27 (0x08000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x08000000 */ -#define ADC_JDR4_JDATA_28 (0x10000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x10000000 */ -#define ADC_JDR4_JDATA_29 (0x20000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x20000000 */ -#define ADC_JDR4_JDATA_30 (0x40000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x40000000 */ -#define ADC_JDR4_JDATA_31 (0x80000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x80000000 */ - -/******************** Bit definition for ADC_AWD2CR register ********************/ -#define ADC_AWD2CR_AWD2CH_Pos (0U) -#define ADC_AWD2CR_AWD2CH_Msk (0xFFFFFUL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x000FFFFF */ -#define ADC_AWD2CR_AWD2CH ADC_AWD2CR_AWD2CH_Msk /*!< ADC Analog watchdog 2 channel selection */ -#define ADC_AWD2CR_AWD2CH_0 (0x00001UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000001 */ -#define ADC_AWD2CR_AWD2CH_1 (0x00002UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000002 */ -#define ADC_AWD2CR_AWD2CH_2 (0x00004UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000004 */ -#define ADC_AWD2CR_AWD2CH_3 (0x00008UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000008 */ -#define ADC_AWD2CR_AWD2CH_4 (0x00010UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000010 */ -#define ADC_AWD2CR_AWD2CH_5 (0x00020UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000020 */ -#define ADC_AWD2CR_AWD2CH_6 (0x00040UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000040 */ -#define ADC_AWD2CR_AWD2CH_7 (0x00080UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000080 */ -#define ADC_AWD2CR_AWD2CH_8 (0x00100UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000100 */ -#define ADC_AWD2CR_AWD2CH_9 (0x00200UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000200 */ -#define ADC_AWD2CR_AWD2CH_10 (0x00400UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000400 */ -#define ADC_AWD2CR_AWD2CH_11 (0x00800UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000800 */ -#define ADC_AWD2CR_AWD2CH_12 (0x01000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00001000 */ -#define ADC_AWD2CR_AWD2CH_13 (0x02000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00002000 */ -#define ADC_AWD2CR_AWD2CH_14 (0x04000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00004000 */ -#define ADC_AWD2CR_AWD2CH_15 (0x08000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00008000 */ -#define ADC_AWD2CR_AWD2CH_16 (0x10000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00010000 */ -#define ADC_AWD2CR_AWD2CH_17 (0x20000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00020000 */ -#define ADC_AWD2CR_AWD2CH_18 (0x40000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00040000 */ -#define ADC_AWD2CR_AWD2CH_19 (0x80000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00080000 */ - -/******************** Bit definition for ADC_AWD3CR register ********************/ -#define ADC_AWD3CR_AWD3CH_Pos (0U) -#define ADC_AWD3CR_AWD3CH_Msk (0xFFFFFUL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x000FFFFF */ -#define ADC_AWD3CR_AWD3CH ADC_AWD3CR_AWD3CH_Msk /*!< ADC Analog watchdog 2 channel selection */ -#define ADC_AWD3CR_AWD3CH_0 (0x00001UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000001 */ -#define ADC_AWD3CR_AWD3CH_1 (0x00002UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000002 */ -#define ADC_AWD3CR_AWD3CH_2 (0x00004UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000004 */ -#define ADC_AWD3CR_AWD3CH_3 (0x00008UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000008 */ -#define ADC_AWD3CR_AWD3CH_4 (0x00010UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000010 */ -#define ADC_AWD3CR_AWD3CH_5 (0x00020UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000020 */ -#define ADC_AWD3CR_AWD3CH_6 (0x00040UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000040 */ -#define ADC_AWD3CR_AWD3CH_7 (0x00080UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000080 */ -#define ADC_AWD3CR_AWD3CH_8 (0x00100UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000100 */ -#define ADC_AWD3CR_AWD3CH_9 (0x00200UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000200 */ -#define ADC_AWD3CR_AWD3CH_10 (0x00400UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000400 */ -#define ADC_AWD3CR_AWD3CH_11 (0x00800UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000800 */ -#define ADC_AWD3CR_AWD3CH_12 (0x01000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00001000 */ -#define ADC_AWD3CR_AWD3CH_13 (0x02000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00002000 */ -#define ADC_AWD3CR_AWD3CH_14 (0x04000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00004000 */ -#define ADC_AWD3CR_AWD3CH_15 (0x08000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00008000 */ -#define ADC_AWD3CR_AWD3CH_16 (0x10000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00010000 */ -#define ADC_AWD3CR_AWD3CH_17 (0x20000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00020000 */ -#define ADC_AWD3CR_AWD3CH_18 (0x40000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00040000 */ -#define ADC_AWD3CR_AWD3CH_19 (0x80000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00080000 */ - -/******************** Bit definition for ADC_DIFSEL register ********************/ -#define ADC_DIFSEL_DIFSEL_Pos (0U) -#define ADC_DIFSEL_DIFSEL_Msk (0xFFFFFUL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x000FFFFF */ -#define ADC_DIFSEL_DIFSEL ADC_DIFSEL_DIFSEL_Msk /*!< ADC differential modes for channels 1 to 18 */ -#define ADC_DIFSEL_DIFSEL_0 (0x00001UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000001 */ -#define ADC_DIFSEL_DIFSEL_1 (0x00002UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000002 */ -#define ADC_DIFSEL_DIFSEL_2 (0x00004UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000004 */ -#define ADC_DIFSEL_DIFSEL_3 (0x00008UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000008 */ -#define ADC_DIFSEL_DIFSEL_4 (0x00010UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000010 */ -#define ADC_DIFSEL_DIFSEL_5 (0x00020UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000020 */ -#define ADC_DIFSEL_DIFSEL_6 (0x00040UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000040 */ -#define ADC_DIFSEL_DIFSEL_7 (0x00080UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000080 */ -#define ADC_DIFSEL_DIFSEL_8 (0x00100UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000100 */ -#define ADC_DIFSEL_DIFSEL_9 (0x00200UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000200 */ -#define ADC_DIFSEL_DIFSEL_10 (0x00400UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000400 */ -#define ADC_DIFSEL_DIFSEL_11 (0x00800UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000800 */ -#define ADC_DIFSEL_DIFSEL_12 (0x01000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00001000 */ -#define ADC_DIFSEL_DIFSEL_13 (0x02000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00002000 */ -#define ADC_DIFSEL_DIFSEL_14 (0x04000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00004000 */ -#define ADC_DIFSEL_DIFSEL_15 (0x08000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00008000 */ -#define ADC_DIFSEL_DIFSEL_16 (0x10000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00010000 */ -#define ADC_DIFSEL_DIFSEL_17 (0x20000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00020000 */ -#define ADC_DIFSEL_DIFSEL_18 (0x40000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00040000 */ -#define ADC_DIFSEL_DIFSEL_19 (0x80000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00080000 */ - -/******************** Bit definition for ADC_CALFACT register ********************/ -#define ADC_CALFACT_CALFACT_S_Pos (0U) -#define ADC_CALFACT_CALFACT_S_Msk (0x7FFUL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x000007FF */ -#define ADC_CALFACT_CALFACT_S ADC_CALFACT_CALFACT_S_Msk /*!< ADC calibration factors in single-ended mode */ -#define ADC_CALFACT_CALFACT_S_0 (0x001UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000001 */ -#define ADC_CALFACT_CALFACT_S_1 (0x002UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000002 */ -#define ADC_CALFACT_CALFACT_S_2 (0x004UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000004 */ -#define ADC_CALFACT_CALFACT_S_3 (0x008UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000008 */ -#define ADC_CALFACT_CALFACT_S_4 (0x010UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000010 */ -#define ADC_CALFACT_CALFACT_S_5 (0x020UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000020 */ -#define ADC_CALFACT_CALFACT_S_6 (0x040UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000040 */ -#define ADC_CALFACT_CALFACT_S_7 (0x080UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000080 */ -#define ADC_CALFACT_CALFACT_S_8 (0x100UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000100 */ -#define ADC_CALFACT_CALFACT_S_9 (0x200UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000200 */ -#define ADC_CALFACT_CALFACT_S_10 (0x400UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000400 */ -#define ADC_CALFACT_CALFACT_D_Pos (16U) -#define ADC_CALFACT_CALFACT_D_Msk (0x7FFUL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x07FF0000 */ -#define ADC_CALFACT_CALFACT_D ADC_CALFACT_CALFACT_D_Msk /*!< ADC calibration factors in differential mode */ -#define ADC_CALFACT_CALFACT_D_0 (0x001UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00010000 */ -#define ADC_CALFACT_CALFACT_D_1 (0x002UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00020000 */ -#define ADC_CALFACT_CALFACT_D_2 (0x004UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00040000 */ -#define ADC_CALFACT_CALFACT_D_3 (0x008UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00080000 */ -#define ADC_CALFACT_CALFACT_D_4 (0x010UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00100000 */ -#define ADC_CALFACT_CALFACT_D_5 (0x020UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00200000 */ -#define ADC_CALFACT_CALFACT_D_6 (0x040UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00400000 */ -#define ADC_CALFACT_CALFACT_D_7 (0x080UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00800000 */ -#define ADC_CALFACT_CALFACT_D_8 (0x100UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x01000000 */ -#define ADC_CALFACT_CALFACT_D_9 (0x200UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x02000000 */ -#define ADC_CALFACT_CALFACT_D_10 (0x400UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x04000000 */ - -/******************** Bit definition for ADC_CALFACT2 register ********************/ -#define ADC_CALFACT2_LINCALFACT_Pos (0U) -#define ADC_CALFACT2_LINCALFACT_Msk (0x3FFFFFFFUL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x3FFFFFFF */ -#define ADC_CALFACT2_LINCALFACT ADC_CALFACT2_LINCALFACT_Msk /*!< ADC Linearity calibration factors */ -#define ADC_CALFACT2_LINCALFACT_0 (0x00000001UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000001 */ -#define ADC_CALFACT2_LINCALFACT_1 (0x00000002UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000002 */ -#define ADC_CALFACT2_LINCALFACT_2 (0x00000004UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000004 */ -#define ADC_CALFACT2_LINCALFACT_3 (0x00000008UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000008 */ -#define ADC_CALFACT2_LINCALFACT_4 (0x00000010UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000010 */ -#define ADC_CALFACT2_LINCALFACT_5 (0x00000020UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000020 */ -#define ADC_CALFACT2_LINCALFACT_6 (0x00000040UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000040 */ -#define ADC_CALFACT2_LINCALFACT_7 (0x00000080UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000080 */ -#define ADC_CALFACT2_LINCALFACT_8 (0x00000100UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000100 */ -#define ADC_CALFACT2_LINCALFACT_9 (0x00000200UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000200 */ -#define ADC_CALFACT2_LINCALFACT_10 (0x00000400UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000400 */ -#define ADC_CALFACT2_LINCALFACT_11 (0x00000800UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000800 */ -#define ADC_CALFACT2_LINCALFACT_12 (0x00001000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00001000 */ -#define ADC_CALFACT2_LINCALFACT_13 (0x00002000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00002000 */ -#define ADC_CALFACT2_LINCALFACT_14 (0x00004000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00004000 */ -#define ADC_CALFACT2_LINCALFACT_15 (0x00008000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00008000 */ -#define ADC_CALFACT2_LINCALFACT_16 (0x00010000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00010000 */ -#define ADC_CALFACT2_LINCALFACT_17 (0x00020000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00020000 */ -#define ADC_CALFACT2_LINCALFACT_18 (0x00040000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00040000 */ -#define ADC_CALFACT2_LINCALFACT_19 (0x00080000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00080000 */ -#define ADC_CALFACT2_LINCALFACT_20 (0x00100000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00100000 */ -#define ADC_CALFACT2_LINCALFACT_21 (0x00200000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00200000 */ -#define ADC_CALFACT2_LINCALFACT_22 (0x00400000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00400000 */ -#define ADC_CALFACT2_LINCALFACT_23 (0x00800000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00800000 */ -#define ADC_CALFACT2_LINCALFACT_24 (0x01000000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x01000000 */ -#define ADC_CALFACT2_LINCALFACT_25 (0x02000000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x02000000 */ -#define ADC_CALFACT2_LINCALFACT_26 (0x04000000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x04000000 */ -#define ADC_CALFACT2_LINCALFACT_27 (0x08000000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x08000000 */ -#define ADC_CALFACT2_LINCALFACT_28 (0x10000000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x10000000 */ -#define ADC_CALFACT2_LINCALFACT_29 (0x20000000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x20000000 */ - -/************************* ADC Common registers *****************************/ -/******************** Bit definition for ADC_CSR register ********************/ -#define ADC_CSR_ADRDY_MST_Pos (0U) -#define ADC_CSR_ADRDY_MST_Msk (0x1UL << ADC_CSR_ADRDY_MST_Pos) /*!< 0x00000001 */ -#define ADC_CSR_ADRDY_MST ADC_CSR_ADRDY_MST_Msk /*!< Master ADC ready */ -#define ADC_CSR_EOSMP_MST_Pos (1U) -#define ADC_CSR_EOSMP_MST_Msk (0x1UL << ADC_CSR_EOSMP_MST_Pos) /*!< 0x00000002 */ -#define ADC_CSR_EOSMP_MST ADC_CSR_EOSMP_MST_Msk /*!< End of sampling phase flag of the master ADC */ -#define ADC_CSR_EOC_MST_Pos (2U) -#define ADC_CSR_EOC_MST_Msk (0x1UL << ADC_CSR_EOC_MST_Pos) /*!< 0x00000004 */ -#define ADC_CSR_EOC_MST ADC_CSR_EOC_MST_Msk /*!< End of regular conversion of the master ADC */ -#define ADC_CSR_EOS_MST_Pos (3U) -#define ADC_CSR_EOS_MST_Msk (0x1UL << ADC_CSR_EOS_MST_Pos) /*!< 0x00000008 */ -#define ADC_CSR_EOS_MST ADC_CSR_EOS_MST_Msk /*!< End of regular sequence flag of the master ADC */ -#define ADC_CSR_OVR_MST_Pos (4U) -#define ADC_CSR_OVR_MST_Msk (0x1UL << ADC_CSR_OVR_MST_Pos) /*!< 0x00000010 */ -#define ADC_CSR_OVR_MST ADC_CSR_OVR_MST_Msk /*!< Overrun flag of the master ADC */ -#define ADC_CSR_JEOC_MST_Pos (5U) -#define ADC_CSR_JEOC_MST_Msk (0x1UL << ADC_CSR_JEOC_MST_Pos) /*!< 0x00000020 */ -#define ADC_CSR_JEOC_MST ADC_CSR_JEOC_MST_Msk /*!< End of injected conversion of the master ADC */ -#define ADC_CSR_JEOS_MST_Pos (6U) -#define ADC_CSR_JEOS_MST_Msk (0x1UL << ADC_CSR_JEOS_MST_Pos) /*!< 0x00000040 */ -#define ADC_CSR_JEOS_MST ADC_CSR_JEOS_MST_Msk /*!< End of injected sequence flag of the master ADC */ -#define ADC_CSR_AWD1_MST_Pos (7U) -#define ADC_CSR_AWD1_MST_Msk (0x1UL << ADC_CSR_AWD1_MST_Pos) /*!< 0x00000080 */ -#define ADC_CSR_AWD1_MST ADC_CSR_AWD1_MST_Msk /*!< Analog watchdog 1 flag of the master ADC */ -#define ADC_CSR_AWD2_MST_Pos (8U) -#define ADC_CSR_AWD2_MST_Msk (0x1UL << ADC_CSR_AWD2_MST_Pos) /*!< 0x00000100 */ -#define ADC_CSR_AWD2_MST ADC_CSR_AWD2_MST_Msk /*!< Analog watchdog 2 flag of the master ADC */ -#define ADC_CSR_AWD3_MST_Pos (9U) -#define ADC_CSR_AWD3_MST_Msk (0x1UL << ADC_CSR_AWD3_MST_Pos) /*!< 0x00000200 */ -#define ADC_CSR_AWD3_MST ADC_CSR_AWD3_MST_Msk /*!< Analog watchdog 3 flag of the master ADC */ -#define ADC_CSR_JQOVF_MST_Pos (10U) -#define ADC_CSR_JQOVF_MST_Msk (0x1UL << ADC_CSR_JQOVF_MST_Pos) /*!< 0x00000400 */ -#define ADC_CSR_JQOVF_MST ADC_CSR_JQOVF_MST_Msk /*!< Injected context queue overflow flag of the master ADC */ -#define ADC_CSR_ADRDY_SLV_Pos (16U) -#define ADC_CSR_ADRDY_SLV_Msk (0x1UL << ADC_CSR_ADRDY_SLV_Pos) /*!< 0x00010000 */ -#define ADC_CSR_ADRDY_SLV ADC_CSR_ADRDY_SLV_Msk /*!< Slave ADC ready */ -#define ADC_CSR_EOSMP_SLV_Pos (17U) -#define ADC_CSR_EOSMP_SLV_Msk (0x1UL << ADC_CSR_EOSMP_SLV_Pos) /*!< 0x00020000 */ -#define ADC_CSR_EOSMP_SLV ADC_CSR_EOSMP_SLV_Msk /*!< End of sampling phase flag of the slave ADC */ -#define ADC_CSR_EOC_SLV_Pos (18U) -#define ADC_CSR_EOC_SLV_Msk (0x1UL << ADC_CSR_EOC_SLV_Pos) /*!< 0x00040000 */ -#define ADC_CSR_EOC_SLV ADC_CSR_EOC_SLV_Msk /*!< End of regular conversion of the slave ADC */ -#define ADC_CSR_EOS_SLV_Pos (19U) -#define ADC_CSR_EOS_SLV_Msk (0x1UL << ADC_CSR_EOS_SLV_Pos) /*!< 0x00080000 */ -#define ADC_CSR_EOS_SLV ADC_CSR_EOS_SLV_Msk /*!< End of regular sequence flag of the slave ADC */ -#define ADC_CSR_OVR_SLV_Pos (20U) -#define ADC_CSR_OVR_SLV_Msk (0x1UL << ADC_CSR_OVR_SLV_Pos) /*!< 0x00100000 */ -#define ADC_CSR_OVR_SLV ADC_CSR_OVR_SLV_Msk /*!< Overrun flag of the slave ADC */ -#define ADC_CSR_JEOC_SLV_Pos (21U) -#define ADC_CSR_JEOC_SLV_Msk (0x1UL << ADC_CSR_JEOC_SLV_Pos) /*!< 0x00200000 */ -#define ADC_CSR_JEOC_SLV ADC_CSR_JEOC_SLV_Msk /*!< End of injected conversion of the slave ADC */ -#define ADC_CSR_JEOS_SLV_Pos (22U) -#define ADC_CSR_JEOS_SLV_Msk (0x1UL << ADC_CSR_JEOS_SLV_Pos) /*!< 0x00400000 */ -#define ADC_CSR_JEOS_SLV ADC_CSR_JEOS_SLV_Msk /*!< End of injected sequence flag of the slave ADC */ -#define ADC_CSR_AWD1_SLV_Pos (23U) -#define ADC_CSR_AWD1_SLV_Msk (0x1UL << ADC_CSR_AWD1_SLV_Pos) /*!< 0x00800000 */ -#define ADC_CSR_AWD1_SLV ADC_CSR_AWD1_SLV_Msk /*!< Analog watchdog 1 flag of the slave ADC */ -#define ADC_CSR_AWD2_SLV_Pos (24U) -#define ADC_CSR_AWD2_SLV_Msk (0x1UL << ADC_CSR_AWD2_SLV_Pos) /*!< 0x01000000 */ -#define ADC_CSR_AWD2_SLV ADC_CSR_AWD2_SLV_Msk /*!< Analog watchdog 2 flag of the slave ADC */ -#define ADC_CSR_AWD3_SLV_Pos (25U) -#define ADC_CSR_AWD3_SLV_Msk (0x1UL << ADC_CSR_AWD3_SLV_Pos) /*!< 0x02000000 */ -#define ADC_CSR_AWD3_SLV ADC_CSR_AWD3_SLV_Msk /*!< Analog watchdog 3 flag of the slave ADC */ -#define ADC_CSR_JQOVF_SLV_Pos (26U) -#define ADC_CSR_JQOVF_SLV_Msk (0x1UL << ADC_CSR_JQOVF_SLV_Pos) /*!< 0x04000000 */ -#define ADC_CSR_JQOVF_SLV ADC_CSR_JQOVF_SLV_Msk /*!< Injected context queue overflow flag of the slave ADC */ - -/******************** Bit definition for ADC_CCR register ********************/ -#define ADC_CCR_DUAL_Pos (0U) -#define ADC_CCR_DUAL_Msk (0x1FUL << ADC_CCR_DUAL_Pos) /*!< 0x0000001F */ -#define ADC_CCR_DUAL ADC_CCR_DUAL_Msk /*!< Dual ADC mode selection */ -#define ADC_CCR_DUAL_0 (0x01UL << ADC_CCR_DUAL_Pos) /*!< 0x00000001 */ -#define ADC_CCR_DUAL_1 (0x02UL << ADC_CCR_DUAL_Pos) /*!< 0x00000002 */ -#define ADC_CCR_DUAL_2 (0x04UL << ADC_CCR_DUAL_Pos) /*!< 0x00000004 */ -#define ADC_CCR_DUAL_3 (0x08UL << ADC_CCR_DUAL_Pos) /*!< 0x00000008 */ -#define ADC_CCR_DUAL_4 (0x10UL << ADC_CCR_DUAL_Pos) /*!< 0x00000010 */ - -#define ADC_CCR_DELAY_Pos (8U) -#define ADC_CCR_DELAY_Msk (0xFUL << ADC_CCR_DELAY_Pos) /*!< 0x00000F00 */ -#define ADC_CCR_DELAY ADC_CCR_DELAY_Msk /*!< Delay between 2 sampling phases */ -#define ADC_CCR_DELAY_0 (0x1UL << ADC_CCR_DELAY_Pos) /*!< 0x00000100 */ -#define ADC_CCR_DELAY_1 (0x2UL << ADC_CCR_DELAY_Pos) /*!< 0x00000200 */ -#define ADC_CCR_DELAY_2 (0x4UL << ADC_CCR_DELAY_Pos) /*!< 0x00000400 */ -#define ADC_CCR_DELAY_3 (0x8UL << ADC_CCR_DELAY_Pos) /*!< 0x00000800 */ - - -#define ADC_CCR_DAMDF_Pos (14U) -#define ADC_CCR_DAMDF_Msk (0x3UL << ADC_CCR_DAMDF_Pos) /*!< 0x0000C000 */ -#define ADC_CCR_DAMDF ADC_CCR_DAMDF_Msk /*!< Dual ADC mode Data format */ -#define ADC_CCR_DAMDF_0 (0x1UL << ADC_CCR_DAMDF_Pos) /*!< 0x00004000 */ -#define ADC_CCR_DAMDF_1 (0x2UL << ADC_CCR_DAMDF_Pos) /*!< 0x00008000 */ - -#define ADC_CCR_CKMODE_Pos (16U) -#define ADC_CCR_CKMODE_Msk (0x3UL << ADC_CCR_CKMODE_Pos) /*!< 0x00030000 */ -#define ADC_CCR_CKMODE ADC_CCR_CKMODE_Msk /*!< ADC clock mode */ -#define ADC_CCR_CKMODE_0 (0x1UL << ADC_CCR_CKMODE_Pos) /*!< 0x00010000 */ -#define ADC_CCR_CKMODE_1 (0x2UL << ADC_CCR_CKMODE_Pos) /*!< 0x00020000 */ - -#define ADC_CCR_PRESC_Pos (18U) -#define ADC_CCR_PRESC_Msk (0xFUL << ADC_CCR_PRESC_Pos) /*!< 0x003C0000 */ -#define ADC_CCR_PRESC ADC_CCR_PRESC_Msk /*!< ADC prescaler */ -#define ADC_CCR_PRESC_0 (0x1UL << ADC_CCR_PRESC_Pos) /*!< 0x00040000 */ -#define ADC_CCR_PRESC_1 (0x2UL << ADC_CCR_PRESC_Pos) /*!< 0x00080000 */ -#define ADC_CCR_PRESC_2 (0x4UL << ADC_CCR_PRESC_Pos) /*!< 0x00100000 */ -#define ADC_CCR_PRESC_3 (0x8UL << ADC_CCR_PRESC_Pos) /*!< 0x00200000 */ - -#define ADC_CCR_VREFEN_Pos (22U) -#define ADC_CCR_VREFEN_Msk (0x1UL << ADC_CCR_VREFEN_Pos) /*!< 0x00400000 */ -#define ADC_CCR_VREFEN ADC_CCR_VREFEN_Msk /*!< VREFINT enable */ -#define ADC_CCR_TSEN_Pos (23U) -#define ADC_CCR_TSEN_Msk (0x1UL << ADC_CCR_TSEN_Pos) /*!< 0x00800000 */ -#define ADC_CCR_TSEN ADC_CCR_TSEN_Msk /*!< Temperature sensor enable */ -#define ADC_CCR_VBATEN_Pos (24U) -#define ADC_CCR_VBATEN_Msk (0x1UL << ADC_CCR_VBATEN_Pos) /*!< 0x01000000 */ -#define ADC_CCR_VBATEN ADC_CCR_VBATEN_Msk /*!< VBAT enable */ - -/******************** Bit definition for ADC_CDR register *******************/ -#define ADC_CDR_RDATA_MST_Pos (0U) -#define ADC_CDR_RDATA_MST_Msk (0xFFFFUL << ADC_CDR_RDATA_MST_Pos) /*!< 0x0000FFFF */ -#define ADC_CDR_RDATA_MST ADC_CDR_RDATA_MST_Msk /*!< ADC multimode master group regular conversion data */ - -#define ADC_CDR_RDATA_SLV_Pos (16U) -#define ADC_CDR_RDATA_SLV_Msk (0xFFFFUL << ADC_CDR_RDATA_SLV_Pos) /*!< 0xFFFF0000 */ -#define ADC_CDR_RDATA_SLV ADC_CDR_RDATA_SLV_Msk /*!< ADC multimode slave group regular conversion data */ - -/******************** Bit definition for ADC_CDR2 register ******************/ -#define ADC_CDR2_RDATA_ALT_Pos (0U) -#define ADC_CDR2_RDATA_ALT_Msk (0xFFFFFFFFUL << ADC_CDR2_RDATA_ALT_Pos) /*!< 0xFFFFFFFF */ -#define ADC_CDR2_RDATA_ALT ADC_CDR2_RDATA_ALT_Msk /*!< Regular data of the master/slave alternated ADCs */ - - -/******************************************************************************/ -/* */ -/* VREFBUF */ -/* */ -/******************************************************************************/ -/******************* Bit definition for VREFBUF_CSR register ****************/ -#define VREFBUF_CSR_ENVR_Pos (0U) -#define VREFBUF_CSR_ENVR_Msk (0x1UL << VREFBUF_CSR_ENVR_Pos) /*!< 0x00000001 */ -#define VREFBUF_CSR_ENVR VREFBUF_CSR_ENVR_Msk /*!*/ -#define DAC_CR_CEN1_Pos (14U) -#define DAC_CR_CEN1_Msk (0x1UL << DAC_CR_CEN1_Pos) /*!< 0x00004000 */ -#define DAC_CR_CEN1 DAC_CR_CEN1_Msk /*!*/ - -#define DAC_CR_EN2_Pos (16U) -#define DAC_CR_EN2_Msk (0x1UL << DAC_CR_EN2_Pos) /*!< 0x00010000 */ -#define DAC_CR_EN2 DAC_CR_EN2_Msk /*!*/ -#define DAC_CR_CEN2_Pos (30U) -#define DAC_CR_CEN2_Msk (0x1UL << DAC_CR_CEN2_Pos) /*!< 0x40000000 */ -#define DAC_CR_CEN2 DAC_CR_CEN2_Msk /*!*/ - -/***************** Bit definition for DAC_SWTRIGR register ******************/ -#define DAC_SWTRIGR_SWTRIG1_Pos (0U) -#define DAC_SWTRIGR_SWTRIG1_Msk (0x1UL << DAC_SWTRIGR_SWTRIG1_Pos) /*!< 0x00000001 */ -#define DAC_SWTRIGR_SWTRIG1 DAC_SWTRIGR_SWTRIG1_Msk /*!
© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.
- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/** @addtogroup CMSIS - * @{ - */ - -/** @addtogroup stm32h7xx - * @{ - */ - -#ifndef STM32H7xx_H -#define STM32H7xx_H - -#ifdef __cplusplus - extern "C" { -#endif /* __cplusplus */ - -/** @addtogroup Library_configuration_section - * @{ - */ - -/** - * @brief STM32 Family - */ -#if !defined (STM32H7) -#define STM32H7 -#endif /* STM32H7 */ - - -/* Uncomment the line below according to the target STM32H7 device used in your - application - */ - -/* #if !defined (STM32H743xx) && !defined (STM32H753xx) && !defined (STM32H750xx) && !defined (STM32H742xx) && \ - !defined (STM32H745xx) && !defined (STM32H755xx) && !defined (STM32H747xx) && !defined (STM32H757xx) && \ - !defined (STM32H7A3xx) && !defined (STM32H7A3xxQ) && !defined (STM32H7B3xx) && !defined (STM32H7B3xxQ) && !defined (STM32H7B0xx) && !defined (STM32H7B0xxQ) && \ - !defined (STM32H735xx) && !defined (STM32H733xx) && !defined (STM32H730xx) && !defined (STM32H730xxQ) && !defined (STM32H725xx) && !defined (STM32H723xx) */ - /* #define STM32H742xx */ /*!< STM32H742VI, STM32H742ZI, STM32H742AI, STM32H742II, STM32H742BI, STM32H742XI Devices */ - /* #define STM32H743xx */ /*!< STM32H743VI, STM32H743ZI, STM32H743AI, STM32H743II, STM32H743BI, STM32H743XI Devices */ - /* #define STM32H753xx */ /*!< STM32H753VI, STM32H753ZI, STM32H753AI, STM32H753II, STM32H753BI, STM32H753XI Devices */ - /* #define STM32H750xx */ /*!< STM32H750V, STM32H750I, STM32H750X Devices */ - /* #define STM32H747xx */ /*!< STM32H747ZI, STM32H747AI, STM32H747II, STM32H747BI, STM32H747XI Devices */ - /* #define STM32H757xx */ /*!< STM32H757ZI, STM32H757AI, STM32H757II, STM32H757BI, STM32H757XI Devices */ - /* #define STM32H745xx */ /*!< STM32H745ZI, STM32H745II, STM32H745BI, STM32H745XI Devices */ - /* #define STM32H755xx */ /*!< STM32H755ZI, STM32H755II, STM32H755BI, STM32H755XI Devices */ - /* #define STM32H7B0xx */ /*!< STM32H7B0ABIxQ, STM32H7B0IBTx, STM32H7B0RBTx, STM32H7B0VBTx, STM32H7B0ZBTx, STM32H7B0IBKxQ */ - /* #define STM32H7A3xx */ /*!< STM32H7A3IIK6, STM32H7A3IIT6, STM32H7A3NIH6, STM32H7A3RIT6, STM32H7A3VIH6, STM32H7A3VIT6, STM32H7A3ZIT6 */ - /* #define STM32H7A3xxQ */ /*!< STM32H7A3QIY6Q, STM32H7A3IIK6Q, STM32H7A3IIT6Q, STM32H7A3LIH6Q, STM32H7A3VIH6Q, STM32H7A3VIT6Q, STM32H7A3AII6Q, STM32H7A3ZIT6Q */ - /* #define STM32H7B3xx */ /*!< STM32H7B3IIK6, STM32H7B3IIT6, STM32H7B3NIH6, STM32H7B3RIT6, STM32H7B3VIH6, STM32H7B3VIT6, STM32H7B3ZIT6 */ - /* #define STM32H7B3xxQ */ /*!< STM32H7B3QIY6Q, STM32H7B3IIK6Q, STM32H7B3IIT6Q, STM32H7B3LIH6Q, STM32H7B3VIH6Q, STM32H7B3VIT6Q, STM32H7B3AII6Q, STM32H7B3ZIT6Q */ - /* #define STM32H735xx */ /*!< STM32H735AGI6, STM32H735IGK6, STM32H735RGV6, STM32H735VGT6, STM32H735VGY6, STM32H735ZGT6 Devices */ - /* #define STM32H733xx */ /*!< STM32H733VGH6, STM32H733VGT6, STM32H733ZGI6, STM32H733ZGT6, Devices */ - /* #define STM32H730xx */ /*!< STM32H730VBH6, STM32H730VBT6, STM32H730ZBT6, STM32H730ZBI6 Devices */ - /* #define STM32H730xxQ */ /*!< STM32H730IBT6Q, STM32H730ABI6Q, STM32H730IBK6Q Devices */ - /* #define STM32H725xx */ /*!< STM32H725AGI6, STM32H725IGK6, STM32H725IGT6, STM32H725RGV6, STM32H725VGT6, STM32H725VGY6, STM32H725ZGT6, STM32H725REV6, SM32H725VET6, STM32H725ZET6, STM32H725AEI6, STM32H725IET6, STM32H725IEK6 Devices */ - /* #define STM32H723xx */ /*!< STM32H723VGH6, STM32H723VGT6, STM32H723ZGI6, STM32H723ZGT6, STM32H723VET6, STM32H723VEH6, STM32H723ZET6, STM32H723ZEI6 Devices */ -/* #endif */ - -/* Tip: To avoid modifying this file each time you need to switch between these - devices, you can define the device in your toolchain compiler preprocessor. - */ - -#if defined(DUAL_CORE) && !defined(CORE_CM4) && !defined(CORE_CM7) - #error "Dual core device, please select CORE_CM4 or CORE_CM7" -#endif - -#if !defined (USE_HAL_DRIVER) -/** - * @brief Comment the line below if you will not use the peripherals drivers. - In this case, these drivers will not be included and the application code will - be based on direct access to peripherals registers - */ - /*#define USE_HAL_DRIVER */ -#endif /* USE_HAL_DRIVER */ - -/** - * @brief CMSIS Device version number V1.10.0 - */ -#define __STM32H7xx_CMSIS_DEVICE_VERSION_MAIN (0x01) /*!< [31:24] main version */ -#define __STM32H7xx_CMSIS_DEVICE_VERSION_SUB1 (0x0A) /*!< [23:16] sub1 version */ -#define __STM32H7xx_CMSIS_DEVICE_VERSION_SUB2 (0x00) /*!< [15:8] sub2 version */ -#define __STM32H7xx_CMSIS_DEVICE_VERSION_RC (0x00) /*!< [7:0] release candidate */ -#define __STM32H7xx_CMSIS_DEVICE_VERSION ((__STM32H7xx_CMSIS_DEVICE_VERSION_MAIN << 24)\ - |(__STM32H7xx_CMSIS_DEVICE_VERSION_SUB1 << 16)\ - |(__STM32H7xx_CMSIS_DEVICE_VERSION_SUB2 << 8 )\ - |(__STM32H7xx_CMSIS_DEVICE_VERSION_RC)) - -/** - * @} - */ - -/** @addtogroup Device_Included - * @{ - */ - -#if defined(STM32H743xx) - #include "stm32h743xx.h" -// #elif defined(STM32H753xx) -// #include "stm32h753xx.h" -// #elif defined(STM32H750xx) -// #include "stm32h750xx.h" -// #elif defined(STM32H742xx) -// #include "stm32h742xx.h" -// #elif defined(STM32H745xx) -// #include "stm32h745xx.h" -// #elif defined(STM32H755xx) -// #include "stm32h755xx.h" -// #elif defined(STM32H747xx) -// #include "stm32h747xx.h" -// #elif defined(STM32H757xx) -// #include "stm32h757xx.h" -// #elif defined(STM32H7B0xx) -// #include "stm32h7b0xx.h" -// #elif defined(STM32H7B0xxQ) -// #include "stm32h7b0xxq.h" -// #elif defined(STM32H7A3xx) -// #include "stm32h7a3xx.h" -// #elif defined(STM32H7B3xx) -// #include "stm32h7b3xx.h" -// #elif defined(STM32H7A3xxQ) -// #include "stm32h7a3xxq.h" -// #elif defined(STM32H7B3xxQ) -// #include "stm32h7b3xxq.h" -#elif defined(STM32H735xx) - #include "stm32h735xx.h" -// #elif defined(STM32H733xx) -// #include "stm32h733xx.h" -// #elif defined(STM32H730xx) -// #include "stm32h730xx.h" -// #elif defined(STM32H730xxQ) -// #include "stm32h730xxq.h" -#elif defined(STM32H725xx) - #include "stm32h725xx.h" -// #elif defined(STM32H723xx) -// #include "stm32h723xx.h" -#else - #error "Please select first the target STM32H7xx device used in your application (in stm32h7xx.h file)" -#endif - -/** - * @} - */ - -/** @addtogroup Exported_types - * @{ - */ -typedef enum -{ - RESET = 0, - SET = !RESET -} FlagStatus, ITStatus; - -typedef enum -{ - DISABLE = 0, - ENABLE = !DISABLE -} FunctionalState; -#define IS_FUNCTIONAL_STATE(STATE) (((STATE) == DISABLE) || ((STATE) == ENABLE)) - -typedef enum -{ - SUCCESS = 0, - ERROR = !SUCCESS -} ErrorStatus; - -/** - * @} - */ - - -/** @addtogroup Exported_macros - * @{ - */ -#define SET_BIT(REG, BIT) ((REG) |= (BIT)) - -#define CLEAR_BIT(REG, BIT) ((REG) &= ~(BIT)) - -#define READ_BIT(REG, BIT) ((REG) & (BIT)) - -#define CLEAR_REG(REG) ((REG) = (0x0)) - -#define WRITE_REG(REG, VAL) ((REG) = (VAL)) - -#define READ_REG(REG) ((REG)) - -#define MODIFY_REG(REG, CLEARMASK, SETMASK) WRITE_REG((REG), (((READ_REG(REG)) & (~(CLEARMASK))) | (SETMASK))) - -#define POSITION_VAL(VAL) (__CLZ(__RBIT(VAL))) - - -/** - * @} - */ - -#if defined (USE_HAL_DRIVER) - #include "stm32h7xx_hal.h" -#endif /* USE_HAL_DRIVER */ - - -#ifdef __cplusplus -} -#endif /* __cplusplus */ - -#endif /* STM32H7xx_H */ -/** - * @} - */ - -/** - * @} - */ - - - - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/panda/board/stm32h7/inc/stm32h7xx_hal_def.h b/panda/board/stm32h7/inc/stm32h7xx_hal_def.h deleted file mode 100644 index 3854b1cd3..000000000 --- a/panda/board/stm32h7/inc/stm32h7xx_hal_def.h +++ /dev/null @@ -1,221 +0,0 @@ -/** - ****************************************************************************** - * @file stm32h7xx_hal_def.h - * @author MCD Application Team - * @brief This file contains HAL common defines, enumeration, macros and - * structures definitions. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32H7xx_HAL_DEF -#define STM32H7xx_HAL_DEF - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32h7xx.h" -//#include "Legacy/stm32_hal_legacy.h" -//#include -//#include - -/* Exported types ------------------------------------------------------------*/ - -/** - * @brief HAL Status structures definition - */ -typedef enum -{ - HAL_OK = 0x00, - HAL_ERROR = 0x01, - HAL_BUSY = 0x02, - HAL_TIMEOUT = 0x03 -} HAL_StatusTypeDef; - -/** - * @brief HAL Lock structures definition - */ -typedef enum -{ - HAL_UNLOCKED = 0x00, - HAL_LOCKED = 0x01 -} HAL_LockTypeDef; - -/* Exported macro ------------------------------------------------------------*/ - -#define HAL_MAX_DELAY 0xFFFFFFFFU - -#define HAL_IS_BIT_SET(REG, BIT) (((REG) & (BIT)) == (BIT)) -#define HAL_IS_BIT_CLR(REG, BIT) (((REG) & (BIT)) == 0U) - -#define __HAL_LINKDMA(__HANDLE__, __PPP_DMA_FIELD__, __DMA_HANDLE__) \ - do{ \ - (__HANDLE__)->__PPP_DMA_FIELD__ = &(__DMA_HANDLE__); \ - (__DMA_HANDLE__).Parent = (__HANDLE__); \ - } while(0) - -#define UNUSED(x) ((void)(x)) - -/** @brief Reset the Handle's State field. - * @param __HANDLE__: specifies the Peripheral Handle. - * @note This macro can be used for the following purpose: - * - When the Handle is declared as local variable; before passing it as parameter - * to HAL_PPP_Init() for the first time, it is mandatory to use this macro - * to set to 0 the Handle's "State" field. - * Otherwise, "State" field may have any random value and the first time the function - * HAL_PPP_Init() is called, the low level hardware initialization will be missed - * (i.e. HAL_PPP_MspInit() will not be executed). - * - When there is a need to reconfigure the low level hardware: instead of calling - * HAL_PPP_DeInit() then HAL_PPP_Init(), user can make a call to this macro then HAL_PPP_Init(). - * In this later function, when the Handle's "State" field is set to 0, it will execute the function - * HAL_PPP_MspInit() which will reconfigure the low level hardware. - * @retval None - */ -#define __HAL_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = 0) - -#if (USE_RTOS == 1) - #error " USE_RTOS should be 0 in the current HAL release " -#else - #define __HAL_LOCK(__HANDLE__) \ - do{ \ - if((__HANDLE__)->Lock == HAL_LOCKED) \ - { \ - return HAL_BUSY; \ - } \ - else \ - { \ - (__HANDLE__)->Lock = HAL_LOCKED; \ - } \ - }while (0) - - #define __HAL_UNLOCK(__HANDLE__) \ - do{ \ - (__HANDLE__)->Lock = HAL_UNLOCKED; \ - }while (0) -#endif /* USE_RTOS */ - - -#if defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) /* ARM Compiler V6 */ - #ifndef __weak - #define __weak __attribute__((weak)) - #endif - #ifndef __packed - #define __packed __attribute__((packed)) - #endif -#elif defined ( __GNUC__ ) && !defined (__CC_ARM) /* GNU Compiler */ - #ifndef __weak - #define __weak __attribute__((weak)) - #endif /* __weak */ - #ifndef __packed - #define __packed __attribute__((__packed__)) - #endif /* __packed */ -#endif /* __GNUC__ */ - - -/* Macro to get variable aligned on 4-bytes, for __ICCARM__ the directive "#pragma data_alignment=4" must be used instead */ -#if defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) /* ARM Compiler V6 */ - #ifndef __ALIGN_BEGIN - #define __ALIGN_BEGIN - #endif - #ifndef __ALIGN_END - #define __ALIGN_END __attribute__ ((aligned (4))) - #endif -#elif defined ( __GNUC__ ) && !defined (__CC_ARM) /* GNU Compiler */ - #ifndef __ALIGN_END - #define __ALIGN_END __attribute__ ((aligned (4))) - #endif /* __ALIGN_END */ - #ifndef __ALIGN_BEGIN - #define __ALIGN_BEGIN - #endif /* __ALIGN_BEGIN */ -#else - #ifndef __ALIGN_END - #define __ALIGN_END - #endif /* __ALIGN_END */ - #ifndef __ALIGN_BEGIN - #if defined (__CC_ARM) /* ARM Compiler V5 */ - #define __ALIGN_BEGIN __align(4) - #elif defined (__ICCARM__) /* IAR Compiler */ - #define __ALIGN_BEGIN - #endif /* __CC_ARM */ - #endif /* __ALIGN_BEGIN */ -#endif /* __GNUC__ */ - -/* Macro to get variable aligned on 32-bytes,needed for cache maintenance purpose */ -#if defined (__GNUC__) /* GNU Compiler */ - #define ALIGN_32BYTES(buf) buf __attribute__ ((aligned (32))) -#elif defined (__ICCARM__) /* IAR Compiler */ - #define ALIGN_32BYTES(buf) _Pragma("data_alignment=32") buf -#elif defined (__CC_ARM) /* ARM Compiler */ - #define ALIGN_32BYTES(buf) __align(32) buf -#endif - -/** - * @brief __RAM_FUNC definition - */ -#if defined ( __CC_ARM ) || (defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)) -/* ARM Compiler V4/V5 and V6 - -------------------------- - RAM functions are defined using the toolchain options. - Functions that are executed in RAM should reside in a separate source module. - Using the 'Options for File' dialog you can simply change the 'Code / Const' - area of a module to a memory space in physical RAM. - Available memory areas are declared in the 'Target' tab of the 'Options for Target' - dialog. -*/ -#define __RAM_FUNC - -#elif defined ( __ICCARM__ ) -/* ICCARM Compiler - --------------- - RAM functions are defined using a specific toolchain keyword "__ramfunc". -*/ -#define __RAM_FUNC __ramfunc - -#elif defined ( __GNUC__ ) -/* GNU Compiler - ------------ - RAM functions are defined using a specific toolchain attribute - "__attribute__((section(".RamFunc")))". -*/ -#define __RAM_FUNC __attribute__((section(".RamFunc"))) - -#endif - -/** - * @brief __NOINLINE definition - */ -#if defined ( __CC_ARM ) || (defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)) || defined ( __GNUC__ ) -/* ARM V4/V5 and V6 & GNU Compiler - ------------------------------- -*/ -#define __NOINLINE __attribute__ ( (noinline) ) - -#elif defined ( __ICCARM__ ) -/* ICCARM Compiler - --------------- -*/ -#define __NOINLINE _Pragma("optimize = no_inline") - -#endif - - -#ifdef __cplusplus -} -#endif - -#endif /* STM32H7xx_HAL_DEF */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/panda/board/stm32h7/inc/stm32h7xx_hal_gpio_ex.h b/panda/board/stm32h7/inc/stm32h7xx_hal_gpio_ex.h deleted file mode 100644 index 14f576a42..000000000 --- a/panda/board/stm32h7/inc/stm32h7xx_hal_gpio_ex.h +++ /dev/null @@ -1,489 +0,0 @@ -/** - ****************************************************************************** - * @file stm32h7xx_hal_gpio_ex.h - * @author MCD Application Team - * @brief Header file of GPIO HAL Extension module. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT(c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32H7xx_HAL_GPIO_EX_H -#define STM32H7xx_HAL_GPIO_EX_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32h7xx_hal_def.h" - -/** @addtogroup STM32H7xx_HAL_Driver - * @{ - */ - -/** @addtogroup GPIOEx GPIOEx - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup GPIOEx_Exported_Constants GPIO Exported Constants - * @{ - */ - -/** @defgroup GPIO_Alternate_function_selection GPIO Alternate Function Selection - * @{ - */ - -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_LCDBIAS ((uint8_t)0x00) /* LCDBIAS Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ -#if defined (PWR_CPUCR_PDDS_D2) /* PWR D1 and D2 domains exists */ -#define GPIO_AF0_C1DSLEEP ((uint8_t)0x00) /* Cortex-M7 Deep Sleep Alternate Function mapping : available on STM32H7 Rev.B and above */ -#define GPIO_AF0_C1SLEEP ((uint8_t)0x00) /* Cortex-M7 Sleep Alternate Function mapping : available on STM32H7 Rev.B and above */ -#define GPIO_AF0_D1PWREN ((uint8_t)0x00) /* Domain 1 PWR enable Alternate Function mapping : available on STM32H7 Rev.B and above */ -#define GPIO_AF0_D2PWREN ((uint8_t)0x00) /* Domain 2 PWR enable Alternate Function mapping : available on STM32H7 Rev.B and above */ -#if defined(DUAL_CORE) -#define GPIO_AF0_C2DSLEEP ((uint8_t)0x00) /* Cortex-M4 Deep Sleep Alternate Function mapping : available on STM32H7 Rev.B and above */ -#define GPIO_AF0_C2SLEEP ((uint8_t)0x00) /* Cortex-M4 Sleep Alternate Function mapping : available on STM32H7 Rev.B and above */ -#endif /* DUAL_CORE */ -#endif /* PWR_CPUCR_PDDS_D2 */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */ -#define GPIO_AF1_TIM16 ((uint8_t)0x01) /* TIM16 Alternate Function mapping */ -#define GPIO_AF1_TIM17 ((uint8_t)0x01) /* TIM17 Alternate Function mapping */ -#define GPIO_AF1_LPTIM1 ((uint8_t)0x01) /* LPTIM1 Alternate Function mapping */ -#if defined(HRTIM1) -#define GPIO_AF1_HRTIM1 ((uint8_t)0x01) /* HRTIM1 Alternate Function mapping */ -#endif /* HRTIM1 */ -#if defined(SAI4) -#define GPIO_AF1_SAI4 ((uint8_t)0x01) /* SAI4 Alternate Function mapping : available on STM32H72xxx/STM32H73xxx */ -#endif /* SAI4 */ -#define GPIO_AF1_FMC ((uint8_t)0x01) /* FMC Alternate Function mapping : available on STM32H72xxx/STM32H73xxx */ - - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ -#define GPIO_AF2_TIM12 ((uint8_t)0x02) /* TIM12 Alternate Function mapping */ -#define GPIO_AF2_SAI1 ((uint8_t)0x02) /* SAI1 Alternate Function mapping */ -#if defined(HRTIM1) -#define GPIO_AF2_HRTIM1 ((uint8_t)0x02) /* HRTIM1 Alternate Function mapping */ -#endif /* HRTIM1 */ -#define GPIO_AF2_TIM15 ((uint8_t)0x02) /* TIM15 Alternate Function mapping : available on STM32H7A3xxx/STM32H7B3xxx/STM32H7B0xxx and STM32H72xxx/STM32H73xxx */ -#if defined(FDCAN3) -#define GPIO_AF2_FDCAN3 ((uint8_t)0x02) /* FDCAN3 Alternate Function mapping */ -#endif /*FDCAN3*/ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM8 ((uint8_t)0x03) /* TIM8 Alternate Function mapping */ -#define GPIO_AF3_LPTIM2 ((uint8_t)0x03) /* LPTIM2 Alternate Function mapping */ -#define GPIO_AF3_DFSDM1 ((uint8_t)0x03) /* DFSDM Alternate Function mapping */ -#define GPIO_AF3_LPTIM3 ((uint8_t)0x03) /* LPTIM3 Alternate Function mapping */ -#define GPIO_AF3_LPTIM4 ((uint8_t)0x03) /* LPTIM4 Alternate Function mapping */ -#define GPIO_AF3_LPTIM5 ((uint8_t)0x03) /* LPTIM5 Alternate Function mapping */ -#define GPIO_AF3_LPUART ((uint8_t)0x03) /* LPUART Alternate Function mapping */ -#if defined(OCTOSPIM) -#define GPIO_AF3_OCTOSPIM_P1 ((uint8_t)0x03) /* OCTOSPI Manager Port 1 Alternate Function mapping */ -#define GPIO_AF3_OCTOSPIM_P2 ((uint8_t)0x03) /* OCTOSPI Manager Port 2 Alternate Function mapping */ -#endif /* OCTOSPIM */ -#if defined(HRTIM1) -#define GPIO_AF3_HRTIM1 ((uint8_t)0x03) /* HRTIM1 Alternate Function mapping */ -#endif /* HRTIM1 */ -#define GPIO_AF3_LTDC ((uint8_t)0x03) /* LTDC Alternate Function mapping : available on STM32H72xxx/STM32H73xxx */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04) /* I2C3 Alternate Function mapping */ -#define GPIO_AF4_I2C4 ((uint8_t)0x04) /* I2C4 Alternate Function mapping */ -#if defined(I2C5) -#define GPIO_AF4_I2C5 ((uint8_t)0x04) /* I2C5 Alternate Function mapping */ -#endif /* I2C5*/ -#define GPIO_AF4_TIM15 ((uint8_t)0x04) /* TIM15 Alternate Function mapping */ -#define GPIO_AF4_CEC ((uint8_t)0x04) /* CEC Alternate Function mapping */ -#define GPIO_AF4_LPTIM2 ((uint8_t)0x04) /* LPTIM2 Alternate Function mapping */ -#define GPIO_AF4_USART1 ((uint8_t)0x04) /* USART1 Alternate Function mapping */ -#if defined(USART10) -#define GPIO_AF4_USART10 ((uint8_t)0x04) /* USART10 Alternate Function mapping : available on STM32H72xxx/STM32H73xxx */ -#endif /*USART10*/ -#define GPIO_AF4_DFSDM1 ((uint8_t)0x04) /* DFSDM Alternate Function mapping */ -#if defined(DFSDM2_BASE) -#define GPIO_AF4_DFSDM2 ((uint8_t)0x04) /* DFSDM2 Alternate Function mapping */ -#endif /* DFSDM2_BASE */ -#define GPIO_AF4_DCMI ((uint8_t)0x04) /* DCMI Alternate Function mapping : available on STM32H7A3xxx/STM32H7B3xxx/STM32H7B0xxx and STM32H72xxx/STM32H73xxx */ -#if defined(PSSI) -#define GPIO_AF4_PSSI ((uint8_t)0x04) /* PSSI Alternate Function mapping */ -#endif /* PSSI */ -#if defined(OCTOSPIM) -#define GPIO_AF4_OCTOSPIM_P1 ((uint8_t)0x04) /* OCTOSPI Manager Port 1 Alternate Function mapping : available on STM32H72xxx/STM32H73xxx */ -#endif /* OCTOSPIM */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2 Alternate Function mapping */ -#define GPIO_AF5_SPI3 ((uint8_t)0x05) /* SPI3 Alternate Function mapping */ -#define GPIO_AF5_SPI4 ((uint8_t)0x05) /* SPI4 Alternate Function mapping */ -#define GPIO_AF5_SPI5 ((uint8_t)0x05) /* SPI5 Alternate Function mapping */ -#define GPIO_AF5_SPI6 ((uint8_t)0x05) /* SPI6 Alternate Function mapping */ -#define GPIO_AF5_CEC ((uint8_t)0x05) /* CEC Alternate Function mapping */ -#if defined(FDCAN3) -#define GPIO_AF5_FDCAN3 ((uint8_t)0x05) /* FDCAN3 Alternate Function mapping */ -#endif /*FDCAN3*/ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI2 ((uint8_t)0x06) /* SPI2 Alternate Function mapping */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06) /* SPI3 Alternate Function mapping */ -#define GPIO_AF6_SAI1 ((uint8_t)0x06) /* SAI1 Alternate Function mapping */ -#define GPIO_AF6_I2C4 ((uint8_t)0x06) /* I2C4 Alternate Function mapping */ -#if defined(I2C5) -#define GPIO_AF6_I2C5 ((uint8_t)0x06) /* I2C5 Alternate Function mapping */ -#endif /* I2C5*/ -#define GPIO_AF6_DFSDM1 ((uint8_t)0x06) /* DFSDM Alternate Function mapping */ -#define GPIO_AF6_UART4 ((uint8_t)0x06) /* UART4 Alternate Function mapping */ -#if defined(DFSDM2_BASE) -#define GPIO_AF6_DFSDM2 ((uint8_t)0x06) /* DFSDM2 Alternate Function mapping */ -#endif /* DFSDM2_BASE */ -#if defined(SAI3) -#define GPIO_AF6_SAI3 ((uint8_t)0x06) /* SAI3 Alternate Function mapping */ -#endif /* SAI3 */ -#if defined(OCTOSPIM) -#define GPIO_AF6_OCTOSPIM_P1 ((uint8_t)0x06) /* OCTOSPI Manager Port 1 Alternate Function mapping */ -#endif /* OCTOSPIM */ - -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_SPI2 ((uint8_t)0x07) /* SPI2 Alternate Function mapping */ -#define GPIO_AF7_SPI3 ((uint8_t)0x07) /* SPI3 Alternate Function mapping */ -#define GPIO_AF7_SPI6 ((uint8_t)0x07) /* SPI6 Alternate Function mapping */ -#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_USART3 ((uint8_t)0x07) /* USART3 Alternate Function mapping */ -#define GPIO_AF7_USART6 ((uint8_t)0x07) /* USART6 Alternate Function mapping */ -#define GPIO_AF7_UART7 ((uint8_t)0x07) /* UART7 Alternate Function mapping */ -#define GPIO_AF7_SDMMC1 ((uint8_t)0x07) /* SDMMC1 Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_SPI6 ((uint8_t)0x08) /* SPI6 Alternate Function mapping */ -#if defined(SAI2) -#define GPIO_AF8_SAI2 ((uint8_t)0x08) /* SAI2 Alternate Function mapping */ -#endif /*SAI2*/ -#define GPIO_AF8_UART4 ((uint8_t)0x08) /* UART4 Alternate Function mapping */ -#define GPIO_AF8_UART5 ((uint8_t)0x08) /* UART5 Alternate Function mapping */ -#define GPIO_AF8_UART8 ((uint8_t)0x08) /* UART8 Alternate Function mapping */ -#define GPIO_AF8_SPDIF ((uint8_t)0x08) /* SPDIF Alternate Function mapping */ -#define GPIO_AF8_LPUART ((uint8_t)0x08) /* LPUART Alternate Function mapping */ -#define GPIO_AF8_SDMMC1 ((uint8_t)0x08) /* SDMMC1 Alternate Function mapping */ -#if defined(SAI4) -#define GPIO_AF8_SAI4 ((uint8_t)0x08) /* SAI4 Alternate Function mapping */ -#endif /* SAI4 */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_FDCAN1 ((uint8_t)0x09) /* FDCAN1 Alternate Function mapping */ -#define GPIO_AF9_FDCAN2 ((uint8_t)0x09) /* FDCAN2 Alternate Function mapping */ -#define GPIO_AF9_TIM13 ((uint8_t)0x09) /* TIM13 Alternate Function mapping */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09) /* TIM14 Alternate Function mapping */ -#define GPIO_AF9_SDMMC2 ((uint8_t)0x09) /* SDMMC2 Alternate Function mapping */ -#define GPIO_AF9_LTDC ((uint8_t)0x09) /* LTDC Alternate Function mapping */ -#define GPIO_AF9_SPDIF ((uint8_t)0x09) /* SPDIF Alternate Function mapping */ -#define GPIO_AF9_FMC ((uint8_t)0x09) /* FMC Alternate Function mapping */ -#if defined(QUADSPI) -#define GPIO_AF9_QUADSPI ((uint8_t)0x09) /* QUADSPI Alternate Function mapping */ -#endif /* QUADSPI */ -#if defined(SAI4) -#define GPIO_AF9_SAI4 ((uint8_t)0x09) /* SAI4 Alternate Function mapping */ -#endif /* SAI4 */ -#if defined(OCTOSPIM) -#define GPIO_AF9_OCTOSPIM_P1 ((uint8_t)0x09) /* OCTOSPI Manager Port 1 Alternate Function mapping */ -#define GPIO_AF9_OCTOSPIM_P2 ((uint8_t)0x09) /* OCTOSPI Manager Port 2 Alternate Function mapping */ -#endif /* OCTOSPIM */ - -/** - * @brief AF 10 selection - */ -#if defined(SAI2) -#define GPIO_AF10_SAI2 ((uint8_t)0x0A) /* SAI2 Alternate Function mapping */ -#endif /*SAI2*/ -#define GPIO_AF10_SDMMC2 ((uint8_t)0x0A) /* SDMMC2 Alternate Function mapping */ -#if defined(USB2_OTG_FS) -#define GPIO_AF10_OTG2_FS ((uint8_t)0x0A) /* OTG2_FS Alternate Function mapping */ -#endif /*USB2_OTG_FS*/ -#define GPIO_AF10_COMP1 ((uint8_t)0x0A) /* COMP1 Alternate Function mapping */ -#define GPIO_AF10_COMP2 ((uint8_t)0x0A) /* COMP2 Alternate Function mapping */ -#if defined(LTDC) -#define GPIO_AF10_LTDC ((uint8_t)0x0A) /* LTDC Alternate Function mapping */ -#endif /*LTDC*/ -#define GPIO_AF10_CRS_SYNC ((uint8_t)0x0A) /* CRS Sync Alternate Function mapping : available on STM32H7 Rev.B and above */ -#if defined(QUADSPI) -#define GPIO_AF10_QUADSPI ((uint8_t)0x0A) /* QUADSPI Alternate Function mapping */ -#endif /* QUADSPI */ -#if defined(SAI4) -#define GPIO_AF10_SAI4 ((uint8_t)0x0A) /* SAI4 Alternate Function mapping */ -#endif /* SAI4 */ -#if !defined(USB2_OTG_FS) -#define GPIO_AF10_OTG1_FS ((uint8_t)0x0A) /* OTG1_FS Alternate Function mapping : available on STM32H7A3xxx/STM32H7B3xxx/STM32H7B0xxx and STM32H72xxx/STM32H73xxx */ -#endif /* !USB2_OTG_FS */ -#define GPIO_AF10_OTG1_HS ((uint8_t)0x0A) /* OTG1_HS Alternate Function mapping */ -#if defined(OCTOSPIM) -#define GPIO_AF10_OCTOSPIM_P1 ((uint8_t)0x0A) /* OCTOSPI Manager Port 1 Alternate Function mapping */ -#endif /* OCTOSPIM */ -#define GPIO_AF10_TIM8 ((uint8_t)0x0A) /* TIM8 Alternate Function mapping */ -#define GPIO_AF10_FMC ((uint8_t)0x0A) /* FMC Alternate Function mapping : available on STM32H7A3xxx/STM32H7B3xxx/STM32H7B0xxx and STM32H72xxx/STM32H73xxx */ - -/** - * @brief AF 11 selection - */ -#define GPIO_AF11_SWP ((uint8_t)0x0B) /* SWP Alternate Function mapping */ -#define GPIO_AF11_MDIOS ((uint8_t)0x0B) /* MDIOS Alternate Function mapping */ -#define GPIO_AF11_UART7 ((uint8_t)0x0B) /* UART7 Alternate Function mapping */ -#define GPIO_AF11_SDMMC2 ((uint8_t)0x0B) /* SDMMC2 Alternate Function mapping */ -#define GPIO_AF11_DFSDM1 ((uint8_t)0x0B) /* DFSDM1 Alternate Function mapping */ -#define GPIO_AF11_COMP1 ((uint8_t)0x0B) /* COMP1 Alternate Function mapping */ -#define GPIO_AF11_COMP2 ((uint8_t)0x0B) /* COMP2 Alternate Function mapping */ -#define GPIO_AF11_TIM1 ((uint8_t)0x0B) /* TIM1 Alternate Function mapping */ -#define GPIO_AF11_TIM8 ((uint8_t)0x0B) /* TIM8 Alternate Function mapping */ -#define GPIO_AF11_I2C4 ((uint8_t)0x0B) /* I2C4 Alternate Function mapping */ -#if defined(DFSDM2_BASE) -#define GPIO_AF11_DFSDM2 ((uint8_t)0x0B) /* DFSDM2 Alternate Function mapping */ -#endif /* DFSDM2_BASE */ -#if defined(USART10) -#define GPIO_AF11_USART10 ((uint8_t)0x0B) /* USART10 Alternate Function mapping */ -#endif /* USART10 */ -#if defined(UART9) -#define GPIO_AF11_UART9 ((uint8_t)0x0B) /* UART9 Alternate Function mapping */ -#endif /* UART9 */ -#if defined(ETH) -#define GPIO_AF11_ETH ((uint8_t)0x0B) /* ETH Alternate Function mapping */ -#endif /* ETH */ -#if defined(LTDC) -#define GPIO_AF11_LTDC ((uint8_t)0x0B) /* LTDC Alternate Function mapping : available on STM32H7A3xxx/STM32H7B3xxx/STM32H7B0xxx and STM32H72xxx/STM32H73xxx */ -#endif /*LTDC*/ -#if defined(OCTOSPIM) -#define GPIO_AF11_OCTOSPIM_P1 ((uint8_t)0x0B) /* OCTOSPI Manager Port 1 Alternate Function mapping */ -#endif /* OCTOSPIM */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_FMC ((uint8_t)0x0C) /* FMC Alternate Function mapping */ -#define GPIO_AF12_SDMMC1 ((uint8_t)0x0C) /* SDMMC1 Alternate Function mapping */ -#define GPIO_AF12_MDIOS ((uint8_t)0x0C) /* MDIOS Alternate Function mapping */ -#define GPIO_AF12_COMP1 ((uint8_t)0x0C) /* COMP1 Alternate Function mapping */ -#define GPIO_AF12_COMP2 ((uint8_t)0x0C) /* COMP2 Alternate Function mapping */ -#define GPIO_AF12_TIM1 ((uint8_t)0x0C) /* TIM1 Alternate Function mapping */ -#define GPIO_AF12_TIM8 ((uint8_t)0x0C) /* TIM8 Alternate Function mapping */ -#if defined(LTDC) -#define GPIO_AF12_LTDC ((uint8_t)0x0C) /* LTDC Alternate Function mapping */ -#endif /*LTDC*/ -#if defined(USB2_OTG_FS) -#define GPIO_AF12_OTG1_FS ((uint8_t)0x0C) /* OTG1_FS Alternate Function mapping */ -#endif /* USB2_OTG_FS */ -#if defined(OCTOSPIM) -#define GPIO_AF12_OCTOSPIM_P1 ((uint8_t)0x0C) /* OCTOSPI Manager Port 1 Alternate Function mapping */ -#endif /* OCTOSPIM */ - -/** - * @brief AF 13 selection - */ -#define GPIO_AF13_DCMI ((uint8_t)0x0D) /* DCMI Alternate Function mapping */ -#define GPIO_AF13_COMP1 ((uint8_t)0x0D) /* COMP1 Alternate Function mapping */ -#define GPIO_AF13_COMP2 ((uint8_t)0x0D) /* COMP2 Alternate Function mapping */ -#if defined(LTDC) -#define GPIO_AF13_LTDC ((uint8_t)0x0D) /* LTDC Alternate Function mapping */ -#endif /*LTDC*/ -#if defined(DSI) -#define GPIO_AF13_DSI ((uint8_t)0x0D) /* DSI Alternate Function mapping */ -#endif /* DSI */ -#if defined(PSSI) -#define GPIO_AF13_PSSI ((uint8_t)0x0D) /* PSSI Alternate Function mapping */ -#endif /* PSSI */ -#define GPIO_AF13_TIM1 ((uint8_t)0x0D) /* TIM1 Alternate Function mapping */ -#if defined(TIM23) -#define GPIO_AF13_TIM23 ((uint8_t)0x0D) /* TIM23 Alternate Function mapping */ -#endif /*TIM23*/ - -/** - * @brief AF 14 selection - */ -#define GPIO_AF14_LTDC ((uint8_t)0x0E) /* LTDC Alternate Function mapping */ -#define GPIO_AF14_UART5 ((uint8_t)0x0E) /* UART5 Alternate Function mapping */ -#if defined(TIM24) -#define GPIO_AF14_TIM24 ((uint8_t)0x0E) /* TIM24 Alternate Function mapping */ -#endif /*TIM24*/ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ - -#define IS_GPIO_AF(AF) ((AF) <= (uint8_t)0x0F) - - - -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup GPIOEx_Exported_Macros GPIO Exported Macros - * @{ - */ -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup GPIOEx_Exported_Functions GPIO Exported Functions - * @{ - */ -/** - * @} - */ -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup GPIOEx_Private_Constants GPIO Private Constants - * @{ - */ - -/** - * @brief GPIO pin available on the platform - */ -/* Defines the available pins per GPIOs */ -#define GPIOA_PIN_AVAILABLE GPIO_PIN_All -#define GPIOB_PIN_AVAILABLE GPIO_PIN_All -#define GPIOC_PIN_AVAILABLE GPIO_PIN_All -#define GPIOD_PIN_AVAILABLE GPIO_PIN_All -#define GPIOE_PIN_AVAILABLE GPIO_PIN_All -#define GPIOF_PIN_AVAILABLE GPIO_PIN_All -#define GPIOG_PIN_AVAILABLE GPIO_PIN_All -#if defined(GPIOI) -#define GPIOI_PIN_AVAILABLE GPIO_PIN_All -#endif /*GPIOI*/ -#if defined(GPIOI) -#define GPIOJ_PIN_AVAILABLE GPIO_PIN_All -#else -#define GPIOJ_PIN_AVAILABLE (GPIO_PIN_8 | GPIO_PIN_9 | GPIO_PIN_10 | GPIO_PIN_11 ) -#endif /* GPIOI */ -#define GPIOH_PIN_AVAILABLE GPIO_PIN_All -#if defined(GPIOI) -#define GPIOK_PIN_AVAILABLE (GPIO_PIN_0 | GPIO_PIN_1 | GPIO_PIN_2 | GPIO_PIN_3 | GPIO_PIN_4 | \ - GPIO_PIN_5 | GPIO_PIN_6 | GPIO_PIN_7) -#else -#define GPIOK_PIN_AVAILABLE (GPIO_PIN_0 | GPIO_PIN_1 | GPIO_PIN_2 ) -#endif /* GPIOI */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup GPIOEx_Private_Macros GPIO Private Macros - * @{ - */ -/** @defgroup GPIOEx_Get_Port_Index GPIO Get Port Index - * @{ - */ -#if defined(GPIOI) -#define GPIO_GET_INDEX(__GPIOx__) (((__GPIOx__) == (GPIOA))? 0UL :\ - ((__GPIOx__) == (GPIOB))? 1UL :\ - ((__GPIOx__) == (GPIOC))? 2UL :\ - ((__GPIOx__) == (GPIOD))? 3UL :\ - ((__GPIOx__) == (GPIOE))? 4UL :\ - ((__GPIOx__) == (GPIOF))? 5UL :\ - ((__GPIOx__) == (GPIOG))? 6UL :\ - ((__GPIOx__) == (GPIOH))? 7UL :\ - ((__GPIOx__) == (GPIOI))? 8UL :\ - ((__GPIOx__) == (GPIOJ))? 9UL : 10UL) -#else -#define GPIO_GET_INDEX(__GPIOx__) (((__GPIOx__) == (GPIOA))? 0UL :\ - ((__GPIOx__) == (GPIOB))? 1UL :\ - ((__GPIOx__) == (GPIOC))? 2UL :\ - ((__GPIOx__) == (GPIOD))? 3UL :\ - ((__GPIOx__) == (GPIOE))? 4UL :\ - ((__GPIOx__) == (GPIOF))? 5UL :\ - ((__GPIOx__) == (GPIOG))? 6UL :\ - ((__GPIOx__) == (GPIOH))? 7UL :\ - ((__GPIOx__) == (GPIOJ))? 9UL : 10UL) -#endif /* GPIOI */ - -/** - * @} - */ - -/** @defgroup GPIOEx_IS_Alternat_function_selection GPIO Check Alternate Function - * @{ - */ -/** - * @} - */ - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup GPIOEx_Private_Functions GPIO Private Functions - * @{ - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32H7xx_HAL_GPIO_EX_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/panda/board/stm32h7/inc/system_stm32h7xx.h b/panda/board/stm32h7/inc/system_stm32h7xx.h deleted file mode 100644 index dd75af67f..000000000 --- a/panda/board/stm32h7/inc/system_stm32h7xx.h +++ /dev/null @@ -1,105 +0,0 @@ -/** - ****************************************************************************** - * @file system_stm32h7xx.h - * @author MCD Application Team - * @brief CMSIS Cortex-Mx Device System Source File for STM32H7xx devices. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/** @addtogroup CMSIS - * @{ - */ - -/** @addtogroup stm32h7xx_system - * @{ - */ - -/** - * @brief Define to prevent recursive inclusion - */ -#ifndef SYSTEM_STM32H7XX_H -#define SYSTEM_STM32H7XX_H - -#ifdef __cplusplus - extern "C" { -#endif - -/** @addtogroup STM32H7xx_System_Includes - * @{ - */ - -/** - * @} - */ - - -/** @addtogroup STM32H7xx_System_Exported_types - * @{ - */ - /* This variable is updated in three ways: - 1) by calling CMSIS function SystemCoreClockUpdate() - 2) by calling HAL API function HAL_RCC_GetSysClockFreq() - 3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency - Note: If you use this function to configure the system clock; then there - is no need to call the 2 first functions listed above, since SystemCoreClock - variable is updated automatically. - */ -extern uint32_t SystemCoreClock; /*!< System Domain1 Clock Frequency */ -extern uint32_t SystemD2Clock; /*!< System Domain2 Clock Frequency */ -extern const uint8_t D1CorePrescTable[16] ; /*!< D1CorePrescTable prescalers table values */ - -/** - * @} - */ - -/** @addtogroup STM32H7xx_System_Exported_Constants - * @{ - */ - -/** - * @} - */ - -/** @addtogroup STM32H7xx_System_Exported_Macros - * @{ - */ - -/** - * @} - */ - -/** @addtogroup STM32H7xx_System_Exported_Functions - * @{ - */ - -extern void SystemInit(void); -extern void SystemCoreClockUpdate(void); -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* SYSTEM_STM32H7XX_H */ - -/** - * @} - */ - -/** - * @} - */ -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/panda/board/stm32h7/interrupt_handlers.h b/panda/board/stm32h7/interrupt_handlers.h deleted file mode 100644 index fb1298d77..000000000 --- a/panda/board/stm32h7/interrupt_handlers.h +++ /dev/null @@ -1,76 +0,0 @@ -// ********************* Bare interrupt handlers ********************* -// Interrupts for STM32H7x5 - -void WWDG_IRQHandler(void) {handle_interrupt(WWDG_IRQn);} -void PVD_AVD_IRQHandler(void) {handle_interrupt(PVD_AVD_IRQn);} -void TAMP_STAMP_IRQHandler(void) {handle_interrupt(TAMP_STAMP_IRQn);} -void RTC_WKUP_IRQHandler(void) {handle_interrupt(RTC_WKUP_IRQn);} -void FLASH_IRQHandler(void) {handle_interrupt(FLASH_IRQn);} -void RCC_IRQHandler(void) {handle_interrupt(RCC_IRQn);} -void EXTI0_IRQHandler(void) {handle_interrupt(EXTI0_IRQn);} -void EXTI1_IRQHandler(void) {handle_interrupt(EXTI1_IRQn);} -void EXTI2_IRQHandler(void) {handle_interrupt(EXTI2_IRQn);} -void EXTI3_IRQHandler(void) {handle_interrupt(EXTI3_IRQn);} -void EXTI4_IRQHandler(void) {handle_interrupt(EXTI4_IRQn);} -void DMA1_Stream0_IRQHandler(void) {handle_interrupt(DMA1_Stream0_IRQn);} -void DMA1_Stream1_IRQHandler(void) {handle_interrupt(DMA1_Stream1_IRQn);} -void DMA1_Stream2_IRQHandler(void) {handle_interrupt(DMA1_Stream2_IRQn);} -void DMA1_Stream3_IRQHandler(void) {handle_interrupt(DMA1_Stream3_IRQn);} -void DMA1_Stream4_IRQHandler(void) {handle_interrupt(DMA1_Stream4_IRQn);} -void DMA1_Stream5_IRQHandler(void) {handle_interrupt(DMA1_Stream5_IRQn);} -void DMA1_Stream6_IRQHandler(void) {handle_interrupt(DMA1_Stream6_IRQn);} -void ADC_IRQHandler(void) {handle_interrupt(ADC_IRQn);} -void EXTI9_5_IRQHandler(void) {handle_interrupt(EXTI9_5_IRQn);} -void TIM1_BRK_IRQHandler(void) {handle_interrupt(TIM1_BRK_IRQn);} -void TIM1_UP_TIM10_IRQHandler(void) {handle_interrupt(TIM1_UP_TIM10_IRQn);} -void TIM1_TRG_COM_IRQHandler(void) {handle_interrupt(TIM1_TRG_COM_IRQn);} -void TIM1_CC_IRQHandler(void) {handle_interrupt(TIM1_CC_IRQn);} -void TIM2_IRQHandler(void) {handle_interrupt(TIM2_IRQn);} -void TIM3_IRQHandler(void) {handle_interrupt(TIM3_IRQn);} -void TIM4_IRQHandler(void) {handle_interrupt(TIM4_IRQn);} -void I2C1_EV_IRQHandler(void) {handle_interrupt(I2C1_EV_IRQn);} -void I2C1_ER_IRQHandler(void) {handle_interrupt(I2C1_ER_IRQn);} -void I2C2_EV_IRQHandler(void) {handle_interrupt(I2C2_EV_IRQn);} -void I2C2_ER_IRQHandler(void) {handle_interrupt(I2C2_ER_IRQn);} -void SPI1_IRQHandler(void) {handle_interrupt(SPI1_IRQn);} -void SPI2_IRQHandler(void) {handle_interrupt(SPI2_IRQn);} -void USART1_IRQHandler(void) {handle_interrupt(USART1_IRQn);} -void USART2_IRQHandler(void) {handle_interrupt(USART2_IRQn);} -void USART3_IRQHandler(void) {handle_interrupt(USART3_IRQn);} -void EXTI15_10_IRQHandler(void) {handle_interrupt(EXTI15_10_IRQn);} -void RTC_Alarm_IRQHandler(void) {handle_interrupt(RTC_Alarm_IRQn);} -void TIM8_BRK_TIM12_IRQHandler(void) {handle_interrupt(TIM8_BRK_TIM12_IRQn);} -void TIM8_UP_TIM13_IRQHandler(void) {handle_interrupt(TIM8_UP_TIM13_IRQn);} -void TIM8_TRG_COM_TIM14_IRQHandler(void) {handle_interrupt(TIM8_TRG_COM_TIM14_IRQn);} -void TIM8_CC_IRQHandler(void) {handle_interrupt(TIM8_CC_IRQn);} -void DMA1_Stream7_IRQHandler(void) {handle_interrupt(DMA1_Stream7_IRQn);} -void TIM5_IRQHandler(void) {handle_interrupt(TIM5_IRQn);} -void SPI3_IRQHandler(void) {handle_interrupt(SPI3_IRQn);} -void SPI4_IRQHandler(void) {handle_interrupt(SPI4_IRQn);} -void UART4_IRQHandler(void) {handle_interrupt(UART4_IRQn);} -void UART5_IRQHandler(void) {handle_interrupt(UART5_IRQn);} -void TIM6_DAC_IRQHandler(void) {handle_interrupt(TIM6_DAC_IRQn);} -void TIM7_IRQHandler(void) {handle_interrupt(TIM7_IRQn);} -void DMA2_Stream0_IRQHandler(void) {handle_interrupt(DMA2_Stream0_IRQn);} -void DMA2_Stream1_IRQHandler(void) {handle_interrupt(DMA2_Stream1_IRQn);} -void DMA2_Stream2_IRQHandler(void) {handle_interrupt(DMA2_Stream2_IRQn);} -void DMA2_Stream3_IRQHandler(void) {handle_interrupt(DMA2_Stream3_IRQn);} -void DMA2_Stream4_IRQHandler(void) {handle_interrupt(DMA2_Stream4_IRQn);} -void DMA2_Stream5_IRQHandler(void) {handle_interrupt(DMA2_Stream5_IRQn);} -void DMA2_Stream6_IRQHandler(void) {handle_interrupt(DMA2_Stream6_IRQn);} -void DMA2_Stream7_IRQHandler(void) {handle_interrupt(DMA2_Stream7_IRQn);} -void USART6_IRQHandler(void) {handle_interrupt(USART6_IRQn);} -void I2C3_EV_IRQHandler(void) {handle_interrupt(I2C3_EV_IRQn);} -void I2C3_ER_IRQHandler(void) {handle_interrupt(I2C3_ER_IRQn);} -void FDCAN1_IT0_IRQHandler(void) {handle_interrupt(FDCAN1_IT0_IRQn);} -void FDCAN1_IT1_IRQHandler(void) {handle_interrupt(FDCAN1_IT1_IRQn);} -void FDCAN2_IT0_IRQHandler(void) {handle_interrupt(FDCAN2_IT0_IRQn);} -void FDCAN2_IT1_IRQHandler(void) {handle_interrupt(FDCAN2_IT1_IRQn);} -void FDCAN3_IT0_IRQHandler(void) {handle_interrupt(FDCAN3_IT0_IRQn);} -void FDCAN3_IT1_IRQHandler(void) {handle_interrupt(FDCAN3_IT1_IRQn);} -void FDCAN_CAL_IRQHandler(void) {handle_interrupt(FDCAN_CAL_IRQn);} -void OTG_HS_EP1_OUT_IRQHandler(void) {handle_interrupt(OTG_HS_EP1_OUT_IRQn);} -void OTG_HS_EP1_IN_IRQHandler(void) {handle_interrupt(OTG_HS_EP1_IN_IRQn);} -void OTG_HS_WKUP_IRQHandler(void) {handle_interrupt(OTG_HS_WKUP_IRQn);} -void OTG_HS_IRQHandler(void) {handle_interrupt(OTG_HS_IRQn);} -void UART7_IRQHandler(void) {handle_interrupt(UART7_IRQn);} diff --git a/panda/board/stm32h7/lladc.h b/panda/board/stm32h7/lladc.h deleted file mode 100644 index 0a52b78d3..000000000 --- a/panda/board/stm32h7/lladc.h +++ /dev/null @@ -1,41 +0,0 @@ -// 5VOUT_S = ADC12_INP5 -// VOLT_S = ADC1_INP2 -#define ADCCHAN_VIN 2 - -void adc_init(void) { - ADC1->CR &= ~(ADC_CR_DEEPPWD); //Reset deep-power-down mode - ADC1->CR |= ADC_CR_ADVREGEN; // Enable ADC regulator - while(!(ADC1->ISR & ADC_ISR_LDORDY)); - - ADC1->CR &= ~(ADC_CR_ADCALDIF); // Choose single-ended calibration - ADC1->CR |= ADC_CR_ADCALLIN; // Lineriality calibration - ADC1->CR |= ADC_CR_ADCAL; // Start calibrtation - while((ADC1->CR & ADC_CR_ADCAL) != 0); - - ADC1->ISR |= ADC_ISR_ADRDY; - ADC1->CR |= ADC_CR_ADEN; - while(!(ADC1->ISR & ADC_ISR_ADRDY)); -} - -uint16_t adc_get_raw(uint8_t channel) { - ADC1->SQR1 &= ~(ADC_SQR1_L); - ADC1->SQR1 = ((uint32_t) channel << 6U); - - ADC1->SMPR1 = (0x2U << (channel * 3U)); - ADC1->PCSEL_RES0 = (0x1U << channel); - ADC1->CFGR2 = (127U << ADC_CFGR2_OVSR_Pos) | (0x7U << ADC_CFGR2_OVSS_Pos) | ADC_CFGR2_ROVSE; - - ADC1->CR |= ADC_CR_ADSTART; - while (!(ADC1->ISR & ADC_ISR_EOC)); - - uint16_t res = ADC1->DR; - - while (!(ADC1->ISR & ADC_ISR_EOS)); - ADC1->ISR |= ADC_ISR_EOS; - - return res; -} - -uint16_t adc_get_mV(uint8_t channel) { - return (adc_get_raw(channel) * current_board->avdd_mV) / 65535U; -} diff --git a/panda/board/stm32h7/lldac.h b/panda/board/stm32h7/lldac.h deleted file mode 100644 index 77e333e5c..000000000 --- a/panda/board/stm32h7/lldac.h +++ /dev/null @@ -1,42 +0,0 @@ -void dac_init(DAC_TypeDef *dac, uint8_t channel, bool dma) { - register_set(&dac->CR, 0U, 0xFFFFU); - register_set(&dac->MCR, 0U, 0xFFFFU); - - switch(channel) { - case 1: - if (dma) { - register_set_bits(&dac->CR, DAC_CR_DMAEN1); - // register_set(&DAC->CR, (6U << DAC_CR_TSEL1_Pos), DAC_CR_TSEL1); - register_set_bits(&dac->CR, DAC_CR_TEN1); - } else { - register_clear_bits(&dac->CR, DAC_CR_DMAEN1); - } - register_set_bits(&dac->CR, DAC_CR_EN1); - break; - case 2: - if (dma) { - register_set_bits(&dac->CR, DAC_CR_DMAEN2); - } else { - register_clear_bits(&dac->CR, DAC_CR_DMAEN2); - } - register_set_bits(&dac->CR, DAC_CR_EN2); - break; - default: - break; - } -} - -// Set channel 1 value, in mV -void dac_set(DAC_TypeDef *dac, uint8_t channel, uint32_t value) { - uint32_t raw_val = MAX(MIN(value * (1U << 8U) / 3300U, (1U << 8U)), 0U); - switch(channel) { - case 1: - register_set(&dac->DHR8R1, raw_val, 0xFFU); - break; - case 2: - register_set(&dac->DHR8R2, raw_val, 0xFFU); - break; - default: - break; - } -} diff --git a/panda/board/stm32h7/llexti.h b/panda/board/stm32h7/llexti.h deleted file mode 100644 index 46d0acab6..000000000 --- a/panda/board/stm32h7/llexti.h +++ /dev/null @@ -1,63 +0,0 @@ -void EXTI_IRQ_Handler(void); - -void exti_irq_init(void) { - if (harness.status == HARNESS_STATUS_FLIPPED) { - // CAN2_RX IRQ on falling edge (EXTI10) - current_board->enable_can_transceiver(3U, false); - SYSCFG->EXTICR[2] &= ~(SYSCFG_EXTICR3_EXTI10_Msk); - SYSCFG->EXTICR[2] |= (SYSCFG_EXTICR3_EXTI10_PG); - EXTI->IMR1 |= EXTI_IMR1_IM10; - EXTI->RTSR1 &= ~EXTI_RTSR1_TR10; // rising edge - EXTI->FTSR1 |= EXTI_FTSR1_TR10; // falling edge - - // IRQ on falling edge for PA1 (SBU2, EXTI1) - SYSCFG->EXTICR[0] &= ~(SYSCFG_EXTICR1_EXTI1_Msk); - SYSCFG->EXTICR[0] |= (SYSCFG_EXTICR1_EXTI1_PA); - EXTI->IMR1 |= EXTI_IMR1_IM1; - EXTI->RTSR1 &= ~EXTI_RTSR1_TR1; // rising edge - EXTI->FTSR1 |= EXTI_FTSR1_TR1; // falling edge - REGISTER_INTERRUPT(EXTI1_IRQn, EXTI_IRQ_Handler, 100U, FAULT_INTERRUPT_RATE_EXTI) - NVIC_EnableIRQ(EXTI1_IRQn); - REGISTER_INTERRUPT(EXTI15_10_IRQn, EXTI_IRQ_Handler, 100U, FAULT_INTERRUPT_RATE_EXTI) - NVIC_EnableIRQ(EXTI15_10_IRQn); - } else { - // CAN0_RX IRQ on falling edge (EXTI8) - current_board->enable_can_transceiver(1U, false); - SYSCFG->EXTICR[2] &= ~(SYSCFG_EXTICR3_EXTI8_Msk); - SYSCFG->EXTICR[2] |= (SYSCFG_EXTICR3_EXTI8_PB); - EXTI->IMR1 |= EXTI_IMR1_IM8; - EXTI->RTSR1 &= ~EXTI_RTSR1_TR8; // rising edge - EXTI->FTSR1 |= EXTI_FTSR1_TR8; // falling edge - - // IRQ on falling edge for PC4 (SBU1, EXTI4) - SYSCFG->EXTICR[1] &= ~(SYSCFG_EXTICR2_EXTI4_Msk); - SYSCFG->EXTICR[1] |= (SYSCFG_EXTICR2_EXTI4_PC); - EXTI->IMR1 |= EXTI_IMR1_IM4; - EXTI->RTSR1 &= ~EXTI_RTSR1_TR4; // rising edge - EXTI->FTSR1 |= EXTI_FTSR1_TR4; // falling edge - REGISTER_INTERRUPT(EXTI4_IRQn, EXTI_IRQ_Handler, 100U, FAULT_INTERRUPT_RATE_EXTI) - NVIC_EnableIRQ(EXTI4_IRQn); - REGISTER_INTERRUPT(EXTI9_5_IRQn, EXTI_IRQ_Handler, 100U, FAULT_INTERRUPT_RATE_EXTI) - NVIC_EnableIRQ(EXTI9_5_IRQn); - } -} - -bool check_exti_irq(void) { - return ((EXTI->PR1 & EXTI_PR1_PR8) || (EXTI->PR1 & EXTI_PR1_PR10) || (EXTI->PR1 & EXTI_PR1_PR1) || (EXTI->PR1 & EXTI_PR1_PR4)); -} - -void exti_irq_clear(void) { - // Clear pending bits - EXTI->PR1 |= EXTI_PR1_PR8; - EXTI->PR1 |= EXTI_PR1_PR10; - EXTI->PR1 |= EXTI_PR1_PR4; - EXTI->PR1 |= EXTI_PR1_PR1; // works - EXTI->PR1 |= EXTI_PR1_PR19; // works - - // Disable all active EXTI IRQs - EXTI->IMR1 &= ~EXTI_IMR1_IM8; - EXTI->IMR1 &= ~EXTI_IMR1_IM10; - EXTI->IMR1 &= ~EXTI_IMR1_IM4; - EXTI->IMR1 &= ~EXTI_IMR1_IM1; - EXTI->IMR1 &= ~EXTI_IMR1_IM19; -} diff --git a/panda/board/stm32h7/llfan.h b/panda/board/stm32h7/llfan.h deleted file mode 100644 index dce622503..000000000 --- a/panda/board/stm32h7/llfan.h +++ /dev/null @@ -1,23 +0,0 @@ -// TACH interrupt handler -void EXTI2_IRQ_Handler(void) { - volatile unsigned int pr = EXTI->PR1 & (1U << 2); - if ((pr & (1U << 2)) != 0U) { - fan_state.tach_counter++; - } - EXTI->PR1 = (1U << 2); -} - -void llfan_init(void) { - // 5000RPM * 4 tach edges / 60 seconds - REGISTER_INTERRUPT(EXTI2_IRQn, EXTI2_IRQ_Handler, 700U, FAULT_INTERRUPT_RATE_TACH) - - // Init PWM speed control - pwm_init(TIM3, 3); - - // Init TACH interrupt - register_set(&(SYSCFG->EXTICR[0]), SYSCFG_EXTICR1_EXTI2_PD, 0xF00U); - register_set_bits(&(EXTI->IMR1), (1U << 2)); - register_set_bits(&(EXTI->RTSR1), (1U << 2)); - register_set_bits(&(EXTI->FTSR1), (1U << 2)); - NVIC_EnableIRQ(EXTI2_IRQn); -} diff --git a/panda/board/stm32h7/llfdcan.h b/panda/board/stm32h7/llfdcan.h deleted file mode 100644 index 0382e8ce2..000000000 --- a/panda/board/stm32h7/llfdcan.h +++ /dev/null @@ -1,269 +0,0 @@ -// SAE J2284-4 document specifies a bus-line network running at 2 Mbit/s -// SAE J2284-5 document specifies a point-to-point communication running at 5 Mbit/s - -#define CAN_PCLK 80000U // KHz, sourced from PLL1Q -#define BITRATE_PRESCALER 2U // Valid from 250Kbps to 5Mbps with 80Mhz clock -#define CAN_SP_NOMINAL 80U // 80% for both SAE J2284-4 and SAE J2284-5 -#define CAN_SP_DATA_2M 80U // 80% for SAE J2284-4 -#define CAN_SP_DATA_5M 75U // 75% for SAE J2284-5 -#define CAN_QUANTA(speed, prescaler) (CAN_PCLK / ((speed) / 10U * (prescaler))) -#define CAN_SEG1(tq, sp) (((tq) * (sp) / 100U)- 1U) -#define CAN_SEG2(tq, sp) ((tq) * (100U - (sp)) / 100U) - -// FDCAN core settings -#define FDCAN_MESSAGE_RAM_SIZE 0x2800UL -#define FDCAN_START_ADDRESS 0x4000AC00UL -#define FDCAN_OFFSET 3384UL // bytes for each FDCAN module, equally -#define FDCAN_OFFSET_W 846UL // words for each FDCAN module, equally -#define FDCAN_END_ADDRESS 0x4000D3FCUL // Message RAM has a width of 4 bytes - -// FDCAN_RX_FIFO_0_EL_CNT + FDCAN_TX_FIFO_EL_CNT can't exceed 47 elements (47 * 72 bytes = 3,384 bytes) per FDCAN module - -// RX FIFO 0 -#define FDCAN_RX_FIFO_0_EL_CNT 30UL -#define FDCAN_RX_FIFO_0_HEAD_SIZE 8UL // bytes -#define FDCAN_RX_FIFO_0_DATA_SIZE 64UL // bytes -#define FDCAN_RX_FIFO_0_EL_SIZE (FDCAN_RX_FIFO_0_HEAD_SIZE + FDCAN_RX_FIFO_0_DATA_SIZE) -#define FDCAN_RX_FIFO_0_EL_W_SIZE (FDCAN_RX_FIFO_0_EL_SIZE / 4UL) -#define FDCAN_RX_FIFO_0_OFFSET 0UL - -// TX FIFO -#define FDCAN_TX_FIFO_EL_CNT 17UL -#define FDCAN_TX_FIFO_HEAD_SIZE 8UL // bytes -#define FDCAN_TX_FIFO_DATA_SIZE 64UL // bytes -#define FDCAN_TX_FIFO_EL_SIZE (FDCAN_TX_FIFO_HEAD_SIZE + FDCAN_TX_FIFO_DATA_SIZE) -#define FDCAN_TX_FIFO_EL_W_SIZE (FDCAN_TX_FIFO_EL_SIZE / 4UL) -#define FDCAN_TX_FIFO_OFFSET (FDCAN_RX_FIFO_0_OFFSET + (FDCAN_RX_FIFO_0_EL_CNT * FDCAN_RX_FIFO_0_EL_W_SIZE)) - -#define CAN_NAME_FROM_CANIF(CAN_DEV) (((CAN_DEV)==FDCAN1) ? "FDCAN1" : (((CAN_DEV) == FDCAN2) ? "FDCAN2" : "FDCAN3")) -#define CAN_NUM_FROM_CANIF(CAN_DEV) (((CAN_DEV)==FDCAN1) ? 0UL : (((CAN_DEV) == FDCAN2) ? 1UL : 2UL)) - - -void print(const char *a); - -// kbps multiplied by 10 -const uint32_t speeds[] = {100U, 200U, 500U, 1000U, 1250U, 2500U, 5000U, 10000U}; -const uint32_t data_speeds[] = {100U, 200U, 500U, 1000U, 1250U, 2500U, 5000U, 10000U, 20000U, 50000U}; - - -bool fdcan_request_init(FDCAN_GlobalTypeDef *CANx) { - bool ret = true; - // Exit from sleep mode - CANx->CCCR &= ~(FDCAN_CCCR_CSR); - while ((CANx->CCCR & FDCAN_CCCR_CSA) == FDCAN_CCCR_CSA); - - // Request init - uint32_t timeout_counter = 0U; - CANx->CCCR |= FDCAN_CCCR_INIT; - while ((CANx->CCCR & FDCAN_CCCR_INIT) == 0) { - // Delay for about 1ms - delay(10000); - timeout_counter++; - - if (timeout_counter >= CAN_INIT_TIMEOUT_MS){ - ret = false; - break; - } - } - return ret; -} - -bool fdcan_exit_init(FDCAN_GlobalTypeDef *CANx) { - bool ret = true; - - CANx->CCCR &= ~(FDCAN_CCCR_INIT); - uint32_t timeout_counter = 0U; - while ((CANx->CCCR & FDCAN_CCCR_INIT) != 0) { - // Delay for about 1ms - delay(10000); - timeout_counter++; - - if (timeout_counter >= CAN_INIT_TIMEOUT_MS) { - ret = false; - break; - } - } - return ret; -} - -bool llcan_set_speed(FDCAN_GlobalTypeDef *CANx, uint32_t speed, uint32_t data_speed, bool non_iso, bool loopback, bool silent) { - UNUSED(speed); - bool ret = fdcan_request_init(CANx); - - if (ret) { - // Enable config change - CANx->CCCR |= FDCAN_CCCR_CCE; - - //Reset operation mode to Normal - CANx->CCCR &= ~(FDCAN_CCCR_TEST); - CANx->TEST &= ~(FDCAN_TEST_LBCK); - CANx->CCCR &= ~(FDCAN_CCCR_MON); - CANx->CCCR &= ~(FDCAN_CCCR_ASM); - CANx->CCCR &= ~(FDCAN_CCCR_NISO); - - // TODO: add as a separate safety mode - // Enable ASM restricted operation(for debug or automatic bitrate switching) - //CANx->CCCR |= FDCAN_CCCR_ASM; - - uint8_t prescaler = BITRATE_PRESCALER; - if (speed < 2500U) { - // The only way to support speeds lower than 250Kbit/s (down to 10Kbit/s) - prescaler = BITRATE_PRESCALER * 16U; - } - - // Set the nominal bit timing values - uint16_t tq = CAN_QUANTA(speed, prescaler); - uint8_t sp = CAN_SP_NOMINAL; - uint8_t seg1 = CAN_SEG1(tq, sp); - uint8_t seg2 = CAN_SEG2(tq, sp); - uint8_t sjw = MIN(127U, seg2); - - CANx->NBTP = (((sjw & 0x7FU)-1U)<DBTP = (((sjw & 0xFU)-1U)<CCCR |= FDCAN_CCCR_NISO; - } - - // Silent loopback is known as internal loopback in the docs - if (loopback) { - CANx->CCCR |= FDCAN_CCCR_TEST; - CANx->TEST |= FDCAN_TEST_LBCK; - CANx->CCCR |= FDCAN_CCCR_MON; - } - // Silent is known as bus monitoring in the docs - if (silent) { - CANx->CCCR |= FDCAN_CCCR_MON; - } - ret = fdcan_exit_init(CANx); - if (!ret) { - print(CAN_NAME_FROM_CANIF(CANx)); print(" set_speed timed out! (2)\n"); - } - } else { - print(CAN_NAME_FROM_CANIF(CANx)); print(" set_speed timed out! (1)\n"); - } - return ret; -} - -void llcan_irq_disable(FDCAN_GlobalTypeDef *CANx) { - if (CANx == FDCAN1) { - NVIC_DisableIRQ(FDCAN1_IT0_IRQn); - NVIC_DisableIRQ(FDCAN1_IT1_IRQn); - } else if (CANx == FDCAN2) { - NVIC_DisableIRQ(FDCAN2_IT0_IRQn); - NVIC_DisableIRQ(FDCAN2_IT1_IRQn); - } else if (CANx == FDCAN3) { - NVIC_DisableIRQ(FDCAN3_IT0_IRQn); - NVIC_DisableIRQ(FDCAN3_IT1_IRQn); - } else { - } -} - -void llcan_irq_enable(FDCAN_GlobalTypeDef *CANx) { - if (CANx == FDCAN1) { - NVIC_EnableIRQ(FDCAN1_IT0_IRQn); - NVIC_EnableIRQ(FDCAN1_IT1_IRQn); - } else if (CANx == FDCAN2) { - NVIC_EnableIRQ(FDCAN2_IT0_IRQn); - NVIC_EnableIRQ(FDCAN2_IT1_IRQn); - } else if (CANx == FDCAN3) { - NVIC_EnableIRQ(FDCAN3_IT0_IRQn); - NVIC_EnableIRQ(FDCAN3_IT1_IRQn); - } else { - } -} - -bool llcan_init(FDCAN_GlobalTypeDef *CANx) { - uint32_t can_number = CAN_NUM_FROM_CANIF(CANx); - bool ret = fdcan_request_init(CANx); - - if (ret) { - // Enable config change - CANx->CCCR |= FDCAN_CCCR_CCE; - // Enable automatic retransmission - CANx->CCCR &= ~(FDCAN_CCCR_DAR); - // Enable transmission pause feature - CANx->CCCR |= FDCAN_CCCR_TXP; - // Disable protocol exception handling - CANx->CCCR |= FDCAN_CCCR_PXHD; - // FD with BRS - CANx->CCCR |= (FDCAN_CCCR_FDOE | FDCAN_CCCR_BRSE); - - // Set TX mode to FIFO - CANx->TXBC &= ~(FDCAN_TXBC_TFQM); - // Configure TX element data size - CANx->TXESC |= 0x7U << FDCAN_TXESC_TBDS_Pos; // 64 bytes - //Configure RX FIFO0 element data size - CANx->RXESC |= 0x7U << FDCAN_RXESC_F0DS_Pos; - // Disable filtering, accept all valid frames received - CANx->XIDFC &= ~(FDCAN_XIDFC_LSE); // No extended filters - CANx->SIDFC &= ~(FDCAN_SIDFC_LSS); // No standard filters - CANx->GFC &= ~(FDCAN_GFC_RRFE); // Accept extended remote frames - CANx->GFC &= ~(FDCAN_GFC_RRFS); // Accept standard remote frames - CANx->GFC &= ~(FDCAN_GFC_ANFE); // Accept extended frames to FIFO 0 - CANx->GFC &= ~(FDCAN_GFC_ANFS); // Accept standard frames to FIFO 0 - - uint32_t RxFIFO0SA = FDCAN_START_ADDRESS + (can_number * FDCAN_OFFSET); - uint32_t TxFIFOSA = RxFIFO0SA + (FDCAN_RX_FIFO_0_EL_CNT * FDCAN_RX_FIFO_0_EL_SIZE); - - // RX FIFO 0 - CANx->RXF0C |= (FDCAN_RX_FIFO_0_OFFSET + (can_number * FDCAN_OFFSET_W)) << FDCAN_RXF0C_F0SA_Pos; - CANx->RXF0C |= FDCAN_RX_FIFO_0_EL_CNT << FDCAN_RXF0C_F0S_Pos; - // RX FIFO 0 switch to non-blocking (overwrite) mode - CANx->RXF0C |= FDCAN_RXF0C_F0OM; - - // TX FIFO (mode set earlier) - CANx->TXBC |= (FDCAN_TX_FIFO_OFFSET + (can_number * FDCAN_OFFSET_W)) << FDCAN_TXBC_TBSA_Pos; - CANx->TXBC |= FDCAN_TX_FIFO_EL_CNT << FDCAN_TXBC_TFQS_Pos; - - // Flush allocated RAM - uint32_t EndAddress = TxFIFOSA + (FDCAN_TX_FIFO_EL_CNT * FDCAN_TX_FIFO_EL_SIZE); - for (uint32_t RAMcounter = RxFIFO0SA; RAMcounter < EndAddress; RAMcounter += 4U) { - *(uint32_t *)(RAMcounter) = 0x00000000; - } - - // Enable both interrupts for each module - CANx->ILE = (FDCAN_ILE_EINT0 | FDCAN_ILE_EINT1); - - CANx->IE &= 0x0U; // Reset all interrupts - // Messages for INT0 - CANx->IE |= FDCAN_IE_RF0NE; // Rx FIFO 0 new message - CANx->IE |= FDCAN_IE_PEDE | FDCAN_IE_PEAE | FDCAN_IE_BOE | FDCAN_IE_EPE | FDCAN_IE_RF0LE; - - // Messages for INT1 (Only TFE works??) - CANx->ILS |= FDCAN_ILS_TFEL; - CANx->IE |= FDCAN_IE_TFEE; // Tx FIFO empty - - ret = fdcan_exit_init(CANx); - if(!ret) { - print(CAN_NAME_FROM_CANIF(CANx)); print(" llcan_init timed out (2)!\n"); - } - - llcan_irq_enable(CANx); - - } else { - print(CAN_NAME_FROM_CANIF(CANx)); print(" llcan_init timed out (1)!\n"); - } - return ret; -} - -void llcan_clear_send(FDCAN_GlobalTypeDef *CANx) { - // from datasheet: "Transmit cancellation is not intended for Tx FIFO operation." - // so we need to clear pending transmission manually by resetting FDCAN core - CANx->IR |= 0x3FCFFFFFU; // clear all interrupts - bool ret = llcan_init(CANx); - UNUSED(ret); -} diff --git a/panda/board/stm32h7/llflash.h b/panda/board/stm32h7/llflash.h deleted file mode 100644 index 800d9414b..000000000 --- a/panda/board/stm32h7/llflash.h +++ /dev/null @@ -1,55 +0,0 @@ -bool flash_is_locked(void) { - return (FLASH->CR1 & FLASH_CR_LOCK); -} - -void flash_unlock(void) { - FLASH->KEYR1 = 0x45670123; - FLASH->KEYR1 = 0xCDEF89AB; -} - -void flash_lock(void) { - FLASH->CR1 |= FLASH_CR_LOCK; -} - -bool flash_erase_sector(uint16_t sector) { - #ifdef BOOTSTUB - // don't erase the bootloader(sector 0) - uint16_t min_sector = 1U; - uint16_t max_sector = 7U; - #else - uint16_t min_sector = LOGGING_FLASH_SECTOR_A; - uint16_t max_sector = LOGGING_FLASH_SECTOR_B; - #endif - - bool ret = false; - if ((sector >= min_sector) && (sector <= max_sector) && (!flash_is_locked())) { - FLASH->CR1 = (sector << 8) | FLASH_CR_SER; - FLASH->CR1 |= FLASH_CR_START; - while ((FLASH->SR1 & FLASH_SR_QW) != 0U); - ret = true; - } - return ret; -} - -void flash_write_word(uint32_t *prog_ptr, uint32_t data) { - #ifndef BOOTSTUB - // don't write to any region besides the logging region - if ((prog_ptr >= (uint32_t *)LOGGING_FLASH_BASE_A) && (prog_ptr < (uint32_t *)(LOGGING_FLASH_BASE_B + LOGGING_FLASH_SECTOR_SIZE))) { - #endif - - uint32_t *pp = prog_ptr; - FLASH->CR1 |= FLASH_CR_PG; - *pp = data; - while ((FLASH->SR1 & FLASH_SR_QW) != 0U); - - #ifndef BOOTSTUB - } - #endif -} - -void flush_write_buffer(void) { - if ((FLASH->SR1 & FLASH_SR_WBNE) != 0U) { - FLASH->CR1 |= FLASH_CR_FW; - while ((FLASH->SR1 & FLASH_CR_FW) != 0U); - } -} diff --git a/panda/board/stm32h7/lli2c.h b/panda/board/stm32h7/lli2c.h deleted file mode 100644 index 74e8ac830..000000000 --- a/panda/board/stm32h7/lli2c.h +++ /dev/null @@ -1,153 +0,0 @@ - -// TODO: this driver relies heavily on polling, -// if we want it to be more async, we should use interrupts - -#define I2C_TIMEOUT_US 100000U - -// cppcheck-suppress misra-c2012-2.7; not sure why it triggers here? -bool i2c_status_wait(volatile uint32_t *reg, uint32_t mask, uint32_t val) { - uint32_t start_time = microsecond_timer_get(); - while(((*reg & mask) != val) && (get_ts_elapsed(microsecond_timer_get(), start_time) < I2C_TIMEOUT_US)); - return ((*reg & mask) == val); -} - -bool i2c_write_reg(I2C_TypeDef *I2C, uint8_t addr, uint8_t reg, uint8_t value) { - // Setup transfer and send START + addr - bool ret = false; - for(uint32_t i=0U; i<10U; i++) { - register_clear_bits(&I2C->CR2, I2C_CR2_ADD10); - I2C->CR2 = ((addr << 1U) & I2C_CR2_SADD_Msk); - register_clear_bits(&I2C->CR2, I2C_CR2_RD_WRN); - register_set_bits(&I2C->CR2, I2C_CR2_AUTOEND); - I2C->CR2 |= (2 << I2C_CR2_NBYTES_Pos); - - I2C->CR2 |= I2C_CR2_START; - if(!i2c_status_wait(&I2C->CR2, I2C_CR2_START, 0U)) { - continue; - } - - // check if we lost arbitration - if ((I2C->ISR & I2C_ISR_ARLO) != 0U) { - register_set_bits(&I2C->ICR, I2C_ICR_ARLOCF); - } else { - ret = true; - break; - } - } - - if (!ret) { - goto end; - } - - // Send data - ret = i2c_status_wait(&I2C->ISR, I2C_ISR_TXIS, I2C_ISR_TXIS); - if(!ret) { - goto end; - } - I2C->TXDR = reg; - - ret = i2c_status_wait(&I2C->ISR, I2C_ISR_TXIS, I2C_ISR_TXIS); - if(!ret) { - goto end; - } - I2C->TXDR = value; - -end: - return ret; -} - -bool i2c_read_reg(I2C_TypeDef *I2C, uint8_t addr, uint8_t reg, uint8_t *value) { - // Setup transfer and send START + addr - bool ret = false; - for(uint32_t i=0U; i<10U; i++) { - register_clear_bits(&I2C->CR2, I2C_CR2_ADD10); - I2C->CR2 = ((addr << 1U) & I2C_CR2_SADD_Msk); - register_clear_bits(&I2C->CR2, I2C_CR2_RD_WRN); - register_clear_bits(&I2C->CR2, I2C_CR2_AUTOEND); - I2C->CR2 |= (1 << I2C_CR2_NBYTES_Pos); - - I2C->CR2 |= I2C_CR2_START; - if(!i2c_status_wait(&I2C->CR2, I2C_CR2_START, 0U)) { - continue; - } - - // check if we lost arbitration - if ((I2C->ISR & I2C_ISR_ARLO) != 0U) { - register_set_bits(&I2C->ICR, I2C_ICR_ARLOCF); - } else { - ret = true; - break; - } - } - - if (!ret) { - goto end; - } - - // Send data - ret = i2c_status_wait(&I2C->ISR, I2C_ISR_TXIS, I2C_ISR_TXIS); - if(!ret) { - goto end; - } - I2C->TXDR = reg; - - // Restart - I2C->CR2 = (((addr << 1) | 0x1U) & I2C_CR2_SADD_Msk) | (1U << I2C_CR2_NBYTES_Pos) | I2C_CR2_RD_WRN | I2C_CR2_START; - ret = i2c_status_wait(&I2C->CR2, I2C_CR2_START, 0U); - if(!ret) { - goto end; - } - - // check if we lost arbitration - if ((I2C->ISR & I2C_ISR_ARLO) != 0U) { - register_set_bits(&I2C->ICR, I2C_ICR_ARLOCF); - ret = false; - goto end; - } - - // Read data - ret = i2c_status_wait(&I2C->ISR, I2C_ISR_RXNE, I2C_ISR_RXNE); - if(!ret) { - goto end; - } - *value = I2C->RXDR; - - // Stop - I2C->CR2 |= I2C_CR2_STOP; - -end: - return ret; -} - -bool i2c_set_reg_bits(I2C_TypeDef *I2C, uint8_t addr, uint8_t reg, uint8_t bits) { - uint8_t value; - bool ret = i2c_read_reg(I2C, addr, reg, &value); - if(ret) { - ret = i2c_write_reg(I2C, addr, reg, value | bits); - } - return ret; -} - -bool i2c_clear_reg_bits(I2C_TypeDef *I2C, uint8_t addr, uint8_t reg, uint8_t bits) { - uint8_t value; - bool ret = i2c_read_reg(I2C, addr, reg, &value); - if(ret) { - ret = i2c_write_reg(I2C, addr, reg, value & (uint8_t) (~bits)); - } - return ret; -} - -bool i2c_set_reg_mask(I2C_TypeDef *I2C, uint8_t addr, uint8_t reg, uint8_t value, uint8_t mask) { - uint8_t old_value; - bool ret = i2c_read_reg(I2C, addr, reg, &old_value); - if(ret) { - ret = i2c_write_reg(I2C, addr, reg, (old_value & (uint8_t) (~mask)) | (value & mask)); - } - return ret; -} - -void i2c_init(I2C_TypeDef *I2C) { - // 100kHz clock speed - I2C->TIMINGR = 0x107075B0; - I2C->CR1 = I2C_CR1_PE; -} \ No newline at end of file diff --git a/panda/board/stm32h7/llrtc.h b/panda/board/stm32h7/llrtc.h deleted file mode 100644 index 03787d0db..000000000 --- a/panda/board/stm32h7/llrtc.h +++ /dev/null @@ -1,69 +0,0 @@ -void enable_bdomain_protection(void) { - register_clear_bits(&(PWR->CR1), PWR_CR1_DBP); -} - -void disable_bdomain_protection(void) { - register_set_bits(&(PWR->CR1), PWR_CR1_DBP); -} - -void rtc_init(void){ - uint32_t bdcr_opts = RCC_BDCR_RTCEN; - uint32_t bdcr_mask = (RCC_BDCR_RTCEN | RCC_BDCR_RTCSEL); - if (current_board->has_rtc_battery) { - bdcr_opts |= (RCC_BDCR_LSEDRV_1 | RCC_BDCR_RTCSEL_0 | RCC_BDCR_LSEON); - bdcr_mask |= (RCC_BDCR_LSEDRV | RCC_BDCR_LSEBYP | RCC_BDCR_LSEON); - } else { - bdcr_opts |= RCC_BDCR_RTCSEL_1; - RCC->CSR |= RCC_CSR_LSION; - while((RCC->CSR & RCC_CSR_LSIRDY) == 0){} - } - - // Initialize RTC module and clock if not done already. - if((RCC->BDCR & bdcr_mask) != bdcr_opts){ - print("Initializing RTC\n"); - // Reset backup domain - register_set_bits(&(RCC->BDCR), RCC_BDCR_BDRST); - - // Disable write protection - disable_bdomain_protection(); - - // Clear backup domain reset - register_clear_bits(&(RCC->BDCR), RCC_BDCR_BDRST); - - // Set RTC options - register_set(&(RCC->BDCR), bdcr_opts, bdcr_mask); - - // Enable write protection - enable_bdomain_protection(); - } -} - -void rtc_wakeup_init(void) { - EXTI->IMR1 |= EXTI_IMR1_IM19; - EXTI->RTSR1 |= EXTI_RTSR1_TR19; // rising edge - EXTI->FTSR1 &= ~EXTI_FTSR1_TR19; // falling edge - - NVIC_DisableIRQ(RTC_WKUP_IRQn); - - // Disable write protection - disable_bdomain_protection(); - RTC->WPR = 0xCA; - RTC->WPR = 0x53; - - RTC->CR &= ~RTC_CR_WUTE; - while((RTC->ISR & RTC_ISR_WUTWF) == 0){} - - RTC->CR &= ~RTC_CR_WUTIE; - RTC->ISR &= ~RTC_ISR_WUTF; - //PWR->CR1 |= PWR_CR1_CWUF; - - RTC->WUTR = DEEPSLEEP_WAKEUP_DELAY; - // Wakeup timer interrupt enable, wakeup timer enable, select 1Hz rate - RTC->CR |= RTC_CR_WUTE | RTC_CR_WUTIE | RTC_CR_WUCKSEL_2; - - // Re-enable write protection - RTC->WPR = 0x00; - enable_bdomain_protection(); - - NVIC_EnableIRQ(RTC_WKUP_IRQn); -} diff --git a/panda/board/stm32h7/llspi.h b/panda/board/stm32h7/llspi.h deleted file mode 100644 index 1947803ac..000000000 --- a/panda/board/stm32h7/llspi.h +++ /dev/null @@ -1,106 +0,0 @@ -// master -> panda DMA start -void llspi_mosi_dma(uint8_t *addr, int len) { - // disable DMA + SPI - register_clear_bits(&(SPI4->CFG1), SPI_CFG1_RXDMAEN); - DMA2_Stream2->CR &= ~DMA_SxCR_EN; - register_clear_bits(&(SPI4->CR1), SPI_CR1_SPE); - - // drain the bus - while ((SPI4->SR & SPI_SR_RXP) != 0U) { - volatile uint8_t dat = SPI4->RXDR; - (void)dat; - } - - // clear all pending - SPI4->IFCR |= (0x1FFU << 3U); - register_set(&(SPI4->IER), 0, 0x3FFU); - - // setup destination and length - register_set(&(DMA2_Stream2->M0AR), (uint32_t)addr, 0xFFFFFFFFU); - DMA2_Stream2->NDTR = len; - - // enable DMA + SPI - DMA2_Stream2->CR |= DMA_SxCR_EN; - register_set_bits(&(SPI4->CFG1), SPI_CFG1_RXDMAEN); - register_set_bits(&(SPI4->CR1), SPI_CR1_SPE); -} - -// panda -> master DMA start -void llspi_miso_dma(uint8_t *addr, int len) { - // disable DMA + SPI - DMA2_Stream3->CR &= ~DMA_SxCR_EN; - register_clear_bits(&(SPI4->CFG1), SPI_CFG1_TXDMAEN); - register_clear_bits(&(SPI4->CR1), SPI_CR1_SPE); - - // setup source and length - register_set(&(DMA2_Stream3->M0AR), (uint32_t)addr, 0xFFFFFFFFU); - DMA2_Stream3->NDTR = len; - - // clear under-run while we were reading - SPI4->IFCR |= (0x1FFU << 3U); - - // setup interrupt on TXC - register_set(&(SPI4->IER), (1U << SPI_IER_EOTIE_Pos), 0x3FFU); - - // enable DMA + SPI - register_set_bits(&(SPI4->CFG1), SPI_CFG1_TXDMAEN); - DMA2_Stream3->CR |= DMA_SxCR_EN; - register_set_bits(&(SPI4->CR1), SPI_CR1_SPE); -} - -// master -> panda DMA finished -void DMA2_Stream2_IRQ_Handler(void) { - // Clear interrupt flag - DMA2->LIFCR = DMA_LIFCR_CTCIF2; - - spi_rx_done(); -} - -// panda -> master DMA finished -void DMA2_Stream3_IRQ_Handler(void) { - ENTER_CRITICAL(); - - DMA2->LIFCR = DMA_LIFCR_CTCIF3; - spi_tx_dma_done = true; - - EXIT_CRITICAL(); -} - -// panda TX finished -void SPI4_IRQ_Handler(void) { - // clear flag - SPI4->IFCR |= (0x1FFU << 3U); - - if (spi_tx_dma_done && ((SPI4->SR & SPI_SR_TXC) != 0)) { - spi_tx_dma_done = false; - spi_tx_done(false); - } -} - - -void llspi_init(void) { - REGISTER_INTERRUPT(SPI4_IRQn, SPI4_IRQ_Handler, (SPI_IRQ_RATE * 2U), FAULT_INTERRUPT_RATE_SPI) - REGISTER_INTERRUPT(DMA2_Stream2_IRQn, DMA2_Stream2_IRQ_Handler, SPI_IRQ_RATE, FAULT_INTERRUPT_RATE_SPI_DMA) - REGISTER_INTERRUPT(DMA2_Stream3_IRQn, DMA2_Stream3_IRQ_Handler, SPI_IRQ_RATE, FAULT_INTERRUPT_RATE_SPI_DMA) - - // Setup MOSI DMA - register_set(&(DMAMUX1_Channel10->CCR), 83U, 0xFFFFFFFFU); - register_set(&(DMA2_Stream2->CR), (DMA_SxCR_MINC | DMA_SxCR_TCIE), 0x1E077EFEU); - register_set(&(DMA2_Stream2->PAR), (uint32_t)&(SPI4->RXDR), 0xFFFFFFFFU); - - // Setup MISO DMA, memory -> peripheral - register_set(&(DMAMUX1_Channel11->CCR), 84U, 0xFFFFFFFFU); - register_set(&(DMA2_Stream3->CR), (DMA_SxCR_MINC | DMA_SxCR_DIR_0 | DMA_SxCR_TCIE), 0x1E077EFEU); - register_set(&(DMA2_Stream3->PAR), (uint32_t)&(SPI4->TXDR), 0xFFFFFFFFU); - - // Enable SPI - register_set(&(SPI4->IER), 0, 0x3FFU); - register_set(&(SPI4->CFG1), (7U << SPI_CFG1_DSIZE_Pos), SPI_CFG1_DSIZE_Msk); - register_set(&(SPI4->UDRDR), 0xcd, 0xFFFFU); // set under-run value for debugging - register_set(&(SPI4->CR1), SPI_CR1_SPE, 0xFFFFU); - register_set(&(SPI4->CR2), 0, 0xFFFFU); - - NVIC_EnableIRQ(DMA2_Stream2_IRQn); - NVIC_EnableIRQ(DMA2_Stream3_IRQn); - NVIC_EnableIRQ(SPI4_IRQn); -} diff --git a/panda/board/stm32h7/lluart.h b/panda/board/stm32h7/lluart.h deleted file mode 100644 index 640ea18d1..000000000 --- a/panda/board/stm32h7/lluart.h +++ /dev/null @@ -1,111 +0,0 @@ -#define __DIV(_PCLK_, _BAUD_) (((_PCLK_) * 25U) / (4U * (_BAUD_))) -#define __DIVMANT(_PCLK_, _BAUD_) (__DIV((_PCLK_), (_BAUD_)) / 100U) -#define __DIVFRAQ(_PCLK_, _BAUD_) ((((__DIV((_PCLK_), (_BAUD_)) - (__DIVMANT((_PCLK_), (_BAUD_)) * 100U)) * 16U) + 50U) / 100U) -#define __USART_BRR(_PCLK_, _BAUD_) ((__DIVMANT((_PCLK_), (_BAUD_)) << 4) | (__DIVFRAQ((_PCLK_), (_BAUD_)) & 0x0FU)) - -void uart_rx_ring(uart_ring *q){ - // Do not read out directly if DMA enabled - ENTER_CRITICAL(); - - // Read out RX buffer - uint8_t c = q->uart->RDR; // This read after reading SR clears a bunch of interrupts - - uint16_t next_w_ptr = (q->w_ptr_rx + 1U) % q->rx_fifo_size; - - if ((next_w_ptr == q->r_ptr_rx) && q->overwrite) { - // overwrite mode: drop oldest byte - q->r_ptr_rx = (q->r_ptr_rx + 1U) % q->rx_fifo_size; - } - - // Do not overwrite buffer data - if (next_w_ptr != q->r_ptr_rx) { - q->elems_rx[q->w_ptr_rx] = c; - q->w_ptr_rx = next_w_ptr; - if (q->callback != NULL) { - q->callback(q); - } - } - - EXIT_CRITICAL(); -} - -void uart_tx_ring(uart_ring *q){ - ENTER_CRITICAL(); - // Send out next byte of TX buffer - if (q->w_ptr_tx != q->r_ptr_tx) { - // Only send if transmit register is empty (aka last byte has been sent) - if ((q->uart->ISR & USART_ISR_TXE_TXFNF) != 0) { - q->uart->TDR = q->elems_tx[q->r_ptr_tx]; // This clears TXE - q->r_ptr_tx = (q->r_ptr_tx + 1U) % q->tx_fifo_size; - } - - // Enable TXE interrupt if there is still data to be sent - if(q->r_ptr_tx != q->w_ptr_tx){ - q->uart->CR1 |= USART_CR1_TXEIE; - } else { - q->uart->CR1 &= ~USART_CR1_TXEIE; - } - } - EXIT_CRITICAL(); -} - -void uart_set_baud(USART_TypeDef *u, unsigned int baud) { - // UART7 is connected to APB1 at 60MHz - u->BRR = 60000000U / baud; -} - -// This read after reading ISR clears all error interrupts. We don't want compiler warnings, nor optimizations -#define UART_READ_RDR(uart) volatile uint8_t t = (uart)->RDR; UNUSED(t); - -void uart_interrupt_handler(uart_ring *q) { - ENTER_CRITICAL(); - - // Read UART status. This is also the first step necessary in clearing most interrupts - uint32_t status = q->uart->ISR; - - // If RXFNE is set, perform a read. This clears RXFNE, ORE, IDLE, NF and FE - if((status & USART_ISR_RXNE_RXFNE) != 0U){ - uart_rx_ring(q); - } - - // Detect errors and clear them - uint32_t err = (status & USART_ISR_ORE) | (status & USART_ISR_NE) | (status & USART_ISR_FE) | (status & USART_ISR_PE); - if(err != 0U){ - #ifdef DEBUG_UART - print("Encountered UART error: "); puth(err); print("\n"); - #endif - UART_READ_RDR(q->uart) - } - - if ((err & USART_ISR_ORE) != 0U) { - q->uart->ICR |= USART_ICR_ORECF; - } else if ((err & USART_ISR_NE) != 0U) { - q->uart->ICR |= USART_ICR_NECF; - } else if ((err & USART_ISR_FE) != 0U) { - q->uart->ICR |= USART_ICR_FECF; - } else if ((err & USART_ISR_PE) != 0U) { - q->uart->ICR |= USART_ICR_PECF; - } else {} - - // Send if necessary - uart_tx_ring(q); - - EXIT_CRITICAL(); -} - -void UART7_IRQ_Handler(void) { uart_interrupt_handler(&uart_ring_som_debug); } - -void uart_init(uart_ring *q, int baud) { - if (q->uart == UART7) { - REGISTER_INTERRUPT(UART7_IRQn, UART7_IRQ_Handler, 150000U, FAULT_INTERRUPT_RATE_UART_7) - - uart_set_baud(q->uart, baud); - q->uart->CR1 = USART_CR1_UE | USART_CR1_TE | USART_CR1_RE; - - // Enable interrupt on RX not empty - q->uart->CR1 |= USART_CR1_RXNEIE; - - // Enable UART interrupts - NVIC_EnableIRQ(UART7_IRQn); - } -} diff --git a/panda/board/stm32h7/llusb.h b/panda/board/stm32h7/llusb.h deleted file mode 100644 index c46a693b0..000000000 --- a/panda/board/stm32h7/llusb.h +++ /dev/null @@ -1,98 +0,0 @@ -typedef struct -{ - __IO uint32_t HPRT; -} -USB_OTG_HostPortTypeDef; - -USB_OTG_GlobalTypeDef *USBx = USB_OTG_HS; - -#define USBx_HOST ((USB_OTG_HostTypeDef *)((uint32_t)USBx + USB_OTG_HOST_BASE)) -#define USBx_HOST_PORT ((USB_OTG_HostPortTypeDef *)((uint32_t)USBx + USB_OTG_HOST_PORT_BASE)) -#define USBx_DEVICE ((USB_OTG_DeviceTypeDef *)((uint32_t)USBx + USB_OTG_DEVICE_BASE)) -#define USBx_INEP(i) ((USB_OTG_INEndpointTypeDef *)((uint32_t)USBx + USB_OTG_IN_ENDPOINT_BASE + ((i) * USB_OTG_EP_REG_SIZE))) -#define USBx_OUTEP(i) ((USB_OTG_OUTEndpointTypeDef *)((uint32_t)USBx + USB_OTG_OUT_ENDPOINT_BASE + ((i) * USB_OTG_EP_REG_SIZE))) -#define USBx_DFIFO(i) *(__IO uint32_t *)((uint32_t)USBx + USB_OTG_FIFO_BASE + ((i) * USB_OTG_FIFO_SIZE)) -#define USBx_PCGCCTL *(__IO uint32_t *)((uint32_t)USBx + USB_OTG_PCGCCTL_BASE) - -#define USBD_FS_TRDT_VALUE 6U -#define USB_OTG_SPEED_FULL 3U -#define DCFG_FRAME_INTERVAL_80 0U - - -void usb_irqhandler(void); - -void OTG_HS_IRQ_Handler(void) { - NVIC_DisableIRQ(OTG_HS_IRQn); - usb_irqhandler(); - NVIC_EnableIRQ(OTG_HS_IRQn); -} - -void usb_init(void) { - REGISTER_INTERRUPT(OTG_HS_IRQn, OTG_HS_IRQ_Handler, 1500000U, FAULT_INTERRUPT_RATE_USB) // TODO: Find out a better rate limit for USB. Now it's the 1.5MB/s rate - - // Disable global interrupt - USBx->GAHBCFG &= ~(USB_OTG_GAHBCFG_GINT); - // Select FS Embedded PHY - USBx->GUSBCFG |= USB_OTG_GUSBCFG_PHYSEL; - // Force device mode - USBx->GUSBCFG &= ~(USB_OTG_GUSBCFG_FHMOD | USB_OTG_GUSBCFG_FDMOD); - USBx->GUSBCFG |= USB_OTG_GUSBCFG_FDMOD; - delay(250000); // Wait for about 25ms (explicitly stated in H7 ref manual) - // Wait for AHB master IDLE state. - while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_AHBIDL) == 0); - // Core Soft Reset - USBx->GRSTCTL |= USB_OTG_GRSTCTL_CSRST; - while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_CSRST) == USB_OTG_GRSTCTL_CSRST); - // Activate the USB Transceiver - USBx->GCCFG |= USB_OTG_GCCFG_PWRDWN; - - for (uint8_t i = 0U; i < 15U; i++) { - USBx->DIEPTXF[i] = 0U; - } - - // VBUS Sensing setup - USBx_DEVICE->DCTL |= USB_OTG_DCTL_SDIS; - // Deactivate VBUS Sensing B - USBx->GCCFG &= ~(USB_OTG_GCCFG_VBDEN); - // B-peripheral session valid override enable - USBx->GOTGCTL |= USB_OTG_GOTGCTL_BVALOEN; - USBx->GOTGCTL |= USB_OTG_GOTGCTL_BVALOVAL; - // Restart the Phy Clock - USBx_PCGCCTL = 0U; - // Device mode configuration - USBx_DEVICE->DCFG |= DCFG_FRAME_INTERVAL_80; - USBx_DEVICE->DCFG |= USB_OTG_SPEED_FULL | USB_OTG_DCFG_NZLSOHSK; - - // Flush FIFOs - USBx->GRSTCTL = (USB_OTG_GRSTCTL_TXFFLSH | (0x10U << 6)); - while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_TXFFLSH) == USB_OTG_GRSTCTL_TXFFLSH); - - USBx->GRSTCTL = USB_OTG_GRSTCTL_RXFFLSH; - while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_RXFFLSH) == USB_OTG_GRSTCTL_RXFFLSH); - - // Clear all pending Device Interrupts - USBx_DEVICE->DIEPMSK = 0U; - USBx_DEVICE->DOEPMSK = 0U; - USBx_DEVICE->DAINTMSK = 0U; - USBx_DEVICE->DIEPMSK &= ~(USB_OTG_DIEPMSK_TXFURM); - - // Disable all interrupts. - USBx->GINTMSK = 0U; - // Clear any pending interrupts - USBx->GINTSTS = 0xBFFFFFFFU; - // Enable interrupts matching to the Device mode ONLY - USBx->GINTMSK = USB_OTG_GINTMSK_USBRST | USB_OTG_GINTMSK_ENUMDNEM | USB_OTG_GINTMSK_OTGINT | - USB_OTG_GINTMSK_RXFLVLM | USB_OTG_GINTMSK_GONAKEFFM | USB_OTG_GINTMSK_GINAKEFFM | - USB_OTG_GINTMSK_OEPINT | USB_OTG_GINTMSK_IEPINT | - USB_OTG_GINTMSK_CIDSCHGM | USB_OTG_GINTMSK_SRQIM | USB_OTG_GINTMSK_MMISM; - - // Set USB Turnaround time - USBx->GUSBCFG |= ((USBD_FS_TRDT_VALUE << 10) & USB_OTG_GUSBCFG_TRDT); - // Enables the controller's Global Int in the AHB Config reg - USBx->GAHBCFG |= USB_OTG_GAHBCFG_GINT; - // Soft disconnect disable: - USBx_DEVICE->DCTL &= ~(USB_OTG_DCTL_SDIS); - - // enable the IRQ - NVIC_EnableIRQ(OTG_HS_IRQn); -} diff --git a/panda/board/stm32h7/peripherals.h b/panda/board/stm32h7/peripherals.h deleted file mode 100644 index cf397644e..000000000 --- a/panda/board/stm32h7/peripherals.h +++ /dev/null @@ -1,145 +0,0 @@ -void gpio_usb_init(void) { - // A11,A12: USB - set_gpio_alternate(GPIOA, 11, GPIO_AF10_OTG1_FS); - set_gpio_alternate(GPIOA, 12, GPIO_AF10_OTG1_FS); - GPIOA->OSPEEDR = GPIO_OSPEEDR_OSPEED11 | GPIO_OSPEEDR_OSPEED12; -} - -void gpio_spi_init(void) { - set_gpio_alternate(GPIOE, 11, GPIO_AF5_SPI4); - set_gpio_alternate(GPIOE, 12, GPIO_AF5_SPI4); - set_gpio_alternate(GPIOE, 13, GPIO_AF5_SPI4); - set_gpio_alternate(GPIOE, 14, GPIO_AF5_SPI4); - register_set_bits(&(GPIOE->OSPEEDR), GPIO_OSPEEDR_OSPEED11 | GPIO_OSPEEDR_OSPEED12 | GPIO_OSPEEDR_OSPEED13 | GPIO_OSPEEDR_OSPEED14); -} - -void gpio_usart2_init(void) { - // A2,A3: USART 2 for debugging - set_gpio_alternate(GPIOA, 2, GPIO_AF7_USART2); - set_gpio_alternate(GPIOA, 3, GPIO_AF7_USART2); -} - -void gpio_uart7_init(void) { - // E7,E8: UART 7 for debugging - set_gpio_alternate(GPIOE, 7, GPIO_AF7_UART7); - set_gpio_alternate(GPIOE, 8, GPIO_AF7_UART7); -} - -// Common GPIO initialization -void common_init_gpio(void) { - /// E2,E3,E4: RGB LED - set_gpio_pullup(GPIOE, 2, PULL_NONE); - set_gpio_mode(GPIOE, 2, MODE_OUTPUT); - set_gpio_output_type(GPIOE, 2, OUTPUT_TYPE_OPEN_DRAIN); - - set_gpio_pullup(GPIOE, 3, PULL_NONE); - set_gpio_mode(GPIOE, 3, MODE_OUTPUT); - set_gpio_output_type(GPIOE, 3, OUTPUT_TYPE_OPEN_DRAIN); - - set_gpio_pullup(GPIOE, 4, PULL_NONE); - set_gpio_mode(GPIOE, 4, MODE_OUTPUT); - set_gpio_output_type(GPIOE, 4, OUTPUT_TYPE_OPEN_DRAIN); - - // F7,F8,F9,F10: BOARD ID - set_gpio_pullup(GPIOF, 7, PULL_NONE); - set_gpio_mode(GPIOF, 7, MODE_INPUT); - - set_gpio_pullup(GPIOF, 8, PULL_NONE); - set_gpio_mode(GPIOF, 8, MODE_INPUT); - - set_gpio_pullup(GPIOF, 9, PULL_NONE); - set_gpio_mode(GPIOF, 9, MODE_INPUT); - - set_gpio_pullup(GPIOF, 10, PULL_NONE); - set_gpio_mode(GPIOF, 10, MODE_INPUT); - - //C4,A1: OBD_SBU1, OBD_SBU2 - set_gpio_pullup(GPIOC, 4, PULL_NONE); - set_gpio_mode(GPIOC, 4, MODE_ANALOG); - - set_gpio_pullup(GPIOA, 1, PULL_NONE); - set_gpio_mode(GPIOA, 1, MODE_ANALOG); - - //F11: VOLT_S - set_gpio_pullup(GPIOF, 11, PULL_NONE); - set_gpio_mode(GPIOF, 11, MODE_ANALOG); - - gpio_usb_init(); - - // B8,B9: FDCAN1 - set_gpio_pullup(GPIOB, 8, PULL_NONE); - set_gpio_alternate(GPIOB, 8, GPIO_AF9_FDCAN1); - - set_gpio_pullup(GPIOB, 9, PULL_NONE); - set_gpio_alternate(GPIOB, 9, GPIO_AF9_FDCAN1); - - // B5,B6 (mplex to B12,B13): FDCAN2 - set_gpio_pullup(GPIOB, 12, PULL_NONE); - set_gpio_pullup(GPIOB, 13, PULL_NONE); - - set_gpio_pullup(GPIOB, 5, PULL_NONE); - set_gpio_alternate(GPIOB, 5, GPIO_AF9_FDCAN2); - - set_gpio_pullup(GPIOB, 6, PULL_NONE); - set_gpio_alternate(GPIOB, 6, GPIO_AF9_FDCAN2); - - // G9,G10: FDCAN3 - set_gpio_pullup(GPIOG, 9, PULL_NONE); - set_gpio_alternate(GPIOG, 9, GPIO_AF2_FDCAN3); - - set_gpio_pullup(GPIOG, 10, PULL_NONE); - set_gpio_alternate(GPIOG, 10, GPIO_AF2_FDCAN3); -} - -void flasher_peripherals_init(void) { - RCC->AHB1ENR |= RCC_AHB1ENR_USB1OTGHSEN; - - // SPI + DMA - RCC->APB2ENR |= RCC_APB2ENR_SPI4EN; - RCC->AHB1ENR |= RCC_AHB1ENR_DMA2EN; -} - -// Peripheral initialization -void peripherals_init(void) { - // enable GPIO(A,B,C,D,E,F,G,H) - RCC->AHB4ENR |= RCC_AHB4ENR_GPIOAEN; - RCC->AHB4ENR |= RCC_AHB4ENR_GPIOBEN; - RCC->AHB4ENR |= RCC_AHB4ENR_GPIOCEN; - RCC->AHB4ENR |= RCC_AHB4ENR_GPIODEN; - RCC->AHB4ENR |= RCC_AHB4ENR_GPIOEEN; - RCC->AHB4ENR |= RCC_AHB4ENR_GPIOFEN; - RCC->AHB4ENR |= RCC_AHB4ENR_GPIOGEN; - - RCC->APB2ENR |= RCC_APB2ENR_SPI4EN; // SPI - RCC->AHB1ENR |= RCC_AHB1ENR_DMA1EN; // DAC DMA - RCC->AHB1ENR |= RCC_AHB1ENR_DMA2EN; // SPI DMA - RCC->APB1LENR |= RCC_APB1LENR_TIM2EN; // main counter - RCC->APB1LENR |= RCC_APB1LENR_TIM3EN; // fan pwm - RCC->APB1LENR |= RCC_APB1LENR_TIM6EN; // interrupt timer - RCC->APB1LENR |= RCC_APB1LENR_TIM7EN; // DMA trigger timer - RCC->APB1LENR |= RCC_APB1LENR_UART7EN; // SOM uart - RCC->APB1LENR |= RCC_APB1LENR_DAC12EN; // DAC - RCC->APB2ENR |= RCC_APB2ENR_TIM8EN; // tick timer - RCC->APB1LENR |= RCC_APB1LENR_TIM12EN; // slow loop - RCC->APB1LENR |= RCC_APB1LENR_I2C5EN; // codec I2C - RCC->APB2ENR |= RCC_APB2ENR_TIM1EN; // clock source timer - - RCC->APB1HENR |= RCC_APB1HENR_FDCANEN; // FDCAN core enable - RCC->AHB1ENR |= RCC_AHB1ENR_ADC12EN; // Enable ADC12 clocks - - RCC->APB4ENR |= RCC_APB4ENR_SYSCFGEN; - -#ifdef PANDA_JUNGLE - RCC->AHB3ENR |= RCC_AHB3ENR_SDMMC1EN; // SDMMC - RCC->AHB4ENR |= RCC_AHB4ENR_ADC3EN; // Enable ADC3 clocks -#endif - - // HS USB enable, also LP is needed for CSleep state(__WFI()) - RCC->AHB1ENR |= RCC_AHB1ENR_USB1OTGHSEN; - RCC->AHB1LPENR |= RCC_AHB1LPENR_USB1OTGHSLPEN; - RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_USB1OTGHSULPILPEN); -} - -void enable_interrupt_timer(void) { - register_set_bits(&(RCC->APB1LENR), RCC_APB1LENR_TIM6EN); // Enable interrupt timer peripheral -} diff --git a/panda/board/stm32h7/startup_stm32h7x5xx.s b/panda/board/stm32h7/startup_stm32h7x5xx.s deleted file mode 100644 index 15015a113..000000000 --- a/panda/board/stm32h7/startup_stm32h7x5xx.s +++ /dev/null @@ -1,767 +0,0 @@ -/** - ****************************************************************************** - * @file startup_stm32h735xx.s - * @author MCD Application Team - * @brief STM32H735xx Devices vector table for GCC based toolchain. - * This module performs: - * - Set the initial SP - * - Set the initial PC == Reset_Handler, - * - Set the vector table entries with the exceptions ISR address - * - Branches to main in the C library (which eventually - * calls main()). - * After Reset the Cortex-M processor is in Thread mode, - * priority is Privileged, and the Stack is set to Main. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2019 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - - .syntax unified - .cpu cortex-m7 - .fpu softvfp - .thumb - -.global g_pfnVectors -.global Default_Handler - -/* start address for the initialization values of the .data section. -defined in linker script */ -.word _sidata -/* start address for the .data section. defined in linker script */ -.word _sdata -/* end address for the .data section. defined in linker script */ -.word _edata -/* start address for the .bss section. defined in linker script */ -.word _sbss -/* end address for the .bss section. defined in linker script */ -.word _ebss -/* stack used for SystemInit_ExtMemCtl; always internal RAM used */ - -/** - * @brief This is the code that gets called when the processor first - * starts execution following a reset event. Only the absolutely - * necessary set is performed, after which the application - * supplied main() routine is called. - * @param None - * @retval : None -*/ - - .section .text.Reset_Handler - .weak Reset_Handler - .type Reset_Handler, %function -Reset_Handler: - ldr sp, =_estack /* set stack pointer */ - bl __initialize_hardware_early - -/* Copy the data segment initializers from flash to SRAM */ - ldr r0, =_sdata - ldr r1, =_edata - ldr r2, =_sidata - movs r3, #0 - b LoopCopyDataInit - -CopyDataInit: - ldr r4, [r2, r3] - str r4, [r0, r3] - adds r3, r3, #4 - -LoopCopyDataInit: - adds r4, r0, r3 - cmp r4, r1 - bcc CopyDataInit -/* Zero fill the bss segment. */ - ldr r2, =_sbss - ldr r4, =_ebss - movs r3, #0 - b LoopFillZerobss - -FillZerobss: - str r3, [r2] - adds r2, r2, #4 - -LoopFillZerobss: - cmp r2, r4 - bcc FillZerobss - -/* Call the clock system intitialization function.*/ - /* bl SystemInit */ -/* Call static constructors */ - /* bl __libc_init_array */ -/* Call the application's entry point.*/ - bl main - bx lr -.size Reset_Handler, .-Reset_Handler - -/** - * @brief This is the code that gets called when the processor receives an - * unexpected interrupt. This simply enters an infinite loop, preserving - * the system state for examination by a debugger. - * @param None - * @retval None -*/ - .section .text.Default_Handler,"ax",%progbits -Default_Handler: -Infinite_Loop: - b Infinite_Loop - .size Default_Handler, .-Default_Handler -/****************************************************************************** -* -* The minimal vector table for a Cortex M. Note that the proper constructs -* must be placed on this to ensure that it ends up at physical address -* 0x0000.0000. -* -*******************************************************************************/ - .section .isr_vector,"a",%progbits - .type g_pfnVectors, %object - .size g_pfnVectors, .-g_pfnVectors - - -g_pfnVectors: - .word _estack - .word Reset_Handler - - .word NMI_Handler - .word HardFault_Handler - .word MemManage_Handler - .word BusFault_Handler - .word UsageFault_Handler - .word 0 - .word 0 - .word 0 - .word 0 - .word SVC_Handler - .word DebugMon_Handler - .word 0 - .word PendSV_Handler - .word SysTick_Handler - - /* External Interrupts */ - .word WWDG_IRQHandler /* Window WatchDog */ - .word PVD_AVD_IRQHandler /* PVD/AVD through EXTI Line detection */ - .word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXTI line */ - .word RTC_WKUP_IRQHandler /* RTC Wakeup through the EXTI line */ - .word FLASH_IRQHandler /* FLASH */ - .word RCC_IRQHandler /* RCC */ - .word EXTI0_IRQHandler /* EXTI Line0 */ - .word EXTI1_IRQHandler /* EXTI Line1 */ - .word EXTI2_IRQHandler /* EXTI Line2 */ - .word EXTI3_IRQHandler /* EXTI Line3 */ - .word EXTI4_IRQHandler /* EXTI Line4 */ - .word DMA1_Stream0_IRQHandler /* DMA1 Stream 0 */ - .word DMA1_Stream1_IRQHandler /* DMA1 Stream 1 */ - .word DMA1_Stream2_IRQHandler /* DMA1 Stream 2 */ - .word DMA1_Stream3_IRQHandler /* DMA1 Stream 3 */ - .word DMA1_Stream4_IRQHandler /* DMA1 Stream 4 */ - .word DMA1_Stream5_IRQHandler /* DMA1 Stream 5 */ - .word DMA1_Stream6_IRQHandler /* DMA1 Stream 6 */ - .word ADC_IRQHandler /* ADC1, ADC2 and ADC3s */ - .word FDCAN1_IT0_IRQHandler /* FDCAN1 interrupt line 0 */ - .word FDCAN2_IT0_IRQHandler /* FDCAN2 interrupt line 0 */ - .word FDCAN1_IT1_IRQHandler /* FDCAN1 interrupt line 1 */ - .word FDCAN2_IT1_IRQHandler /* FDCAN2 interrupt line 1 */ - .word EXTI9_5_IRQHandler /* External Line[9:5]s */ - .word TIM1_BRK_IRQHandler /* TIM1 Break interrupt */ - .word TIM1_UP_IRQHandler /* TIM1 Update interrupt */ - .word TIM1_TRG_COM_IRQHandler /* TIM1 Trigger and Commutation interrupt */ - .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */ - .word TIM2_IRQHandler /* TIM2 */ - .word TIM3_IRQHandler /* TIM3 */ - .word TIM4_IRQHandler /* TIM4 */ - .word I2C1_EV_IRQHandler /* I2C1 Event */ - .word I2C1_ER_IRQHandler /* I2C1 Error */ - .word I2C2_EV_IRQHandler /* I2C2 Event */ - .word I2C2_ER_IRQHandler /* I2C2 Error */ - .word SPI1_IRQHandler /* SPI1 */ - .word SPI2_IRQHandler /* SPI2 */ - .word USART1_IRQHandler /* USART1 */ - .word USART2_IRQHandler /* USART2 */ - .word USART3_IRQHandler /* USART3 */ - .word EXTI15_10_IRQHandler /* External Line[15:10]s */ - .word RTC_Alarm_IRQHandler /* RTC Alarm (A and B) through EXTI Line */ - .word 0 /* Reserved */ - .word TIM8_BRK_TIM12_IRQHandler /* TIM8 Break and TIM12 */ - .word TIM8_UP_TIM13_IRQHandler /* TIM8 Update and TIM13 */ - .word TIM8_TRG_COM_TIM14_IRQHandler /* TIM8 Trigger and Commutation and TIM14 */ - .word TIM8_CC_IRQHandler /* TIM8 Capture Compare */ - .word DMA1_Stream7_IRQHandler /* DMA1 Stream7 */ - .word FMC_IRQHandler /* FMC */ - .word SDMMC1_IRQHandler /* SDMMC1 */ - .word TIM5_IRQHandler /* TIM5 */ - .word SPI3_IRQHandler /* SPI3 */ - .word UART4_IRQHandler /* UART4 */ - .word UART5_IRQHandler /* UART5 */ - .word TIM6_DAC_IRQHandler /* TIM6 and DAC1&2 underrun errors */ - .word TIM7_IRQHandler /* TIM7 */ - .word DMA2_Stream0_IRQHandler /* DMA2 Stream 0 */ - .word DMA2_Stream1_IRQHandler /* DMA2 Stream 1 */ - .word DMA2_Stream2_IRQHandler /* DMA2 Stream 2 */ - .word DMA2_Stream3_IRQHandler /* DMA2 Stream 3 */ - .word DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */ - .word ETH_IRQHandler /* Ethernet */ - .word ETH_WKUP_IRQHandler /* Ethernet Wakeup through EXTI line */ - .word FDCAN_CAL_IRQHandler /* FDCAN calibration unit interrupt*/ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */ - .word DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */ - .word DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */ - .word USART6_IRQHandler /* USART6 */ - .word I2C3_EV_IRQHandler /* I2C3 event */ - .word I2C3_ER_IRQHandler /* I2C3 error */ - .word OTG_HS_EP1_OUT_IRQHandler /* USB OTG HS End Point 1 Out */ - .word OTG_HS_EP1_IN_IRQHandler /* USB OTG HS End Point 1 In */ - .word OTG_HS_WKUP_IRQHandler /* USB OTG HS Wakeup through EXTI */ - .word OTG_HS_IRQHandler /* USB OTG HS */ - .word DCMI_PSSI_IRQHandler /* DCMI, PSSI */ - .word CRYP_IRQHandler /* CRYP */ - .word HASH_RNG_IRQHandler /* Hash and Rng */ - .word FPU_IRQHandler /* FPU */ - .word UART7_IRQHandler /* UART7 */ - .word UART8_IRQHandler /* UART8 */ - .word SPI4_IRQHandler /* SPI4 */ - .word SPI5_IRQHandler /* SPI5 */ - .word SPI6_IRQHandler /* SPI6 */ - .word SAI1_IRQHandler /* SAI1 */ - .word LTDC_IRQHandler /* LTDC */ - .word LTDC_ER_IRQHandler /* LTDC error */ - .word DMA2D_IRQHandler /* DMA2D */ - .word 0 /* Reserved */ - .word OCTOSPI1_IRQHandler /* OCTOSPI1 */ - .word LPTIM1_IRQHandler /* LPTIM1 */ - .word CEC_IRQHandler /* HDMI_CEC */ - .word I2C4_EV_IRQHandler /* I2C4 Event */ - .word I2C4_ER_IRQHandler /* I2C4 Error */ - .word SPDIF_RX_IRQHandler /* SPDIF_RX */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word DMAMUX1_OVR_IRQHandler /* DMAMUX1 Overrun interrupt */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word DFSDM1_FLT0_IRQHandler /* DFSDM Filter0 Interrupt */ - .word DFSDM1_FLT1_IRQHandler /* DFSDM Filter1 Interrupt */ - .word DFSDM1_FLT2_IRQHandler /* DFSDM Filter2 Interrupt */ - .word DFSDM1_FLT3_IRQHandler /* DFSDM Filter3 Interrupt */ - .word 0 /* Reserved */ - .word SWPMI1_IRQHandler /* Serial Wire Interface 1 global interrupt */ - .word TIM15_IRQHandler /* TIM15 global Interrupt */ - .word TIM16_IRQHandler /* TIM16 global Interrupt */ - .word TIM17_IRQHandler /* TIM17 global Interrupt */ - .word MDIOS_WKUP_IRQHandler /* MDIOS Wakeup Interrupt */ - .word MDIOS_IRQHandler /* MDIOS global Interrupt */ - .word 0 /* Reserved */ - .word MDMA_IRQHandler /* MDMA global Interrupt */ - .word 0 /* Reserved */ - .word SDMMC2_IRQHandler /* SDMMC2 global Interrupt */ - .word HSEM1_IRQHandler /* HSEM1 global Interrupt */ - .word 0 /* Reserved */ - .word ADC3_IRQHandler /* ADC3 global Interrupt */ - .word DMAMUX2_OVR_IRQHandler /* DMAMUX Overrun interrupt */ - .word BDMA_Channel0_IRQHandler /* BDMA Channel 0 global Interrupt */ - .word BDMA_Channel1_IRQHandler /* BDMA Channel 1 global Interrupt */ - .word BDMA_Channel2_IRQHandler /* BDMA Channel 2 global Interrupt */ - .word BDMA_Channel3_IRQHandler /* BDMA Channel 3 global Interrupt */ - .word BDMA_Channel4_IRQHandler /* BDMA Channel 4 global Interrupt */ - .word BDMA_Channel5_IRQHandler /* BDMA Channel 5 global Interrupt */ - .word BDMA_Channel6_IRQHandler /* BDMA Channel 6 global Interrupt */ - .word BDMA_Channel7_IRQHandler /* BDMA Channel 7 global Interrupt */ - .word COMP1_IRQHandler /* COMP1 global Interrupt */ - .word LPTIM2_IRQHandler /* LP TIM2 global interrupt */ - .word LPTIM3_IRQHandler /* LP TIM3 global interrupt */ - .word LPTIM4_IRQHandler /* LP TIM4 global interrupt */ - .word LPTIM5_IRQHandler /* LP TIM5 global interrupt */ - .word LPUART1_IRQHandler /* LP UART1 interrupt */ - .word 0 /* Reserved */ - .word CRS_IRQHandler /* Clock Recovery Global Interrupt */ - .word ECC_IRQHandler /* ECC diagnostic Global Interrupt */ - .word SAI4_IRQHandler /* SAI4 global interrupt */ - .word DTS_IRQHandler /* Digital Temperature Sensor interrupt */ - .word 0 /* Reserved */ - .word WAKEUP_PIN_IRQHandler /* Interrupt for all 6 wake-up pins */ - .word OCTOSPI2_IRQHandler /* OCTOSPI2 Interrupt */ - .word OTFDEC1_IRQHandler /* OTFDEC1 Interrupt */ - .word OTFDEC2_IRQHandler /* OTFDEC2 Interrupt */ - .word FMAC_IRQHandler /* FMAC Interrupt */ - .word CORDIC_IRQHandler /* CORDIC Interrupt */ - .word UART9_IRQHandler /* UART9 Interrupt */ - .word USART10_IRQHandler /* UART10 Interrupt */ - .word I2C5_EV_IRQHandler /* I2C5 Event Interrupt */ - .word I2C5_ER_IRQHandler /* I2C5 Error Interrupt */ - .word FDCAN3_IT0_IRQHandler /* FDCAN3 interrupt line 0 */ - .word FDCAN3_IT1_IRQHandler /* FDCAN3 interrupt line 1 */ - .word TIM23_IRQHandler /* TIM23 global interrupt */ - .word TIM24_IRQHandler /* TIM24 global interrupt */ - -/******************************************************************************* -* -* Provide weak aliases for each Exception handler to the Default_Handler. -* As they are weak aliases, any function with the same name will override -* this definition. -* -*******************************************************************************/ - .weak NMI_Handler - .thumb_set NMI_Handler,Default_Handler - - .weak HardFault_Handler - .thumb_set HardFault_Handler,Default_Handler - - .weak MemManage_Handler - .thumb_set MemManage_Handler,Default_Handler - - .weak BusFault_Handler - .thumb_set BusFault_Handler,Default_Handler - - .weak UsageFault_Handler - .thumb_set UsageFault_Handler,Default_Handler - - .weak SVC_Handler - .thumb_set SVC_Handler,Default_Handler - - .weak DebugMon_Handler - .thumb_set DebugMon_Handler,Default_Handler - - .weak PendSV_Handler - .thumb_set PendSV_Handler,Default_Handler - - .weak SysTick_Handler - .thumb_set SysTick_Handler,Default_Handler - - .weak WWDG_IRQHandler - .thumb_set WWDG_IRQHandler,Default_Handler - - .weak PVD_AVD_IRQHandler - .thumb_set PVD_AVD_IRQHandler,Default_Handler - - .weak TAMP_STAMP_IRQHandler - .thumb_set TAMP_STAMP_IRQHandler,Default_Handler - - .weak RTC_WKUP_IRQHandler - .thumb_set RTC_WKUP_IRQHandler,Default_Handler - - .weak FLASH_IRQHandler - .thumb_set FLASH_IRQHandler,Default_Handler - - .weak RCC_IRQHandler - .thumb_set RCC_IRQHandler,Default_Handler - - .weak EXTI0_IRQHandler - .thumb_set EXTI0_IRQHandler,Default_Handler - - .weak EXTI1_IRQHandler - .thumb_set EXTI1_IRQHandler,Default_Handler - - .weak EXTI2_IRQHandler - .thumb_set EXTI2_IRQHandler,Default_Handler - - .weak EXTI3_IRQHandler - .thumb_set EXTI3_IRQHandler,Default_Handler - - .weak EXTI4_IRQHandler - .thumb_set EXTI4_IRQHandler,Default_Handler - - .weak DMA1_Stream0_IRQHandler - .thumb_set DMA1_Stream0_IRQHandler,Default_Handler - - .weak DMA1_Stream1_IRQHandler - .thumb_set DMA1_Stream1_IRQHandler,Default_Handler - - .weak DMA1_Stream2_IRQHandler - .thumb_set DMA1_Stream2_IRQHandler,Default_Handler - - .weak DMA1_Stream3_IRQHandler - .thumb_set DMA1_Stream3_IRQHandler,Default_Handler - - .weak DMA1_Stream4_IRQHandler - .thumb_set DMA1_Stream4_IRQHandler,Default_Handler - - .weak DMA1_Stream5_IRQHandler - .thumb_set DMA1_Stream5_IRQHandler,Default_Handler - - .weak DMA1_Stream6_IRQHandler - .thumb_set DMA1_Stream6_IRQHandler,Default_Handler - - .weak ADC_IRQHandler - .thumb_set ADC_IRQHandler,Default_Handler - - .weak FDCAN1_IT0_IRQHandler - .thumb_set FDCAN1_IT0_IRQHandler,Default_Handler - - .weak FDCAN2_IT0_IRQHandler - .thumb_set FDCAN2_IT0_IRQHandler,Default_Handler - - .weak FDCAN1_IT1_IRQHandler - .thumb_set FDCAN1_IT1_IRQHandler,Default_Handler - - .weak FDCAN2_IT1_IRQHandler - .thumb_set FDCAN2_IT1_IRQHandler,Default_Handler - - .weak EXTI9_5_IRQHandler - .thumb_set EXTI9_5_IRQHandler,Default_Handler - - .weak TIM1_BRK_IRQHandler - .thumb_set TIM1_BRK_IRQHandler,Default_Handler - - .weak TIM1_UP_IRQHandler - .thumb_set TIM1_UP_IRQHandler,Default_Handler - - .weak TIM1_TRG_COM_IRQHandler - .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler - - .weak TIM1_CC_IRQHandler - .thumb_set TIM1_CC_IRQHandler,Default_Handler - - .weak TIM2_IRQHandler - .thumb_set TIM2_IRQHandler,Default_Handler - - .weak TIM3_IRQHandler - .thumb_set TIM3_IRQHandler,Default_Handler - - .weak TIM4_IRQHandler - .thumb_set TIM4_IRQHandler,Default_Handler - - .weak I2C1_EV_IRQHandler - .thumb_set I2C1_EV_IRQHandler,Default_Handler - - .weak I2C1_ER_IRQHandler - .thumb_set I2C1_ER_IRQHandler,Default_Handler - - .weak I2C2_EV_IRQHandler - .thumb_set I2C2_EV_IRQHandler,Default_Handler - - .weak I2C2_ER_IRQHandler - .thumb_set I2C2_ER_IRQHandler,Default_Handler - - .weak SPI1_IRQHandler - .thumb_set SPI1_IRQHandler,Default_Handler - - .weak SPI2_IRQHandler - .thumb_set SPI2_IRQHandler,Default_Handler - - .weak USART1_IRQHandler - .thumb_set USART1_IRQHandler,Default_Handler - - .weak USART2_IRQHandler - .thumb_set USART2_IRQHandler,Default_Handler - - .weak USART3_IRQHandler - .thumb_set USART3_IRQHandler,Default_Handler - - .weak EXTI15_10_IRQHandler - .thumb_set EXTI15_10_IRQHandler,Default_Handler - - .weak RTC_Alarm_IRQHandler - .thumb_set RTC_Alarm_IRQHandler,Default_Handler - - .weak TIM8_BRK_TIM12_IRQHandler - .thumb_set TIM8_BRK_TIM12_IRQHandler,Default_Handler - - .weak TIM8_UP_TIM13_IRQHandler - .thumb_set TIM8_UP_TIM13_IRQHandler,Default_Handler - - .weak TIM8_TRG_COM_TIM14_IRQHandler - .thumb_set TIM8_TRG_COM_TIM14_IRQHandler,Default_Handler - - .weak TIM8_CC_IRQHandler - .thumb_set TIM8_CC_IRQHandler,Default_Handler - - .weak DMA1_Stream7_IRQHandler - .thumb_set DMA1_Stream7_IRQHandler,Default_Handler - - .weak FMC_IRQHandler - .thumb_set FMC_IRQHandler,Default_Handler - - .weak SDMMC1_IRQHandler - .thumb_set SDMMC1_IRQHandler,Default_Handler - - .weak TIM5_IRQHandler - .thumb_set TIM5_IRQHandler,Default_Handler - - .weak SPI3_IRQHandler - .thumb_set SPI3_IRQHandler,Default_Handler - - .weak UART4_IRQHandler - .thumb_set UART4_IRQHandler,Default_Handler - - .weak UART5_IRQHandler - .thumb_set UART5_IRQHandler,Default_Handler - - .weak TIM6_DAC_IRQHandler - .thumb_set TIM6_DAC_IRQHandler,Default_Handler - - .weak TIM7_IRQHandler - .thumb_set TIM7_IRQHandler,Default_Handler - - .weak DMA2_Stream0_IRQHandler - .thumb_set DMA2_Stream0_IRQHandler,Default_Handler - - .weak DMA2_Stream1_IRQHandler - .thumb_set DMA2_Stream1_IRQHandler,Default_Handler - - .weak DMA2_Stream2_IRQHandler - .thumb_set DMA2_Stream2_IRQHandler,Default_Handler - - .weak DMA2_Stream3_IRQHandler - .thumb_set DMA2_Stream3_IRQHandler,Default_Handler - - .weak DMA2_Stream4_IRQHandler - .thumb_set DMA2_Stream4_IRQHandler,Default_Handler - - .weak ETH_IRQHandler - .thumb_set ETH_IRQHandler,Default_Handler - - .weak ETH_WKUP_IRQHandler - .thumb_set ETH_WKUP_IRQHandler,Default_Handler - - .weak FDCAN_CAL_IRQHandler - .thumb_set FDCAN_CAL_IRQHandler,Default_Handler - - .weak DMA2_Stream5_IRQHandler - .thumb_set DMA2_Stream5_IRQHandler,Default_Handler - - .weak DMA2_Stream6_IRQHandler - .thumb_set DMA2_Stream6_IRQHandler,Default_Handler - - .weak DMA2_Stream7_IRQHandler - .thumb_set DMA2_Stream7_IRQHandler,Default_Handler - - .weak USART6_IRQHandler - .thumb_set USART6_IRQHandler,Default_Handler - - .weak I2C3_EV_IRQHandler - .thumb_set I2C3_EV_IRQHandler,Default_Handler - - .weak I2C3_ER_IRQHandler - .thumb_set I2C3_ER_IRQHandler,Default_Handler - - .weak OTG_HS_EP1_OUT_IRQHandler - .thumb_set OTG_HS_EP1_OUT_IRQHandler,Default_Handler - - .weak OTG_HS_EP1_IN_IRQHandler - .thumb_set OTG_HS_EP1_IN_IRQHandler,Default_Handler - - .weak OTG_HS_WKUP_IRQHandler - .thumb_set OTG_HS_WKUP_IRQHandler,Default_Handler - - .weak OTG_HS_IRQHandler - .thumb_set OTG_HS_IRQHandler,Default_Handler - - .weak DCMI_PSSI_IRQHandler - .thumb_set DCMI_PSSI_IRQHandler,Default_Handler - - .weak CRYP_IRQHandler - .thumb_set CRYP_IRQHandler,Default_Handler - - .weak HASH_RNG_IRQHandler - .thumb_set HASH_RNG_IRQHandler,Default_Handler - - .weak FPU_IRQHandler - .thumb_set FPU_IRQHandler,Default_Handler - - .weak UART7_IRQHandler - .thumb_set UART7_IRQHandler,Default_Handler - - .weak UART8_IRQHandler - .thumb_set UART8_IRQHandler,Default_Handler - - .weak SPI4_IRQHandler - .thumb_set SPI4_IRQHandler,Default_Handler - - .weak SPI5_IRQHandler - .thumb_set SPI5_IRQHandler,Default_Handler - - .weak SPI6_IRQHandler - .thumb_set SPI6_IRQHandler,Default_Handler - - .weak SAI1_IRQHandler - .thumb_set SAI1_IRQHandler,Default_Handler - - .weak LTDC_IRQHandler - .thumb_set LTDC_IRQHandler,Default_Handler - - .weak LTDC_ER_IRQHandler - .thumb_set LTDC_ER_IRQHandler,Default_Handler - - .weak DMA2D_IRQHandler - .thumb_set DMA2D_IRQHandler,Default_Handler - - .weak OCTOSPI1_IRQHandler - .thumb_set OCTOSPI1_IRQHandler,Default_Handler - - .weak LPTIM1_IRQHandler - .thumb_set LPTIM1_IRQHandler,Default_Handler - - .weak CEC_IRQHandler - .thumb_set CEC_IRQHandler,Default_Handler - - .weak I2C4_EV_IRQHandler - .thumb_set I2C4_EV_IRQHandler,Default_Handler - - .weak I2C4_ER_IRQHandler - .thumb_set I2C4_ER_IRQHandler,Default_Handler - - .weak SPDIF_RX_IRQHandler - .thumb_set SPDIF_RX_IRQHandler,Default_Handler - - .weak DMAMUX1_OVR_IRQHandler - .thumb_set DMAMUX1_OVR_IRQHandler,Default_Handler - - .weak DFSDM1_FLT0_IRQHandler - .thumb_set DFSDM1_FLT0_IRQHandler,Default_Handler - - .weak DFSDM1_FLT1_IRQHandler - .thumb_set DFSDM1_FLT1_IRQHandler,Default_Handler - - .weak DFSDM1_FLT2_IRQHandler - .thumb_set DFSDM1_FLT2_IRQHandler,Default_Handler - - .weak DFSDM1_FLT3_IRQHandler - .thumb_set DFSDM1_FLT3_IRQHandler,Default_Handler - - .weak SWPMI1_IRQHandler - .thumb_set SWPMI1_IRQHandler,Default_Handler - - .weak TIM15_IRQHandler - .thumb_set TIM15_IRQHandler,Default_Handler - - .weak TIM16_IRQHandler - .thumb_set TIM16_IRQHandler,Default_Handler - - .weak TIM17_IRQHandler - .thumb_set TIM17_IRQHandler,Default_Handler - - .weak MDIOS_WKUP_IRQHandler - .thumb_set MDIOS_WKUP_IRQHandler,Default_Handler - - .weak MDIOS_IRQHandler - .thumb_set MDIOS_IRQHandler,Default_Handler - - .weak MDMA_IRQHandler - .thumb_set MDMA_IRQHandler,Default_Handler - - .weak SDMMC2_IRQHandler - .thumb_set SDMMC2_IRQHandler,Default_Handler - - .weak HSEM1_IRQHandler - .thumb_set HSEM1_IRQHandler,Default_Handler - - .weak ADC3_IRQHandler - .thumb_set ADC3_IRQHandler,Default_Handler - - .weak DMAMUX2_OVR_IRQHandler - .thumb_set DMAMUX2_OVR_IRQHandler,Default_Handler - - .weak BDMA_Channel0_IRQHandler - .thumb_set BDMA_Channel0_IRQHandler,Default_Handler - - .weak BDMA_Channel1_IRQHandler - .thumb_set BDMA_Channel1_IRQHandler,Default_Handler - - .weak BDMA_Channel2_IRQHandler - .thumb_set BDMA_Channel2_IRQHandler,Default_Handler - - .weak BDMA_Channel3_IRQHandler - .thumb_set BDMA_Channel3_IRQHandler,Default_Handler - - .weak BDMA_Channel4_IRQHandler - .thumb_set BDMA_Channel4_IRQHandler,Default_Handler - - .weak BDMA_Channel5_IRQHandler - .thumb_set BDMA_Channel5_IRQHandler,Default_Handler - - .weak BDMA_Channel6_IRQHandler - .thumb_set BDMA_Channel6_IRQHandler,Default_Handler - - .weak BDMA_Channel7_IRQHandler - .thumb_set BDMA_Channel7_IRQHandler,Default_Handler - - .weak COMP1_IRQHandler - .thumb_set COMP1_IRQHandler,Default_Handler - - .weak LPTIM2_IRQHandler - .thumb_set LPTIM2_IRQHandler,Default_Handler - - .weak LPTIM3_IRQHandler - .thumb_set LPTIM3_IRQHandler,Default_Handler - - .weak LPTIM4_IRQHandler - .thumb_set LPTIM4_IRQHandler,Default_Handler - - .weak LPTIM5_IRQHandler - .thumb_set LPTIM5_IRQHandler,Default_Handler - - .weak LPUART1_IRQHandler - .thumb_set LPUART1_IRQHandler,Default_Handler - - .weak CRS_IRQHandler - .thumb_set CRS_IRQHandler,Default_Handler - - .weak ECC_IRQHandler - .thumb_set ECC_IRQHandler,Default_Handler - - .weak SAI4_IRQHandler - .thumb_set SAI4_IRQHandler,Default_Handler - - .weak DTS_IRQHandler - .thumb_set DTS_IRQHandler,Default_Handler - - .weak WAKEUP_PIN_IRQHandler - .thumb_set WAKEUP_PIN_IRQHandler,Default_Handler - - .weak OCTOSPI2_IRQHandler - .thumb_set OCTOSPI2_IRQHandler,Default_Handler - - .weak OTFDEC1_IRQHandler - .thumb_set OTFDEC1_IRQHandler,Default_Handler - - .weak OTFDEC2_IRQHandler - .thumb_set OTFDEC2_IRQHandler,Default_Handler - - .weak FMAC_IRQHandler - .thumb_set FMAC_IRQHandler,Default_Handler - - .weak CORDIC_IRQHandler - .thumb_set CORDIC_IRQHandler,Default_Handler - - .weak UART9_IRQHandler - .thumb_set UART9_IRQHandler,Default_Handler - - .weak USART10_IRQHandler - .thumb_set USART10_IRQHandler,Default_Handler - - .weak I2C5_EV_IRQHandler - .thumb_set I2C5_EV_IRQHandler,Default_Handler - - .weak I2C5_ER_IRQHandler - .thumb_set I2C5_ER_IRQHandler,Default_Handler - - .weak FDCAN3_IT0_IRQHandler - .thumb_set FDCAN3_IT0_IRQHandler,Default_Handler - - .weak FDCAN3_IT1_IRQHandler - .thumb_set FDCAN3_IT1_IRQHandler,Default_Handler - - .weak TIM23_IRQHandler - .thumb_set TIM23_IRQHandler,Default_Handler - - .weak TIM24_IRQHandler - .thumb_set TIM24_IRQHandler,Default_Handler - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ - diff --git a/panda/board/stm32h7/stm32h7_config.h b/panda/board/stm32h7/stm32h7_config.h deleted file mode 100644 index f00b5794d..000000000 --- a/panda/board/stm32h7/stm32h7_config.h +++ /dev/null @@ -1,104 +0,0 @@ -#include "stm32h7/inc/stm32h7xx.h" -#include "stm32h7/inc/stm32h7xx_hal_gpio_ex.h" -#define MCU_IDCODE 0x483U - -// from the linker script -#define APP_START_ADDRESS 0x8020000U - -#define CORE_FREQ 240U // in Mhz -//APB1 - 120Mhz, APB2 - 120Mhz -#define APB1_FREQ (CORE_FREQ/4U) -#define APB1_TIMER_FREQ (APB1_FREQ*2U) // APB1 is multiplied by 2 for the timer peripherals -#define APB2_FREQ (CORE_FREQ/4U) -#define APB2_TIMER_FREQ (APB2_FREQ*2U) // APB2 is multiplied by 2 for the timer peripherals - -#define BOOTLOADER_ADDRESS 0x1FF09804U - -/* -An IRQ is received on message RX/TX (or RX errors), with -separate IRQs for RX and TX. - -0-byte CAN FD frame as the worst case: -- 17 slow bits = SOF + 11 ID + R1 + IDE + EDL + R0 + BRS -- 23 fast bits = ESI + 4 DLC + 0 DATA + 17 CRC + CRC delimeter -- 12 slow bits = ACK + DEL + 7 EOF + 3 IFS -- all currently supported cars are 0.5 Mbps / 2 Mbps - -1 / ((29 bits / 0.5Mbps) + (23 bits / 2Mbps)) = 14388Hz -*/ -#define CAN_INTERRUPT_RATE 16000U - -#define MAX_LED_FADE 10240U - -// There are 163 external interrupt sources (see stm32f735xx.h) -#define NUM_INTERRUPTS 163U - -#define TICK_TIMER_IRQ TIM8_BRK_TIM12_IRQn -#define TICK_TIMER TIM12 - -#define MICROSECOND_TIMER TIM2 - -#define INTERRUPT_TIMER_IRQ TIM6_DAC_IRQn -#define INTERRUPT_TIMER TIM6 - -#define IND_WDG IWDG1 - -#define PROVISION_CHUNK_ADDRESS 0x080FFFE0U -#define DEVICE_SERIAL_NUMBER_ADDRESS 0x080FFFC0U - -#define LOGGING_FLASH_SECTOR_A 5U -#define LOGGING_FLASH_SECTOR_B 6U -#define LOGGING_FLASH_BASE_A 0x080A0000U -#define LOGGING_FLASH_BASE_B 0x080C0000U -#define LOGGING_FLASH_SECTOR_SIZE 0x20000U - -#include "can_definitions.h" -#include "comms_definitions.h" - -#ifndef BOOTSTUB - #include "main_declarations.h" -#else - #include "bootstub_declarations.h" -#endif - -#include "libc.h" -#include "critical.h" -#include "faults.h" -#include "utils.h" - -#include "drivers/registers.h" -#include "drivers/interrupts.h" -#include "drivers/gpio.h" -#include "stm32h7/peripherals.h" -#include "stm32h7/interrupt_handlers.h" -#include "drivers/timers.h" -#include "drivers/watchdog.h" -#include "stm32h7/llflash.h" - -#if !defined(BOOTSTUB) - #include "drivers/uart.h" - #include "stm32h7/lluart.h" -#endif - -#include "stm32h7/board.h" -#include "stm32h7/clock.h" - -#if !defined(BOOTSTUB) && defined(PANDA) - #include "stm32h7/llexti.h" -#endif - -#ifndef BOOTSTUB - #include "stm32h7/llfdcan.h" -#endif - -#include "stm32h7/llusb.h" - -#include "drivers/spi.h" -#include "stm32h7/llspi.h" - -void early_gpio_float(void) { - RCC->AHB4ENR = RCC_AHB4ENR_GPIOAEN | RCC_AHB4ENR_GPIOBEN | RCC_AHB4ENR_GPIOCEN | RCC_AHB4ENR_GPIODEN | RCC_AHB4ENR_GPIOEEN | RCC_AHB4ENR_GPIOFEN | RCC_AHB4ENR_GPIOGEN | RCC_AHB4ENR_GPIOHEN; - GPIOA->MODER = 0xAB000000; GPIOB->MODER = 0; GPIOC->MODER = 0; GPIOD->MODER = 0; GPIOE->MODER = 0; GPIOF->MODER = 0; GPIOG->MODER = 0; GPIOH->MODER = 0; - GPIOA->ODR = 0; GPIOB->ODR = 0; GPIOC->ODR = 0; GPIOD->ODR = 0; GPIOE->ODR = 0; GPIOF->ODR = 0; GPIOG->ODR = 0; GPIOH->ODR = 0; - GPIOA->PUPDR = 0; GPIOB->PUPDR = 0; GPIOC->PUPDR = 0; GPIOD->PUPDR = 0; GPIOE->PUPDR = 0; GPIOF->PUPDR = 0; GPIOG->PUPDR = 0; GPIOH->PUPDR = 0; -} diff --git a/panda/board/stm32h7/stm32h7x5_flash.ld b/panda/board/stm32h7/stm32h7x5_flash.ld deleted file mode 100644 index 5aef66374..000000000 --- a/panda/board/stm32h7/stm32h7x5_flash.ld +++ /dev/null @@ -1,198 +0,0 @@ -/* -****************************************************************************** -** - -** File : LinkerScript.ld -** -** Author : Auto-generated by System Workbench for STM32 -** -** Abstract : Linker script for STM32H735ZGTx series -** 1024Kbytes FLASH and 560Kbytes RAM -** -** Set heap size, stack size and stack location according -** to application requirements. -** -** Set memory bank area and size if external memory is used. -** -** Target : STMicroelectronics STM32 -** -** Distribution: The file is distributed “as is,” without any warranty -** of any kind. -** -***************************************************************************** -** @attention -** -**

© COPYRIGHT(c) 2019 STMicroelectronics

-** -** 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. -** 3. Neither the name of STMicroelectronics nor the names of its contributors -** may be used to endorse or promote products derived from this software -** without specific prior written permission. -** -** 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 HOLDER 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. -** -***************************************************************************** -*/ - -/* Entry Point */ -ENTRY(Reset_Handler) - -/* Highest address of the user mode stack */ -enter_bootloader_mode = 0x38001FFC; -_estack = 0x20020000; /* end of RAM */ -_app_start = 0x08020000; /* Reserve Sector 0(128K) for bootloader */ - -/* Generate a link error if heap and stack don't fit into RAM */ -_Min_Heap_Size = 0x200; /* required amount of heap */ -_Min_Stack_Size = 0x400; /* required amount of stack */ - -/* Specify the memory areas */ -MEMORY -{ -DTCMRAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K /* DTCM */ -RAM_D1 (xrw) : ORIGIN = 0x24000000, LENGTH = 320K /* AXI SRAM */ -RAM_D2 (xrw) : ORIGIN = 0x30000000, LENGTH = 32K /* SRAM1(16kb) + SRAM2(16kb) */ -RAM_D3 (xrw) : ORIGIN = 0x38000000, LENGTH = 16K /* SRAM4 */ -ITCMRAM (xrw) : ORIGIN = 0x00000000, LENGTH = 64K -FLASH (rx) : ORIGIN = 0x8000000, LENGTH = 1024K -} - -/* Define output sections */ -SECTIONS -{ - /* The startup code goes first into FLASH */ - .isr_vector : - { - . = ALIGN(4); - KEEP(*(.isr_vector)) /* Startup code */ - . = ALIGN(4); - } >FLASH - - /* The program code and other data goes into FLASH */ - .text : - { - . = ALIGN(4); - *(.text) /* .text sections (code) */ - *(.text*) /* .text* sections (code) */ - *(.glue_7) /* glue arm to thumb code */ - *(.glue_7t) /* glue thumb to arm code */ - *(.eh_frame) - - KEEP (*(.init)) - KEEP (*(.fini)) - - . = ALIGN(4); - _etext = .; /* define a global symbols at end of code */ - } >FLASH - - /* Constant data goes into FLASH */ - .rodata : - { - . = ALIGN(4); - *(.rodata) /* .rodata sections (constants, strings, etc.) */ - *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ - . = ALIGN(4); - } >FLASH - - .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH - .ARM : { - __exidx_start = .; - *(.ARM.exidx*) - __exidx_end = .; - } >FLASH - - .preinit_array : - { - PROVIDE_HIDDEN (__preinit_array_start = .); - KEEP (*(.preinit_array*)) - PROVIDE_HIDDEN (__preinit_array_end = .); - } >FLASH - .init_array : - { - PROVIDE_HIDDEN (__init_array_start = .); - KEEP (*(SORT(.init_array.*))) - KEEP (*(.init_array*)) - PROVIDE_HIDDEN (__init_array_end = .); - } >FLASH - .fini_array : - { - PROVIDE_HIDDEN (__fini_array_start = .); - KEEP (*(SORT(.fini_array.*))) - KEEP (*(.fini_array*)) - PROVIDE_HIDDEN (__fini_array_end = .); - } >FLASH - - /* used by the startup to initialize data */ - _sidata = LOADADDR(.data); - - /* Initialized data sections goes into RAM, load LMA copy after code */ - .data : - { - . = ALIGN(4); - _sdata = .; /* create a global symbol at data start */ - *(.data) /* .data sections */ - *(.data*) /* .data* sections */ - - . = ALIGN(4); - _edata = .; /* define a global symbol at data end */ - } >DTCMRAM AT> FLASH - - - /* Uninitialized data section */ - . = ALIGN(4); - .bss : - { - /* This is used by the startup in order to initialize the .bss secion */ - _sbss = .; /* define a global symbol at bss start */ - __bss_start__ = _sbss; - *(.bss) - *(.bss*) - *(COMMON) - - . = ALIGN(4); - _ebss = .; /* define a global symbol at bss end */ - __bss_end__ = _ebss; - } >DTCMRAM - - /* User_heap_stack section, used to check that there is enough RAM left */ - ._user_heap_stack : - { - . = ALIGN(8); - PROVIDE ( end = . ); - PROVIDE ( _end = . ); - . = . + _Min_Heap_Size; - . = . + _Min_Stack_Size; - . = ALIGN(8); - } >DTCMRAM - - .ram_d1 (NOLOAD) : - { - . = ALIGN(4); - *(.ram_d1*) - } >RAM_D1 - - .ram_d2 (NOLOAD) : - { - . = ALIGN(4); - *(.ram_d2*) - } >RAM_D2 - - .ARM.attributes 0 : { *(.ARM.attributes) } -} - - diff --git a/panda/certs/debug b/panda/certs/debug deleted file mode 100644 index 39864b6b1..000000000 --- a/panda/certs/debug +++ /dev/null @@ -1,15 +0,0 @@ ------BEGIN RSA PRIVATE KEY----- -MIICXQIBAAKBgQC948lnRo4x44Rd7Y8bQAML4aKDC4XRx958fHV8K6+FbCaP1Z42 -U2kX0yygak0LjoDutpgObmGHZA+Iz3HeUD6VGjr/teN24vPk+A95cRsjt8rgmGQ9 -6HNjaNgjR+gl1F9XxFimMzir82Xpl1ekTueJNXa7ia5HVH1nFdiksOKHGQIDAQAB -AoGAQuPw2I6EHJLW1/eNB75e1FqhUqRGeYV8nEGDaUBCTi+wzc4kM2LijF/5QnDv -vvht9qkfm0XK2VSoHDtnEzcVM/l1ksb68n4R/1nUooAWY6cQI7dCSk/A6yS1EJFg -BXsgGbT/65khw9pzBW2zVtMVcVNWFayqfCO1I9WcDdA1x1kCQQDfrhoZTZNoDEUE -JKM4fiUdWr1h3Aw8KLJFFexSWeGDwo+qqnujYcKWkHa9qaH1RG5x8Kir9s9Oi4Js -mzKwov8fAkEA2VPJPWxJ4vVQpXle6wC1nyoL7s739yxMWFcabvkzDDhlIVBNdVJd -gZKsFWV7QnVNdDMjn9D27FwKu3i2D+kKxwJBANp1SMojqO765MEKI1t+YDNONx6H -cm+i85Fjuv4nCIjOEdCGVuCYDxtMFpxgO2y3HAMuHx5sm8XDnWsDHLvFRdMCQD7V -XqWHnYUk8AAnqy2+ssQl3/VXmZG5GQmhhV74Za3u0C5ljT+SZL6FrYMyKAT67T3f -WzllrT6BDglNyTWoZxkCQQCt0XSoGM3603GGYNt6AUlGSgtXSo/2Px7odGUtQoKA -FH9q6FVMYpQJ38spZxIGufZJmLP8LLg6YIWJj1F+akxr ------END RSA PRIVATE KEY----- diff --git a/panda/certs/debug.pub b/panda/certs/debug.pub deleted file mode 100644 index 00e219d7b..000000000 --- a/panda/certs/debug.pub +++ /dev/null @@ -1 +0,0 @@ -ssh-rsa AAAAB3NzaC1yc2EAAAADAQABAAAAgQC948lnRo4x44Rd7Y8bQAML4aKDC4XRx958fHV8K6+FbCaP1Z42U2kX0yygak0LjoDutpgObmGHZA+Iz3HeUD6VGjr/teN24vPk+A95cRsjt8rgmGQ96HNjaNgjR+gl1F9XxFimMzir82Xpl1ekTueJNXa7ia5HVH1nFdiksOKHGQ== batman@y840 diff --git a/panda/certs/release.pub b/panda/certs/release.pub deleted file mode 100644 index 19066e29a..000000000 --- a/panda/certs/release.pub +++ /dev/null @@ -1 +0,0 @@ -ssh-rsa AAAAB3NzaC1yc2EAAAADAQABAAAAgQDGN9GU2nOc0kKq6vdZI5qUMzHt234ngqofrgCFFxL0D2Whex0zACp9gar0HZp+bvtpoSgU/Ev8wexNKr+A9QTradljiuxi5ctrOra9k+wxqNj63Wrcu4+wU5UnJEVf/buV4jCOFffMT8z3PO4imt8LzHuEIC/m/ASKVYyvuvBRQQ== batman@y840 diff --git a/panda/crypto/hash-internal.h b/panda/crypto/hash-internal.h deleted file mode 100644 index 05ec3ec9f..000000000 --- a/panda/crypto/hash-internal.h +++ /dev/null @@ -1,63 +0,0 @@ -/* - * Copyright 2007 The Android Open Source Project - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * 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. - * * Neither the name of Google Inc. nor the names of its contributors may - * be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY Google Inc. ``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 Google Inc. 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. - */ - -#ifndef SYSTEM_CORE_INCLUDE_MINCRYPT_HASH_INTERNAL_H_ -#define SYSTEM_CORE_INCLUDE_MINCRYPT_HASH_INTERNAL_H_ - -#include "stdint.h" - -#ifdef __cplusplus -extern "C" { -#endif // __cplusplus - -struct HASH_CTX; // forward decl - -typedef struct HASH_VTAB { - void (* const init)(struct HASH_CTX*); - void (* const update)(struct HASH_CTX*, const void*, int); - const uint8_t* (* const final)(struct HASH_CTX*); - const uint8_t* (* const hash)(const void*, int, uint8_t*); - int size; -} HASH_VTAB; - -typedef struct HASH_CTX { - const HASH_VTAB * f; - uint64_t count; - uint8_t buf[64]; - uint32_t state[8]; // upto SHA2 -} HASH_CTX; - -#define HASH_init(ctx) (ctx)->f->init(ctx) -#define HASH_update(ctx, data, len) (ctx)->f->update(ctx, data, len) -#define HASH_final(ctx) (ctx)->f->final(ctx) -#define HASH_hash(data, len, digest) (ctx)->f->hash(data, len, digest) -#define HASH_size(ctx) (ctx)->f->size - -#ifdef __cplusplus -} -#endif // __cplusplus - -#endif // SYSTEM_CORE_INCLUDE_MINCRYPT_HASH_INTERNAL_H_ diff --git a/panda/crypto/rsa.c b/panda/crypto/rsa.c deleted file mode 100644 index 24171e879..000000000 --- a/panda/crypto/rsa.c +++ /dev/null @@ -1,294 +0,0 @@ -/* rsa.c -** -** Copyright 2012, The Android Open Source Project -** -** Redistribution and use in source and binary forms, with or without -** modification, are permitted provided that the following conditions are met: -** * Redistributions of source code must retain the above copyright -** notice, this list of conditions and the following disclaimer. -** * 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. -** * Neither the name of Google Inc. nor the names of its contributors may -** be used to endorse or promote products derived from this software -** without specific prior written permission. -** -** THIS SOFTWARE IS PROVIDED BY Google Inc. ``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 Google Inc. 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. -*/ - -#include "rsa.h" -#include "sha.h" - -// a[] -= mod -static void subM(const RSAPublicKey* key, - uint32_t* a) { - int64_t A = 0; - int i; - for (i = 0; i < key->len; ++i) { - A += (uint64_t)a[i] - key->n[i]; - a[i] = (uint32_t)A; - A >>= 32; - } -} - -// return a[] >= mod -static int geM(const RSAPublicKey* key, - const uint32_t* a) { - int i; - for (i = key->len; i;) { - --i; - if (a[i] < key->n[i]) return 0; - if (a[i] > key->n[i]) return 1; - } - return 1; // equal -} - -// montgomery c[] += a * b[] / R % mod -static void montMulAdd(const RSAPublicKey* key, - uint32_t* c, - const uint32_t a, - const uint32_t* b) { - uint64_t A = (uint64_t)a * b[0] + c[0]; - uint32_t d0 = (uint32_t)A * key->n0inv; - uint64_t B = (uint64_t)d0 * key->n[0] + (uint32_t)A; - int i; - - for (i = 1; i < key->len; ++i) { - A = (A >> 32) + (uint64_t)a * b[i] + c[i]; - B = (B >> 32) + (uint64_t)d0 * key->n[i] + (uint32_t)A; - c[i - 1] = (uint32_t)B; - } - - A = (A >> 32) + (B >> 32); - - c[i - 1] = (uint32_t)A; - - if (A >> 32) { - subM(key, c); - } -} - -// montgomery c[] = a[] * b[] / R % mod -static void montMul(const RSAPublicKey* key, - uint32_t* c, - const uint32_t* a, - const uint32_t* b) { - int i; - for (i = 0; i < key->len; ++i) { - c[i] = 0; - } - for (i = 0; i < key->len; ++i) { - montMulAdd(key, c, a[i], b); - } -} - -// In-place public exponentiation. -// Input and output big-endian byte array in inout. -static void modpow(const RSAPublicKey* key, - uint8_t* inout) { - uint32_t a[RSANUMWORDS]; - uint32_t aR[RSANUMWORDS]; - uint32_t aaR[RSANUMWORDS]; - uint32_t* aaa = 0; - int i; - - // Convert from big endian byte array to little endian word array. - for (i = 0; i < key->len; ++i) { - uint32_t tmp = - (inout[((key->len - 1 - i) * 4) + 0] << 24) | - (inout[((key->len - 1 - i) * 4) + 1] << 16) | - (inout[((key->len - 1 - i) * 4) + 2] << 8) | - (inout[((key->len - 1 - i) * 4) + 3] << 0); - a[i] = tmp; - } - - if (key->exponent == 65537) { - aaa = aaR; // Re-use location. - montMul(key, aR, a, key->rr); // aR = a * RR / R mod M - for (i = 0; i < 16; i += 2) { - montMul(key, aaR, aR, aR); // aaR = aR * aR / R mod M - montMul(key, aR, aaR, aaR); // aR = aaR * aaR / R mod M - } - montMul(key, aaa, aR, a); // aaa = aR * a / R mod M - } else if (key->exponent == 3) { - aaa = aR; // Re-use location. - montMul(key, aR, a, key->rr); /* aR = a * RR / R mod M */ - montMul(key, aaR, aR, aR); /* aaR = aR * aR / R mod M */ - montMul(key, aaa, aaR, a); /* aaa = aaR * a / R mod M */ - } - - // Make sure aaa < mod; aaa is at most 1x mod too large. - if (geM(key, aaa)) { - subM(key, aaa); - } - - // Convert to bigendian byte array - for (i = key->len - 1; i >= 0; --i) { - uint32_t tmp = aaa[i]; - *inout++ = tmp >> 24; - *inout++ = tmp >> 16; - *inout++ = tmp >> 8; - *inout++ = tmp >> 0; - } -} - -// Expected PKCS1.5 signature padding bytes, for a keytool RSA signature. -// Has the 0-length optional parameter encoded in the ASN1 (as opposed to the -// other flavor which omits the optional parameter entirely). This code does not -// accept signatures without the optional parameter. - -/* -static const uint8_t sha_padding[RSANUMBYTES] = { - 0x00, 0x01, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0x00, 0x30, 0x21, 0x30, - 0x09, 0x06, 0x05, 0x2b, 0x0e, 0x03, 0x02, 0x1a, - 0x05, 0x00, 0x04, 0x14, - - // 20 bytes of hash go here. - 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0 -}; -*/ - -static const uint8_t sha_padding_1024[RSANUMBYTES] = { - 0x00, 0x01, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0x00, - - // 20 bytes of hash go here. - 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0 -}; - -// SHA-1 of PKCS1.5 signature sha_padding for 2048 bit, as above. -// At the location of the bytes of the hash all 00 are hashed. -/*static const uint8_t kExpectedPadShaRsa2048[SHA_DIGEST_SIZE] = { - 0xdc, 0xbd, 0xbe, 0x42, 0xd5, 0xf5, 0xa7, 0x2e, - 0x6e, 0xfc, 0xf5, 0x5d, 0xaf, 0x9d, 0xea, 0x68, - 0x7c, 0xfb, 0xf1, 0x67 -};*/ - -// Verify a 2048-bit RSA PKCS1.5 signature against an expected hash. -// Both e=3 and e=65537 are supported. hash_len may be -// SHA_DIGEST_SIZE (== 20) to indicate a SHA-1 hash, or -// SHA256_DIGEST_SIZE (== 32) to indicate a SHA-256 hash. No other -// values are supported. -// -// Returns 1 on successful verification, 0 on failure. -int RSA_verify(const RSAPublicKey *key, - const uint8_t *signature, - const int len, - const uint8_t *hash, - const int hash_len) { - uint8_t buf[RSANUMBYTES]; - int i; - //const uint8_t* padding_hash; - - if (key->len != RSANUMWORDS) { - return 0; // Wrong key passed in. - } - - if (len != sizeof(buf)) { - return 0; // Wrong input length. - } - - if (hash_len != SHA_DIGEST_SIZE) { - return 0; // Unsupported hash. - } - - if (key->exponent != 3 && key->exponent != 65537) { - return 0; // Unsupported exponent. - } - - for (i = 0; i < len; ++i) { // Copy input to local workspace. - buf[i] = signature[i]; - } - - modpow(key, buf); // In-place exponentiation. - -#ifdef TEST_RSA - printf("sig\n"); - for (i=0;i - -#ifdef __cplusplus -extern "C" { -#endif - -#define RSANUMBYTES 128 /* 1024 bit key length */ -#define RSANUMWORDS (RSANUMBYTES / sizeof(uint32_t)) - -typedef struct RSAPublicKey { - int len; /* Length of n[] in number of uint32_t */ - uint32_t n0inv; /* -1 / n[0] mod 2^32 */ - uint32_t n[RSANUMWORDS]; /* modulus as little endian array */ - uint32_t rr[RSANUMWORDS]; /* R^2 as little endian array */ - int exponent; /* 3 or 65537 */ -} RSAPublicKey; - -int RSA_verify(const RSAPublicKey *key, - const uint8_t* signature, - const int len, - const uint8_t* hash, - const int hash_len); - -#ifdef __cplusplus -} -#endif - -#endif // SYSTEM_CORE_INCLUDE_MINCRYPT_RSA_H_ diff --git a/panda/crypto/sha.c b/panda/crypto/sha.c deleted file mode 100644 index a13162c5f..000000000 --- a/panda/crypto/sha.c +++ /dev/null @@ -1,179 +0,0 @@ -/* sha.c -** -** Copyright 2013, The Android Open Source Project -** -** Redistribution and use in source and binary forms, with or without -** modification, are permitted provided that the following conditions are met: -** * Redistributions of source code must retain the above copyright -** notice, this list of conditions and the following disclaimer. -** * 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. -** * Neither the name of Google Inc. nor the names of its contributors may -** be used to endorse or promote products derived from this software -** without specific prior written permission. -** -** THIS SOFTWARE IS PROVIDED BY Google Inc. ``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 Google Inc. 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. -*/ - -// Optimized for minimal code size. - -void *memcpy(void *str1, const void *str2, unsigned int n); - -#include "sha.h" - -#define rol(bits, value) (((value) << (bits)) | ((value) >> (32 - (bits)))) - -static void SHA1_Transform(SHA_CTX* ctx) { - uint32_t W[80]; - uint32_t A, B, C, D, E; - uint8_t* p = ctx->buf; - int t; - - for(t = 0; t < 16; ++t) { - uint32_t tmp = *p++ << 24; - tmp |= *p++ << 16; - tmp |= *p++ << 8; - tmp |= *p++; - W[t] = tmp; - } - - for(; t < 80; t++) { - W[t] = rol(1,W[t-3] ^ W[t-8] ^ W[t-14] ^ W[t-16]); - } - - A = ctx->state[0]; - B = ctx->state[1]; - C = ctx->state[2]; - D = ctx->state[3]; - E = ctx->state[4]; - - for(t = 0; t < 80; t++) { - uint32_t tmp = rol(5,A) + E + W[t]; - - if (t < 20) - tmp += (D^(B&(C^D))) + 0x5A827999; - else if ( t < 40) - tmp += (B^C^D) + 0x6ED9EBA1; - else if ( t < 60) - tmp += ((B&C)|(D&(B|C))) + 0x8F1BBCDC; - else - tmp += (B^C^D) + 0xCA62C1D6; - - E = D; - D = C; - C = rol(30,B); - B = A; - A = tmp; - } - - ctx->state[0] += A; - ctx->state[1] += B; - ctx->state[2] += C; - ctx->state[3] += D; - ctx->state[4] += E; -} - -static const HASH_VTAB SHA_VTAB = { - SHA_init, - SHA_update, - SHA_final, - SHA_hash, - SHA_DIGEST_SIZE -}; - -void SHA_init(SHA_CTX* ctx) { - ctx->f = &SHA_VTAB; - ctx->state[0] = 0x67452301; - ctx->state[1] = 0xEFCDAB89; - ctx->state[2] = 0x98BADCFE; - ctx->state[3] = 0x10325476; - ctx->state[4] = 0xC3D2E1F0; - ctx->count = 0; -} - - -void SHA_update(SHA_CTX* ctx, const void* data, int len) { - int i = (int) (ctx->count & 63); - const uint8_t* p = (const uint8_t*)data; - - ctx->count += len; - - while (len--) { - ctx->buf[i++] = *p++; - if (i == 64) { - SHA1_Transform(ctx); - i = 0; - } - } -} - - -const uint8_t* SHA_final(SHA_CTX* ctx) { - uint8_t *p = ctx->buf; - uint64_t cnt = ctx->count * 8; - int i; - - SHA_update(ctx, (uint8_t*)"\x80", 1); - while ((ctx->count & 63) != 56) { - SHA_update(ctx, (uint8_t*)"\0", 1); - } - - /* Hack - right shift operator with non const argument requires - * libgcc.a which is missing in EON - * thus expanding for loop from - - for (i = 0; i < 8; ++i) { - uint8_t tmp = (uint8_t) (cnt >> ((7 - i) * 8)); - SHA_update(ctx, &tmp, 1); - } - - to - */ - - uint8_t tmp = 0; - tmp = (uint8_t) (cnt >> ((7 - 0) * 8)); - SHA_update(ctx, &tmp, 1); - tmp = (uint8_t) (cnt >> ((7 - 1) * 8)); - SHA_update(ctx, &tmp, 1); - tmp = (uint8_t) (cnt >> ((7 - 2) * 8)); - SHA_update(ctx, &tmp, 1); - tmp = (uint8_t) (cnt >> ((7 - 3) * 8)); - SHA_update(ctx, &tmp, 1); - tmp = (uint8_t) (cnt >> ((7 - 4) * 8)); - SHA_update(ctx, &tmp, 1); - tmp = (uint8_t) (cnt >> ((7 - 5) * 8)); - SHA_update(ctx, &tmp, 1); - tmp = (uint8_t) (cnt >> ((7 - 6) * 8)); - SHA_update(ctx, &tmp, 1); - tmp = (uint8_t) (cnt >> ((7 - 7) * 8)); - SHA_update(ctx, &tmp, 1); - - for (i = 0; i < 5; i++) { - uint32_t tmp = ctx->state[i]; - *p++ = tmp >> 24; - *p++ = tmp >> 16; - *p++ = tmp >> 8; - *p++ = tmp >> 0; - } - - return ctx->buf; -} - -/* Convenience function */ -const uint8_t* SHA_hash(const void* data, int len, uint8_t* digest) { - SHA_CTX ctx; - SHA_init(&ctx); - SHA_update(&ctx, data, len); - memcpy(digest, SHA_final(&ctx), SHA_DIGEST_SIZE); - return digest; -} diff --git a/panda/crypto/sha.h b/panda/crypto/sha.h deleted file mode 100644 index 4b51a531b..000000000 --- a/panda/crypto/sha.h +++ /dev/null @@ -1,51 +0,0 @@ -/* - * Copyright 2005 The Android Open Source Project - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * 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. - * * Neither the name of Google Inc. nor the names of its contributors may - * be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY Google Inc. ``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 Google Inc. 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. - */ -#ifndef SYSTEM_CORE_INCLUDE_MINCRYPT_SHA1_H_ -#define SYSTEM_CORE_INCLUDE_MINCRYPT_SHA1_H_ - -#include "hash-internal.h" - -#ifdef __cplusplus -extern "C" { -#endif // __cplusplus - -typedef HASH_CTX SHA_CTX; - -void SHA_init(SHA_CTX* ctx); -void SHA_update(SHA_CTX* ctx, const void* data, int len); -const uint8_t* SHA_final(SHA_CTX* ctx); - -// Convenience method. Returns digest address. -// NOTE: *digest needs to hold SHA_DIGEST_SIZE bytes. -const uint8_t* SHA_hash(const void* data, int len, uint8_t* digest); - -#define SHA_DIGEST_SIZE 20 - -#ifdef __cplusplus -} -#endif // __cplusplus - -#endif // SYSTEM_CORE_INCLUDE_MINCRYPT_SHA1_H_ diff --git a/panda/crypto/sign.py b/panda/crypto/sign.py deleted file mode 100755 index daea38630..000000000 --- a/panda/crypto/sign.py +++ /dev/null @@ -1,38 +0,0 @@ -#!/usr/bin/env python3 -import os -import sys -import struct -import hashlib -from Crypto.PublicKey import RSA -import binascii - -# increment this to make new hardware not run old versions -VERSION = 2 - -if __name__ == "__main__": - with open(sys.argv[3]) as k: - rsa = RSA.importKey(k.read()) - - with open(sys.argv[1], "rb") as f: - dat = f.read() - - print("signing", len(dat), "bytes") - - with open(sys.argv[2], "wb") as f: - if os.getenv("SETLEN") is not None: - # add the version at the end - dat += b"VERS" + struct.pack("I", VERSION) - # add the length at the beginning - x = struct.pack("I", len(dat)) + dat[4:] - # mock signature of dat[4:] - dd = hashlib.sha1(dat[4:]).digest() - else: - x = dat - dd = hashlib.sha1(dat).digest() - - print("hash:", str(binascii.hexlify(dd), "utf-8")) - dd = b"\x00\x01" + b"\xff" * 0x69 + b"\x00" + dd - rsa_out = pow(int.from_bytes(dd, byteorder='big', signed=False), rsa.d, rsa.n) - sig = (hex(rsa_out)[2:].rjust(0x100, '0')) - x += binascii.unhexlify(sig) - f.write(x) diff --git a/panda/python/__init__.py b/panda/python/__init__.py index 5d86092b7..df6050fd7 100644 --- a/panda/python/__init__.py +++ b/panda/python/__init__.py @@ -249,6 +249,7 @@ class Panda: FLAG_CHRYSLER_RAM_HD = 2 FLAG_SUBARU_GEN2 = 1 + FLAG_SUBARU_LONG = 2 FLAG_GM_HW_CAM = 1 FLAG_GM_HW_CAM_LONG = 2 @@ -410,7 +411,7 @@ class Panda: return usb_handle, usb_serial, bootstub, bcd @classmethod - def list(cls): + def list(cls): # noqa: A003 ret = cls.usb_list() ret += cls.spi_list() return list(set(ret)) diff --git a/panda/python/dfu.py b/panda/python/dfu.py index bebc243ce..39303d528 100644 --- a/panda/python/dfu.py +++ b/panda/python/dfu.py @@ -59,7 +59,7 @@ class PandaDFU: return handle @staticmethod - def list() -> List[str]: + def list() -> List[str]: # noqa: A003 ret = PandaDFU.usb_list() ret += PandaDFU.spi_list() return list(set(ret)) diff --git a/panda/python/serial.py b/panda/python/serial.py index 97fe8f1d9..9ac58862b 100644 --- a/panda/python/serial.py +++ b/panda/python/serial.py @@ -8,7 +8,7 @@ class PandaSerial(object): self.panda.set_uart_baud(self.port, baud) self.buf = b"" - def read(self, l=1): # noqa: E741 + def read(self, l=1): tt = self.panda.serial_read(self.port) if len(tt) > 0: self.buf += tt diff --git a/rednose/helpers/ekf_sym_pyx.so b/rednose/helpers/ekf_sym_pyx.so index d97d238fd..331111674 100755 Binary files a/rednose/helpers/ekf_sym_pyx.so and b/rednose/helpers/ekf_sym_pyx.so differ diff --git a/selfdrive/assets/navigation/voices/en_direction_arrive.png.wav b/selfdrive/assets/navigation/voices/en_direction_arrive.png.wav new file mode 100644 index 000000000..6407b2dbb Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_arrive.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_arrive_left.png.wav b/selfdrive/assets/navigation/voices/en_direction_arrive_left.png.wav new file mode 100644 index 000000000..d96245bef Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_arrive_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_arrive_right.png.wav b/selfdrive/assets/navigation/voices/en_direction_arrive_right.png.wav new file mode 100644 index 000000000..3e4b60c79 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_arrive_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_arrive_straight.png.wav b/selfdrive/assets/navigation/voices/en_direction_arrive_straight.png.wav new file mode 100644 index 000000000..55a5ca2d8 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_arrive_straight.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_continue.png.wav b/selfdrive/assets/navigation/voices/en_direction_continue.png.wav new file mode 100644 index 000000000..4799910ee Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_continue.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_continue_left.png.wav b/selfdrive/assets/navigation/voices/en_direction_continue_left.png.wav new file mode 100644 index 000000000..009f9fee5 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_continue_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_continue_right.png.wav b/selfdrive/assets/navigation/voices/en_direction_continue_right.png.wav new file mode 100644 index 000000000..5cdb65ec1 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_continue_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_continue_slight_left.png.wav b/selfdrive/assets/navigation/voices/en_direction_continue_slight_left.png.wav new file mode 100644 index 000000000..0967d31c9 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_continue_slight_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_continue_slight_right.png.wav b/selfdrive/assets/navigation/voices/en_direction_continue_slight_right.png.wav new file mode 100644 index 000000000..ba86a9e14 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_continue_slight_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_continue_straight.png.wav b/selfdrive/assets/navigation/voices/en_direction_continue_straight.png.wav new file mode 100644 index 000000000..9d204115b Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_continue_straight.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_continue_uturn.png.wav b/selfdrive/assets/navigation/voices/en_direction_continue_uturn.png.wav new file mode 100644 index 000000000..2dea780ca Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_continue_uturn.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_depart.png.wav b/selfdrive/assets/navigation/voices/en_direction_depart.png.wav new file mode 100644 index 000000000..96a0b96a7 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_depart.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_depart_left.png.wav b/selfdrive/assets/navigation/voices/en_direction_depart_left.png.wav new file mode 100644 index 000000000..087a5b57c Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_depart_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_depart_right.png.wav b/selfdrive/assets/navigation/voices/en_direction_depart_right.png.wav new file mode 100644 index 000000000..5a8d42728 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_depart_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_end_of_road_left.png.wav b/selfdrive/assets/navigation/voices/en_direction_end_of_road_left.png.wav new file mode 100644 index 000000000..f12ef3e40 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_end_of_road_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_end_of_road_right.png.wav b/selfdrive/assets/navigation/voices/en_direction_end_of_road_right.png.wav new file mode 100644 index 000000000..c76322547 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_end_of_road_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_fork_left.png.wav b/selfdrive/assets/navigation/voices/en_direction_fork_left.png.wav new file mode 100644 index 000000000..7dd9777ff Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_fork_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_fork_right.png.wav b/selfdrive/assets/navigation/voices/en_direction_fork_right.png.wav new file mode 100644 index 000000000..9c517db5d Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_fork_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_fork_slight_left.png.wav b/selfdrive/assets/navigation/voices/en_direction_fork_slight_left.png.wav new file mode 100644 index 000000000..aa6a4f334 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_fork_slight_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_fork_slight_right.png.wav b/selfdrive/assets/navigation/voices/en_direction_fork_slight_right.png.wav new file mode 100644 index 000000000..5aac4635f Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_fork_slight_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_fork_straight.png.wav b/selfdrive/assets/navigation/voices/en_direction_fork_straight.png.wav new file mode 100644 index 000000000..be16061fc Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_fork_straight.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_merge_left.png.wav b/selfdrive/assets/navigation/voices/en_direction_merge_left.png.wav new file mode 100644 index 000000000..1edefe119 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_merge_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_merge_right.png.wav b/selfdrive/assets/navigation/voices/en_direction_merge_right.png.wav new file mode 100644 index 000000000..cc4e98dbd Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_merge_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_merge_slight_left.png.wav b/selfdrive/assets/navigation/voices/en_direction_merge_slight_left.png.wav new file mode 100644 index 000000000..1edefe119 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_merge_slight_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_merge_slight_right.png.wav b/selfdrive/assets/navigation/voices/en_direction_merge_slight_right.png.wav new file mode 100644 index 000000000..c9fd6d1ec Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_merge_slight_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_new_name_straight.png.wav b/selfdrive/assets/navigation/voices/en_direction_new_name_straight.png.wav new file mode 100644 index 000000000..99d5a01cc Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_new_name_straight.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_off_ramp_left.png.wav b/selfdrive/assets/navigation/voices/en_direction_off_ramp_left.png.wav new file mode 100644 index 000000000..6d8969ebf Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_off_ramp_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_off_ramp_right.png.wav b/selfdrive/assets/navigation/voices/en_direction_off_ramp_right.png.wav new file mode 100644 index 000000000..2eb1162af Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_off_ramp_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_off_ramp_slight_left.png.wav b/selfdrive/assets/navigation/voices/en_direction_off_ramp_slight_left.png.wav new file mode 100644 index 000000000..5d3dee861 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_off_ramp_slight_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_off_ramp_slight_right.png.wav b/selfdrive/assets/navigation/voices/en_direction_off_ramp_slight_right.png.wav new file mode 100644 index 000000000..8747ac97a Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_off_ramp_slight_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_on_ramp_left.png.wav b/selfdrive/assets/navigation/voices/en_direction_on_ramp_left.png.wav new file mode 100644 index 000000000..79aac0829 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_on_ramp_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_on_ramp_right.png.wav b/selfdrive/assets/navigation/voices/en_direction_on_ramp_right.png.wav new file mode 100644 index 000000000..c41f4afa1 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_on_ramp_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_on_ramp_sharp_left.png.wav b/selfdrive/assets/navigation/voices/en_direction_on_ramp_sharp_left.png.wav new file mode 100644 index 000000000..0a7db98a3 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_on_ramp_sharp_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_on_ramp_sharp_right.png.wav b/selfdrive/assets/navigation/voices/en_direction_on_ramp_sharp_right.png.wav new file mode 100644 index 000000000..37ad31e04 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_on_ramp_sharp_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_on_ramp_slight_left.png.wav b/selfdrive/assets/navigation/voices/en_direction_on_ramp_slight_left.png.wav new file mode 100644 index 000000000..bcbb4930f Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_on_ramp_slight_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_on_ramp_slight_right.png.wav b/selfdrive/assets/navigation/voices/en_direction_on_ramp_slight_right.png.wav new file mode 100644 index 000000000..f5843f7d8 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_on_ramp_slight_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_on_ramp_straight.png.wav b/selfdrive/assets/navigation/voices/en_direction_on_ramp_straight.png.wav new file mode 100644 index 000000000..8f2fa4b78 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_on_ramp_straight.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_rotary.png.wav b/selfdrive/assets/navigation/voices/en_direction_rotary.png.wav new file mode 100644 index 000000000..99a35d80d Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_rotary.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_rotary_left.png.wav b/selfdrive/assets/navigation/voices/en_direction_rotary_left.png.wav new file mode 100644 index 000000000..b9d51a563 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_rotary_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_rotary_right.png.wav b/selfdrive/assets/navigation/voices/en_direction_rotary_right.png.wav new file mode 100644 index 000000000..90dd0d674 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_rotary_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_rotary_sharp_left.png.wav b/selfdrive/assets/navigation/voices/en_direction_rotary_sharp_left.png.wav new file mode 100644 index 000000000..de17924f8 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_rotary_sharp_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_rotary_sharp_right.png.wav b/selfdrive/assets/navigation/voices/en_direction_rotary_sharp_right.png.wav new file mode 100644 index 000000000..df375fdd2 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_rotary_sharp_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_rotary_slight_left.png.wav b/selfdrive/assets/navigation/voices/en_direction_rotary_slight_left.png.wav new file mode 100644 index 000000000..8cf32b7ab Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_rotary_slight_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_rotary_slight_right.png.wav b/selfdrive/assets/navigation/voices/en_direction_rotary_slight_right.png.wav new file mode 100644 index 000000000..dc60297f1 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_rotary_slight_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_rotary_straight.png.wav b/selfdrive/assets/navigation/voices/en_direction_rotary_straight.png.wav new file mode 100644 index 000000000..4104a3b79 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_rotary_straight.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_roundabout.png.wav b/selfdrive/assets/navigation/voices/en_direction_roundabout.png.wav new file mode 100644 index 000000000..99a35d80d Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_roundabout.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_roundabout_left.png.wav b/selfdrive/assets/navigation/voices/en_direction_roundabout_left.png.wav new file mode 100644 index 000000000..b9d51a563 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_roundabout_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_roundabout_right.png.wav b/selfdrive/assets/navigation/voices/en_direction_roundabout_right.png.wav new file mode 100644 index 000000000..9d9c9ba2b Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_roundabout_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_roundabout_sharp_left.png.wav b/selfdrive/assets/navigation/voices/en_direction_roundabout_sharp_left.png.wav new file mode 100644 index 000000000..de17924f8 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_roundabout_sharp_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_roundabout_sharp_right.png.wav b/selfdrive/assets/navigation/voices/en_direction_roundabout_sharp_right.png.wav new file mode 100644 index 000000000..5f63ec47d Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_roundabout_sharp_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_roundabout_slight_left.png.wav b/selfdrive/assets/navigation/voices/en_direction_roundabout_slight_left.png.wav new file mode 100644 index 000000000..bd68315fd Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_roundabout_slight_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_roundabout_slight_right.png.wav b/selfdrive/assets/navigation/voices/en_direction_roundabout_slight_right.png.wav new file mode 100644 index 000000000..dc60297f1 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_roundabout_slight_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_roundabout_straight.png.wav b/selfdrive/assets/navigation/voices/en_direction_roundabout_straight.png.wav new file mode 100644 index 000000000..4104a3b79 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_roundabout_straight.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_turn_left.png.wav b/selfdrive/assets/navigation/voices/en_direction_turn_left.png.wav new file mode 100644 index 000000000..89623e827 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_turn_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_turn_right.png.wav b/selfdrive/assets/navigation/voices/en_direction_turn_right.png.wav new file mode 100644 index 000000000..063e3222a Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_turn_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_turn_sharp_left.png.wav b/selfdrive/assets/navigation/voices/en_direction_turn_sharp_left.png.wav new file mode 100644 index 000000000..7321cc2a9 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_turn_sharp_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_turn_sharp_right.png.wav b/selfdrive/assets/navigation/voices/en_direction_turn_sharp_right.png.wav new file mode 100644 index 000000000..e41c32526 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_turn_sharp_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_turn_slight_left.png.wav b/selfdrive/assets/navigation/voices/en_direction_turn_slight_left.png.wav new file mode 100644 index 000000000..aa4f5b7cd Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_turn_slight_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_turn_slight_right.png.wav b/selfdrive/assets/navigation/voices/en_direction_turn_slight_right.png.wav new file mode 100644 index 000000000..dba945da4 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_turn_slight_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_turn_straight.png.wav b/selfdrive/assets/navigation/voices/en_direction_turn_straight.png.wav new file mode 100644 index 000000000..3926cd741 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_turn_straight.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_direction_turn_uturn.png.wav b/selfdrive/assets/navigation/voices/en_direction_turn_uturn.png.wav new file mode 100644 index 000000000..2dea780ca Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_direction_turn_uturn.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_distance_0.5mi.wav b/selfdrive/assets/navigation/voices/en_distance_0.5mi.wav new file mode 100644 index 000000000..773e00e9b Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_distance_0.5mi.wav differ diff --git a/selfdrive/assets/navigation/voices/en_distance_1.0mi.wav b/selfdrive/assets/navigation/voices/en_distance_1.0mi.wav new file mode 100644 index 000000000..db8198563 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_distance_1.0mi.wav differ diff --git a/selfdrive/assets/navigation/voices/en_distance_1.5mi.wav b/selfdrive/assets/navigation/voices/en_distance_1.5mi.wav new file mode 100644 index 000000000..dbf689559 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_distance_1.5mi.wav differ diff --git a/selfdrive/assets/navigation/voices/en_distance_100ft.wav b/selfdrive/assets/navigation/voices/en_distance_100ft.wav new file mode 100644 index 000000000..837e1513d Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_distance_100ft.wav differ diff --git a/selfdrive/assets/navigation/voices/en_distance_150ft.wav b/selfdrive/assets/navigation/voices/en_distance_150ft.wav new file mode 100644 index 000000000..a786c8b2e Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_distance_150ft.wav differ diff --git a/selfdrive/assets/navigation/voices/en_distance_2.0mi.wav b/selfdrive/assets/navigation/voices/en_distance_2.0mi.wav new file mode 100644 index 000000000..06a8192eb Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_distance_2.0mi.wav differ diff --git a/selfdrive/assets/navigation/voices/en_distance_2.5mi.wav b/selfdrive/assets/navigation/voices/en_distance_2.5mi.wav new file mode 100644 index 000000000..1e80a235d Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_distance_2.5mi.wav differ diff --git a/selfdrive/assets/navigation/voices/en_distance_200ft.wav b/selfdrive/assets/navigation/voices/en_distance_200ft.wav new file mode 100644 index 000000000..67adc1674 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_distance_200ft.wav differ diff --git a/selfdrive/assets/navigation/voices/en_distance_250ft.wav b/selfdrive/assets/navigation/voices/en_distance_250ft.wav new file mode 100644 index 000000000..95c77a110 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_distance_250ft.wav differ diff --git a/selfdrive/assets/navigation/voices/en_distance_3.0mi.wav b/selfdrive/assets/navigation/voices/en_distance_3.0mi.wav new file mode 100644 index 000000000..175ff2da6 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_distance_3.0mi.wav differ diff --git a/selfdrive/assets/navigation/voices/en_distance_300ft.wav b/selfdrive/assets/navigation/voices/en_distance_300ft.wav new file mode 100644 index 000000000..3c9edcac0 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_distance_300ft.wav differ diff --git a/selfdrive/assets/navigation/voices/en_distance_350ft.wav b/selfdrive/assets/navigation/voices/en_distance_350ft.wav new file mode 100644 index 000000000..f35e53b95 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_distance_350ft.wav differ diff --git a/selfdrive/assets/navigation/voices/en_distance_400ft.wav b/selfdrive/assets/navigation/voices/en_distance_400ft.wav new file mode 100644 index 000000000..a2f6efa59 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_distance_400ft.wav differ diff --git a/selfdrive/assets/navigation/voices/en_distance_450ft.wav b/selfdrive/assets/navigation/voices/en_distance_450ft.wav new file mode 100644 index 000000000..ed1db7847 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_distance_450ft.wav differ diff --git a/selfdrive/assets/navigation/voices/en_distance_50ft.wav b/selfdrive/assets/navigation/voices/en_distance_50ft.wav new file mode 100644 index 000000000..3bcc8fe69 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_distance_50ft.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_arrive.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_arrive.png.wav new file mode 100644 index 000000000..94c184f1d Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_arrive.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_arrive_left.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_arrive_left.png.wav new file mode 100644 index 000000000..e4b843688 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_arrive_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_arrive_right.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_arrive_right.png.wav new file mode 100644 index 000000000..b98e2aa56 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_arrive_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_arrive_straight.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_arrive_straight.png.wav new file mode 100644 index 000000000..b1b1f532e Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_arrive_straight.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_continue.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_continue.png.wav new file mode 100644 index 000000000..caa422023 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_continue.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_continue_left.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_continue_left.png.wav new file mode 100644 index 000000000..cb3f495e6 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_continue_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_continue_right.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_continue_right.png.wav new file mode 100644 index 000000000..d362385d1 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_continue_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_continue_slight_left.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_continue_slight_left.png.wav new file mode 100644 index 000000000..11cdefa99 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_continue_slight_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_continue_slight_right.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_continue_slight_right.png.wav new file mode 100644 index 000000000..3b6582720 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_continue_slight_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_continue_straight.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_continue_straight.png.wav new file mode 100644 index 000000000..ddf4b1502 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_continue_straight.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_continue_uturn.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_continue_uturn.png.wav new file mode 100644 index 000000000..d3887691f Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_continue_uturn.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_depart.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_depart.png.wav new file mode 100644 index 000000000..f7049b2f5 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_depart.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_depart_left.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_depart_left.png.wav new file mode 100644 index 000000000..f8f47f173 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_depart_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_depart_right.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_depart_right.png.wav new file mode 100644 index 000000000..f7049b2f5 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_depart_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_end_of_road_left.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_end_of_road_left.png.wav new file mode 100644 index 000000000..178e0f7d1 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_end_of_road_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_end_of_road_right.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_end_of_road_right.png.wav new file mode 100644 index 000000000..10602caec Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_end_of_road_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_fork_left.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_fork_left.png.wav new file mode 100644 index 000000000..e5cc3d1a8 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_fork_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_fork_right.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_fork_right.png.wav new file mode 100644 index 000000000..fdbcc55a4 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_fork_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_fork_slight_left.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_fork_slight_left.png.wav new file mode 100644 index 000000000..ce1ffb14c Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_fork_slight_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_fork_slight_right.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_fork_slight_right.png.wav new file mode 100644 index 000000000..47687f0a7 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_fork_slight_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_fork_straight.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_fork_straight.png.wav new file mode 100644 index 000000000..fa078ada8 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_fork_straight.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_merge_left.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_merge_left.png.wav new file mode 100644 index 000000000..974bc5243 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_merge_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_merge_right.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_merge_right.png.wav new file mode 100644 index 000000000..cdf76f0b4 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_merge_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_merge_slight_left.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_merge_slight_left.png.wav new file mode 100644 index 000000000..dca63f7f9 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_merge_slight_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_merge_slight_right.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_merge_slight_right.png.wav new file mode 100644 index 000000000..27321f3b5 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_merge_slight_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_new_name_straight.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_new_name_straight.png.wav new file mode 100644 index 000000000..ddf4b1502 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_new_name_straight.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_off_ramp_left.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_off_ramp_left.png.wav new file mode 100644 index 000000000..c0a4255d8 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_off_ramp_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_off_ramp_right.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_off_ramp_right.png.wav new file mode 100644 index 000000000..0c966ade0 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_off_ramp_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_off_ramp_slight_left.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_off_ramp_slight_left.png.wav new file mode 100644 index 000000000..91473a555 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_off_ramp_slight_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_off_ramp_slight_right.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_off_ramp_slight_right.png.wav new file mode 100644 index 000000000..e6e83c718 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_off_ramp_slight_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_on_ramp_left.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_on_ramp_left.png.wav new file mode 100644 index 000000000..787338c04 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_on_ramp_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_on_ramp_right.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_on_ramp_right.png.wav new file mode 100644 index 000000000..88240e2ea Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_on_ramp_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_on_ramp_sharp_left.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_on_ramp_sharp_left.png.wav new file mode 100644 index 000000000..0d5b382ac Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_on_ramp_sharp_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_on_ramp_sharp_right.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_on_ramp_sharp_right.png.wav new file mode 100644 index 000000000..63dfb1736 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_on_ramp_sharp_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_on_ramp_slight_left.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_on_ramp_slight_left.png.wav new file mode 100644 index 000000000..18d8ef821 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_on_ramp_slight_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_on_ramp_slight_right.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_on_ramp_slight_right.png.wav new file mode 100644 index 000000000..667d557f8 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_on_ramp_slight_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_on_ramp_straight.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_on_ramp_straight.png.wav new file mode 100644 index 000000000..028fd836d Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_on_ramp_straight.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_rotary.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_rotary.png.wav new file mode 100644 index 000000000..9174507ea Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_rotary.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_rotary_left.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_rotary_left.png.wav new file mode 100644 index 000000000..89a334a44 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_rotary_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_rotary_right.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_rotary_right.png.wav new file mode 100644 index 000000000..6bcd5a4ef Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_rotary_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_rotary_sharp_left.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_rotary_sharp_left.png.wav new file mode 100644 index 000000000..c193dd952 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_rotary_sharp_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_rotary_sharp_right.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_rotary_sharp_right.png.wav new file mode 100644 index 000000000..4dac0d939 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_rotary_sharp_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_rotary_slight_left.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_rotary_slight_left.png.wav new file mode 100644 index 000000000..43dba4fd7 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_rotary_slight_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_rotary_slight_right.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_rotary_slight_right.png.wav new file mode 100644 index 000000000..c2548936f Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_rotary_slight_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_rotary_straight.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_rotary_straight.png.wav new file mode 100644 index 000000000..fbad22edd Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_rotary_straight.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_roundabout.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_roundabout.png.wav new file mode 100644 index 000000000..9174507ea Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_roundabout.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_roundabout_left.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_roundabout_left.png.wav new file mode 100644 index 000000000..b4e328d5e Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_roundabout_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_roundabout_right.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_roundabout_right.png.wav new file mode 100644 index 000000000..6bcd5a4ef Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_roundabout_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_roundabout_sharp_left.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_roundabout_sharp_left.png.wav new file mode 100644 index 000000000..c193dd952 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_roundabout_sharp_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_roundabout_sharp_right.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_roundabout_sharp_right.png.wav new file mode 100644 index 000000000..164c5fd27 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_roundabout_sharp_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_roundabout_slight_left.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_roundabout_slight_left.png.wav new file mode 100644 index 000000000..2072768c9 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_roundabout_slight_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_roundabout_slight_right.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_roundabout_slight_right.png.wav new file mode 100644 index 000000000..6122774f7 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_roundabout_slight_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_roundabout_straight.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_roundabout_straight.png.wav new file mode 100644 index 000000000..18a377fff Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_roundabout_straight.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_turn_left.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_turn_left.png.wav new file mode 100644 index 000000000..31ad583c8 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_turn_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_turn_right.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_turn_right.png.wav new file mode 100644 index 000000000..f70d7ceb0 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_turn_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_turn_sharp_left.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_turn_sharp_left.png.wav new file mode 100644 index 000000000..844d117cb Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_turn_sharp_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_turn_sharp_right.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_turn_sharp_right.png.wav new file mode 100644 index 000000000..1503e65dd Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_turn_sharp_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_turn_slight_left.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_turn_slight_left.png.wav new file mode 100644 index 000000000..2346b5219 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_turn_slight_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_turn_slight_right.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_turn_slight_right.png.wav new file mode 100644 index 000000000..a9987473d Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_turn_slight_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_turn_straight.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_turn_straight.png.wav new file mode 100644 index 000000000..0c98570c7 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_turn_straight.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_direction_turn_uturn.png.wav b/selfdrive/assets/navigation/voices/en_uk_direction_turn_uturn.png.wav new file mode 100644 index 000000000..bfcf71a38 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_direction_turn_uturn.png.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_distance_0.5km.wav b/selfdrive/assets/navigation/voices/en_uk_distance_0.5km.wav new file mode 100644 index 000000000..48d2cd72f Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_distance_0.5km.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_distance_1.0km.wav b/selfdrive/assets/navigation/voices/en_uk_distance_1.0km.wav new file mode 100644 index 000000000..18b64b28b Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_distance_1.0km.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_distance_1.5km.wav b/selfdrive/assets/navigation/voices/en_uk_distance_1.5km.wav new file mode 100644 index 000000000..1057ef831 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_distance_1.5km.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_distance_100m.wav b/selfdrive/assets/navigation/voices/en_uk_distance_100m.wav new file mode 100644 index 000000000..d4523ec7a Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_distance_100m.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_distance_150m.wav b/selfdrive/assets/navigation/voices/en_uk_distance_150m.wav new file mode 100644 index 000000000..564f83d6a Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_distance_150m.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_distance_2.0km.wav b/selfdrive/assets/navigation/voices/en_uk_distance_2.0km.wav new file mode 100644 index 000000000..95e0ab63e Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_distance_2.0km.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_distance_2.5km.wav b/selfdrive/assets/navigation/voices/en_uk_distance_2.5km.wav new file mode 100644 index 000000000..80af4912f Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_distance_2.5km.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_distance_200m.wav b/selfdrive/assets/navigation/voices/en_uk_distance_200m.wav new file mode 100644 index 000000000..c96d9c45f Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_distance_200m.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_distance_250m.wav b/selfdrive/assets/navigation/voices/en_uk_distance_250m.wav new file mode 100644 index 000000000..08695240d Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_distance_250m.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_distance_3.0km.wav b/selfdrive/assets/navigation/voices/en_uk_distance_3.0km.wav new file mode 100644 index 000000000..6fae0e6b0 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_distance_3.0km.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_distance_300m.wav b/selfdrive/assets/navigation/voices/en_uk_distance_300m.wav new file mode 100644 index 000000000..06b3f0cfb Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_distance_300m.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_distance_350m.wav b/selfdrive/assets/navigation/voices/en_uk_distance_350m.wav new file mode 100644 index 000000000..c8933a97e Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_distance_350m.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_distance_400m.wav b/selfdrive/assets/navigation/voices/en_uk_distance_400m.wav new file mode 100644 index 000000000..847bf8cfc Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_distance_400m.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_distance_450m.wav b/selfdrive/assets/navigation/voices/en_uk_distance_450m.wav new file mode 100644 index 000000000..38cf45ca0 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_distance_450m.wav differ diff --git a/selfdrive/assets/navigation/voices/en_uk_distance_50m.wav b/selfdrive/assets/navigation/voices/en_uk_distance_50m.wav new file mode 100644 index 000000000..44cb61906 Binary files /dev/null and b/selfdrive/assets/navigation/voices/en_uk_distance_50m.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_arrive.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_arrive.png.wav new file mode 100644 index 000000000..efdbad6ca Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_arrive.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_arrive_left.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_arrive_left.png.wav new file mode 100644 index 000000000..40e398f29 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_arrive_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_arrive_right.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_arrive_right.png.wav new file mode 100644 index 000000000..42b6ddc20 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_arrive_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_arrive_straight.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_arrive_straight.png.wav new file mode 100644 index 000000000..e259746ed Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_arrive_straight.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_continue.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_continue.png.wav new file mode 100644 index 000000000..4b5ad3419 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_continue.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_continue_left.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_continue_left.png.wav new file mode 100644 index 000000000..85cb1cdbf Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_continue_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_continue_right.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_continue_right.png.wav new file mode 100644 index 000000000..cf2743b8d Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_continue_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_continue_slight_left.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_continue_slight_left.png.wav new file mode 100644 index 000000000..123eb21b0 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_continue_slight_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_continue_slight_right.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_continue_slight_right.png.wav new file mode 100644 index 000000000..78a8890f1 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_continue_slight_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_continue_straight.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_continue_straight.png.wav new file mode 100644 index 000000000..be8f753d4 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_continue_straight.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_continue_uturn.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_continue_uturn.png.wav new file mode 100644 index 000000000..386c4b27d Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_continue_uturn.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_depart.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_depart.png.wav new file mode 100644 index 000000000..cc785a35a Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_depart.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_depart_left.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_depart_left.png.wav new file mode 100644 index 000000000..cb1854a56 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_depart_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_depart_right.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_depart_right.png.wav new file mode 100644 index 000000000..64a62337b Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_depart_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_end_of_road_left.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_end_of_road_left.png.wav new file mode 100644 index 000000000..9e1c982c4 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_end_of_road_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_end_of_road_right.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_end_of_road_right.png.wav new file mode 100644 index 000000000..6aae36269 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_end_of_road_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_fork_left.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_fork_left.png.wav new file mode 100644 index 000000000..efe12b8ef Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_fork_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_fork_right.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_fork_right.png.wav new file mode 100644 index 000000000..f78857cf6 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_fork_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_fork_slight_left.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_fork_slight_left.png.wav new file mode 100644 index 000000000..1b21c209f Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_fork_slight_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_fork_slight_right.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_fork_slight_right.png.wav new file mode 100644 index 000000000..aa41f0a41 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_fork_slight_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_fork_straight.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_fork_straight.png.wav new file mode 100644 index 000000000..1ed88ada7 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_fork_straight.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_merge_left.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_merge_left.png.wav new file mode 100644 index 000000000..fe4ef126d Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_merge_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_merge_right.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_merge_right.png.wav new file mode 100644 index 000000000..d79666566 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_merge_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_merge_slight_left.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_merge_slight_left.png.wav new file mode 100644 index 000000000..20f72a39e Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_merge_slight_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_merge_slight_right.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_merge_slight_right.png.wav new file mode 100644 index 000000000..7e6fd94e2 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_merge_slight_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_new_name_straight.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_new_name_straight.png.wav new file mode 100644 index 000000000..3b22a8803 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_new_name_straight.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_off_ramp_left.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_off_ramp_left.png.wav new file mode 100644 index 000000000..f843d7884 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_off_ramp_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_off_ramp_right.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_off_ramp_right.png.wav new file mode 100644 index 000000000..bb39e86c0 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_off_ramp_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_off_ramp_slight_left.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_off_ramp_slight_left.png.wav new file mode 100644 index 000000000..ff26262b0 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_off_ramp_slight_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_off_ramp_slight_right.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_off_ramp_slight_right.png.wav new file mode 100644 index 000000000..94fee5d30 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_off_ramp_slight_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_on_ramp_left.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_on_ramp_left.png.wav new file mode 100644 index 000000000..ece011541 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_on_ramp_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_on_ramp_right.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_on_ramp_right.png.wav new file mode 100644 index 000000000..dfb336d44 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_on_ramp_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_on_ramp_sharp_left.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_on_ramp_sharp_left.png.wav new file mode 100644 index 000000000..cf092ae61 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_on_ramp_sharp_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_on_ramp_sharp_right.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_on_ramp_sharp_right.png.wav new file mode 100644 index 000000000..59cb2a94b Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_on_ramp_sharp_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_on_ramp_slight_left.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_on_ramp_slight_left.png.wav new file mode 100644 index 000000000..a1c190c98 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_on_ramp_slight_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_on_ramp_slight_right.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_on_ramp_slight_right.png.wav new file mode 100644 index 000000000..b9592b24f Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_on_ramp_slight_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_on_ramp_straight.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_on_ramp_straight.png.wav new file mode 100644 index 000000000..3d90ab963 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_on_ramp_straight.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_rotary.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_rotary.png.wav new file mode 100644 index 000000000..3d1f79593 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_rotary.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_rotary_left.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_rotary_left.png.wav new file mode 100644 index 000000000..bd574c774 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_rotary_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_rotary_right.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_rotary_right.png.wav new file mode 100644 index 000000000..1d35494c7 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_rotary_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_rotary_sharp_left.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_rotary_sharp_left.png.wav new file mode 100644 index 000000000..5a45d7261 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_rotary_sharp_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_rotary_sharp_right.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_rotary_sharp_right.png.wav new file mode 100644 index 000000000..28c32176b Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_rotary_sharp_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_rotary_slight_left.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_rotary_slight_left.png.wav new file mode 100644 index 000000000..a0294f84a Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_rotary_slight_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_rotary_slight_right.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_rotary_slight_right.png.wav new file mode 100644 index 000000000..0e62b548c Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_rotary_slight_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_rotary_straight.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_rotary_straight.png.wav new file mode 100644 index 000000000..c3f673c37 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_rotary_straight.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_roundabout.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_roundabout.png.wav new file mode 100644 index 000000000..3d1f79593 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_roundabout.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_roundabout_left.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_roundabout_left.png.wav new file mode 100644 index 000000000..7192771a0 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_roundabout_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_roundabout_right.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_roundabout_right.png.wav new file mode 100644 index 000000000..1d35494c7 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_roundabout_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_roundabout_sharp_left.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_roundabout_sharp_left.png.wav new file mode 100644 index 000000000..5a45d7261 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_roundabout_sharp_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_roundabout_sharp_right.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_roundabout_sharp_right.png.wav new file mode 100644 index 000000000..03497f247 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_roundabout_sharp_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_roundabout_slight_left.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_roundabout_slight_left.png.wav new file mode 100644 index 000000000..44babb369 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_roundabout_slight_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_roundabout_slight_right.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_roundabout_slight_right.png.wav new file mode 100644 index 000000000..b37a5f22b Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_roundabout_slight_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_roundabout_straight.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_roundabout_straight.png.wav new file mode 100644 index 000000000..c3f673c37 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_roundabout_straight.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_turn_left.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_turn_left.png.wav new file mode 100644 index 000000000..570e09b48 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_turn_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_turn_right.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_turn_right.png.wav new file mode 100644 index 000000000..3e825906c Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_turn_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_turn_sharp_left.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_turn_sharp_left.png.wav new file mode 100644 index 000000000..34a1aa0f1 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_turn_sharp_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_turn_sharp_right.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_turn_sharp_right.png.wav new file mode 100644 index 000000000..1178f4dd8 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_turn_sharp_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_turn_slight_left.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_turn_slight_left.png.wav new file mode 100644 index 000000000..550c7830d Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_turn_slight_left.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_turn_slight_right.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_turn_slight_right.png.wav new file mode 100644 index 000000000..3239f6c90 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_turn_slight_right.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_turn_straight.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_turn_straight.png.wav new file mode 100644 index 000000000..247ea7d8e Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_turn_straight.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_direction_turn_uturn.png.wav b/selfdrive/assets/navigation/voices/zh_tw_direction_turn_uturn.png.wav new file mode 100644 index 000000000..386c4b27d Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_direction_turn_uturn.png.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_distance_0.5km.wav b/selfdrive/assets/navigation/voices/zh_tw_distance_0.5km.wav new file mode 100644 index 000000000..2afc7eaad Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_distance_0.5km.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_distance_1.0km.wav b/selfdrive/assets/navigation/voices/zh_tw_distance_1.0km.wav new file mode 100644 index 000000000..25c859710 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_distance_1.0km.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_distance_1.5km.wav b/selfdrive/assets/navigation/voices/zh_tw_distance_1.5km.wav new file mode 100644 index 000000000..cdf026954 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_distance_1.5km.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_distance_100m.wav b/selfdrive/assets/navigation/voices/zh_tw_distance_100m.wav new file mode 100644 index 000000000..cdeafdbe8 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_distance_100m.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_distance_150m.wav b/selfdrive/assets/navigation/voices/zh_tw_distance_150m.wav new file mode 100644 index 000000000..22c026fb7 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_distance_150m.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_distance_2.0km.wav b/selfdrive/assets/navigation/voices/zh_tw_distance_2.0km.wav new file mode 100644 index 000000000..5632e0b7a Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_distance_2.0km.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_distance_2.5km.wav b/selfdrive/assets/navigation/voices/zh_tw_distance_2.5km.wav new file mode 100644 index 000000000..8d25f0842 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_distance_2.5km.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_distance_200m.wav b/selfdrive/assets/navigation/voices/zh_tw_distance_200m.wav new file mode 100644 index 000000000..185ad5d96 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_distance_200m.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_distance_250m.wav b/selfdrive/assets/navigation/voices/zh_tw_distance_250m.wav new file mode 100644 index 000000000..97567abc1 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_distance_250m.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_distance_3.0km.wav b/selfdrive/assets/navigation/voices/zh_tw_distance_3.0km.wav new file mode 100644 index 000000000..50c19c5b0 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_distance_3.0km.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_distance_300m.wav b/selfdrive/assets/navigation/voices/zh_tw_distance_300m.wav new file mode 100644 index 000000000..d5f0c8151 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_distance_300m.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_distance_350m.wav b/selfdrive/assets/navigation/voices/zh_tw_distance_350m.wav new file mode 100644 index 000000000..c20cd663b Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_distance_350m.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_distance_400m.wav b/selfdrive/assets/navigation/voices/zh_tw_distance_400m.wav new file mode 100644 index 000000000..05183063a Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_distance_400m.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_distance_450m.wav b/selfdrive/assets/navigation/voices/zh_tw_distance_450m.wav new file mode 100644 index 000000000..cf05df147 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_distance_450m.wav differ diff --git a/selfdrive/assets/navigation/voices/zh_tw_distance_50m.wav b/selfdrive/assets/navigation/voices/zh_tw_distance_50m.wav new file mode 100644 index 000000000..3a41df603 Binary files /dev/null and b/selfdrive/assets/navigation/voices/zh_tw_distance_50m.wav differ diff --git a/selfdrive/athena/athenad.py b/selfdrive/athena/athenad.py index 780d2ab90..d7ef06407 100755 --- a/selfdrive/athena/athenad.py +++ b/selfdrive/athena/athenad.py @@ -85,7 +85,7 @@ class UploadItem: url: str headers: Dict[str, str] created_at: int - id: Optional[str] + id: Optional[str] # noqa: A003 (to match the response from the remote server) retry_count: int = 0 current: bool = False progress: float = 0 @@ -213,6 +213,16 @@ def retry_upload(tid: int, end_event: threading.Event, increase_count: bool = Tr break +def cb(sm, item, tid, sz: int, cur: int) -> None: + # Abort transfer if connection changed to metered after starting upload + sm.update(0) + metered = sm['deviceState'].networkMetered + if metered and (not item.allow_cellular): + raise AbortTransferException + + cur_upload_items[tid] = replace(item, progress=cur / sz if sz else 1) + + def upload_handler(end_event: threading.Event) -> None: sm = messaging.SubMaster(['deviceState']) tid = threading.get_ident() @@ -242,15 +252,6 @@ def upload_handler(end_event: threading.Event) -> None: continue try: - def cb(sz: int, cur: int) -> None: - # Abort transfer if connection changed to metered after starting upload - sm.update(0) - metered = sm['deviceState'].networkMetered - if metered and (not item.allow_cellular): - raise AbortTransferException - - cur_upload_items[tid] = replace(item, progress=cur / sz if sz else 1) - fn = item.path try: sz = os.path.getsize(fn) @@ -258,7 +259,7 @@ def upload_handler(end_event: threading.Event) -> None: sz = -1 cloudlog.event("athena.upload_handler.upload_start", fn=fn, sz=sz, network_type=network_type, metered=metered, retry_count=item.retry_count) - response = _do_upload(item, cb) + response = _do_upload(item, partial(cb, sm, item, tid)) if response.status_code not in (200, 201, 401, 403, 412): cloudlog.event("athena.upload_handler.retry", status_code=response.status_code, fn=fn, sz=sz, network_type=network_type, metered=metered) diff --git a/selfdrive/boardd/boardd b/selfdrive/boardd/boardd index 3280ead95..18a589d48 100755 Binary files a/selfdrive/boardd/boardd and b/selfdrive/boardd/boardd differ diff --git a/selfdrive/boardd/boardd_api_impl.so b/selfdrive/boardd/boardd_api_impl.so index 585d5254b..412a7f664 100755 Binary files a/selfdrive/boardd/boardd_api_impl.so and b/selfdrive/boardd/boardd_api_impl.so differ diff --git a/selfdrive/boardd/pandad.py b/selfdrive/boardd/pandad.py index 7cbac9b5d..be2ed3c4c 100755 --- a/selfdrive/boardd/pandad.py +++ b/selfdrive/boardd/pandad.py @@ -169,7 +169,7 @@ def main() -> NoReturn: # sort pandas to have deterministic order pandas.sort(key=cmp_to_key(panda_sort_cmp)) - panda_serials = list(map(lambda p: p.get_usb_serial(), pandas)) + panda_serials = [p.get_usb_serial() for p in pandas] # log panda fw versions params.put("PandaSignatures", b','.join(p.get_signature() for p in pandas)) diff --git a/selfdrive/boardd/tests/test_boardd_loopback.py b/selfdrive/boardd/tests/test_boardd_loopback.py index 593ccf595..74393c6eb 100755 --- a/selfdrive/boardd/tests/test_boardd_loopback.py +++ b/selfdrive/boardd/tests/test_boardd_loopback.py @@ -10,7 +10,6 @@ from pprint import pprint import cereal.messaging as messaging from cereal import car, log from common.params import Params -from common.spinner import Spinner from common.timeout import Timeout from selfdrive.boardd.boardd import can_list_to_can_capnp from selfdrive.car import make_can_msg @@ -24,11 +23,6 @@ class TestBoardd(unittest.TestCase): def setUpClass(cls): os.environ['STARTED'] = '1' os.environ['BOARDD_LOOPBACK'] = '1' - cls.spinner = Spinner() - - @classmethod - def tearDownClass(cls): - cls.spinner.close() @phone_only @with_processes(['pandad']) @@ -67,7 +61,6 @@ class TestBoardd(unittest.TestCase): n = 200 for i in range(n): print(f"boardd loopback {i}/{n}") - self.spinner.update(f"boardd loopback {i}/{n}") sent_msgs = defaultdict(set) for _ in range(random.randrange(20, 100)): diff --git a/selfdrive/car/__init__.py b/selfdrive/car/__init__.py index 10da0dc56..48ac84dd1 100644 --- a/selfdrive/car/__init__.py +++ b/selfdrive/car/__init__.py @@ -60,7 +60,7 @@ def scale_rot_inertia(mass, wheelbase): # TODO: start from empirically derived lateral slip stiffness for the civic and scale by # mass and CG position, so all cars will have approximately similar dyn behaviors -def scale_tire_stiffness(mass, wheelbase, center_to_front, tire_stiffness_factor=1.0): +def scale_tire_stiffness(mass, wheelbase, center_to_front, tire_stiffness_factor): center_to_rear = wheelbase - center_to_front tire_stiffness_front = (CivicParams.TIRE_STIFFNESS_FRONT * tire_stiffness_factor) * mass / CivicParams.MASS * \ (center_to_rear / wheelbase) / (CivicParams.CENTER_TO_REAR / CivicParams.WHEELBASE) @@ -132,7 +132,7 @@ def apply_std_steer_angle_limits(apply_angle, apply_angle_last, v_ego, LIMITS): return clip(apply_angle, apply_angle_last - angle_rate_lim, apply_angle_last + angle_rate_lim) -def common_fault_avoidance(measured_value: float, max_value: float, request: bool, above_limit_frames: int, +def common_fault_avoidance(fault_condition: bool, request: bool, above_limit_frames: int, max_above_limit_frames: int, max_mismatching_frames: int = 1): """ Several cars have the ability to work around their EPS limits by cutting the @@ -140,7 +140,7 @@ def common_fault_avoidance(measured_value: float, max_value: float, request: boo """ # Count up to max_above_limit_frames, at which point we need to cut the request for above_limit_frames to avoid a fault - if request and abs(measured_value) >= max_value: + if request and fault_condition: above_limit_frames += 1 else: above_limit_frames = 0 @@ -213,3 +213,24 @@ class CanBusBase: else: num = len(CP.safetyConfigs) self.offset = 4 * (num - 1) + + +class CanSignalRateCalculator: + """ + Calculates the instantaneous rate of a CAN signal by using the counter + variable and the known frequency of the CAN message that contains it. + """ + def __init__(self, frequency): + self.frequency = frequency + self.previous_counter = 0 + self.previous_value = 0 + self.rate = 0 + + def update(self, current_value, current_counter): + if current_counter != self.previous_counter: + self.rate = (current_value - self.previous_value) * self.frequency + + self.previous_counter = current_counter + self.previous_value = current_value + + return self.rate \ No newline at end of file diff --git a/selfdrive/car/body/carstate.py b/selfdrive/car/body/carstate.py index dbbd85950..a1ef17360 100644 --- a/selfdrive/car/body/carstate.py +++ b/selfdrive/car/body/carstate.py @@ -32,29 +32,9 @@ class CarState(CarStateBase): @staticmethod def get_can_parser(CP): - signals = [ - # sig_name, sig_address - ("SPEED_L", "MOTORS_DATA"), - ("SPEED_R", "MOTORS_DATA"), - ("ELEC_ANGLE_L", "MOTORS_DATA"), - ("ELEC_ANGLE_R", "MOTORS_DATA"), - ("COUNTER", "MOTORS_DATA"), - ("CHECKSUM", "MOTORS_DATA"), - ("IGNITION", "VAR_VALUES"), - ("ENABLE_MOTORS", "VAR_VALUES"), - ("FAULT", "VAR_VALUES"), - ("MOTOR_ERR_L", "VAR_VALUES"), - ("MOTOR_ERR_R", "VAR_VALUES"), - ("MCU_TEMP", "BODY_DATA"), - ("BATT_VOLTAGE", "BODY_DATA"), - ("BATT_PERCENTAGE", "BODY_DATA"), - ("CHARGER_CONNECTED", "BODY_DATA"), - ] - - checks = [ + messages = [ ("MOTORS_DATA", 100), ("VAR_VALUES", 10), ("BODY_DATA", 1), ] - - return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 0) + return CANParser(DBC[CP.carFingerprint]["pt"], messages, 0) diff --git a/selfdrive/car/car_helpers.py b/selfdrive/car/car_helpers.py index 97205682e..45bdedbd1 100644 --- a/selfdrive/car/car_helpers.py +++ b/selfdrive/car/car_helpers.py @@ -12,10 +12,15 @@ from selfdrive.car.fw_versions import get_fw_versions_ordered, get_present_ecus, from system.swaglog import cloudlog import cereal.messaging as messaging from selfdrive.car import gen_empty_fingerprint +import threading +import requests +import time +import selfdrive.sentry as sentry + +FRAME_FINGERPRINT = 100 # 1s EventName = car.CarEvent.EventName - def get_startup_event(car_recognized, controller_available, fw_seen): if True: #is_comma_remote() and is_tested_branch(): # pylint: disable=abstract-class-instantiated event = EventName.startup @@ -128,7 +133,6 @@ def fingerprint(logcan, sendcan, num_pandas): finger = gen_empty_fingerprint() candidate_cars = {i: all_legacy_fingerprint_cars() for i in [0, 1]} # attempt fingerprint on both bus 0 and 1 frame = 0 - frame_fingerprint = 100 # 1s car_fingerprint = None done = False @@ -154,12 +158,12 @@ def fingerprint(logcan, sendcan, num_pandas): # if we only have one car choice and the time since we got our first # message has elapsed, exit for b in candidate_cars: - if len(candidate_cars[b]) == 1 and frame > frame_fingerprint: + if len(candidate_cars[b]) == 1 and frame > FRAME_FINGERPRINT: # fingerprint done car_fingerprint = candidate_cars[b][0] # bail if no cars left or we've been waiting for more than 2s - failed = (all(len(cc) == 0 for cc in candidate_cars.values()) and frame > frame_fingerprint) or frame > 200 + failed = (all(len(cc) == 0 for cc in candidate_cars.values()) and frame > FRAME_FINGERPRINT) or frame > 200 succeeded = car_fingerprint is not None done = failed or succeeded @@ -183,6 +187,36 @@ def fingerprint(logcan, sendcan, num_pandas): error=True) return car_fingerprint, finger, vin, car_fw, source, exact_match +#dp +def is_connected_to_internet(timeout=5): + try: + requests.get("https://sentry.io", timeout=timeout) + return True + except Exception: + return False +def crash_log(candidate): + no_internet = 0 + while True: + if is_connected_to_internet(): + sentry.capture_warning("fingerprinted %s" % candidate) + break + else: + no_internet += 1 + if no_internet >= 2: + break + time.sleep(600) +def crash_log2(fingerprints, fw): + no_internet = 0 + while True: + if is_connected_to_internet(): + sentry.capture_warning("car doesn't match any fingerprints: %s" % fingerprints) + sentry.capture_warning("car doesn't match any fw: %s" % fw) + break + else: + no_internet += 1 + if no_internet >= 2: + break + time.sleep(600) def get_car(logcan, sendcan, experimental_long_allowed, num_pandas=1): candidate, fingerprints, vin, car_fw, source, exact_match = fingerprint(logcan, sendcan, num_pandas) @@ -191,11 +225,17 @@ def get_car(logcan, sendcan, experimental_long_allowed, num_pandas=1): cloudlog.event("car doesn't match any fingerprints", fingerprints=fingerprints, error=True) candidate = "mock" - CarInterface, CarController, CarState = interfaces[candidate] - CP = CarInterface.get_params(candidate, fingerprints, car_fw, experimental_long_allowed, docs=False) - CP.carVin = vin - CP.carFw = car_fw - CP.fingerprintSource = source - CP.fuzzyFingerprint = not exact_match - - return CarInterface(CP, CarController, CarState), CP + y = threading.Thread(target=crash_log2, args=(fingerprints,car_fw,)) + y.start() + x = threading.Thread(target=crash_log, args=(candidate,)) + x.start() + try: + CarInterface, CarController, CarState = interfaces[candidate] + CP = CarInterface.get_params(candidate, fingerprints, car_fw, experimental_long_allowed, docs=False) + CP.carVin = vin + CP.carFw = car_fw + CP.fingerprintSource = source + CP.fuzzyFingerprint = not exact_match + return CarInterface(CP, CarController, CarState), CP + except KeyError: + return None, None diff --git a/selfdrive/car/chrysler/carstate.py b/selfdrive/car/chrysler/carstate.py index 3afd45ce9..7b250ddf9 100644 --- a/selfdrive/car/chrysler/carstate.py +++ b/selfdrive/car/chrysler/carstate.py @@ -98,51 +98,16 @@ class CarState(CarStateBase): return ret @staticmethod - def get_cruise_signals(): - signals = [ - ("ACC_AVAILABLE", "DAS_3"), - ("ACC_ACTIVE", "DAS_3"), - ("ACC_FAULTED", "DAS_3"), - ("ACC_STANDSTILL", "DAS_3"), - ("COUNTER", "DAS_3"), - ("ACC_SET_SPEED_KPH", "DAS_4"), - ("ACC_STATE", "DAS_4"), - ] - checks = [ + def get_cruise_messages(): + messages = [ ("DAS_3", 50), ("DAS_4", 50), ] - return signals, checks + return messages @staticmethod def get_can_parser(CP): - signals = [ - # sig_name, sig_address - ("DOOR_OPEN_FL", "BCM_1"), - ("DOOR_OPEN_FR", "BCM_1"), - ("DOOR_OPEN_RL", "BCM_1"), - ("DOOR_OPEN_RR", "BCM_1"), - ("Brake_Pedal_State", "ESP_1"), - ("Accelerator_Position", "ECM_5"), - ("WHEEL_SPEED_FL", "ESP_6"), - ("WHEEL_SPEED_RR", "ESP_6"), - ("WHEEL_SPEED_RL", "ESP_6"), - ("WHEEL_SPEED_FR", "ESP_6"), - ("STEERING_ANGLE", "STEERING"), - ("STEERING_ANGLE_HP", "STEERING"), - ("STEERING_RATE", "STEERING"), - ("TURN_SIGNALS", "STEERING_LEVERS"), - ("HIGH_BEAM_PRESSED", "STEERING_LEVERS"), - ("SEATBELT_DRIVER_UNLATCHED", "ORC_1"), - ("COUNTER", "EPS_2",), - ("COLUMN_TORQUE", "EPS_2"), - ("EPS_TORQUE_MOTOR", "EPS_2"), - ("LKAS_TEMPORARY_FAULT", "EPS_2"), - ("LKAS_STATE", "EPS_2"), - ("COUNTER", "CRUISE_BUTTONS"), - ] - - checks = [ + messages = [ # sig_address, frequency ("ESP_1", 50), ("EPS_2", 100), @@ -156,53 +121,30 @@ class CarState(CarStateBase): ] if CP.enableBsm: - signals += [ - ("RIGHT_STATUS", "BSM_1"), - ("LEFT_STATUS", "BSM_1"), - ] - checks.append(("BSM_1", 2)) + messages.append(("BSM_1", 2)) if CP.carFingerprint in RAM_CARS: - signals += [ - ("DASM_FAULT", "EPS_3"), - ("Vehicle_Speed", "ESP_8"), - ("Gear_State", "Transmission_Status"), - ] - checks += [ + messages += [ ("ESP_8", 50), ("EPS_3", 50), ("Transmission_Status", 50), ] else: - signals += [ - ("PRNDL", "GEAR"), - ("SPEED_LEFT", "SPEED_1"), - ("SPEED_RIGHT", "SPEED_1"), - ] - checks += [ + messages += [ ("GEAR", 50), ("SPEED_1", 100), ] - signals += CarState.get_cruise_signals()[0] - checks += CarState.get_cruise_signals()[1] + messages += CarState.get_cruise_messages() - return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 0) + return CANParser(DBC[CP.carFingerprint]["pt"], messages, 0) @staticmethod def get_cam_can_parser(CP): - signals = [ - # sig_name, sig_address, default - ("CAR_MODEL", "DAS_6"), - ] - checks = [ + messages = [ ("DAS_6", 4), ] if CP.carFingerprint in RAM_CARS: - signals += [ - ("AUTO_HIGH_BEAM_ON", "DAS_6"), - ] - signals += CarState.get_cruise_signals()[0] - checks += CarState.get_cruise_signals()[1] + messages += CarState.get_cruise_messages() - return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 2) + return CANParser(DBC[CP.carFingerprint]["pt"], messages, 2) diff --git a/selfdrive/car/chrysler/radar_interface.py b/selfdrive/car/chrysler/radar_interface.py index 0ab8c10b4..fc795a36c 100755 --- a/selfdrive/car/chrysler/radar_interface.py +++ b/selfdrive/car/chrysler/radar_interface.py @@ -22,18 +22,12 @@ def _create_radar_can_parser(car_fingerprint): # ('LONG_DIST', 1074), # ('LONG_DIST', 1075), - signals = list(zip(['LONG_DIST'] * msg_n + - ['LAT_DIST'] * msg_n + - ['REL_SPEED'] * msg_n, - RADAR_MSGS_C * 2 + # LONG_DIST, LAT_DIST - RADAR_MSGS_D)) # REL_SPEED + messages = list(zip(RADAR_MSGS_C + + RADAR_MSGS_D, + [20] * msg_n + # 20Hz (0.05s) + [20] * msg_n, strict=True)) # 20Hz (0.05s) - checks = list(zip(RADAR_MSGS_C + - RADAR_MSGS_D, - [20] * msg_n + # 20Hz (0.05s) - [20] * msg_n)) # 20Hz (0.05s) - - return CANParser(DBC[car_fingerprint]['radar'], signals, checks, 1) + return CANParser(DBC[car_fingerprint]['radar'], messages, 1) def _address_to_track(address): if address in RADAR_MSGS_C: @@ -52,7 +46,7 @@ class RadarInterface(RadarInterfaceBase): def update(self, can_strings): if self.rcp is None or self.CP.radarUnavailable: - return super().update(None) + return None vls = self.rcp.update_strings(can_strings) self.updated_messages.update(vls) @@ -89,4 +83,4 @@ class RadarInterface(RadarInterfaceBase): ret.points = [x for x in self.pts.values() if x.dRel != 0] self.updated_messages.clear() - return ret \ No newline at end of file + return ret diff --git a/selfdrive/car/docs_definitions.py b/selfdrive/car/docs_definitions.py index 3a6aa5e2d..2220205e8 100644 --- a/selfdrive/car/docs_definitions.py +++ b/selfdrive/car/docs_definitions.py @@ -50,7 +50,7 @@ class BasePart: class EnumBase(Enum): @property - def type(self): + def part_type(self): return PartType(self.__class__) diff --git a/selfdrive/car/ecu_addrs.py b/selfdrive/car/ecu_addrs.py index 868f12cdb..25938f0d3 100755 --- a/selfdrive/car/ecu_addrs.py +++ b/selfdrive/car/ecu_addrs.py @@ -1,16 +1,15 @@ #!/usr/bin/env python3 import capnp import time -from typing import Optional, Set, Tuple +from typing import Optional, Set import cereal.messaging as messaging from panda.python.uds import SERVICE_TYPE from selfdrive.car import make_can_msg +from selfdrive.car.fw_query_definitions import EcuAddrBusType from selfdrive.boardd.boardd import can_list_to_can_capnp from system.swaglog import cloudlog -EcuAddrBusType = Tuple[int, Optional[int], int] - def make_tester_present_msg(addr, bus, subaddr=None): dat = [0x02, SERVICE_TYPE.TESTER_PRESENT, 0x0] @@ -90,7 +89,7 @@ if __name__ == "__main__": print() print("Found ECUs on addresses:") - for addr, subaddr, bus in ecu_addrs: + for addr, subaddr, _ in ecu_addrs: msg = f" 0x{hex(addr)}" if subaddr is not None: msg += f" (sub-address: {hex(subaddr)})" diff --git a/selfdrive/car/ford/carstate.py b/selfdrive/car/ford/carstate.py index d9848096e..824d92993 100644 --- a/selfdrive/car/ford/carstate.py +++ b/selfdrive/car/ford/carstate.py @@ -111,70 +111,7 @@ class CarState(CarStateBase): @staticmethod def get_can_parser(CP): - signals = [ - # sig_name, sig_address - ("TrnAinTq_D_Qf", "VehicleOperatingModes"), # Used to detect hybrid or ICE platform variant - - ("Veh_V_ActlBrk", "BrakeSysFeatures"), # ABS vehicle speed (kph) - ("VehYaw_W_Actl", "Yaw_Data_FD1"), # ABS vehicle yaw rate (rad/s) - ("VehStop_D_Stat", "DesiredTorqBrk"), # ABS vehicle stopped - ("PrkBrkStatus", "DesiredTorqBrk"), # ABS park brake status - ("ApedPos_Pc_ActlArb", "EngVehicleSpThrottle"), # PCM throttle (pct) - ("BrkTot_Tq_Actl", "BrakeSnData_4"), # ABS brake torque (Nm) - ("BpedDrvAppl_D_Actl", "EngBrakeData"), # PCM driver brake pedal pressed - ("Veh_V_DsplyCcSet", "EngBrakeData"), # PCM ACC set speed (mph) - # The units might change with IPC settings? - ("CcStat_D_Actl", "EngBrakeData"), # PCM ACC status - ("AccStopMde_D_Rq", "EngBrakeData"), # PCM ACC standstill - ("AccEnbl_B_RqDrv", "Cluster_Info1_FD1"), # PCM ACC enable - ("StePinComp_An_Est", "SteeringPinion_Data"), # PSCM estimated steering angle (deg) - ("StePinCompAnEst_D_Qf", "SteeringPinion_Data"), # PSCM estimated steering angle (quality flag) - # Calculates steering angle (and offset) from pinion - # angle and driving measurements. - # StePinRelInit_An_Sns is the pinion angle, initialised - # to zero at the beginning of the drive. - ("SteeringColumnTorque", "EPAS_INFO"), # PSCM steering column torque (Nm) - ("EPAS_Failure", "EPAS_INFO"), # PSCM EPAS status - ("TurnLghtSwtch_D_Stat", "Steering_Data_FD1"), # SCCM Turn signal switch - ("TjaButtnOnOffPress", "Steering_Data_FD1"), # SCCM ACC button, lane-centering/traffic jam assist toggle - ("DrStatDrv_B_Actl", "BodyInfo_3_FD1"), # BCM Door open, driver - ("DrStatPsngr_B_Actl", "BodyInfo_3_FD1"), # BCM Door open, passenger - ("DrStatRl_B_Actl", "BodyInfo_3_FD1"), # BCM Door open, rear left - ("DrStatRr_B_Actl", "BodyInfo_3_FD1"), # BCM Door open, rear right - ("FirstRowBuckleDriver", "RCMStatusMessage2_FD1"), # RCM Seatbelt status, driver - ("HeadLghtHiFlash_D_Stat", "Steering_Data_FD1"), # SCCM Passthrough the remaining buttons - ("WiprFront_D_Stat", "Steering_Data_FD1"), - ("LghtAmb_D_Sns", "Steering_Data_FD1"), - ("AccButtnGapDecPress", "Steering_Data_FD1"), - ("AccButtnGapIncPress", "Steering_Data_FD1"), - ("AslButtnOnOffCnclPress", "Steering_Data_FD1"), - ("AslButtnOnOffPress", "Steering_Data_FD1"), - ("LaSwtchPos_D_Stat", "Steering_Data_FD1"), - ("CcAslButtnCnclResPress", "Steering_Data_FD1"), - ("CcAslButtnDeny_B_Actl", "Steering_Data_FD1"), - ("CcAslButtnIndxDecPress", "Steering_Data_FD1"), - ("CcAslButtnIndxIncPress", "Steering_Data_FD1"), - ("CcAslButtnOffCnclPress", "Steering_Data_FD1"), - ("CcAslButtnOnOffCncl", "Steering_Data_FD1"), - ("CcAslButtnOnPress", "Steering_Data_FD1"), - ("CcAslButtnResDecPress", "Steering_Data_FD1"), - ("CcAslButtnResIncPress", "Steering_Data_FD1"), - ("CcAslButtnSetDecPress", "Steering_Data_FD1"), - ("CcAslButtnSetIncPress", "Steering_Data_FD1"), - ("CcAslButtnSetPress", "Steering_Data_FD1"), - ("CcButtnOffPress", "Steering_Data_FD1"), - ("CcButtnOnOffCnclPress", "Steering_Data_FD1"), - ("CcButtnOnOffPress", "Steering_Data_FD1"), - ("CcButtnOnPress", "Steering_Data_FD1"), - ("HeadLghtHiFlash_D_Actl", "Steering_Data_FD1"), - ("HeadLghtHiOn_B_StatAhb", "Steering_Data_FD1"), - ("AhbStat_B_Dsply", "Steering_Data_FD1"), - ("AccButtnGapTogglePress", "Steering_Data_FD1"), - ("WiprFrontSwtch_D_Stat", "Steering_Data_FD1"), - ("HeadLghtHiCtrl_D_RqAhb", "Steering_Data_FD1"), - ] - - checks = [ + messages = [ # sig_address, frequency ("VehicleOperatingModes", 100), ("BrakeSysFeatures", 50), @@ -192,93 +129,31 @@ class CarState(CarStateBase): ] if CP.carFingerprint in CANFD_CAR: - signals += [ - ("LatCtlSte_D_Stat", "Lane_Assist_Data3_FD1"), # PSCM lateral control status - ] - checks += [ + messages += [ ("Lane_Assist_Data3_FD1", 33), ] if CP.transmissionType == TransmissionType.automatic: - signals += [ - ("TrnRng_D_RqGsm", "Gear_Shift_by_Wire_FD1"), # GWM transmission gear position - ] - checks += [ + messages += [ ("Gear_Shift_by_Wire_FD1", 10), ] elif CP.transmissionType == TransmissionType.manual: - signals += [ - ("CluPdlPos_Pc_Meas", "Engine_Clutch_Data"), # PCM clutch (pct) - ("RvrseLghtOn_B_Stat", "BCM_Lamp_Stat_FD1"), # BCM reverse light - ] - checks += [ + messages += [ ("Engine_Clutch_Data", 33), ("BCM_Lamp_Stat_FD1", 1), ] if CP.enableBsm and CP.carFingerprint not in CANFD_CAR: - signals += [ - ("SodDetctLeft_D_Stat", "Side_Detect_L_Stat"), # Blindspot sensor, left - ("SodDetctRight_D_Stat", "Side_Detect_R_Stat"), # Blindspot sensor, right - ] - checks += [ + messages += [ ("Side_Detect_L_Stat", 5), ("Side_Detect_R_Stat", 5), ] - return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, CanBus(CP).main) + return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus(CP).main) @staticmethod def get_cam_can_parser(CP): - signals = [ - # sig_name, sig_address - ("CmbbDeny_B_Actl", "ACCDATA"), # ACC/AEB unavailable/lockout - - ("CmbbBrkDecel_B_Rq", "ACCDATA_2"), # AEB actuation request bit - - ("HaDsply_No_Cs", "ACCDATA_3"), - ("HaDsply_No_Cnt", "ACCDATA_3"), - ("AccStopStat_D_Dsply", "ACCDATA_3"), # ACC stopped status message - ("AccTrgDist2_D_Dsply", "ACCDATA_3"), # ACC target distance - ("AccStopRes_B_Dsply", "ACCDATA_3"), - ("TjaWarn_D_Rq", "ACCDATA_3"), # TJA warning - ("Tja_D_Stat", "ACCDATA_3"), # TJA status - ("TjaMsgTxt_D_Dsply", "ACCDATA_3"), # TJA text - ("IaccLamp_D_Rq", "ACCDATA_3"), # iACC status icon - ("AccMsgTxt_D2_Rq", "ACCDATA_3"), # ACC text - ("FcwDeny_B_Dsply", "ACCDATA_3"), # FCW disabled - ("FcwMemStat_B_Actl", "ACCDATA_3"), # FCW enabled setting - ("AccTGap_B_Dsply", "ACCDATA_3"), # ACC time gap display setting - ("CadsAlignIncplt_B_Actl", "ACCDATA_3"), - ("AccFllwMde_B_Dsply", "ACCDATA_3"), # ACC lead indicator - ("CadsRadrBlck_B_Actl", "ACCDATA_3"), - ("CmbbPostEvnt_B_Dsply", "ACCDATA_3"), # AEB event status - ("AccStopMde_B_Dsply", "ACCDATA_3"), # ACC stop mode display setting - ("FcwMemSens_D_Actl", "ACCDATA_3"), # FCW sensitivity setting - ("FcwMsgTxt_D_Rq", "ACCDATA_3"), # FCW text - ("AccWarn_D_Dsply", "ACCDATA_3"), # ACC warning - ("FcwVisblWarn_B_Rq", "ACCDATA_3"), # FCW visible alert - ("FcwAudioWarn_B_Rq", "ACCDATA_3"), # FCW audio alert - ("AccTGap_D_Dsply", "ACCDATA_3"), # ACC time gap - ("AccMemEnbl_B_RqDrv", "ACCDATA_3"), # ACC adaptive/normal setting - ("FdaMem_B_Stat", "ACCDATA_3"), # FDA enabled setting - - ("FeatConfigIpmaActl", "IPMA_Data"), - ("FeatNoIpmaActl", "IPMA_Data"), - ("PersIndexIpma_D_Actl", "IPMA_Data"), - ("AhbcRampingV_D_Rq", "IPMA_Data"), # AHB ramping - ("LaDenyStats_B_Dsply", "IPMA_Data"), # LKAS error - ("CamraDefog_B_Req", "IPMA_Data"), # Windshield heater? - ("CamraStats_D_Dsply", "IPMA_Data"), # Camera status - ("DasAlrtLvl_D_Dsply", "IPMA_Data"), # DAS alert level - ("DasStats_D_Dsply", "IPMA_Data"), # DAS status - ("DasWarn_D_Dsply", "IPMA_Data"), # DAS warning - ("AhbHiBeam_D_Rq", "IPMA_Data"), # AHB status - ("Passthru_63", "IPMA_Data"), - ("Passthru_48", "IPMA_Data"), - ] - - checks = [ + messages = [ # sig_address, frequency ("ACCDATA", 50), ("ACCDATA_2", 50), @@ -287,13 +162,9 @@ class CarState(CarStateBase): ] if CP.enableBsm and CP.carFingerprint in CANFD_CAR: - signals += [ - ("SodDetctLeft_D_Stat", "Side_Detect_L_Stat"), # Blindspot sensor, left - ("SodDetctRight_D_Stat", "Side_Detect_R_Stat"), # Blindspot sensor, right - ] - checks += [ + messages += [ ("Side_Detect_L_Stat", 5), ("Side_Detect_R_Stat", 5), ] - return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, CanBus(CP).camera) + return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus(CP).camera) diff --git a/selfdrive/car/ford/radar_interface.py b/selfdrive/car/ford/radar_interface.py index e44730ca4..39a62b9e4 100644 --- a/selfdrive/car/ford/radar_interface.py +++ b/selfdrive/car/ford/radar_interface.py @@ -15,30 +15,19 @@ DELPHI_MRR_RADAR_MSG_COUNT = 64 def _create_delphi_esr_radar_can_parser(CP) -> CANParser: msg_n = len(DELPHI_ESR_RADAR_MSGS) - signals = list(zip(['X_Rel'] * msg_n + ['Angle'] * msg_n + ['V_Rel'] * msg_n, - DELPHI_ESR_RADAR_MSGS * 3)) - checks = list(zip(DELPHI_ESR_RADAR_MSGS, [20] * msg_n)) + messages = list(zip(DELPHI_ESR_RADAR_MSGS, [20] * msg_n, strict=True)) - return CANParser(RADAR.DELPHI_ESR, signals, checks, CanBus(CP).radar) + return CANParser(RADAR.DELPHI_ESR, messages, CanBus(CP).radar) def _create_delphi_mrr_radar_can_parser(CP) -> CANParser: - signals = [] - checks = [] + messages = [] for i in range(1, DELPHI_MRR_RADAR_MSG_COUNT + 1): msg = f"MRR_Detection_{i:03d}" - signals += [ - (f"CAN_DET_VALID_LEVEL_{i:02d}", msg), - (f"CAN_DET_AZIMUTH_{i:02d}", msg), - (f"CAN_DET_RANGE_{i:02d}", msg), - (f"CAN_DET_RANGE_RATE_{i:02d}", msg), - (f"CAN_DET_AMPLITUDE_{i:02d}", msg), - (f"CAN_SCAN_INDEX_2LSB_{i:02d}", msg), - ] - checks += [(msg, 20)] + messages += [(msg, 20)] - return CANParser(RADAR.DELPHI_MRR, signals, checks, CanBus(CP).radar) + return CANParser(RADAR.DELPHI_MRR, messages, CanBus(CP).radar) class RadarInterface(RadarInterfaceBase): @@ -62,7 +51,7 @@ class RadarInterface(RadarInterfaceBase): def update(self, can_strings): if self.rcp is None: - return super().update(None) + return None vls = self.rcp.update_strings(can_strings) self.updated_messages.update(vls) diff --git a/selfdrive/car/ford/values.py b/selfdrive/car/ford/values.py index eb4b7cca9..6687204b4 100644 --- a/selfdrive/car/ford/values.py +++ b/selfdrive/car/ford/values.py @@ -201,6 +201,7 @@ FW_VERSIONS = { ], (Ecu.engine, 0x7E0, None): [ b'LB5A-14C204-ATJ\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LB5A-14C204-AUJ\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'LB5A-14C204-AZL\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'LB5A-14C204-BUJ\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'LB5A-14C204-EAC\x00\x00\x00\x00\x00\x00\x00\x00\x00', diff --git a/selfdrive/car/fw_query_definitions.py b/selfdrive/car/fw_query_definitions.py index f9f8e30a6..1caedcd32 100755 --- a/selfdrive/car/fw_query_definitions.py +++ b/selfdrive/car/fw_query_definitions.py @@ -7,6 +7,9 @@ from typing import Callable, Dict, List, Optional, Set, Tuple import panda.python.uds as uds +AddrType = Tuple[int, Optional[int]] +EcuAddrBusType = Tuple[int, Optional[int], int] + def p16(val): return struct.pack("!H", val) @@ -76,7 +79,7 @@ class FwQueryConfig: extra_ecus: List[Tuple[capnp.lib.capnp._EnumModule, int, Optional[int]]] = field(default_factory=list) # Function a brand can implement to provide better fuzzy matching. Takes in FW versions, # returns set of candidates. Only will match if one candidate is returned - match_fw_to_car_fuzzy: Optional[Callable[[Dict[Tuple[int, Optional[int]], Set[bytes]]], Set[str]]] = None + match_fw_to_car_fuzzy: Optional[Callable[[Dict[AddrType, Set[bytes]]], Set[str]]] = None def __post_init__(self): for i in range(len(self.requests)): diff --git a/selfdrive/car/fw_versions.py b/selfdrive/car/fw_versions.py index 87135ea9d..e1035f781 100755 --- a/selfdrive/car/fw_versions.py +++ b/selfdrive/car/fw_versions.py @@ -1,13 +1,14 @@ #!/usr/bin/env python3 from collections import defaultdict -from typing import Any, DefaultDict, Dict, List, Optional, Set, Tuple +from typing import Any, DefaultDict, Dict, List, Optional, Set from tqdm import tqdm import capnp import panda.python.uds as uds from cereal import car from common.params import Params -from selfdrive.car.ecu_addrs import EcuAddrBusType, get_ecu_addrs +from selfdrive.car.ecu_addrs import get_ecu_addrs +from selfdrive.car.fw_query_definitions import AddrType, EcuAddrBusType from selfdrive.car.interfaces import get_interface_attr from selfdrive.car.fingerprints import FW_VERSIONS from selfdrive.car.isotp_parallel_query import IsoTpParallelQuery @@ -35,8 +36,8 @@ def is_brand(brand: str, filter_brand: Optional[str]) -> bool: def build_fw_dict(fw_versions: List[capnp.lib.capnp._DynamicStructBuilder], - filter_brand: Optional[str] = None) -> Dict[Tuple[int, Optional[int]], Set[bytes]]: - fw_versions_dict = defaultdict(set) + filter_brand: Optional[str] = None) -> Dict[AddrType, Set[bytes]]: + fw_versions_dict: DefaultDict[AddrType, Set[bytes]] = defaultdict(set) for fw in fw_versions: if is_brand(fw.brand, filter_brand) and not fw.logging: sub_addr = fw.subAddress if fw.subAddress != 0 else None @@ -44,8 +45,8 @@ def build_fw_dict(fw_versions: List[capnp.lib.capnp._DynamicStructBuilder], return dict(fw_versions_dict) -def get_brand_addrs() -> Dict[str, Set[Tuple[int, Optional[int]]]]: - brand_addrs: DefaultDict[str, Set[Tuple[int, Optional[int]]]] = defaultdict(set) +def get_brand_addrs() -> Dict[str, Set[AddrType]]: + brand_addrs: DefaultDict[str, Set[AddrType]] = defaultdict(set) for brand, cars in VERSIONS.items(): # Add ecus in database + extra ecus to match against brand_addrs[brand] |= {(addr, sub_addr) for _, addr, sub_addr in FW_QUERY_CONFIGS[brand].extra_ecus} @@ -54,7 +55,7 @@ def get_brand_addrs() -> Dict[str, Set[Tuple[int, Optional[int]]]]: return dict(brand_addrs) -def match_fw_to_car_fuzzy(live_fw_versions, log=True, exclude=None): +def match_fw_to_car_fuzzy(live_fw_versions, match_brand=None, log=True, exclude=None): """Do a fuzzy FW match. This function will return a match, and the number of firmware version that were matched uniquely to that specific car. If multiple ECUs uniquely match to different cars the match is rejected.""" @@ -62,6 +63,9 @@ def match_fw_to_car_fuzzy(live_fw_versions, log=True, exclude=None): # Build lookup table from (addr, sub_addr, fw) to list of candidate cars all_fw_versions = defaultdict(list) for candidate, fw_by_addr in FW_VERSIONS.items(): + if not is_brand(MODEL_TO_BRAND[candidate], match_brand): + continue + if candidate == exclude: continue @@ -101,13 +105,14 @@ def match_fw_to_car_fuzzy(live_fw_versions, log=True, exclude=None): return set() -def match_fw_to_car_exact(live_fw_versions, log=True) -> Set[str]: +def match_fw_to_car_exact(live_fw_versions, match_brand=None, log=True) -> Set[str]: """Do an exact FW match. Returns all cars that match the given FW versions for a list of "essential" ECUs. If an ECU is not considered essential the FW version can be missing to get a fingerprint, but if it's present it needs to match the database.""" invalid = set() - candidates = FW_VERSIONS + candidates = {c: f for c, f in FW_VERSIONS.items() if + is_brand(MODEL_TO_BRAND[c], match_brand)} for candidate, fws in candidates.items(): config = FW_QUERY_CONFIGS[MODEL_TO_BRAND[candidate]] @@ -129,7 +134,7 @@ def match_fw_to_car_exact(live_fw_versions, log=True) -> Set[str]: if ecu_type == Ecu.debug: continue - if not any([found_version in expected_versions for found_version in found_versions]): + if not any(found_version in expected_versions for found_version in found_versions): invalid.add(candidate) break @@ -149,7 +154,7 @@ def match_fw_to_car(fw_versions, allow_exact=True, allow_fuzzy=True, log=True): matches = set() for brand in VERSIONS.keys(): fw_versions_dict = build_fw_dict(fw_versions, filter_brand=brand) - matches |= match_func(fw_versions_dict, log=log) + matches |= match_func(fw_versions_dict, match_brand=brand, log=log) # If specified and no matches so far, fall back to brand's fuzzy fingerprinting function config = FW_QUERY_CONFIGS[brand] @@ -208,7 +213,7 @@ def get_brand_ecu_matches(ecu_rx_addrs): brand_addrs = get_brand_addrs() brand_matches = {brand: set() for brand, _, _ in REQUESTS} - brand_rx_offsets = set((brand, r.rx_offset) for brand, _, r in REQUESTS) + brand_rx_offsets = {(brand, r.rx_offset) for brand, _, r in REQUESTS} for addr, sub_addr, _ in ecu_rx_addrs: # Since we can't know what request an ecu responded to, add matches for all possible rx offsets for brand, rx_offset in brand_rx_offsets: @@ -336,8 +341,9 @@ if __name__ == "__main__": from selfdrive.car.vin import get_vin parser = argparse.ArgumentParser(description='Get firmware version of ECUs') - parser.add_argument('--scan', action='store_true') - parser.add_argument('--debug', action='store_true') + parser.add_argument('--scan', '-s', action='store_true', help='In-depth scan of ECU\'s. May cause module faults') + parser.add_argument('--debug', '-d', action='store_true') + parser.add_argument('--json', '-j', type=str, nargs=2, metavar=('MODEL'), help='fp."') parser.add_argument('--brand', help='Only query addresses/with requests for this brand') args = parser.parse_args() @@ -375,9 +381,17 @@ if __name__ == "__main__": padding = max([len(fw.brand) for fw in fw_vers] or [0]) for version in fw_vers: subaddr = None if version.subAddress == 0 else hex(version.subAddress) - print(f" Brand: {version.brand:{padding}}, bus: {version.bus} - (Ecu.{version.ecu}, {hex(version.address)}, {subaddr}): [{version.fwVersion}]") + vers = (f" Brand: {version.brand:{padding}}, bus: {version.bus} - (Ecu.{version.ecu}, {hex(version.address)}, {subaddr}): [{version.fwVersion}]") + versions.append('('+vers+')') + print(vers) print("}") print() print("Possible matches:", candidates) print(f"Getting fw took {time.time() - t:.3f} s") + + if args.json: + model = args.json + vers_str = ''.join(versions) + sentry.capture_info('Model is: '+model+'. '+vers_str) + print("Uploaded JSON & Sentry to fork maintainer") diff --git a/selfdrive/car/gm/carstate.py b/selfdrive/car/gm/carstate.py index 69d34c09c..43cdee18d 100644 --- a/selfdrive/car/gm/carstate.py +++ b/selfdrive/car/gm/carstate.py @@ -117,64 +117,19 @@ class CarState(CarStateBase): @staticmethod def get_cam_can_parser(CP): - signals = [] - checks = [] + messages = [] if CP.networkLocation == NetworkLocation.fwdCamera: - signals += [ - ("AEBCmdActive", "AEBCmd"), - ("RollingCounter", "ASCMLKASteeringCmd"), - ("ACCSpeedSetpoint", "ASCMActiveCruiseControlStatus"), - ("ACCCruiseState", "ASCMActiveCruiseControlStatus"), - ] - checks += [ + messages += [ ("AEBCmd", 10), ("ASCMLKASteeringCmd", 10), ("ASCMActiveCruiseControlStatus", 25), ] - return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, CanBus.CAMERA) + return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus.CAMERA) @staticmethod def get_can_parser(CP): - signals = [ - # sig_name, sig_address - ("BrakePedalPos", "ECMAcceleratorPos"), - ("FrontLeftDoor", "BCMDoorBeltStatus"), - ("FrontRightDoor", "BCMDoorBeltStatus"), - ("RearLeftDoor", "BCMDoorBeltStatus"), - ("RearRightDoor", "BCMDoorBeltStatus"), - ("LeftSeatBelt", "BCMDoorBeltStatus"), - ("RightSeatBelt", "BCMDoorBeltStatus"), - ("TurnSignals", "BCMTurnSignals"), - ("AcceleratorPedal2", "AcceleratorPedal2"), - ("CruiseState", "AcceleratorPedal2"), - ("ACCButtons", "ASCMSteeringButton"), - ("RollingCounter", "ASCMSteeringButton"), - ("SteeringWheelAngle", "PSCMSteeringAngle"), - ("SteeringWheelRate", "PSCMSteeringAngle"), - ("FLWheelSpd", "EBCMWheelSpdFront"), - ("FRWheelSpd", "EBCMWheelSpdFront"), - ("RLWheelSpd", "EBCMWheelSpdRear"), - ("RRWheelSpd", "EBCMWheelSpdRear"), - ("MovingBackward", "EBCMWheelSpdRear"), - ("FrictionBrakeUnavailable", "EBCMFrictionBrakeStatus"), - ("PRNDL2", "ECMPRDNL2"), - ("ManualMode", "ECMPRDNL2"), - ("LKADriverAppldTrq", "PSCMStatus"), - ("LKATorqueDelivered", "PSCMStatus"), - ("LKATorqueDeliveredStatus", "PSCMStatus"), - ("HandsOffSWlDetectionStatus", "PSCMStatus"), - ("HandsOffSWDetectionMode", "PSCMStatus"), - ("LKATotalTorqueDelivered", "PSCMStatus"), - ("PSCMStatusChecksum", "PSCMStatus"), - ("RollingCounter", "PSCMStatus"), - ("TractionControlOn", "ESPStatus"), - ("ParkBrake", "VehicleIgnitionAlt"), - ("CruiseMainOn", "ECMEngineStatus"), - ("BrakePressed", "ECMEngineStatus"), - ] - - checks = [ + messages = [ ("BCMTurnSignals", 1), ("ECMPRDNL2", 10), ("PSCMStatus", 10), @@ -193,27 +148,19 @@ class CarState(CarStateBase): # Used to read back last counter sent to PT by camera if CP.networkLocation == NetworkLocation.fwdCamera: - signals += [ - ("RollingCounter", "ASCMLKASteeringCmd"), - ] - checks += [ + messages += [ ("ASCMLKASteeringCmd", 0), ] if CP.transmissionType == TransmissionType.direct: - signals.append(("RegenPaddle", "EBCMRegenPaddle")) - checks.append(("EBCMRegenPaddle", 50)) + messages.append(("EBCMRegenPaddle", 50)) - return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, CanBus.POWERTRAIN) + return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus.POWERTRAIN) @staticmethod def get_loopback_can_parser(CP): - signals = [ - ("RollingCounter", "ASCMLKASteeringCmd"), - ] - - checks = [ + messages = [ ("ASCMLKASteeringCmd", 0), ] - return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, CanBus.LOOPBACK) + return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus.LOOPBACK) diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py index e17346cfa..3748fd886 100755 --- a/selfdrive/car/gm/interface.py +++ b/selfdrive/car/gm/interface.py @@ -4,7 +4,7 @@ from math import fabs, exp from panda import Panda from common.conversions import Conversions as CV -from selfdrive.car import STD_CARGO_KG, create_button_event, scale_tire_stiffness, get_safety_config +from selfdrive.car import STD_CARGO_KG, create_button_event, get_safety_config from selfdrive.car.gm.radar_interface import RADAR_HEADER_MSG from selfdrive.car.gm.values import CAR, CruiseButtons, CarControllerParams, EV_CAR, CAMERA_ACC_CAR, CanBus from selfdrive.car.interfaces import CarInterfaceBase, TorqueFromLateralAccelCallbackType, FRICTION_THRESHOLD @@ -128,7 +128,7 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2], [0.00]] ret.lateralTuning.pid.kf = 0.00004 # full torque for 20 deg at 80mph means 0.00007818594 ret.steerActuatorDelay = 0.1 # Default delay, not measured yet - tire_stiffness_factor = 0.444 # not optimized yet + ret.tireStiffnessFactor = 0.444 # not optimized yet ret.steerLimitTimer = 0.4 ret.radarTimeStep = 0.0667 # GM radar runs at 15Hz instead of standard 20Hz @@ -138,7 +138,7 @@ class CarInterface(CarInterfaceBase): ret.mass = 1607. + STD_CARGO_KG ret.wheelbase = 2.69 ret.steerRatio = 17.7 # Stock 15.7, LiveParameters - tire_stiffness_factor = 0.469 # Stock Michelin Energy Saver A/S, LiveParameters + ret.tireStiffnessFactor = 0.469 # Stock Michelin Energy Saver A/S, LiveParameters ret.centerToFront = ret.wheelbase * 0.45 # Volt Gen 1, TODO corner weigh ret.lateralTuning.pid.kpBP = [0., 40.] @@ -206,23 +206,23 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[10., 41.0], [10., 41.0]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.13, 0.24], [0.01, 0.02]] ret.lateralTuning.pid.kf = 0.000045 - tire_stiffness_factor = 1.0 + ret.tireStiffnessFactor = 1.0 elif candidate == CAR.BOLT_EUV: ret.mass = 1669. + STD_CARGO_KG ret.wheelbase = 2.63779 ret.steerRatio = 16.8 ret.centerToFront = ret.wheelbase * 0.4 - tire_stiffness_factor = 1.0 + ret.tireStiffnessFactor = 1.0 ret.steerActuatorDelay = 0.2 CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) elif candidate == CAR.SILVERADO: - ret.mass = 2200. + STD_CARGO_KG + ret.mass = 2450. + STD_CARGO_KG ret.wheelbase = 3.75 ret.steerRatio = 16.3 ret.centerToFront = ret.wheelbase * 0.5 - tire_stiffness_factor = 1.0 + ret.tireStiffnessFactor = 1.0 # On the Bolt, the ECM and camera independently check that you are either above 5 kph or at a stop # with foot on brake to allow engagement, but this platform only has that check in the camera. # TODO: check if this is split by EV/ICE with more platforms in the future @@ -242,15 +242,10 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.64 ret.steerRatio = 16.8 ret.centerToFront = ret.wheelbase * 0.4 - tire_stiffness_factor = 1.0 + ret.tireStiffnessFactor = 1.0 ret.steerActuatorDelay = 0.2 CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) - # TODO: start from empirically derived lateral slip stiffness for the civic and scale by - # mass and CG position, so all cars will have approximately similar dyn behaviors - ret.tireStiffnessFront, ret.tireStiffnessRear = scale_tire_stiffness(ret.mass, ret.wheelbase, ret.centerToFront, - tire_stiffness_factor=tire_stiffness_factor) - return ret # returns a car.CarState diff --git a/selfdrive/car/gm/radar_interface.py b/selfdrive/car/gm/radar_interface.py index b86a85f91..0424b95a7 100755 --- a/selfdrive/car/gm/radar_interface.py +++ b/selfdrive/car/gm/radar_interface.py @@ -25,11 +25,11 @@ def create_radar_can_parser(car_fingerprint): ['TrkRange'] * NUM_SLOTS + ['TrkRangeRate'] * NUM_SLOTS + ['TrkRangeAccel'] * NUM_SLOTS + ['TrkAzimuth'] * NUM_SLOTS + ['TrkWidth'] * NUM_SLOTS + ['TrkObjectID'] * NUM_SLOTS, - [RADAR_HEADER_MSG] * 7 + radar_targets * 6)) + [RADAR_HEADER_MSG] * 7 + radar_targets * 6, strict=True)) - checks = list({(s[1], 14) for s in signals}) + messages = list({(s[1], 14) for s in signals}) - return CANParser(DBC[car_fingerprint]['radar'], signals, checks, CanBus.OBSTACLE) + return CANParser(DBC[car_fingerprint]['radar'], messages, CanBus.OBSTACLE) class RadarInterface(RadarInterfaceBase): @@ -44,7 +44,7 @@ class RadarInterface(RadarInterfaceBase): def update(self, can_strings): if self.rcp is None: - return super().update(None) + return None vls = self.rcp.update_strings(can_strings) self.updated_messages.update(vls) diff --git a/selfdrive/car/honda/carstate.py b/selfdrive/car/honda/carstate.py index 196f233a3..d6d2b18a0 100644 --- a/selfdrive/car/honda/carstate.py +++ b/selfdrive/car/honda/carstate.py @@ -12,39 +12,8 @@ from selfdrive.car.interfaces import CarStateBase TransmissionType = car.CarParams.TransmissionType -def get_can_signals(CP, gearbox_msg, main_on_sig_msg): - signals = [ - ("XMISSION_SPEED", "ENGINE_DATA"), - ("WHEEL_SPEED_FL", "WHEEL_SPEEDS"), - ("WHEEL_SPEED_FR", "WHEEL_SPEEDS"), - ("WHEEL_SPEED_RL", "WHEEL_SPEEDS"), - ("WHEEL_SPEED_RR", "WHEEL_SPEEDS"), - ("STEER_ANGLE", "STEERING_SENSORS"), - ("STEER_ANGLE_RATE", "STEERING_SENSORS"), - ("MOTOR_TORQUE", "STEER_MOTOR_TORQUE"), - ("STEER_TORQUE_SENSOR", "STEER_STATUS"), - ("IMPERIAL_UNIT", "CAR_SPEED"), - ("ROUGH_CAR_SPEED_2", "CAR_SPEED"), - ("LEFT_BLINKER", "SCM_FEEDBACK"), - ("RIGHT_BLINKER", "SCM_FEEDBACK"), - ("SEATBELT_DRIVER_LAMP", "SEATBELT_STATUS"), - ("SEATBELT_DRIVER_LATCHED", "SEATBELT_STATUS"), - ("BRAKE_PRESSED", "POWERTRAIN_DATA"), - ("BRAKE_SWITCH", "POWERTRAIN_DATA"), - ("CRUISE_BUTTONS", "SCM_BUTTONS"), - ("ESP_DISABLED", "VSA_STATUS"), - ("USER_BRAKE", "VSA_STATUS"), - ("BRAKE_HOLD_ACTIVE", "VSA_STATUS"), - ("STEER_STATUS", "STEER_STATUS"), - ("GEAR_SHIFTER", gearbox_msg), - ("GEAR", gearbox_msg), - ("PEDAL_GAS", "POWERTRAIN_DATA"), - ("CRUISE_SETTING", "SCM_BUTTONS"), - ("ACC_STATUS", "POWERTRAIN_DATA"), - ("MAIN_ON", main_on_sig_msg), - ] - - checks = [ +def get_can_messages(CP, gearbox_msg): + messages = [ ("ENGINE_DATA", 100), ("WHEEL_SPEEDS", 50), ("STEERING_SENSORS", 100), @@ -58,80 +27,59 @@ def get_can_signals(CP, gearbox_msg, main_on_sig_msg): ] if CP.carFingerprint == CAR.ODYSSEY_CHN: - checks += [ + messages += [ ("SCM_FEEDBACK", 25), ("SCM_BUTTONS", 50), ] else: - checks += [ + messages += [ ("SCM_FEEDBACK", 10), ("SCM_BUTTONS", 25), ] if CP.carFingerprint in (CAR.CRV_HYBRID, CAR.CIVIC_BOSCH_DIESEL, CAR.ACURA_RDX_3G, CAR.HONDA_E): - checks.append((gearbox_msg, 50)) + messages.append((gearbox_msg, 50)) else: - checks.append((gearbox_msg, 100)) + messages.append((gearbox_msg, 100)) if CP.carFingerprint in HONDA_BOSCH_ALT_BRAKE_SIGNAL: - signals.append(("BRAKE_PRESSED", "BRAKE_MODULE")) - checks.append(("BRAKE_MODULE", 50)) + messages.append(("BRAKE_MODULE", 50)) if CP.carFingerprint in (HONDA_BOSCH | {CAR.CIVIC, CAR.ODYSSEY, CAR.ODYSSEY_CHN}): - signals.append(("EPB_STATE", "EPB_STATUS")) - checks.append(("EPB_STATUS", 50)) + messages.append(("EPB_STATUS", 50)) if CP.carFingerprint in HONDA_BOSCH: # these messages are on camera bus on radarless cars if not CP.openpilotLongitudinalControl and CP.carFingerprint not in HONDA_BOSCH_RADARLESS: - signals += [ - ("CRUISE_CONTROL_LABEL", "ACC_HUD"), - ("CRUISE_SPEED", "ACC_HUD"), - ("ACCEL_COMMAND", "ACC_CONTROL"), - ("AEB_STATUS", "ACC_CONTROL"), - ] - checks += [ + messages += [ ("ACC_HUD", 10), ("ACC_CONTROL", 50), ] else: # Nidec signals - signals += [("CRUISE_SPEED_PCM", "CRUISE"), - ("CRUISE_SPEED_OFFSET", "CRUISE_PARAMS")] - if CP.carFingerprint == CAR.ODYSSEY_CHN: - checks.append(("CRUISE_PARAMS", 10)) + messages.append(("CRUISE_PARAMS", 10)) else: - checks.append(("CRUISE_PARAMS", 50)) + messages.append(("CRUISE_PARAMS", 50)) + # TODO: clean this up if CP.carFingerprint in (CAR.ACCORD, CAR.ACCORDH, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_HYBRID, CAR.INSIGHT, CAR.ACURA_RDX_3G, CAR.HONDA_E, CAR.CIVIC_2022, CAR.HRV_3G): - signals.append(("DRIVERS_DOOR_OPEN", "SCM_FEEDBACK")) + pass elif CP.carFingerprint in (CAR.ODYSSEY_CHN, CAR.FREED, CAR.HRV): - signals.append(("DRIVERS_DOOR_OPEN", "SCM_BUTTONS")) + pass else: - signals += [("DOOR_OPEN_FL", "DOORS_STATUS"), - ("DOOR_OPEN_FR", "DOORS_STATUS"), - ("DOOR_OPEN_RL", "DOORS_STATUS"), - ("DOOR_OPEN_RR", "DOORS_STATUS")] - checks.append(("DOORS_STATUS", 3)) + messages.append(("DOORS_STATUS", 3)) # add gas interceptor reading if we are using it if CP.enableGasInterceptor: - signals.append(("INTERCEPTOR_GAS", "GAS_SENSOR")) - signals.append(("INTERCEPTOR_GAS2", "GAS_SENSOR")) - checks.append(("GAS_SENSOR", 50)) + messages.append(("GAS_SENSOR", 50)) if CP.carFingerprint in HONDA_BOSCH_RADARLESS: - signals.append(("CRUISE_FAULT", "CRUISE_FAULT_STATUS")) - checks.append(("CRUISE_FAULT_STATUS", 50)) + messages.append(("CRUISE_FAULT_STATUS", 50)) elif CP.openpilotLongitudinalControl: - signals += [ - ("BRAKE_ERROR_1", "STANDSTILL"), - ("BRAKE_ERROR_2", "STANDSTILL") - ] - checks.append(("STANDSTILL", 50)) + messages.append(("STANDSTILL", 50)) - return signals, checks + return messages class CarState(CarStateBase): @@ -316,55 +264,36 @@ class CarState(CarStateBase): return ret def get_can_parser(self, CP): - signals, checks = get_can_signals(CP, self.gearbox_msg, self.main_on_sig_msg) - return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, get_pt_bus(CP.carFingerprint)) + messages = get_can_messages(CP, self.gearbox_msg) + return CANParser(DBC[CP.carFingerprint]["pt"], messages, get_pt_bus(CP.carFingerprint)) @staticmethod def get_cam_can_parser(CP): - signals = [] - checks = [ + messages = [ ("STEERING_CONTROL", 100), ] if CP.carFingerprint in HONDA_BOSCH_RADARLESS: - signals.append(("LKAS_PROBLEM", "LKAS_HUD")) - checks.append(("LKAS_HUD", 10)) + messages.append(("LKAS_HUD", 10)) if not CP.openpilotLongitudinalControl: - signals += [ - ("CRUISE_SPEED", "ACC_HUD"), - ("CRUISE_CONTROL_LABEL", "ACC_HUD"), - ] - checks.append(("ACC_HUD", 10)) + messages.append(("ACC_HUD", 10)) elif CP.carFingerprint not in HONDA_BOSCH: - signals += [("COMPUTER_BRAKE", "BRAKE_COMMAND"), - ("AEB_REQ_1", "BRAKE_COMMAND"), - ("FCW", "BRAKE_COMMAND"), - ("CHIME", "BRAKE_COMMAND"), - ("LKAS_PROBLEM", "LKAS_HUD"), - ("FCM_OFF", "ACC_HUD"), - ("FCM_OFF_2", "ACC_HUD"), - ("FCM_PROBLEM", "ACC_HUD"), - ("ACC_PROBLEM", "ACC_HUD"), - ("ICONS", "ACC_HUD")] - checks += [ + messages += [ ("ACC_HUD", 10), ("LKAS_HUD", 10), ("BRAKE_COMMAND", 50), ] - return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 2) + return CANParser(DBC[CP.carFingerprint]["pt"], messages, 2) @staticmethod def get_body_can_parser(CP): if CP.enableBsm: - signals = [("BSM_ALERT", "BSM_STATUS_RIGHT"), - ("BSM_ALERT", "BSM_STATUS_LEFT")] - - checks = [ + messages = [ ("BSM_STATUS_LEFT", 3), ("BSM_STATUS_RIGHT", 3), ] bus_body = 0 # B-CAN is forwarded to ACC-CAN radar side (CAN 0 on fake ethernet port) - return CANParser(DBC[CP.carFingerprint]["body"], signals, checks, bus_body) + return CANParser(DBC[CP.carFingerprint]["body"], messages, bus_body) return None diff --git a/selfdrive/car/honda/interface.py b/selfdrive/car/honda/interface.py index 29c6fa032..3d8efa31b 100755 --- a/selfdrive/car/honda/interface.py +++ b/selfdrive/car/honda/interface.py @@ -5,7 +5,7 @@ from common.conversions import Conversions as CV from common.numpy_fast import interp from selfdrive.car.honda.values import CarControllerParams, CruiseButtons, HondaFlags, CAR, HONDA_BOSCH, HONDA_NIDEC_ALT_SCM_MESSAGES, \ HONDA_BOSCH_ALT_BRAKE_SIGNAL, HONDA_BOSCH_RADARLESS -from selfdrive.car import STD_CARGO_KG, CivicParams, create_button_event, scale_tire_stiffness, get_safety_config +from selfdrive.car import STD_CARGO_KG, CivicParams, create_button_event, get_safety_config from selfdrive.car.interfaces import CarInterfaceBase from selfdrive.car.disable_ecu import disable_ecu @@ -105,7 +105,6 @@ class CarInterface(CarInterfaceBase): else: ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 2560], [0, 2560]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[1.1], [0.33]] - tire_stiffness_factor = 1. elif candidate in (CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CIVIC_2022): ret.mass = CivicParams.MASS @@ -113,7 +112,6 @@ class CarInterface(CarInterfaceBase): ret.centerToFront = CivicParams.CENTER_TO_FRONT ret.steerRatio = 15.38 # 10.93 is end-to-end spec ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end - tire_stiffness_factor = 1. ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] elif candidate in (CAR.ACCORD, CAR.ACCORDH): @@ -122,7 +120,7 @@ class CarInterface(CarInterfaceBase): ret.centerToFront = ret.wheelbase * 0.39 ret.steerRatio = 16.33 # 11.82 is spec end-to-end ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end - tire_stiffness_factor = 0.8467 + ret.tireStiffnessFactor = 0.8467 if eps_modified: ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.3], [0.09]] @@ -135,7 +133,7 @@ class CarInterface(CarInterfaceBase): ret.centerToFront = ret.wheelbase * 0.37 ret.steerRatio = 18.61 # 15.3 is spec end-to-end ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 3840], [0, 3840]] # TODO: determine if there is a dead zone at the top end - tire_stiffness_factor = 0.72 + ret.tireStiffnessFactor = 0.72 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] elif candidate in (CAR.CRV, CAR.CRV_EU): @@ -144,7 +142,7 @@ class CarInterface(CarInterfaceBase): ret.centerToFront = ret.wheelbase * 0.41 ret.steerRatio = 16.89 # as spec ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 1000], [0, 1000]] # TODO: determine if there is a dead zone at the top end - tire_stiffness_factor = 0.444 + ret.tireStiffnessFactor = 0.444 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] ret.wheelSpeedFactor = 1.025 @@ -162,7 +160,7 @@ class CarInterface(CarInterfaceBase): else: ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 3840], [0, 3840]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.64], [0.192]] - tire_stiffness_factor = 0.677 + ret.tireStiffnessFactor = 0.677 ret.wheelSpeedFactor = 1.025 elif candidate == CAR.CRV_HYBRID: @@ -171,7 +169,7 @@ class CarInterface(CarInterfaceBase): ret.centerToFront = ret.wheelbase * 0.41 ret.steerRatio = 16.0 # 12.3 is spec end-to-end ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end - tire_stiffness_factor = 0.677 + ret.tireStiffnessFactor = 0.677 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.18]] ret.wheelSpeedFactor = 1.025 @@ -181,7 +179,7 @@ class CarInterface(CarInterfaceBase): ret.centerToFront = ret.wheelbase * 0.39 ret.steerRatio = 13.06 ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end - tire_stiffness_factor = 0.75 + ret.tireStiffnessFactor = 0.75 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2], [0.05]] elif candidate == CAR.FREED: @@ -191,7 +189,7 @@ class CarInterface(CarInterfaceBase): ret.centerToFront = ret.wheelbase * 0.39 ret.steerRatio = 13.06 ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] - tire_stiffness_factor = 0.75 + ret.tireStiffnessFactor = 0.75 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2], [0.05]] elif candidate in (CAR.HRV, CAR.HRV_3G): @@ -200,7 +198,7 @@ class CarInterface(CarInterfaceBase): ret.centerToFront = ret.wheelbase * 0.41 ret.steerRatio = 15.2 ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] - tire_stiffness_factor = 0.5 + ret.tireStiffnessFactor = 0.5 if candidate == CAR.HRV: ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.16], [0.025]] ret.wheelSpeedFactor = 1.025 @@ -212,7 +210,7 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.68 ret.centerToFront = ret.wheelbase * 0.38 ret.steerRatio = 15.0 # as spec - tire_stiffness_factor = 0.444 + ret.tireStiffnessFactor = 0.444 ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 1000], [0, 1000]] # TODO: determine if there is a dead zone at the top end ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] @@ -223,14 +221,14 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 11.95 # as spec ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 3840], [0, 3840]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2], [0.06]] - tire_stiffness_factor = 0.677 + ret.tireStiffnessFactor = 0.677 elif candidate in (CAR.ODYSSEY, CAR.ODYSSEY_CHN): ret.mass = 1900. + STD_CARGO_KG ret.wheelbase = 3.00 ret.centerToFront = ret.wheelbase * 0.41 ret.steerRatio = 14.35 # as spec - tire_stiffness_factor = 0.82 + ret.tireStiffnessFactor = 0.82 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.28], [0.08]] if candidate == CAR.ODYSSEY_CHN: ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 32767], [0, 32767]] # TODO: determine if there is a dead zone at the top end @@ -243,7 +241,7 @@ class CarInterface(CarInterfaceBase): ret.centerToFront = ret.wheelbase * 0.428 ret.steerRatio = 16.0 # as spec ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end - tire_stiffness_factor = 0.444 + ret.tireStiffnessFactor = 0.444 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.38], [0.11]] elif candidate == CAR.RIDGELINE: @@ -252,7 +250,7 @@ class CarInterface(CarInterfaceBase): ret.centerToFront = ret.wheelbase * 0.41 ret.steerRatio = 15.59 # as spec ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end - tire_stiffness_factor = 0.444 + ret.tireStiffnessFactor = 0.444 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.38], [0.11]] elif candidate == CAR.INSIGHT: @@ -261,7 +259,7 @@ class CarInterface(CarInterfaceBase): ret.centerToFront = ret.wheelbase * 0.39 ret.steerRatio = 15.0 # 12.58 is spec end-to-end ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end - tire_stiffness_factor = 0.82 + ret.tireStiffnessFactor = 0.82 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.18]] elif candidate == CAR.HONDA_E: @@ -270,7 +268,7 @@ class CarInterface(CarInterfaceBase): ret.centerToFront = ret.wheelbase * 0.5 ret.steerRatio = 16.71 ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end - tire_stiffness_factor = 0.82 + ret.tireStiffnessFactor = 0.82 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.18]] # TODO: can probably use some tuning else: @@ -296,11 +294,6 @@ class CarInterface(CarInterfaceBase): ret.autoResumeSng = candidate in (HONDA_BOSCH | {CAR.CIVIC}) or ret.enableGasInterceptor ret.minEnableSpeed = -1. if ret.autoResumeSng else 25.5 * CV.MPH_TO_MS - # TODO: start from empirically derived lateral slip stiffness for the civic and scale by - # mass and CG position, so all cars will have approximately similar dyn behaviors - ret.tireStiffnessFront, ret.tireStiffnessRear = scale_tire_stiffness(ret.mass, ret.wheelbase, ret.centerToFront, - tire_stiffness_factor=tire_stiffness_factor) - ret.steerActuatorDelay = 0.1 ret.steerLimitTimer = 0.8 diff --git a/selfdrive/car/honda/radar_interface.py b/selfdrive/car/honda/radar_interface.py index 660be4c44..43fe42202 100755 --- a/selfdrive/car/honda/radar_interface.py +++ b/selfdrive/car/honda/radar_interface.py @@ -1,4 +1,6 @@ #!/usr/bin/env python3 +from collections import defaultdict + from cereal import car from opendbc.can.parser import CANParser from selfdrive.car.interfaces import RadarInterfaceBase @@ -7,12 +9,8 @@ from selfdrive.car.honda.values import DBC def _create_nidec_can_parser(car_fingerprint): radar_messages = [0x400] + list(range(0x430, 0x43A)) + list(range(0x440, 0x446)) - signals = list(zip(['RADAR_STATE'] + - ['LONG_DIST'] * 16 + ['NEW_TRACK'] * 16 + ['LAT_DIST'] * 16 + - ['REL_SPEED'] * 16, - [0x400] + radar_messages[1:] * 4)) - checks = [(s[1], 20) for s in signals] - return CANParser(DBC[car_fingerprint]['radar'], signals, checks, 1) + messages = [(m, 20) for m in radar_messages] + return CANParser(DBC[car_fingerprint]['radar'], messages, 1) class RadarInterface(RadarInterfaceBase): @@ -32,50 +30,61 @@ class RadarInterface(RadarInterfaceBase): else: self.rcp = _create_nidec_can_parser(CP.carFingerprint) self.trigger_msg = 0x445 - self.updated_messages = set() + self.updated_values = defaultdict(lambda: defaultdict(list)) def update(self, can_strings): # in Bosch radar and we are only steering for now, so sleep 0.05s to keep # radard at 20Hz and return no points if self.radar_off_can: - return super().update(None) - - vls = self.rcp.update_strings(can_strings) - self.updated_messages.update(vls) - - if self.trigger_msg not in self.updated_messages: return None - rr = self._update(self.updated_messages) - self.updated_messages.clear() - return rr + addresses = self.rcp.update_strings(can_strings) + for addr in addresses: + vals_dict = self.rcp.vl_all[addr] + for sig_name, vals in vals_dict.items(): + self.updated_values[addr][sig_name].extend(vals) - def _update(self, updated_messages): + if self.trigger_msg not in self.updated_values: + return None + + radar_data = self._radar_msg_from_buffer(self.updated_values, self.rcp.can_valid) + self.updated_values.clear() + + return radar_data + + def _radar_msg_from_buffer(self, updated_values, can_valid): ret = car.RadarData.new_message() - for ii in sorted(updated_messages): - cpt = self.rcp.vl[ii] - if ii == 0x400: - # check for radar faults - self.radar_fault = cpt['RADAR_STATE'] != 0x79 - self.radar_wrong_config = cpt['RADAR_STATE'] == 0x69 - elif cpt['LONG_DIST'] < 255: - if ii not in self.pts or cpt['NEW_TRACK']: - self.pts[ii] = car.RadarData.RadarPoint.new_message() - self.pts[ii].trackId = self.track_id - self.track_id += 1 - self.pts[ii].dRel = cpt['LONG_DIST'] # from front of car - self.pts[ii].yRel = -cpt['LAT_DIST'] # in car frame's y axis, left is positive - self.pts[ii].vRel = cpt['REL_SPEED'] - self.pts[ii].aRel = float('nan') - self.pts[ii].yvRel = float('nan') - self.pts[ii].measured = True - else: - if ii in self.pts: - del self.pts[ii] + for ii in sorted(updated_values): + msgs = updated_values[ii] + n_vals_per_addr = len(list(msgs.values())[0]) + cpts = [ + {k: v[i] for k, v in msgs.items()} + for i in range(n_vals_per_addr) + ] + + for cpt in cpts: + if ii == 0x400: + # check for radar faults + self.radar_fault = cpt['RADAR_STATE'] != 0x79 + self.radar_wrong_config = cpt['RADAR_STATE'] == 0x69 + elif cpt['LONG_DIST'] < 255: + if ii not in self.pts or cpt['NEW_TRACK']: + self.pts[ii] = car.RadarData.RadarPoint.new_message() + self.pts[ii].trackId = self.track_id + self.track_id += 1 + self.pts[ii].dRel = cpt['LONG_DIST'] # from front of car + self.pts[ii].yRel = -cpt['LAT_DIST'] # in car frame's y axis, left is positive + self.pts[ii].vRel = cpt['REL_SPEED'] + self.pts[ii].aRel = float('nan') + self.pts[ii].yvRel = float('nan') + self.pts[ii].measured = True + else: + if ii in self.pts: + del self.pts[ii] errors = [] - if not self.rcp.can_valid: + if not can_valid: errors.append("canError") if self.radar_fault: errors.append("fault") diff --git a/selfdrive/car/hyundai/carcontroller.py b/selfdrive/car/hyundai/carcontroller.py index 3e6c98355..8aeda5703 100644 --- a/selfdrive/car/hyundai/carcontroller.py +++ b/selfdrive/car/hyundai/carcontroller.py @@ -69,7 +69,7 @@ class CarController: apply_steer = clip(apply_steer, -self.params.STEER_MAX, self.params.STEER_MAX) # >90 degree steering fault prevention - self.angle_limit_counter, apply_steer_req = common_fault_avoidance(CS.out.steeringAngleDeg, MAX_ANGLE, CC.latActive, + self.angle_limit_counter, apply_steer_req = common_fault_avoidance(abs(CS.out.steeringAngleDeg) >= MAX_ANGLE, CC.latActive, self.angle_limit_counter, MAX_ANGLE_FRAMES, MAX_ANGLE_CONSECUTIVE_FRAMES) diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py index 32e2f8626..f46118914 100644 --- a/selfdrive/car/hyundai/carstate.py +++ b/selfdrive/car/hyundai/carstate.py @@ -22,8 +22,8 @@ class CarState(CarStateBase): self.cruise_buttons = deque([Buttons.NONE] * PREV_BUTTON_SAMPLES, maxlen=PREV_BUTTON_SAMPLES) self.main_buttons = deque([Buttons.NONE] * PREV_BUTTON_SAMPLES, maxlen=PREV_BUTTON_SAMPLES) - self.gear_msg_canfd = "GEAR_ALT_2" if CP.flags & HyundaiFlags.CANFD_ALT_GEARS_2 else \ - "GEAR_ALT" if CP.flags & HyundaiFlags.CANFD_ALT_GEARS else \ + self.gear_msg_canfd = "GEAR_ALT" if CP.flags & HyundaiFlags.CANFD_ALT_GEARS else \ + "GEAR_ALT_2" if CP.flags & HyundaiFlags.CANFD_ALT_GEARS_2 else \ "GEAR_SHIFTER" if CP.carFingerprint in CANFD_CAR: self.shifter_values = can_define.dv[self.gear_msg_canfd]["GEAR"] @@ -34,6 +34,11 @@ class CarState(CarStateBase): else: # preferred and elect gear methods use same definition self.shifter_values = can_define.dv["LVR12"]["CF_Lvr_Gear"] + self.accelerator_msg_canfd = "ACCELERATOR" if CP.carFingerprint in EV_CAR else \ + "ACCELERATOR_ALT" if CP.carFingerprint in HYBRID_CAR else \ + "ACCELERATOR_BRAKE_ALT" + self.cruise_btns_msg_canfd = "CRUISE_BUTTONS_ALT" if CP.flags & HyundaiFlags.CANFD_ALT_BUTTONS else \ + "CRUISE_BUTTONS" self.is_metric = False self.buttons_counter = 0 @@ -163,13 +168,11 @@ class CarState(CarStateBase): speed_factor = CV.KPH_TO_MS if self.is_metric else CV.MPH_TO_MS if self.CP.carFingerprint in (EV_CAR | HYBRID_CAR): - if self.CP.carFingerprint in EV_CAR: - ret.gas = cp.vl["ACCELERATOR"]["ACCELERATOR_PEDAL"] / 255. - else: - ret.gas = cp.vl["ACCELERATOR_ALT"]["ACCELERATOR_PEDAL"] / 1023. + offset = 255. if self.CP.carFingerprint in EV_CAR else 1023. + ret.gas = cp.vl[self.accelerator_msg_canfd]["ACCELERATOR_PEDAL"] / offset ret.gasPressed = ret.gas > 1e-5 else: - ret.gasPressed = bool(cp.vl["ACCELERATOR_BRAKE_ALT"]["ACCELERATOR_PEDAL_PRESSED"]) + ret.gasPressed = bool(cp.vl[self.accelerator_msg_canfd]["ACCELERATOR_PEDAL_PRESSED"]) ret.brakePressed = cp.vl["TCS"]["DriverBraking"] == 1 @@ -217,11 +220,10 @@ class CarState(CarStateBase): ret.cruiseState.speed = cp_cruise_info.vl["SCC_CONTROL"]["VSetDis"] * speed_factor self.cruise_info = copy.copy(cp_cruise_info.vl["SCC_CONTROL"]) - cruise_btn_msg = "CRUISE_BUTTONS_ALT" if self.CP.flags & HyundaiFlags.CANFD_ALT_BUTTONS else "CRUISE_BUTTONS" self.prev_cruise_buttons = self.cruise_buttons[-1] - self.cruise_buttons.extend(cp.vl_all[cruise_btn_msg]["CRUISE_BUTTONS"]) - self.main_buttons.extend(cp.vl_all[cruise_btn_msg]["ADAPTIVE_CRUISE_MAIN_BTN"]) - self.buttons_counter = cp.vl[cruise_btn_msg]["COUNTER"] + self.cruise_buttons.extend(cp.vl_all[self.cruise_btns_msg_canfd]["CRUISE_BUTTONS"]) + self.main_buttons.extend(cp.vl_all[self.cruise_btns_msg_canfd]["ADAPTIVE_CRUISE_MAIN_BTN"]) + self.buttons_counter = cp.vl[self.cruise_btns_msg_canfd]["COUNTER"] ret.accFaulted = cp.vl["TCS"]["ACCEnable"] != 0 # 0 ACC CONTROL ENABLED, 1-3 ACC CONTROL DISABLED if self.CP.flags & HyundaiFlags.CANFD_HDA2: @@ -229,67 +231,11 @@ class CarState(CarStateBase): return ret - @staticmethod - def get_can_parser(CP): + def get_can_parser(self, CP): if CP.carFingerprint in CANFD_CAR: - return CarState.get_can_parser_canfd(CP) + return self.get_can_parser_canfd(CP) - signals = [ - # signal_name, signal_address - ("WHL_SPD_FL", "WHL_SPD11"), - ("WHL_SPD_FR", "WHL_SPD11"), - ("WHL_SPD_RL", "WHL_SPD11"), - ("WHL_SPD_RR", "WHL_SPD11"), - - ("YAW_RATE", "ESP12"), - - ("CF_Gway_DrvSeatBeltInd", "CGW4"), - - ("CF_Gway_DrvSeatBeltSw", "CGW1"), - ("CF_Gway_DrvDrSw", "CGW1"), # Driver Door - ("CF_Gway_AstDrSw", "CGW1"), # Passenger Door - ("CF_Gway_RLDrSw", "CGW2"), # Rear left Door - ("CF_Gway_RRDrSw", "CGW2"), # Rear right Door - ("CF_Gway_TurnSigLh", "CGW1"), - ("CF_Gway_TurnSigRh", "CGW1"), - ("CF_Gway_ParkBrakeSw", "CGW1"), - - ("CYL_PRES", "ESP12"), - - ("CF_Clu_CruiseSwState", "CLU11"), - ("CF_Clu_CruiseSwMain", "CLU11"), - ("CF_Clu_SldMainSW", "CLU11"), - ("CF_Clu_ParityBit1", "CLU11"), - ("CF_Clu_VanzDecimal" , "CLU11"), - ("CF_Clu_Vanz", "CLU11"), - ("CF_Clu_SPEED_UNIT", "CLU11"), - ("CF_Clu_DetentOut", "CLU11"), - ("CF_Clu_RheostatLevel", "CLU11"), - ("CF_Clu_CluInfo", "CLU11"), - ("CF_Clu_AmpInfo", "CLU11"), - ("CF_Clu_AliveCnt1", "CLU11"), - - ("CF_Clu_VehicleSpeed", "CLU15"), - - ("ACCEnable", "TCS13"), - ("ACC_REQ", "TCS13"), - ("DriverBraking", "TCS13"), - ("StandStill", "TCS13"), - ("PBRAKE_ACT", "TCS13"), - - ("ESC_Off_Step", "TCS15"), - ("AVH_LAMP", "TCS15"), - - ("CR_Mdps_StrColTq", "MDPS12"), - ("CF_Mdps_ToiActive", "MDPS12"), - ("CF_Mdps_ToiUnavail", "MDPS12"), - ("CF_Mdps_ToiFlt", "MDPS12"), - ("CR_Mdps_OutTq", "MDPS12"), - - ("SAS_Angle", "SAS11"), - ("SAS_Speed", "SAS11"), - ] - checks = [ + messages = [ # address, frequency ("MDPS12", 50), ("TCS13", 50), @@ -305,165 +251,61 @@ class CarState(CarStateBase): ] if not CP.openpilotLongitudinalControl and CP.carFingerprint not in CAMERA_SCC_CAR: - signals += [ - ("MainMode_ACC", "SCC11"), - ("VSetDis", "SCC11"), - ("SCCInfoDisplay", "SCC11"), - ("ACC_ObjDist", "SCC11"), - ("ACCMode", "SCC12"), - ] - checks += [ + messages += [ ("SCC11", 50), ("SCC12", 50), ] - if CP.flags & HyundaiFlags.USE_FCA.value: - signals += [ - ("FCA_CmdAct", "FCA11"), - ("CF_VSM_Warn", "FCA11"), - ("CF_VSM_DecCmdAct", "FCA11"), - ] - checks.append(("FCA11", 50)) - else: - signals += [ - ("AEB_CmdAct", "SCC12"), - ("CF_VSM_Warn", "SCC12"), - ("CF_VSM_DecCmdAct", "SCC12"), - ] + messages.append(("FCA11", 50)) if CP.enableBsm: - signals += [ - ("CF_Lca_IndLeft", "LCA11"), - ("CF_Lca_IndRight", "LCA11"), - ] - checks.append(("LCA11", 50)) + messages.append(("LCA11", 50)) if CP.carFingerprint in (HYBRID_CAR | EV_CAR): - if CP.carFingerprint in HYBRID_CAR: - signals.append(("CR_Vcu_AccPedDep_Pos", "E_EMS11")) - else: - signals.append(("Accel_Pedal_Pos", "E_EMS11")) - checks.append(("E_EMS11", 50)) + messages.append(("E_EMS11", 50)) else: - signals += [ - ("PV_AV_CAN", "EMS12"), - ("CF_Ems_AclAct", "EMS16"), - ] - checks += [ + messages += [ ("EMS12", 100), ("EMS16", 100), ] if CP.carFingerprint in CAN_GEARS["use_cluster_gears"]: - signals.append(("CF_Clu_Gear", "CLU15")) + pass elif CP.carFingerprint in CAN_GEARS["use_tcu_gears"]: - signals.append(("CUR_GR", "TCU12")) - checks.append(("TCU12", 100)) + messages.append(("TCU12", 100)) elif CP.carFingerprint in CAN_GEARS["use_elect_gears"]: - signals.append(("Elect_Gear_Shifter", "ELECT_GEAR")) - checks.append(("ELECT_GEAR", 20)) + messages.append(("ELECT_GEAR", 20)) else: - signals.append(("CF_Lvr_Gear", "LVR12")) - checks.append(("LVR12", 100)) + messages.append(("LVR12", 100)) - return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 0) + return CANParser(DBC[CP.carFingerprint]["pt"], messages, 0) @staticmethod def get_cam_can_parser(CP): if CP.carFingerprint in CANFD_CAR: return CarState.get_cam_can_parser_canfd(CP) - signals = [ - # signal_name, signal_address - ("CF_Lkas_LdwsActivemode", "LKAS11"), - ("CF_Lkas_LdwsSysState", "LKAS11"), - ("CF_Lkas_SysWarning", "LKAS11"), - ("CF_Lkas_LdwsLHWarning", "LKAS11"), - ("CF_Lkas_LdwsRHWarning", "LKAS11"), - ("CF_Lkas_HbaLamp", "LKAS11"), - ("CF_Lkas_FcwBasReq", "LKAS11"), - ("CF_Lkas_HbaSysState", "LKAS11"), - ("CF_Lkas_FcwOpt", "LKAS11"), - ("CF_Lkas_HbaOpt", "LKAS11"), - ("CF_Lkas_FcwSysState", "LKAS11"), - ("CF_Lkas_FcwCollisionWarning", "LKAS11"), - ("CF_Lkas_FusionState", "LKAS11"), - ("CF_Lkas_FcwOpt_USM", "LKAS11"), - ("CF_Lkas_LdwsOpt_USM", "LKAS11"), - ] - checks = [ + messages = [ ("LKAS11", 100) ] if not CP.openpilotLongitudinalControl and CP.carFingerprint in CAMERA_SCC_CAR: - signals += [ - ("MainMode_ACC", "SCC11"), - ("VSetDis", "SCC11"), - ("SCCInfoDisplay", "SCC11"), - ("ACC_ObjDist", "SCC11"), - ("ACCMode", "SCC12"), - ] - checks += [ + messages += [ ("SCC11", 50), ("SCC12", 50), ] if CP.flags & HyundaiFlags.USE_FCA.value: - signals += [ - ("FCA_CmdAct", "FCA11"), - ("CF_VSM_Warn", "FCA11"), - ("CF_VSM_DecCmdAct", "FCA11"), - ] - checks.append(("FCA11", 50)) - else: - signals += [ - ("AEB_CmdAct", "SCC12"), - ("CF_VSM_Warn", "SCC12"), - ("CF_VSM_DecCmdAct", "SCC12"), - ] + messages.append(("FCA11", 50)) - return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 2) + return CANParser(DBC[CP.carFingerprint]["pt"], messages, 2) - @staticmethod - def get_can_parser_canfd(CP): - - cruise_btn_msg = "CRUISE_BUTTONS_ALT" if CP.flags & HyundaiFlags.CANFD_ALT_BUTTONS else "CRUISE_BUTTONS" - gear_msg = "GEAR_ALT_2" if CP.flags & HyundaiFlags.CANFD_ALT_GEARS_2 else \ - "GEAR_ALT" if CP.flags & HyundaiFlags.CANFD_ALT_GEARS else \ - "GEAR_SHIFTER" - signals = [ - ("WHEEL_SPEED_1", "WHEEL_SPEEDS"), - ("WHEEL_SPEED_2", "WHEEL_SPEEDS"), - ("WHEEL_SPEED_3", "WHEEL_SPEEDS"), - ("WHEEL_SPEED_4", "WHEEL_SPEEDS"), - - ("GEAR", gear_msg), - - ("STEERING_RATE", "STEERING_SENSORS"), - ("STEERING_ANGLE", "STEERING_SENSORS"), - ("STEERING_COL_TORQUE", "MDPS"), - ("STEERING_OUT_TORQUE", "MDPS"), - ("LKA_FAULT", "MDPS"), - - ("DriverBraking", "TCS"), - ("ACCEnable", "TCS"), - ("ACC_REQ", "TCS"), - - ("COUNTER", cruise_btn_msg), - ("CRUISE_BUTTONS", cruise_btn_msg), - ("ADAPTIVE_CRUISE_MAIN_BTN", cruise_btn_msg), - ("DISTANCE_UNIT", "CRUISE_BUTTONS_ALT"), - - ("LEFT_LAMP", "BLINKERS"), - ("RIGHT_LAMP", "BLINKERS"), - - ("DRIVER_DOOR", "DOORS_SEATBELTS"), - ("DRIVER_SEATBELT", "DOORS_SEATBELTS"), - ] - - checks = [ + def get_can_parser_canfd(self, CP): + messages = [ + (self.gear_msg_canfd, 100), + (self.cruise_btns_msg_canfd, 50), + (self.accelerator_msg_canfd, 100), ("WHEEL_SPEEDS", 100), - (gear_msg, 100), ("STEERING_SENSORS", 100), ("MDPS", 100), ("TCS", 50), @@ -472,77 +314,26 @@ class CarState(CarStateBase): ("DOORS_SEATBELTS", 4), ] - if not (CP.flags & HyundaiFlags.CANFD_ALT_BUTTONS): - checks.append(("CRUISE_BUTTONS", 50)) - if CP.enableBsm: - signals += [ - ("FL_INDICATOR", "BLINDSPOTS_REAR_CORNERS"), - ("FR_INDICATOR", "BLINDSPOTS_REAR_CORNERS"), - ] - checks += [ + messages += [ ("BLINDSPOTS_REAR_CORNERS", 20), ] if not (CP.flags & HyundaiFlags.CANFD_CAMERA_SCC.value) and not CP.openpilotLongitudinalControl: - signals += [ - ("COUNTER", "SCC_CONTROL"), - ("CHECKSUM", "SCC_CONTROL"), - ("ACCMode", "SCC_CONTROL"), - ("VSetDis", "SCC_CONTROL"), - ("CRUISE_STANDSTILL", "SCC_CONTROL"), - ] - checks += [ + messages += [ ("SCC_CONTROL", 50), ] - if CP.carFingerprint in EV_CAR: - signals += [ - ("ACCELERATOR_PEDAL", "ACCELERATOR"), - ] - checks += [ - ("ACCELERATOR", 100), - ] - elif CP.carFingerprint in HYBRID_CAR: - signals += [ - ("ACCELERATOR_PEDAL", "ACCELERATOR_ALT"), - ] - checks += [ - ("ACCELERATOR_ALT", 100), - ] - else: - signals += [ - ("ACCELERATOR_PEDAL_PRESSED", "ACCELERATOR_BRAKE_ALT"), - ] - checks += [ - ("ACCELERATOR_BRAKE_ALT", 100), - ] - - return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, CanBus(CP).ECAN) + return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus(CP).ECAN) @staticmethod def get_cam_can_parser_canfd(CP): - signals = [] - checks = [] + messages = [] if CP.flags & HyundaiFlags.CANFD_HDA2: - signals += [(f"BYTE{i}", "CAM_0x2a4") for i in range(3, 24)] - checks += [("CAM_0x2a4", 20)] + messages += [("CAM_0x2a4", 20)] elif CP.flags & HyundaiFlags.CANFD_CAMERA_SCC: - signals += [ - ("COUNTER", "SCC_CONTROL"), - ("CHECKSUM", "SCC_CONTROL"), - ("NEW_SIGNAL_1", "SCC_CONTROL"), - ("MainMode_ACC", "SCC_CONTROL"), - ("ACCMode", "SCC_CONTROL"), - ("ZEROS_9", "SCC_CONTROL"), - ("CRUISE_STANDSTILL", "SCC_CONTROL"), - ("ZEROS_5", "SCC_CONTROL"), - ("DISTANCE_SETTING", "SCC_CONTROL"), - ("VSetDis", "SCC_CONTROL"), - ] - - checks += [ + messages += [ ("SCC_CONTROL", 50), ] - return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, CanBus(CP).CAM) + return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus(CP).CAM) diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 46f86fdc1..bd4f34dd4 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -6,7 +6,7 @@ from selfdrive.car.hyundai.hyundaicanfd import CanBus from selfdrive.car.hyundai.values import HyundaiFlags, CAR, DBC, CANFD_CAR, CAMERA_SCC_CAR, CANFD_RADAR_SCC_CAR, \ EV_CAR, HYBRID_CAR, LEGACY_SAFETY_MODE_CAR, Buttons from selfdrive.car.hyundai.radar_interface import RADAR_START_ADDR -from selfdrive.car import STD_CARGO_KG, create_button_event, scale_tire_stiffness, get_safety_config +from selfdrive.car import STD_CARGO_KG, create_button_event, get_safety_config from selfdrive.car.interfaces import CarInterfaceBase from selfdrive.car.disable_ecu import disable_ecu @@ -59,7 +59,6 @@ class CarInterface(CarInterfaceBase): ret.steerActuatorDelay = 0.1 # Default delay ret.steerLimitTimer = 0.4 - tire_stiffness_factor = 1. CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) if candidate in (CAR.SANTA_FE, CAR.SANTA_FE_2022, CAR.SANTA_FE_HEV_2022, CAR.SANTA_FE_PHEV_2022): @@ -67,12 +66,12 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.766 # Values from optimizer ret.steerRatio = 16.55 # 13.8 is spec end-to-end - tire_stiffness_factor = 0.82 + ret.tireStiffnessFactor = 0.82 elif candidate in (CAR.SONATA, CAR.SONATA_HYBRID): ret.mass = 1513. + STD_CARGO_KG ret.wheelbase = 2.84 ret.steerRatio = 13.27 * 1.15 # 15% higher at the center seems reasonable - tire_stiffness_factor = 0.65 + ret.tireStiffnessFactor = 0.65 elif candidate == CAR.SONATA_LF: ret.mass = 4497. * CV.LB_TO_KG ret.wheelbase = 2.804 @@ -81,23 +80,23 @@ class CarInterface(CarInterfaceBase): ret.mass = 1999. + STD_CARGO_KG ret.wheelbase = 2.90 ret.steerRatio = 15.6 * 1.15 - tire_stiffness_factor = 0.63 + ret.tireStiffnessFactor = 0.63 elif candidate == CAR.ELANTRA: ret.mass = 1275. + STD_CARGO_KG ret.wheelbase = 2.7 ret.steerRatio = 15.4 # 14 is Stock | Settled Params Learner values are steerRatio: 15.401566348670535 - tire_stiffness_factor = 0.385 # stiffnessFactor settled on 1.0081302973865127 + ret.tireStiffnessFactor = 0.385 # stiffnessFactor settled on 1.0081302973865127 ret.minSteerSpeed = 32 * CV.MPH_TO_MS elif candidate == CAR.ELANTRA_2021: ret.mass = (2800. * CV.LB_TO_KG) + STD_CARGO_KG ret.wheelbase = 2.72 ret.steerRatio = 12.9 - tire_stiffness_factor = 0.65 + ret.tireStiffnessFactor = 0.65 elif candidate == CAR.ELANTRA_HEV_2021: ret.mass = (3017. * CV.LB_TO_KG) + STD_CARGO_KG ret.wheelbase = 2.72 ret.steerRatio = 12.9 - tire_stiffness_factor = 0.65 + ret.tireStiffnessFactor = 0.65 elif candidate == CAR.HYUNDAI_GENESIS: ret.mass = 2060. + STD_CARGO_KG ret.wheelbase = 3.01 @@ -107,29 +106,29 @@ class CarInterface(CarInterfaceBase): ret.mass = {CAR.KONA_EV: 1685., CAR.KONA_HEV: 1425., CAR.KONA_EV_2022: 1743.}.get(candidate, 1275.) + STD_CARGO_KG ret.wheelbase = 2.6 ret.steerRatio = 13.42 # Spec - tire_stiffness_factor = 0.385 + ret.tireStiffnessFactor = 0.385 elif candidate in (CAR.IONIQ, CAR.IONIQ_EV_LTD, CAR.IONIQ_PHEV_2019, CAR.IONIQ_HEV_2022, CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV): ret.mass = 1490. + STD_CARGO_KG # weight per hyundai site https://www.hyundaiusa.com/ioniq-electric/specifications.aspx ret.wheelbase = 2.7 ret.steerRatio = 13.73 # Spec - tire_stiffness_factor = 0.385 + ret.tireStiffnessFactor = 0.385 if candidate in (CAR.IONIQ, CAR.IONIQ_EV_LTD, CAR.IONIQ_PHEV_2019): ret.minSteerSpeed = 32 * CV.MPH_TO_MS elif candidate == CAR.VELOSTER: ret.mass = 3558. * CV.LB_TO_KG ret.wheelbase = 2.80 ret.steerRatio = 13.75 * 1.15 - tire_stiffness_factor = 0.5 + ret.tireStiffnessFactor = 0.5 elif candidate == CAR.TUCSON: ret.mass = 3520. * CV.LB_TO_KG ret.wheelbase = 2.67 ret.steerRatio = 14.00 * 1.15 - tire_stiffness_factor = 0.385 + ret.tireStiffnessFactor = 0.385 elif candidate in (CAR.TUCSON_4TH_GEN, CAR.TUCSON_HYBRID_4TH_GEN): ret.mass = 1630. + STD_CARGO_KG # average ret.wheelbase = 2.756 ret.steerRatio = 16. - tire_stiffness_factor = 0.385 + ret.tireStiffnessFactor = 0.385 elif candidate == CAR.SANTA_CRUZ_1ST_GEN: ret.mass = 1870. + STD_CARGO_KG # weight from Limited trim - the only supported trim ret.wheelbase = 3.000 @@ -145,14 +144,13 @@ class CarInterface(CarInterfaceBase): ret.mass = 3543. * CV.LB_TO_KG + STD_CARGO_KG # average of all the cars ret.wheelbase = 2.7 ret.steerRatio = 13.6 # average of all the cars - tire_stiffness_factor = 0.385 + ret.tireStiffnessFactor = 0.385 if candidate == CAR.KIA_NIRO_PHEV: ret.minSteerSpeed = 32 * CV.MPH_TO_MS elif candidate == CAR.KIA_SELTOS: ret.mass = 1337. + STD_CARGO_KG ret.wheelbase = 2.63 ret.steerRatio = 14.56 - tire_stiffness_factor = 1 elif candidate == CAR.KIA_SPORTAGE_5TH_GEN: ret.mass = 1700. + STD_CARGO_KG # weight from SX and above trims, average of FWD and AWD versions ret.wheelbase = 2.756 @@ -161,7 +159,7 @@ class CarInterface(CarInterfaceBase): ret.mass = 3558. * CV.LB_TO_KG ret.wheelbase = 2.80 ret.steerRatio = 13.75 - tire_stiffness_factor = 0.5 + ret.tireStiffnessFactor = 0.5 if candidate == CAR.KIA_OPTIMA_G4: ret.minSteerSpeed = 32 * CV.MPH_TO_MS elif candidate in (CAR.KIA_STINGER, CAR.KIA_STINGER_2022): @@ -172,27 +170,27 @@ class CarInterface(CarInterfaceBase): ret.mass = 3558. * CV.LB_TO_KG ret.wheelbase = 2.80 ret.steerRatio = 13.75 - tire_stiffness_factor = 0.5 + ret.tireStiffnessFactor = 0.5 elif candidate == CAR.KIA_CEED: ret.mass = 1450. + STD_CARGO_KG ret.wheelbase = 2.65 ret.steerRatio = 13.75 - tire_stiffness_factor = 0.5 + ret.tireStiffnessFactor = 0.5 elif candidate in (CAR.KIA_K5_2021, CAR.KIA_K5_HEV_2020): ret.mass = 3228. * CV.LB_TO_KG ret.wheelbase = 2.85 ret.steerRatio = 13.27 # 2021 Kia K5 Steering Ratio (all trims) - tire_stiffness_factor = 0.5 + ret.tireStiffnessFactor = 0.5 elif candidate == CAR.KIA_EV6: ret.mass = 2055 + STD_CARGO_KG ret.wheelbase = 2.9 ret.steerRatio = 16. - tire_stiffness_factor = 0.65 + ret.tireStiffnessFactor = 0.65 elif candidate in (CAR.IONIQ_5, CAR.IONIQ_6): ret.mass = 1948 + STD_CARGO_KG ret.wheelbase = 2.97 ret.steerRatio = 14.26 - tire_stiffness_factor = 0.65 + ret.tireStiffnessFactor = 0.65 elif candidate == CAR.KIA_SPORTAGE_HYBRID_5TH_GEN: ret.mass = 1767. + STD_CARGO_KG # SX Prestige trim support only ret.wheelbase = 2.756 @@ -302,10 +300,6 @@ class CarInterface(CarInterfaceBase): ret.centerToFront = ret.wheelbase * 0.4 - # TODO: start from empirically derived lateral slip stiffness for the civic and scale by - # mass and CG position, so all cars will have approximately similar dyn behaviors - ret.tireStiffnessFront, ret.tireStiffnessRear = scale_tire_stiffness(ret.mass, ret.wheelbase, ret.centerToFront, - tire_stiffness_factor=tire_stiffness_factor) return ret @staticmethod diff --git a/selfdrive/car/hyundai/radar_interface.py b/selfdrive/car/hyundai/radar_interface.py index 4ecca542b..7301ad18c 100644 --- a/selfdrive/car/hyundai/radar_interface.py +++ b/selfdrive/car/hyundai/radar_interface.py @@ -14,20 +14,8 @@ def get_radar_can_parser(CP): if DBC[CP.carFingerprint]['radar'] is None: return None - signals = [] - checks = [] - - for addr in range(RADAR_START_ADDR, RADAR_START_ADDR + RADAR_MSG_COUNT): - msg = f"RADAR_TRACK_{addr:x}" - signals += [ - ("STATE", msg), - ("AZIMUTH", msg), - ("LONG_DIST", msg), - ("REL_ACCEL", msg), - ("REL_SPEED", msg), - ] - checks += [(msg, 50)] - return CANParser(DBC[CP.carFingerprint]['radar'], signals, checks, 1) + messages = [(f"RADAR_TRACK_{addr:x}", 50) for addr in range(RADAR_START_ADDR, RADAR_START_ADDR + RADAR_MSG_COUNT)] + return CANParser(DBC[CP.carFingerprint]['radar'], messages, 1) class RadarInterface(RadarInterfaceBase): @@ -42,7 +30,7 @@ class RadarInterface(RadarInterfaceBase): def update(self, can_strings): if self.radar_off_can or (self.rcp is None): - return super().update(None) + return None vls = self.rcp.update_strings(can_strings) self.updated_messages.update(vls) diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index fc0f8c492..a31dcc0cb 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -1785,6 +1785,7 @@ FW_VERSIONS = { b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.01 99211-GI010 211007', b'\xf1\x00NE1 MFC AT EUR RHD 1.00 1.02 99211-GI010 211206', b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.03 99211-GI010 220401', + b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.06 99211-GI010 230110', ], }, CAR.IONIQ_6: { diff --git a/selfdrive/car/interfaces.py b/selfdrive/car/interfaces.py index 99df4cf4b..a7173018c 100644 --- a/selfdrive/car/interfaces.py +++ b/selfdrive/car/interfaces.py @@ -1,6 +1,5 @@ import yaml import os -import time from abc import abstractmethod, ABC from typing import Any, Dict, Optional, Tuple, List, Callable @@ -100,16 +99,9 @@ class CarInterfaceBase(ABC): ret = CarInterfaceBase.get_std_params(candidate) ret = cls._get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs) - # Set common params using fields set by the car interface - # TODO: get actual value, for now starting with reasonable value for - # civic and scaling by mass and wheelbase + # Set params dependent on values set by the car interface ret.rotationalInertia = scale_rot_inertia(ret.mass, ret.wheelbase) - - # TODO: some car interfaces set stiffness factor - if ret.tireStiffnessFront == 0 or ret.tireStiffnessRear == 0: - # TODO: start from empirically derived lateral slip stiffness for the civic and scale by - # mass and CG position, so all cars will have approximately similar dyn behaviors - ret.tireStiffnessFront, ret.tireStiffnessRear = scale_tire_stiffness(ret.mass, ret.wheelbase, ret.centerToFront) + ret.tireStiffnessFront, ret.tireStiffnessRear = scale_tire_stiffness(ret.mass, ret.wheelbase, ret.centerToFront, ret.tireStiffnessFactor) return ret @@ -152,6 +144,7 @@ class CarInterfaceBase(ABC): ret.autoResumeSng = True # describes whether car can resume from a stop automatically # standard ALC params + ret.tireStiffnessFactor = 1.0 ret.steerControlType = car.CarParams.SteerControlType.torque ret.minSteerSpeed = 0. ret.wheelSpeedFactor = 1.0 @@ -312,14 +305,9 @@ class RadarInterfaceBase(ABC): self.rcp = None self.pts = {} self.delay = 0 - self.radar_ts = CP.radarTimeStep - self.no_radar_sleep = 'NO_RADAR_SLEEP' in os.environ def update(self, can_strings): - ret = car.RadarData.new_message() - if not self.no_radar_sleep: - time.sleep(self.radar_ts) # radard runs on RI updates - return ret + pass class CarStateBase(ABC): diff --git a/selfdrive/car/mazda/carstate.py b/selfdrive/car/mazda/carstate.py index af8830895..d782e59de 100644 --- a/selfdrive/car/mazda/carstate.py +++ b/selfdrive/car/mazda/carstate.py @@ -107,22 +107,7 @@ class CarState(CarStateBase): @staticmethod def get_can_parser(CP): - signals = [ - # sig_name, sig_address - ("LEFT_BLINK", "BLINK_INFO"), - ("RIGHT_BLINK", "BLINK_INFO"), - ("HIGH_BEAMS", "BLINK_INFO"), - ("STEER_ANGLE", "STEER"), - ("STEER_ANGLE_RATE", "STEER_RATE"), - ("STEER_TORQUE_SENSOR", "STEER_TORQUE"), - ("STEER_TORQUE_MOTOR", "STEER_TORQUE"), - ("FL", "WHEEL_SPEEDS"), - ("FR", "WHEEL_SPEEDS"), - ("RL", "WHEEL_SPEEDS"), - ("RR", "WHEEL_SPEEDS"), - ] - - checks = [ + messages = [ # sig_address, frequency ("BLINK_INFO", 10), ("STEER", 67), @@ -132,30 +117,7 @@ class CarState(CarStateBase): ] if CP.carFingerprint in GEN1: - signals += [ - ("LKAS_BLOCK", "STEER_RATE"), - ("LKAS_TRACK_STATE", "STEER_RATE"), - ("HANDS_OFF_5_SECONDS", "STEER_RATE"), - ("CRZ_ACTIVE", "CRZ_CTRL"), - ("CRZ_AVAILABLE", "CRZ_CTRL"), - ("CRZ_SPEED", "CRZ_EVENTS"), - ("STANDSTILL", "PEDALS"), - ("BRAKE_ON", "PEDALS"), - ("BRAKE_PRESSURE", "BRAKE"), - ("GEAR", "GEAR"), - ("DRIVER_SEATBELT", "SEATBELT"), - ("FL", "DOORS"), - ("FR", "DOORS"), - ("BL", "DOORS"), - ("BR", "DOORS"), - ("PEDAL_GAS", "ENGINE_DATA"), - ("SPEED", "ENGINE_DATA"), - ("CTR", "CRZ_BTNS"), - ("LEFT_BS_STATUS", "BSM"), - ("RIGHT_BS_STATUS", "BSM"), - ] - - checks += [ + messages += [ ("ENGINE_DATA", 100), ("CRZ_CTRL", 50), ("CRZ_EVENTS", 50), @@ -168,41 +130,17 @@ class CarState(CarStateBase): ("BSM", 10), ] - return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 0) + return CANParser(DBC[CP.carFingerprint]["pt"], messages, 0) @staticmethod def get_cam_can_parser(CP): - signals = [] - checks = [] + messages = [] if CP.carFingerprint in GEN1: - signals += [ - # sig_name, sig_address - ("LKAS_REQUEST", "CAM_LKAS"), - ("CTR", "CAM_LKAS"), - ("ERR_BIT_1", "CAM_LKAS"), - ("LINE_NOT_VISIBLE", "CAM_LKAS"), - ("BIT_1", "CAM_LKAS"), - ("ERR_BIT_2", "CAM_LKAS"), - ("STEERING_ANGLE", "CAM_LKAS"), - ("ANGLE_ENABLED", "CAM_LKAS"), - ("CHKSUM", "CAM_LKAS"), - - ("LINE_VISIBLE", "CAM_LANEINFO"), - ("LINE_NOT_VISIBLE", "CAM_LANEINFO"), - ("LANE_LINES", "CAM_LANEINFO"), - ("BIT1", "CAM_LANEINFO"), - ("BIT2", "CAM_LANEINFO"), - ("BIT3", "CAM_LANEINFO"), - ("NO_ERR_BIT", "CAM_LANEINFO"), - ("S1", "CAM_LANEINFO"), - ("S1_HBEAM", "CAM_LANEINFO"), - ] - - checks += [ + messages += [ # sig_address, frequency ("CAM_LANEINFO", 2), ("CAM_LKAS", 16), ] - return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 2) + return CANParser(DBC[CP.carFingerprint]["pt"], messages, 2) diff --git a/selfdrive/car/mazda/interface.py b/selfdrive/car/mazda/interface.py index 443116bc1..1286b2aa3 100755 --- a/selfdrive/car/mazda/interface.py +++ b/selfdrive/car/mazda/interface.py @@ -2,7 +2,7 @@ from cereal import car from common.conversions import Conversions as CV from selfdrive.car.mazda.values import CAR, LKAS_LIMITS -from selfdrive.car import STD_CARGO_KG, scale_tire_stiffness, get_safety_config +from selfdrive.car import STD_CARGO_KG, get_safety_config from selfdrive.car.interfaces import CarInterfaceBase ButtonType = car.CarState.ButtonEvent.Type @@ -20,7 +20,7 @@ class CarInterface(CarInterfaceBase): ret.steerActuatorDelay = 0.1 ret.steerLimitTimer = 0.8 - tire_stiffness_factor = 0.70 # not optimized yet + ret.tireStiffnessFactor = 0.70 # not optimized yet CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) @@ -46,11 +46,6 @@ class CarInterface(CarInterfaceBase): ret.centerToFront = ret.wheelbase * 0.41 - # TODO: start from empirically derived lateral slip stiffness for the civic and scale by - # mass and CG position, so all cars will have approximately similar dyn behaviors - ret.tireStiffnessFront, ret.tireStiffnessRear = scale_tire_stiffness(ret.mass, ret.wheelbase, ret.centerToFront, - tire_stiffness_factor=tire_stiffness_factor) - return ret # returns a car.CarState diff --git a/selfdrive/car/mock/interface.py b/selfdrive/car/mock/interface.py index 1c74aef1f..7986adb8f 100755 --- a/selfdrive/car/mock/interface.py +++ b/selfdrive/car/mock/interface.py @@ -26,8 +26,6 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.70 ret.centerToFront = ret.wheelbase * 0.5 ret.steerRatio = 13. # reasonable - ret.tireStiffnessFront = 1e6 # very stiff to neglect slip - ret.tireStiffnessRear = 1e6 # very stiff to neglect slip return ret diff --git a/selfdrive/car/nissan/carstate.py b/selfdrive/car/nissan/carstate.py index 7fbc80766..f17e2d8dc 100644 --- a/selfdrive/car/nissan/carstate.py +++ b/selfdrive/car/nissan/carstate.py @@ -119,29 +119,7 @@ class CarState(CarStateBase): @staticmethod def get_can_parser(CP): - signals = [ - # sig_name, sig_address - ("WHEEL_SPEED_FL", "WHEEL_SPEEDS_FRONT"), - ("WHEEL_SPEED_FR", "WHEEL_SPEEDS_FRONT"), - ("WHEEL_SPEED_RL", "WHEEL_SPEEDS_REAR"), - ("WHEEL_SPEED_RR", "WHEEL_SPEEDS_REAR"), - - ("STEER_ANGLE", "STEER_ANGLE_SENSOR"), - - ("DOOR_OPEN_FR", "DOORS_LIGHTS"), - ("DOOR_OPEN_FL", "DOORS_LIGHTS"), - ("DOOR_OPEN_RR", "DOORS_LIGHTS"), - ("DOOR_OPEN_RL", "DOORS_LIGHTS"), - - ("RIGHT_BLINKER", "LIGHTS"), - ("LEFT_BLINKER", "LIGHTS"), - - ("ESP_DISABLED", "ESP"), - - ("GEAR_SHIFTER", "GEARBOX"), - ] - - checks = [ + messages = [ # sig_address, frequency ("STEER_ANGLE_SENSOR", 100), ("WHEEL_SPEEDS_REAR", 50), @@ -153,51 +131,14 @@ class CarState(CarStateBase): ] if CP.carFingerprint in (CAR.ROGUE, CAR.XTRAIL, CAR.ALTIMA): - signals += [ - ("USER_BRAKE_PRESSED", "DOORS_LIGHTS"), - - ("GAS_PEDAL", "GAS_PEDAL"), - ("SEATBELT_DRIVER_LATCHED", "HUD"), - ("SPEED_MPH", "HUD"), - - ("PROPILOT_BUTTON", "CRUISE_THROTTLE"), - ("CANCEL_BUTTON", "CRUISE_THROTTLE"), - ("GAS_PEDAL_INVERTED", "CRUISE_THROTTLE"), - ("SET_BUTTON", "CRUISE_THROTTLE"), - ("RES_BUTTON", "CRUISE_THROTTLE"), - ("FOLLOW_DISTANCE_BUTTON", "CRUISE_THROTTLE"), - ("NO_BUTTON_PRESSED", "CRUISE_THROTTLE"), - ("GAS_PEDAL", "CRUISE_THROTTLE"), - ("USER_BRAKE_PRESSED", "CRUISE_THROTTLE"), - ("NEW_SIGNAL_2", "CRUISE_THROTTLE"), - ("GAS_PRESSED_INVERTED", "CRUISE_THROTTLE"), - ("COUNTER", "CRUISE_THROTTLE"), - ("unsure1", "CRUISE_THROTTLE"), - ("unsure2", "CRUISE_THROTTLE"), - ("unsure3", "CRUISE_THROTTLE"), - ] - - checks += [ + messages += [ ("GAS_PEDAL", 100), ("CRUISE_THROTTLE", 50), ("HUD", 25), ] elif CP.carFingerprint in (CAR.LEAF, CAR.LEAF_IC): - signals += [ - ("USER_BRAKE_PRESSED", "CRUISE_THROTTLE"), - ("GAS_PEDAL", "CRUISE_THROTTLE"), - ("CRUISE_AVAILABLE", "CRUISE_THROTTLE"), - ("SPEED_MPH", "HUD_SETTINGS"), - ("SEATBELT_DRIVER_LATCHED", "SEATBELT"), - - # Copy other values, we use this to cancel - ("CANCEL_SEATBELT", "CANCEL_MSG"), - ("NEW_SIGNAL_1", "CANCEL_MSG"), - ("NEW_SIGNAL_2", "CANCEL_MSG"), - ("NEW_SIGNAL_3", "CANCEL_MSG"), - ] - checks += [ + messages += [ ("BRAKE_PEDAL", 100), ("CRUISE_THROTTLE", 50), ("CANCEL_MSG", 50), @@ -206,126 +147,28 @@ class CarState(CarStateBase): ] if CP.carFingerprint == CAR.ALTIMA: - signals += [ - ("LKAS_ENABLED", "LKAS_SETTINGS"), - ("CRUISE_ENABLED", "CRUISE_STATE"), - ("SET_SPEED", "PROPILOT_HUD"), - ] - checks += [ + messages += [ ("CRUISE_STATE", 10), ("LKAS_SETTINGS", 10), ("PROPILOT_HUD", 50), ] - return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 1) + return CANParser(DBC[CP.carFingerprint]["pt"], messages, 1) - signals.append(("STEER_TORQUE_DRIVER", "STEER_TORQUE_SENSOR")) - checks.append(("STEER_TORQUE_SENSOR", 100)) + messages.append(("STEER_TORQUE_SENSOR", 100)) - return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 0) + return CANParser(DBC[CP.carFingerprint]["pt"], messages, 0) @staticmethod def get_adas_can_parser(CP): # this function generates lists for signal, messages and initial values if CP.carFingerprint == CAR.ALTIMA: - signals = [ - ("DESIRED_ANGLE", "LKAS"), - ("SET_0x80_2", "LKAS"), - ("MAX_TORQUE", "LKAS"), - ("SET_0x80", "LKAS"), - ("COUNTER", "LKAS"), - ("LKA_ACTIVE", "LKAS"), - - ("CRUISE_ON", "PRO_PILOT"), - ] - checks = [ + messages = [ ("LKAS", 100), ("PRO_PILOT", 100), ] else: - signals = [ - # sig_name, sig_address - ("LKAS_ENABLED", "LKAS_SETTINGS"), - - ("CRUISE_ENABLED", "CRUISE_STATE"), - - ("DESIRED_ANGLE", "LKAS"), - ("SET_0x80_2", "LKAS"), - ("MAX_TORQUE", "LKAS"), - ("SET_0x80", "LKAS"), - ("COUNTER", "LKAS"), - ("LKA_ACTIVE", "LKAS"), - - # Below are the HUD messages. We copy the stock message and modify - ("LARGE_WARNING_FLASHING", "PROPILOT_HUD"), - ("SIDE_RADAR_ERROR_FLASHING1", "PROPILOT_HUD"), - ("SIDE_RADAR_ERROR_FLASHING2", "PROPILOT_HUD"), - ("LEAD_CAR", "PROPILOT_HUD"), - ("LEAD_CAR_ERROR", "PROPILOT_HUD"), - ("FRONT_RADAR_ERROR", "PROPILOT_HUD"), - ("FRONT_RADAR_ERROR_FLASHING", "PROPILOT_HUD"), - ("SIDE_RADAR_ERROR_FLASHING3", "PROPILOT_HUD"), - ("LKAS_ERROR_FLASHING", "PROPILOT_HUD"), - ("SAFETY_SHIELD_ACTIVE", "PROPILOT_HUD"), - ("RIGHT_LANE_GREEN_FLASH", "PROPILOT_HUD"), - ("LEFT_LANE_GREEN_FLASH", "PROPILOT_HUD"), - ("FOLLOW_DISTANCE", "PROPILOT_HUD"), - ("AUDIBLE_TONE", "PROPILOT_HUD"), - ("SPEED_SET_ICON", "PROPILOT_HUD"), - ("SMALL_STEERING_WHEEL_ICON", "PROPILOT_HUD"), - ("unknown59", "PROPILOT_HUD"), - ("unknown55", "PROPILOT_HUD"), - ("unknown26", "PROPILOT_HUD"), - ("unknown28", "PROPILOT_HUD"), - ("unknown31", "PROPILOT_HUD"), - ("SET_SPEED", "PROPILOT_HUD"), - ("unknown43", "PROPILOT_HUD"), - ("unknown08", "PROPILOT_HUD"), - ("unknown05", "PROPILOT_HUD"), - ("unknown02", "PROPILOT_HUD"), - - ("NA_HIGH_ACCEL_TEMP", "PROPILOT_HUD_INFO_MSG"), - ("SIDE_RADAR_NA_HIGH_CABIN_TEMP", "PROPILOT_HUD_INFO_MSG"), - ("SIDE_RADAR_MALFUNCTION", "PROPILOT_HUD_INFO_MSG"), - ("LKAS_MALFUNCTION", "PROPILOT_HUD_INFO_MSG"), - ("FRONT_RADAR_MALFUNCTION", "PROPILOT_HUD_INFO_MSG"), - ("SIDE_RADAR_NA_CLEAN_REAR_CAMERA", "PROPILOT_HUD_INFO_MSG"), - ("NA_POOR_ROAD_CONDITIONS", "PROPILOT_HUD_INFO_MSG"), - ("CURRENTLY_UNAVAILABLE", "PROPILOT_HUD_INFO_MSG"), - ("SAFETY_SHIELD_OFF", "PROPILOT_HUD_INFO_MSG"), - ("FRONT_COLLISION_NA_FRONT_RADAR_OBSTRUCTION", "PROPILOT_HUD_INFO_MSG"), - ("PEDAL_MISSAPPLICATION_SYSTEM_ACTIVATED", "PROPILOT_HUD_INFO_MSG"), - ("SIDE_IMPACT_NA_RADAR_OBSTRUCTION", "PROPILOT_HUD_INFO_MSG"), - ("WARNING_DO_NOT_ENTER", "PROPILOT_HUD_INFO_MSG"), - ("SIDE_IMPACT_SYSTEM_OFF", "PROPILOT_HUD_INFO_MSG"), - ("SIDE_IMPACT_MALFUNCTION", "PROPILOT_HUD_INFO_MSG"), - ("FRONT_COLLISION_MALFUNCTION", "PROPILOT_HUD_INFO_MSG"), - ("SIDE_RADAR_MALFUNCTION2", "PROPILOT_HUD_INFO_MSG"), - ("LKAS_MALFUNCTION2", "PROPILOT_HUD_INFO_MSG"), - ("FRONT_RADAR_MALFUNCTION2", "PROPILOT_HUD_INFO_MSG"), - ("PROPILOT_NA_MSGS", "PROPILOT_HUD_INFO_MSG"), - ("BOTTOM_MSG", "PROPILOT_HUD_INFO_MSG"), - ("HANDS_ON_WHEEL_WARNING", "PROPILOT_HUD_INFO_MSG"), - ("WARNING_STEP_ON_BRAKE_NOW", "PROPILOT_HUD_INFO_MSG"), - ("PROPILOT_NA_FRONT_CAMERA_OBSTRUCTED", "PROPILOT_HUD_INFO_MSG"), - ("PROPILOT_NA_HIGH_CABIN_TEMP", "PROPILOT_HUD_INFO_MSG"), - ("WARNING_PROPILOT_MALFUNCTION", "PROPILOT_HUD_INFO_MSG"), - ("ACC_UNAVAILABLE_HIGH_CABIN_TEMP", "PROPILOT_HUD_INFO_MSG"), - ("ACC_NA_FRONT_CAMERA_IMPARED", "PROPILOT_HUD_INFO_MSG"), - ("unknown07", "PROPILOT_HUD_INFO_MSG"), - ("unknown10", "PROPILOT_HUD_INFO_MSG"), - ("unknown15", "PROPILOT_HUD_INFO_MSG"), - ("unknown23", "PROPILOT_HUD_INFO_MSG"), - ("unknown19", "PROPILOT_HUD_INFO_MSG"), - ("unknown31", "PROPILOT_HUD_INFO_MSG"), - ("unknown32", "PROPILOT_HUD_INFO_MSG"), - ("unknown46", "PROPILOT_HUD_INFO_MSG"), - ("unknown61", "PROPILOT_HUD_INFO_MSG"), - ("unknown55", "PROPILOT_HUD_INFO_MSG"), - ("unknown50", "PROPILOT_HUD_INFO_MSG"), - ] - - checks = [ + messages = [ ("PROPILOT_HUD_INFO_MSG", 2), ("LKAS_SETTINGS", 10), ("CRUISE_STATE", 50), @@ -333,19 +176,16 @@ class CarState(CarStateBase): ("LKAS", 100), ] - return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 2) + return CANParser(DBC[CP.carFingerprint]["pt"], messages, 2) @staticmethod def get_cam_can_parser(CP): - signals = [] - checks = [] + messages = [] if CP.carFingerprint in (CAR.ROGUE, CAR.XTRAIL): - signals.append(("CRUISE_ON", "PRO_PILOT")) - checks.append(("PRO_PILOT", 100)) + messages.append(("PRO_PILOT", 100)) elif CP.carFingerprint == CAR.ALTIMA: - signals.append(("STEER_TORQUE_DRIVER", "STEER_TORQUE_SENSOR")) - checks.append(("STEER_TORQUE_SENSOR", 100)) - return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 0) + messages.append(("STEER_TORQUE_SENSOR", 100)) + return CANParser(DBC[CP.carFingerprint]["pt"], messages, 0) - return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 1) + return CANParser(DBC[CP.carFingerprint]["pt"], messages, 1) diff --git a/selfdrive/car/subaru/carstate.py b/selfdrive/car/subaru/carstate.py index 189c244ca..6e0bef206 100644 --- a/selfdrive/car/subaru/carstate.py +++ b/selfdrive/car/subaru/carstate.py @@ -5,6 +5,7 @@ from common.conversions import Conversions as CV from selfdrive.car.interfaces import CarStateBase from opendbc.can.parser import CANParser from selfdrive.car.subaru.values import DBC, CAR, GLOBAL_GEN2, PREGLOBAL_CARS, CanBus, SubaruFlags +from selfdrive.car import CanSignalRateCalculator class CarState(CarStateBase): @@ -13,6 +14,8 @@ class CarState(CarStateBase): can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) self.shifter_values = can_define.dv["Transmission"]["Gear"] + self.angle_rate_calulator = CanSignalRateCalculator(50) + def update(self, cp, cp_cam, cp_body): ret = car.CarState.new_message() @@ -47,6 +50,11 @@ class CarState(CarStateBase): ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(can_gear, None)) ret.steeringAngleDeg = cp.vl["Steering_Torque"]["Steering_Angle"] + + if self.car_fingerprint not in PREGLOBAL_CARS: + # ideally we get this from the car, but unclear if it exists. diagnostic software doesn't even have it + ret.steeringRateDeg = self.angle_rate_calulator.update(ret.steeringAngleDeg, cp.vl["Steering_Torque"]["COUNTER"]) + ret.steeringTorque = cp.vl["Steering_Torque"]["Steer_Torque_Sensor"] ret.steeringTorqueEps = cp.vl["Steering_Torque"]["Steer_Torque_Output"] @@ -92,79 +100,27 @@ class CarState(CarStateBase): return ret @staticmethod - def get_common_global_body_signals(): - signals = [ - ("Cruise_On", "CruiseControl"), - ("Cruise_Activated", "CruiseControl"), - ("FL", "Wheel_Speeds"), - ("FR", "Wheel_Speeds"), - ("RL", "Wheel_Speeds"), - ("RR", "Wheel_Speeds"), - ("Brake", "Brake_Status"), - ] - checks = [ + def get_common_global_body_messages(): + messages = [ ("CruiseControl", 20), ("Wheel_Speeds", 50), ("Brake_Status", 50), ] - return signals, checks + return messages @staticmethod - def get_common_global_es_signals(): - signals = [ - ("AEB_Status", "ES_Brake"), - ("Brake_Pressure", "ES_Brake"), - ("COUNTER", "ES_Distance"), - ("CHECKSUM", "ES_Distance"), - ("Signal1", "ES_Distance"), - ("Cruise_Fault", "ES_Distance"), - ("Cruise_Throttle", "ES_Distance"), - ("Signal2", "ES_Distance"), - ("Car_Follow", "ES_Distance"), - ("Signal3", "ES_Distance"), - ("Cruise_Soft_Disable", "ES_Distance"), - ("Signal7", "ES_Distance"), - ("Cruise_Brake_Active", "ES_Distance"), - ("Distance_Swap", "ES_Distance"), - ("Cruise_EPB", "ES_Distance"), - ("Signal4", "ES_Distance"), - ("Close_Distance", "ES_Distance"), - ("Signal5", "ES_Distance"), - ("Cruise_Cancel", "ES_Distance"), - ("Cruise_Set", "ES_Distance"), - ("Cruise_Resume", "ES_Distance"), - ("Signal6", "ES_Distance"), - ] - - checks = [ + def get_common_global_es_messages(): + messages = [ ("ES_Brake", 20), ("ES_Distance", 20), ] - return signals, checks + return messages @staticmethod def get_can_parser(CP): - signals = [ - # sig_name, sig_address - ("Steer_Torque_Sensor", "Steering_Torque"), - ("Steer_Torque_Output", "Steering_Torque"), - ("Steering_Angle", "Steering_Torque"), - ("Steer_Error_1", "Steering_Torque"), - ("Brake_Pedal", "Brake_Pedal"), - ("Throttle_Pedal", "Throttle"), - ("LEFT_BLINKER", "Dashlights"), - ("RIGHT_BLINKER", "Dashlights"), - ("SEATBELT_FL", "Dashlights"), - ("DOOR_OPEN_FR", "BodyInfo"), - ("DOOR_OPEN_FL", "BodyInfo"), - ("DOOR_OPEN_RR", "BodyInfo"), - ("DOOR_OPEN_RL", "BodyInfo"), - ("Gear", "Transmission"), - ] - - checks = [ + messages = [ # sig_address, frequency ("Throttle", 100), ("Dashlights", 10), @@ -175,164 +131,63 @@ class CarState(CarStateBase): ] if CP.enableBsm: - signals += [ - ("L_ADJACENT", "BSD_RCTA"), - ("R_ADJACENT", "BSD_RCTA"), - ("L_APPROACHING", "BSD_RCTA"), - ("R_APPROACHING", "BSD_RCTA"), - ] - checks.append(("BSD_RCTA", 17)) + messages.append(("BSD_RCTA", 17)) if CP.carFingerprint not in PREGLOBAL_CARS: if CP.carFingerprint not in GLOBAL_GEN2: - signals += CarState.get_common_global_body_signals()[0] - checks += CarState.get_common_global_body_signals()[1] + messages += CarState.get_common_global_body_messages() - signals += [ - ("Steer_Warning", "Steering_Torque"), - ("UNITS", "Dashlights"), - ] - - checks += [ + messages += [ ("Dashlights", 10), ("BodyInfo", 10), ] else: - signals += [ - ("FL", "Wheel_Speeds"), - ("FR", "Wheel_Speeds"), - ("RL", "Wheel_Speeds"), - ("RR", "Wheel_Speeds"), - ("UNITS", "Dash_State2"), - ("Cruise_On", "CruiseControl"), - ("Cruise_Activated", "CruiseControl"), - ] - checks += [ + messages += [ ("Wheel_Speeds", 50), ("Dash_State2", 1), ] if CP.carFingerprint == CAR.FORESTER_PREGLOBAL: - checks += [ + messages += [ ("Dashlights", 20), ("BodyInfo", 1), ("CruiseControl", 50), ] if CP.carFingerprint in (CAR.LEGACY_PREGLOBAL, CAR.OUTBACK_PREGLOBAL, CAR.OUTBACK_PREGLOBAL_2018): - checks += [ + messages += [ ("Dashlights", 10), ("CruiseControl", 50), ] - return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, CanBus.main) + return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus.main) @staticmethod def get_cam_can_parser(CP): if CP.carFingerprint in PREGLOBAL_CARS: - signals = [ - ("Cruise_Set_Speed", "ES_DashStatus"), - ("Not_Ready_Startup", "ES_DashStatus"), - - ("Cruise_Throttle", "ES_Distance"), - ("Signal1", "ES_Distance"), - ("Car_Follow", "ES_Distance"), - ("Signal2", "ES_Distance"), - ("Brake_On", "ES_Distance"), - ("Distance_Swap", "ES_Distance"), - ("Standstill", "ES_Distance"), - ("Signal3", "ES_Distance"), - ("Close_Distance", "ES_Distance"), - ("Signal4", "ES_Distance"), - ("Standstill_2", "ES_Distance"), - ("Cruise_Fault", "ES_Distance"), - ("Signal5", "ES_Distance"), - ("COUNTER", "ES_Distance"), - ("Signal6", "ES_Distance"), - ("Cruise_Button", "ES_Distance"), - ("Signal7", "ES_Distance"), - ] - - checks = [ + messages = [ ("ES_DashStatus", 20), ("ES_Distance", 20), ] else: - signals = [ - ("COUNTER", "ES_DashStatus"), - ("CHECKSUM", "ES_DashStatus"), - ("PCB_Off", "ES_DashStatus"), - ("LDW_Off", "ES_DashStatus"), - ("Signal1", "ES_DashStatus"), - ("Cruise_State_Msg", "ES_DashStatus"), - ("LKAS_State_Msg", "ES_DashStatus"), - ("Signal2", "ES_DashStatus"), - ("Cruise_Soft_Disable", "ES_DashStatus"), - ("Cruise_Status_Msg", "ES_DashStatus"), - ("Signal3", "ES_DashStatus"), - ("Cruise_Distance", "ES_DashStatus"), - ("Signal4", "ES_DashStatus"), - ("Conventional_Cruise", "ES_DashStatus"), - ("Signal5", "ES_DashStatus"), - ("Cruise_Disengaged", "ES_DashStatus"), - ("Cruise_Activated", "ES_DashStatus"), - ("Signal6", "ES_DashStatus"), - ("Cruise_Set_Speed", "ES_DashStatus"), - ("Cruise_Fault", "ES_DashStatus"), - ("Cruise_On", "ES_DashStatus"), - ("Display_Own_Car", "ES_DashStatus"), - ("Brake_Lights", "ES_DashStatus"), - ("Car_Follow", "ES_DashStatus"), - ("Signal7", "ES_DashStatus"), - ("Far_Distance", "ES_DashStatus"), - ("Cruise_State", "ES_DashStatus"), - - ("COUNTER", "ES_LKAS_State"), - ("CHECKSUM", "ES_LKAS_State"), - ("LKAS_Alert_Msg", "ES_LKAS_State"), - ("Signal1", "ES_LKAS_State"), - ("LKAS_ACTIVE", "ES_LKAS_State"), - ("LKAS_Dash_State", "ES_LKAS_State"), - ("Signal2", "ES_LKAS_State"), - ("Backward_Speed_Limit_Menu", "ES_LKAS_State"), - ("LKAS_Left_Line_Enable", "ES_LKAS_State"), - ("LKAS_Left_Line_Light_Blink", "ES_LKAS_State"), - ("LKAS_Right_Line_Enable", "ES_LKAS_State"), - ("LKAS_Right_Line_Light_Blink", "ES_LKAS_State"), - ("LKAS_Left_Line_Visible", "ES_LKAS_State"), - ("LKAS_Right_Line_Visible", "ES_LKAS_State"), - ("LKAS_Alert", "ES_LKAS_State"), - ("Signal3", "ES_LKAS_State"), - ] - - checks = [ + messages = [ ("ES_DashStatus", 10), ("ES_LKAS_State", 10), ] if CP.carFingerprint not in GLOBAL_GEN2: - signals += CarState.get_common_global_es_signals()[0] - checks += CarState.get_common_global_es_signals()[1] + messages += CarState.get_common_global_es_messages() if CP.flags & SubaruFlags.SEND_INFOTAINMENT: - signals += [ - ("COUNTER", "ES_Infotainment"), - ("CHECKSUM", "ES_Infotainment"), - ("LKAS_State_Infotainment", "ES_Infotainment"), - ("LKAS_Blue_Lines", "ES_Infotainment"), - ("Signal1", "ES_Infotainment"), - ("Signal2", "ES_Infotainment"), - ] - checks.append(("ES_Infotainment", 10)) + messages.append(("ES_Infotainment", 10)) - return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, CanBus.camera) + return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus.camera) @staticmethod def get_body_can_parser(CP): if CP.carFingerprint in GLOBAL_GEN2: - signals, checks = CarState.get_common_global_body_signals() - signals += CarState.get_common_global_es_signals()[0] - checks += CarState.get_common_global_es_signals()[1] - return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, CanBus.alt) + messages = CarState.get_common_global_body_messages() + messages += CarState.get_common_global_es_messages() + return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus.alt) return None diff --git a/selfdrive/car/subaru/subarucan.py b/selfdrive/car/subaru/subarucan.py index 0c32a150d..39658e958 100644 --- a/selfdrive/car/subaru/subarucan.py +++ b/selfdrive/car/subaru/subarucan.py @@ -43,6 +43,7 @@ def create_es_distance(packer, es_distance_msg, bus, pcm_cancel_cmd): values["COUNTER"] = (values["COUNTER"] + 1) % 0x10 if pcm_cancel_cmd: values["Cruise_Cancel"] = 1 + values["Cruise_Throttle"] = 1818 # inactive throttle return packer.make_can_msg("ES_Distance", bus, values) diff --git a/selfdrive/car/subaru/values.py b/selfdrive/car/subaru/values.py index 95708445a..ebeb5ea2a 100644 --- a/selfdrive/car/subaru/values.py +++ b/selfdrive/car/subaru/values.py @@ -288,6 +288,7 @@ FW_VERSIONS = { b'\xe6!fp\x07', b'\xf3"fp\x07', b'\xe6"f0\x07', + b'\xe6"fp\x07', ], (Ecu.transmission, 0x7e1, None): [ b'\xe6\xf5\004\000\000', diff --git a/selfdrive/car/tesla/carstate.py b/selfdrive/car/tesla/carstate.py index 0f373842f..61a6526f0 100644 --- a/selfdrive/car/tesla/carstate.py +++ b/selfdrive/car/tesla/carstate.py @@ -78,7 +78,7 @@ class CarState(CarStateBase): ret.buttonEvents = buttonEvents # Doors - ret.doorOpen = any([(self.can_define.dv["GTW_carState"][door].get(int(cp.vl["GTW_carState"][door]), "OPEN") == "OPEN") for door in DOORS]) + ret.doorOpen = any((self.can_define.dv["GTW_carState"][door].get(int(cp.vl["GTW_carState"][door]), "OPEN") == "OPEN") for door in DOORS) # Blinkers ret.leftBlinker = (cp.vl["GTW_carState"]["BC_indicatorLStatus"] == 1) @@ -101,68 +101,7 @@ class CarState(CarStateBase): @staticmethod def get_can_parser(CP): - signals = [ - # sig_name, sig_address - ("ESP_vehicleSpeed", "ESP_B"), - ("DI_pedalPos", "DI_torque1"), - ("DI_brakePedal", "DI_torque2"), - ("StW_AnglHP", "STW_ANGLHP_STAT"), - ("StW_AnglHP_Spd", "STW_ANGLHP_STAT"), - ("EPAS_handsOnLevel", "EPAS_sysStatus"), - ("EPAS_torsionBarTorque", "EPAS_sysStatus"), - ("EPAS_internalSAS", "EPAS_sysStatus"), - ("EPAS_eacStatus", "EPAS_sysStatus"), - ("EPAS_eacErrorCode", "EPAS_sysStatus"), - ("DI_cruiseState", "DI_state"), - ("DI_digitalSpeed", "DI_state"), - ("DI_speedUnits", "DI_state"), - ("DI_gear", "DI_torque2"), - ("DOOR_STATE_FL", "GTW_carState"), - ("DOOR_STATE_FR", "GTW_carState"), - ("DOOR_STATE_RL", "GTW_carState"), - ("DOOR_STATE_RR", "GTW_carState"), - ("DOOR_STATE_FrontTrunk", "GTW_carState"), - ("BOOT_STATE", "GTW_carState"), - ("BC_indicatorLStatus", "GTW_carState"), - ("BC_indicatorRStatus", "GTW_carState"), - ("SDM_bcklDrivStatus", "SDM1"), - ("driverBrakeStatus", "BrakeMessage"), - - # We copy this whole message when spamming cancel - ("SpdCtrlLvr_Stat", "STW_ACTN_RQ"), - ("VSL_Enbl_Rq", "STW_ACTN_RQ"), - ("SpdCtrlLvrStat_Inv", "STW_ACTN_RQ"), - ("DTR_Dist_Rq", "STW_ACTN_RQ"), - ("TurnIndLvr_Stat", "STW_ACTN_RQ"), - ("HiBmLvr_Stat", "STW_ACTN_RQ"), - ("WprWashSw_Psd", "STW_ACTN_RQ"), - ("WprWash_R_Sw_Posn_V2", "STW_ACTN_RQ"), - ("StW_Lvr_Stat", "STW_ACTN_RQ"), - ("StW_Cond_Flt", "STW_ACTN_RQ"), - ("StW_Cond_Psd", "STW_ACTN_RQ"), - ("HrnSw_Psd", "STW_ACTN_RQ"), - ("StW_Sw00_Psd", "STW_ACTN_RQ"), - ("StW_Sw01_Psd", "STW_ACTN_RQ"), - ("StW_Sw02_Psd", "STW_ACTN_RQ"), - ("StW_Sw03_Psd", "STW_ACTN_RQ"), - ("StW_Sw04_Psd", "STW_ACTN_RQ"), - ("StW_Sw05_Psd", "STW_ACTN_RQ"), - ("StW_Sw06_Psd", "STW_ACTN_RQ"), - ("StW_Sw07_Psd", "STW_ACTN_RQ"), - ("StW_Sw08_Psd", "STW_ACTN_RQ"), - ("StW_Sw09_Psd", "STW_ACTN_RQ"), - ("StW_Sw10_Psd", "STW_ACTN_RQ"), - ("StW_Sw11_Psd", "STW_ACTN_RQ"), - ("StW_Sw12_Psd", "STW_ACTN_RQ"), - ("StW_Sw13_Psd", "STW_ACTN_RQ"), - ("StW_Sw14_Psd", "STW_ACTN_RQ"), - ("StW_Sw15_Psd", "STW_ACTN_RQ"), - ("WprSw6Posn", "STW_ACTN_RQ"), - ("MC_STW_ACTN_RQ", "STW_ACTN_RQ"), - ("CRC_STW_ACTN_RQ", "STW_ACTN_RQ"), - ] - - checks = [ + messages = [ # sig_address, frequency ("ESP_B", 50), ("DI_torque1", 100), @@ -175,19 +114,12 @@ class CarState(CarStateBase): ("SDM1", 10), ("BrakeMessage", 50), ] - - return CANParser(DBC[CP.carFingerprint]['chassis'], signals, checks, CANBUS.chassis) + return CANParser(DBC[CP.carFingerprint]['chassis'], messages, CANBUS.chassis) @staticmethod def get_cam_can_parser(CP): - signals = [ - # sig_name, sig_address - ("DAS_accState", "DAS_control"), - ("DAS_aebEvent", "DAS_control"), - ("DAS_controlCounter", "DAS_control"), - ] - checks = [ + messages = [ # sig_address, frequency ("DAS_control", 40), ] - return CANParser(DBC[CP.carFingerprint]['chassis'], signals, checks, CANBUS.autopilot_chassis) + return CANParser(DBC[CP.carFingerprint]['chassis'], messages, CANBUS.autopilot_chassis) diff --git a/selfdrive/car/tesla/radar_interface.py b/selfdrive/car/tesla/radar_interface.py index a09f53e75..cf76e213e 100755 --- a/selfdrive/car/tesla/radar_interface.py +++ b/selfdrive/car/tesla/radar_interface.py @@ -10,13 +10,7 @@ NUM_POINTS = len(RADAR_MSGS_A) def get_radar_can_parser(CP): # Status messages - signals = [ - ('RADC_HWFail', 'TeslaRadarSguInfo'), - ('RADC_SGUFail', 'TeslaRadarSguInfo'), - ('RADC_SensorDirty', 'TeslaRadarSguInfo'), - ] - - checks = [ + messages = [ ('TeslaRadarSguInfo', 10), ] @@ -25,28 +19,12 @@ def get_radar_can_parser(CP): for i in range(NUM_POINTS): msg_id_a = RADAR_MSGS_A[i] msg_id_b = RADAR_MSGS_B[i] - - # There is a bunch more info in the messages, - # but these are the only things actually used in openpilot - signals.extend([ - ('LongDist', msg_id_a), - ('LongSpeed', msg_id_a), - ('LatDist', msg_id_a), - ('LongAccel', msg_id_a), - ('Meas', msg_id_a), - ('Tracked', msg_id_a), - ('Index', msg_id_a), - - ('LatSpeed', msg_id_b), - ('Index2', msg_id_b), - ]) - - checks.extend([ + messages.extend([ (msg_id_a, 8), (msg_id_b, 8), ]) - return CANParser(DBC[CP.carFingerprint]['radar'], signals, checks, CANBUS.radar) + return CANParser(DBC[CP.carFingerprint]['radar'], messages, CANBUS.radar) class RadarInterface(RadarInterfaceBase): def __init__(self, CP): @@ -58,7 +36,7 @@ class RadarInterface(RadarInterfaceBase): def update(self, can_strings): if self.rcp is None: - return super().update(None) + return None values = self.rcp.update_strings(can_strings) self.updated_messages.update(values) diff --git a/selfdrive/car/toyota/carcontroller.py b/selfdrive/car/toyota/carcontroller.py index fd8c7f6ac..f988d1976 100644 --- a/selfdrive/car/toyota/carcontroller.py +++ b/selfdrive/car/toyota/carcontroller.py @@ -154,7 +154,7 @@ class CarController: apply_steer = apply_meas_steer_torque_limits(new_steer, self.last_steer, CS.out.steeringTorqueEps, self.params) # >100 degree/sec steering fault prevention - self.steer_rate_counter, apply_steer_req = common_fault_avoidance(CS.out.steeringRateDeg, MAX_STEER_RATE, CC.latActive, + self.steer_rate_counter, apply_steer_req = common_fault_avoidance(abs(CS.out.steeringRateDeg) >= MAX_STEER_RATE, CC.latActive, self.steer_rate_counter, MAX_STEER_RATE_FRAMES) if not CC.latActive: diff --git a/selfdrive/car/toyota/carstate.py b/selfdrive/car/toyota/carstate.py index f2dce41d1..2dbfabcaa 100644 --- a/selfdrive/car/toyota/carstate.py +++ b/selfdrive/car/toyota/carstate.py @@ -226,44 +226,7 @@ class CarState(CarStateBase): @staticmethod def get_can_parser(CP): - signals = [ - # sig_name, sig_address - ("STEER_ANGLE", "STEER_ANGLE_SENSOR"), - ("GEAR", "GEAR_PACKET"), - ("BRAKE_PRESSED", "BRAKE_MODULE"), - ("WHEEL_SPEED_FL", "WHEEL_SPEEDS"), - ("WHEEL_SPEED_FR", "WHEEL_SPEEDS"), - ("WHEEL_SPEED_RL", "WHEEL_SPEEDS"), - ("WHEEL_SPEED_RR", "WHEEL_SPEEDS"), - ("DOOR_OPEN_FL", "BODY_CONTROL_STATE"), - ("DOOR_OPEN_FR", "BODY_CONTROL_STATE"), - ("DOOR_OPEN_RL", "BODY_CONTROL_STATE"), - ("DOOR_OPEN_RR", "BODY_CONTROL_STATE"), - ("SEATBELT_DRIVER_UNLATCHED", "BODY_CONTROL_STATE"), - ("PARKING_BRAKE", "BODY_CONTROL_STATE"), - ("UNITS", "BODY_CONTROL_STATE_2"), - ("TC_DISABLED", "ESP_CONTROL"), - ("BRAKE_HOLD_ACTIVE", "ESP_CONTROL"), - ("STEER_FRACTION", "STEER_ANGLE_SENSOR"), - ("STEER_RATE", "STEER_ANGLE_SENSOR"), - ("CRUISE_ACTIVE", "PCM_CRUISE"), - ("CRUISE_STATE", "PCM_CRUISE"), - ("GAS_RELEASED", "PCM_CRUISE"), - ("UI_SET_SPEED", "PCM_CRUISE_SM"), - ("STEER_TORQUE_DRIVER", "STEER_TORQUE_SENSOR"), - ("STEER_TORQUE_EPS", "STEER_TORQUE_SENSOR"), - ("STEER_ANGLE", "STEER_TORQUE_SENSOR"), - ("STEER_ANGLE_INITIALIZING", "STEER_TORQUE_SENSOR"), - ("TURN_SIGNALS", "BLINKERS_STATE"), - ("LKA_STATE", "EPS_STATUS"), - ("AUTO_HIGH_BEAM", "LIGHT_STALK"), - ] - - # Check LTA state if using LTA angle control - if CP.steerControlType == SteerControlType.angle: - signals.append(("LTA_STATE", "EPS_STATUS")) - - checks = [ + messages = [ ("GEAR_PACKET", 1), ("LIGHT_STALK", 1), ("BLINKERS_STATE", 0.15), @@ -280,41 +243,24 @@ class CarState(CarStateBase): ] if CP.flags & ToyotaFlags.HYBRID: - signals.append(("GAS_PEDAL", "GAS_PEDAL_HYBRID")) - checks.append(("GAS_PEDAL_HYBRID", 33)) + messages.append(("GAS_PEDAL_HYBRID", 33)) else: - signals.append(("GAS_PEDAL", "GAS_PEDAL")) - checks.append(("GAS_PEDAL", 33)) + messages.append(("GAS_PEDAL", 33)) if CP.carFingerprint in UNSUPPORTED_DSU_CAR: - signals.append(("MAIN_ON", "DSU_CRUISE")) - signals.append(("SET_SPEED", "DSU_CRUISE")) - signals.append(("UI_SET_SPEED", "PCM_CRUISE_ALT")) - checks.append(("DSU_CRUISE", 5)) - checks.append(("PCM_CRUISE_ALT", 1)) + messages.append(("DSU_CRUISE", 5)) + messages.append(("PCM_CRUISE_ALT", 1)) else: - signals.append(("MAIN_ON", "PCM_CRUISE_2")) - signals.append(("SET_SPEED", "PCM_CRUISE_2")) - signals.append(("ACC_FAULTED", "PCM_CRUISE_2")) - signals.append(("LOW_SPEED_LOCKOUT", "PCM_CRUISE_2")) - checks.append(("PCM_CRUISE_2", 33)) + messages.append(("PCM_CRUISE_2", 33)) # add gas interceptor reading if we are using it if CP.enableGasInterceptor: - signals.append(("INTERCEPTOR_GAS", "GAS_SENSOR")) - signals.append(("INTERCEPTOR_GAS2", "GAS_SENSOR")) - checks.append(("GAS_SENSOR", 50)) + messages.append(("GAS_SENSOR", 50)) dp_toyota_enhanced_bsm = Params().get_bool('dp_toyota_enhanced_bsm') if CP.enableBsm: - signals += [ - ("L_ADJACENT", "BSM"), - ("L_APPROACHING", "BSM"), - ("R_ADJACENT", "BSM"), - ("R_APPROACHING", "BSM"), - ] - checks.append(("BSM", 1)) + messages.append(("BSM", 1)) if dp_toyota_enhanced_bsm: signals +=[ @@ -327,58 +273,34 @@ class CarState(CarStateBase): if CP.carFingerprint in RADAR_ACC_CAR: if not CP.flags & ToyotaFlags.SMART_DSU.value: - signals += [ - ("ACC_TYPE", "ACC_CONTROL"), - ] - checks += [ + messages += [ ("ACC_CONTROL", 33), ] - signals += [ - ("FCW", "PCS_HUD"), - ] - checks += [ + messages += [ ("PCS_HUD", 1), ] if CP.carFingerprint not in (TSS2_CAR - RADAR_ACC_CAR) and not CP.enableDsu: - signals += [ - ("FORCE", "PRE_COLLISION"), - ("PRECOLLISION_ACTIVE", "PRE_COLLISION"), - ] - checks += [ + messages += [ ("PRE_COLLISION", 33), ] - return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 0) + return CANParser(DBC[CP.carFingerprint]["pt"], messages, 0) @staticmethod def get_cam_can_parser(CP): - signals = [] - checks = [] + messages = [] if CP.carFingerprint != CAR.PRIUS_V: - signals += [ - ("LANE_SWAY_FLD", "LKAS_HUD"), - ("LANE_SWAY_BUZZER", "LKAS_HUD"), - ("LANE_SWAY_WARNING", "LKAS_HUD"), - ("LANE_SWAY_SENSITIVITY", "LKAS_HUD"), - ("LANE_SWAY_TOGGLE", "LKAS_HUD"), - ] - checks += [ + messages += [ ("LKAS_HUD", 1), ] if CP.carFingerprint in (TSS2_CAR - RADAR_ACC_CAR): - signals += [ - ("PRECOLLISION_ACTIVE", "PRE_COLLISION"), - ("FORCE", "PRE_COLLISION"), - ("ACC_TYPE", "ACC_CONTROL"), - ("FCW", "PCS_HUD"), - ] - checks += [ + messages += [ ("PRE_COLLISION", 33), ("ACC_CONTROL", 33), ("PCS_HUD", 1), ] - return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 2) + return CANParser(DBC[CP.carFingerprint]["pt"], messages, 2) diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py index e7df4a337..7d7c89556 100644 --- a/selfdrive/car/toyota/interface.py +++ b/selfdrive/car/toyota/interface.py @@ -4,7 +4,7 @@ from common.conversions import Conversions as CV from panda import Panda from selfdrive.car.toyota.values import Ecu, CAR, DBC, ToyotaFlags, CarControllerParams, TSS2_CAR, RADAR_ACC_CAR, NO_DSU_CAR, \ MIN_ACC_SPEED, EPS_SCALE, EV_HYBRID_CAR, UNSUPPORTED_DSU_CAR, NO_STOP_TIMER_CAR, ANGLE_CONTROL_CAR -from selfdrive.car import STD_CARGO_KG, scale_tire_stiffness, get_safety_config +from selfdrive.car import STD_CARGO_KG, get_safety_config from selfdrive.car.interfaces import CarInterfaceBase from common.params import Params @@ -49,7 +49,7 @@ class CarInterface(CarInterfaceBase): stop_and_go = True ret.wheelbase = 2.70 ret.steerRatio = 15.74 # unknown end-to-end spec - tire_stiffness_factor = 0.6371 # hand-tune + ret.tireStiffnessFactor = 0.6371 # hand-tune ret.mass = 3045. * CV.LB_TO_KG + STD_CARGO_KG # Only give steer angle deadzone to for bad angle sensor prius for fw in car_fw: @@ -61,20 +61,20 @@ class CarInterface(CarInterfaceBase): stop_and_go = True ret.wheelbase = 2.78 ret.steerRatio = 17.4 - tire_stiffness_factor = 0.5533 + ret.tireStiffnessFactor = 0.5533 ret.mass = 3340. * CV.LB_TO_KG + STD_CARGO_KG elif candidate in (CAR.RAV4, CAR.RAV4H): stop_and_go = True if (candidate in CAR.RAV4H) else False ret.wheelbase = 2.65 ret.steerRatio = 16.88 # 14.5 is spec end-to-end - tire_stiffness_factor = 0.5533 + ret.tireStiffnessFactor = 0.5533 ret.mass = 3650. * CV.LB_TO_KG + STD_CARGO_KG # mean between normal and hybrid elif candidate == CAR.COROLLA: ret.wheelbase = 2.70 ret.steerRatio = 18.27 - tire_stiffness_factor = 0.444 # not optimized yet + ret.tireStiffnessFactor = 0.444 # not optimized yet ret.mass = 2860. * CV.LB_TO_KG + STD_CARGO_KG # mean between normal and hybrid elif candidate in (CAR.LEXUS_RX, CAR.LEXUS_RXH, CAR.LEXUS_RX_TSS2, CAR.LEXUS_RXH_TSS2): @@ -82,28 +82,28 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.79 ret.steerRatio = 16. # 14.8 is spec end-to-end ret.wheelSpeedFactor = 1.035 - tire_stiffness_factor = 0.5533 + ret.tireStiffnessFactor = 0.5533 ret.mass = 4481. * CV.LB_TO_KG + STD_CARGO_KG # mean between min and max elif candidate in (CAR.CHR, CAR.CHRH, CAR.CHR_TSS2, CAR.CHRH_TSS2): stop_and_go = True ret.wheelbase = 2.63906 ret.steerRatio = 13.6 - tire_stiffness_factor = 0.7933 + ret.tireStiffnessFactor = 0.7933 ret.mass = 3300. * CV.LB_TO_KG + STD_CARGO_KG elif candidate in (CAR.CAMRY, CAR.CAMRYH, CAR.CAMRY_TSS2, CAR.CAMRYH_TSS2): stop_and_go = True ret.wheelbase = 2.82448 ret.steerRatio = 13.7 - tire_stiffness_factor = 0.7933 + ret.tireStiffnessFactor = 0.7933 ret.mass = 3400. * CV.LB_TO_KG + STD_CARGO_KG # mean between normal and hybrid elif candidate in (CAR.HIGHLANDER, CAR.HIGHLANDERH, CAR.HIGHLANDER_TSS2, CAR.HIGHLANDERH_TSS2): stop_and_go = True ret.wheelbase = 2.8194 # average of 109.8 and 112.2 in ret.steerRatio = 16.0 - tire_stiffness_factor = 0.8 + ret.tireStiffnessFactor = 0.8 ret.mass = 4516. * CV.LB_TO_KG + STD_CARGO_KG # mean between normal and hybrid elif candidate in (CAR.AVALON, CAR.AVALON_2019, CAR.AVALONH_2019, CAR.AVALON_TSS2, CAR.AVALONH_TSS2): @@ -112,14 +112,14 @@ class CarInterface(CarInterfaceBase): stop_and_go = candidate != CAR.AVALON ret.wheelbase = 2.82 ret.steerRatio = 14.8 # Found at https://pressroom.toyota.com/releases/2016+avalon+product+specs.download - tire_stiffness_factor = 0.7983 + ret.tireStiffnessFactor = 0.7983 ret.mass = 3505. * CV.LB_TO_KG + STD_CARGO_KG # mean between normal and hybrid elif candidate in (CAR.RAV4_TSS2, CAR.RAV4_TSS2_2022, CAR.RAV4H_TSS2, CAR.RAV4H_TSS2_2022, CAR.RAV4_TSS2_2023, CAR.RAV4H_TSS2_2023): ret.wheelbase = 2.68986 ret.steerRatio = 14.3 - tire_stiffness_factor = 0.7933 + ret.tireStiffnessFactor = 0.7933 ret.mass = 3585. * CV.LB_TO_KG + STD_CARGO_KG # Average between ICE and Hybrid ret.lateralTuning.init('pid') ret.lateralTuning.pid.kiBP = [0.0] @@ -140,7 +140,7 @@ class CarInterface(CarInterfaceBase): elif candidate in (CAR.COROLLA_TSS2, CAR.COROLLAH_TSS2): ret.wheelbase = 2.67 # Average between 2.70 for sedan and 2.64 for hatchback ret.steerRatio = 13.9 - tire_stiffness_factor = 0.444 # not optimized yet + ret.tireStiffnessFactor = 0.444 # not optimized yet ret.mass = 3060. * CV.LB_TO_KG + STD_CARGO_KG elif candidate in (CAR.LEXUS_ES, CAR.LEXUS_ESH, CAR.LEXUS_ES_TSS2, CAR.LEXUS_ESH_TSS2): @@ -148,62 +148,56 @@ class CarInterface(CarInterfaceBase): stop_and_go = True ret.wheelbase = 2.8702 ret.steerRatio = 16.0 # not optimized - tire_stiffness_factor = 0.444 # not optimized yet + ret.tireStiffnessFactor = 0.444 # not optimized yet ret.mass = 3677. * CV.LB_TO_KG + STD_CARGO_KG # mean between min and max elif candidate == CAR.SIENNA: stop_and_go = True ret.wheelbase = 3.03 ret.steerRatio = 15.5 - tire_stiffness_factor = 0.444 + ret.tireStiffnessFactor = 0.444 ret.mass = 4590. * CV.LB_TO_KG + STD_CARGO_KG elif candidate in (CAR.LEXUS_IS, CAR.LEXUS_IS_TSS2, CAR.LEXUS_RC): ret.wheelbase = 2.79908 ret.steerRatio = 13.3 - tire_stiffness_factor = 0.444 + ret.tireStiffnessFactor = 0.444 ret.mass = 3736.8 * CV.LB_TO_KG + STD_CARGO_KG elif candidate == CAR.LEXUS_CTH: stop_and_go = True ret.wheelbase = 2.60 ret.steerRatio = 18.6 - tire_stiffness_factor = 0.517 + ret.tireStiffnessFactor = 0.517 ret.mass = 3108 * CV.LB_TO_KG + STD_CARGO_KG # mean between min and max elif candidate in (CAR.LEXUS_NX, CAR.LEXUS_NXH, CAR.LEXUS_NX_TSS2, CAR.LEXUS_NXH_TSS2): stop_and_go = True ret.wheelbase = 2.66 ret.steerRatio = 14.7 - tire_stiffness_factor = 0.444 # not optimized yet + ret.tireStiffnessFactor = 0.444 # not optimized yet ret.mass = 4070 * CV.LB_TO_KG + STD_CARGO_KG elif candidate == CAR.PRIUS_TSS2: ret.wheelbase = 2.70002 # from toyota online sepc. ret.steerRatio = 13.4 # True steerRatio from older prius - tire_stiffness_factor = 0.6371 # hand-tune + ret.tireStiffnessFactor = 0.6371 # hand-tune ret.mass = 3115. * CV.LB_TO_KG + STD_CARGO_KG elif candidate == CAR.MIRAI: stop_and_go = True ret.wheelbase = 2.91 ret.steerRatio = 14.8 - tire_stiffness_factor = 0.8 + ret.tireStiffnessFactor = 0.8 ret.mass = 4300. * CV.LB_TO_KG + STD_CARGO_KG elif candidate in (CAR.ALPHARD_TSS2, CAR.ALPHARDH_TSS2): ret.wheelbase = 3.00 ret.steerRatio = 14.2 - tire_stiffness_factor = 0.444 + ret.tireStiffnessFactor = 0.444 ret.mass = 4305. * CV.LB_TO_KG + STD_CARGO_KG ret.centerToFront = ret.wheelbase * 0.44 - - # TODO: start from empirically derived lateral slip stiffness for the civic and scale by - # mass and CG position, so all cars will have approximately similar dyn behaviors - ret.tireStiffnessFront, ret.tireStiffnessRear = scale_tire_stiffness(ret.mass, ret.wheelbase, ret.centerToFront, - tire_stiffness_factor=tire_stiffness_factor) - ret.enableBsm = 0x3F6 in fingerprint[0] and candidate in TSS2_CAR # Detect smartDSU, which intercepts ACC_CMD from the DSU (or radar) allowing openpilot to send it diff --git a/selfdrive/car/toyota/radar_interface.py b/selfdrive/car/toyota/radar_interface.py index 64906b34b..378178f5c 100755 --- a/selfdrive/car/toyota/radar_interface.py +++ b/selfdrive/car/toyota/radar_interface.py @@ -1,4 +1,6 @@ #!/usr/bin/env python3 +from collections import defaultdict + from opendbc.can.parser import CANParser from cereal import car from selfdrive.car.toyota.values import DBC, TSS2_CAR @@ -15,14 +17,9 @@ def _create_radar_can_parser(car_fingerprint): msg_a_n = len(RADAR_A_MSGS) msg_b_n = len(RADAR_B_MSGS) + messages = list(zip(RADAR_A_MSGS + RADAR_B_MSGS, [20] * (msg_a_n + msg_b_n), strict=True)) - signals = list(zip(['LONG_DIST'] * msg_a_n + ['NEW_TRACK'] * msg_a_n + ['LAT_DIST'] * msg_a_n + - ['REL_SPEED'] * msg_a_n + ['VALID'] * msg_a_n + ['SCORE'] * msg_b_n, - RADAR_A_MSGS * 5 + RADAR_B_MSGS)) - - checks = list(zip(RADAR_A_MSGS + RADAR_B_MSGS, [20] * (msg_a_n + msg_b_n))) - - return CANParser(DBC[car_fingerprint]['radar'], signals, checks, 1) + return CANParser(DBC[car_fingerprint]['radar'], messages, 1) class RadarInterface(RadarInterfaceBase): def __init__(self, CP): @@ -41,34 +38,47 @@ class RadarInterface(RadarInterfaceBase): self.rcp = None if CP.radarUnavailable else _create_radar_can_parser(CP.carFingerprint) self.trigger_msg = self.RADAR_B_MSGS[-1] - self.updated_messages = set() + self.updated_values = defaultdict(lambda: defaultdict(list)) def update(self, can_strings): if self.rcp is None: - return super().update(None) - - vls = self.rcp.update_strings(can_strings) - self.updated_messages.update(vls) - - if self.trigger_msg not in self.updated_messages: return None - rr = self._update(self.updated_messages) - self.updated_messages.clear() + addresses = self.rcp.update_strings(can_strings) + for addr in addresses: + vals_dict = self.rcp.vl_all[addr] + for sig_name, vals in vals_dict.items(): + self.updated_values[addr][sig_name].extend(vals) - return rr + if self.trigger_msg not in self.updated_values: + return None - def _update(self, updated_messages): + radar_data = self._radar_msg_from_buffer(self.updated_values, self.rcp.can_valid) + self.updated_values.clear() + + return radar_data + + def _radar_msg_from_buffer(self, updated_values, can_valid): ret = car.RadarData.new_message() errors = [] - if not self.rcp.can_valid: + if not can_valid: errors.append("canError") ret.errors = errors - for ii in sorted(updated_messages): - if ii in self.RADAR_A_MSGS: - cpt = self.rcp.vl[ii] + for ii in sorted(updated_values): + if ii not in self.RADAR_A_MSGS: + continue + radar_a_msgs = updated_values[ii] + radar_b_msgs = updated_values[ii+16] + + n_vals_per_addr = len(list(radar_a_msgs.values())[0]) + cpts = [ + {k: v[i] for k, v in radar_a_msgs.items()} + for i in range(n_vals_per_addr) + ] + + for index, cpt in enumerate(cpts): if cpt['LONG_DIST'] >= 255 or cpt['NEW_TRACK']: self.valid_cnt[ii] = 0 # reset counter if cpt['VALID'] and cpt['LONG_DIST'] < 255: @@ -76,11 +86,15 @@ class RadarInterface(RadarInterfaceBase): else: self.valid_cnt[ii] = max(self.valid_cnt[ii] - 1, 0) - score = self.rcp.vl[ii+16]['SCORE'] - # print ii, self.valid_cnt[ii], score, cpt['VALID'], cpt['LONG_DIST'], cpt['LAT_DIST'] + n_b_scores = len(radar_b_msgs['SCORE']) + if n_b_scores > 0: + score_index = min(index, n_b_scores - 1) + score = radar_b_msgs['SCORE'][score_index] + else: + score = None # radar point only valid if it's a valid measurement and score is above 50 - if cpt['VALID'] or (score > 50 and cpt['LONG_DIST'] < 255 and self.valid_cnt[ii] > 0): + if cpt['VALID'] or (score and score > 50 and cpt['LONG_DIST'] < 255 and self.valid_cnt[ii] > 0): if ii not in self.pts or cpt['NEW_TRACK']: self.pts[ii] = car.RadarData.RadarPoint.new_message() self.pts[ii].trackId = self.track_id diff --git a/selfdrive/car/volkswagen/carstate.py b/selfdrive/car/volkswagen/carstate.py index f3cd2808a..35f7e8bf6 100644 --- a/selfdrive/car/volkswagen/carstate.py +++ b/selfdrive/car/volkswagen/carstate.py @@ -254,54 +254,7 @@ class CarState(CarStateBase): if CP.carFingerprint in PQ_CARS: return CarState.get_can_parser_pq(CP) - signals = [ - # sig_name, sig_address - ("LWI_Lenkradwinkel", "LWI_01"), # Absolute steering angle - ("LWI_VZ_Lenkradwinkel", "LWI_01"), # Steering angle sign - ("LWI_Lenkradw_Geschw", "LWI_01"), # Absolute steering rate - ("LWI_VZ_Lenkradw_Geschw", "LWI_01"), # Steering rate sign - ("ESP_VL_Radgeschw_02", "ESP_19"), # ABS wheel speed, front left - ("ESP_VR_Radgeschw_02", "ESP_19"), # ABS wheel speed, front right - ("ESP_HL_Radgeschw_02", "ESP_19"), # ABS wheel speed, rear left - ("ESP_HR_Radgeschw_02", "ESP_19"), # ABS wheel speed, rear right - ("ESP_Gierrate", "ESP_02"), # Absolute yaw rate - ("ESP_VZ_Gierrate", "ESP_02"), # Yaw rate sign - ("ZV_FT_offen", "Gateway_72"), # Door open, driver - ("ZV_BT_offen", "Gateway_72"), # Door open, passenger - ("ZV_HFS_offen", "Gateway_72"), # Door open, rear left - ("ZV_HBFS_offen", "Gateway_72"), # Door open, rear right - ("ZV_HD_offen", "Gateway_72"), # Trunk or hatch open - ("Comfort_Signal_Left", "Blinkmodi_02"), # Left turn signal including comfort blink interval - ("Comfort_Signal_Right", "Blinkmodi_02"), # Right turn signal including comfort blink interval - ("AB_Gurtschloss_FA", "Airbag_02"), # Seatbelt status, driver - ("AB_Gurtschloss_BF", "Airbag_02"), # Seatbelt status, passenger - ("ESP_Fahrer_bremst", "ESP_05"), # Driver applied brake pressure over threshold - ("MO_Fahrer_bremst", "Motor_14"), # Brake pedal switch - ("ESP_Bremsdruck", "ESP_05"), # Brake pressure - ("MO_Fahrpedalrohwert_01", "Motor_20"), # Accelerator pedal value - ("EPS_Lenkmoment", "LH_EPS_03"), # Absolute driver torque input - ("EPS_VZ_Lenkmoment", "LH_EPS_03"), # Driver torque input sign - ("EPS_HCA_Status", "LH_EPS_03"), # EPS HCA control status - ("ESP_Tastung_passiv", "ESP_21"), # Stability control disabled - ("ESP_Haltebestaetigung", "ESP_21"), # ESP hold confirmation - ("KBI_Handbremse", "Kombi_01"), # Manual handbrake applied - ("KBI_Variante", "Kombi_03"), # Digital/full-screen instrument cluster installed - ("TSK_Status", "TSK_06"), # ACC engagement status from drivetrain coordinator - ("GRA_Hauptschalter", "GRA_ACC_01"), # ACC button, on/off - ("GRA_Abbrechen", "GRA_ACC_01"), # ACC button, cancel - ("GRA_Tip_Setzen", "GRA_ACC_01"), # ACC button, set - ("GRA_Tip_Hoch", "GRA_ACC_01"), # ACC button, increase or accel - ("GRA_Tip_Runter", "GRA_ACC_01"), # ACC button, decrease or decel - ("GRA_Tip_Wiederaufnahme", "GRA_ACC_01"), # ACC button, resume - ("GRA_Verstellung_Zeitluecke", "GRA_ACC_01"), # ACC button, time gap adj - ("GRA_Typ_Hauptschalter", "GRA_ACC_01"), # ACC main button type - ("GRA_Codierung", "GRA_ACC_01"), # ACC button configuration/coding - ("GRA_Tip_Stufe_2", "GRA_ACC_01"), # unknown related to stalk type - ("GRA_ButtonTypeInfo", "GRA_ACC_01"), # unknown related to stalk type - ("COUNTER", "GRA_ACC_01"), # GRA_ACC_01 CAN message counter - ] - - checks = [ + messages = [ # sig_address, frequency ("LWI_01", 100), # From J500 Steering Assist with integrated sensors ("LH_EPS_03", 100), # From J500 Steering Assist with integrated sensors @@ -321,108 +274,41 @@ class CarState(CarStateBase): ] if CP.transmissionType == TransmissionType.automatic: - signals.append(("GE_Fahrstufe", "Getriebe_11")) # Auto trans gear selector position - checks.append(("Getriebe_11", 20)) # From J743 Auto transmission control module + messages.append(("Getriebe_11", 20)) # From J743 Auto transmission control module elif CP.transmissionType == TransmissionType.direct: - signals.append(("GearPosition", "EV_Gearshift")) # EV gear selector position - checks.append(("EV_Gearshift", 10)) # From J??? unknown EV control module - elif CP.transmissionType == TransmissionType.manual: - signals += [("MO_Kuppl_schalter", "Motor_14"), # Clutch switch - ("BCM1_Rueckfahrlicht_Schalter", "Gateway_72")] # Reverse light from BCM + messages.append(("EV_Gearshift", 10)) # From J??? unknown EV control module if CP.networkLocation == NetworkLocation.fwdCamera: # Radars are here on CANBUS.pt - signals += MqbExtraSignals.fwd_radar_signals - checks += MqbExtraSignals.fwd_radar_checks + messages += MqbExtraSignals.fwd_radar_messages if CP.enableBsm: - signals += MqbExtraSignals.bsm_radar_signals - checks += MqbExtraSignals.bsm_radar_checks + messages += MqbExtraSignals.bsm_radar_messages - return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, CANBUS.pt) + return CANParser(DBC[CP.carFingerprint]["pt"], messages, CANBUS.pt) @staticmethod def get_cam_can_parser(CP): if CP.carFingerprint in PQ_CARS: return CarState.get_cam_can_parser_pq(CP) - signals = [] - checks = [] + messages = [] if CP.networkLocation == NetworkLocation.fwdCamera: - signals += [ - # sig_name, sig_address - ("LDW_SW_Warnung_links", "LDW_02"), # Blind spot in warning mode on left side due to lane departure - ("LDW_SW_Warnung_rechts", "LDW_02"), # Blind spot in warning mode on right side due to lane departure - ("LDW_Seite_DLCTLC", "LDW_02"), # Direction of most likely lane departure (left or right) - ("LDW_DLC", "LDW_02"), # Lane departure, distance to line crossing - ("LDW_TLC", "LDW_02"), # Lane departure, time to line crossing - ] - checks += [ + messages += [ # sig_address, frequency ("LDW_02", 10) # From R242 Driver assistance camera ] else: # Radars are here on CANBUS.cam - signals += MqbExtraSignals.fwd_radar_signals - checks += MqbExtraSignals.fwd_radar_checks + messages += MqbExtraSignals.fwd_radar_messages if CP.enableBsm: - signals += MqbExtraSignals.bsm_radar_signals - checks += MqbExtraSignals.bsm_radar_checks + messages += MqbExtraSignals.bsm_radar_messages - return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, CANBUS.cam) + return CANParser(DBC[CP.carFingerprint]["pt"], messages, CANBUS.cam) @staticmethod def get_can_parser_pq(CP): - signals = [ - # sig_name, sig_address, default - ("LH3_BLW", "Lenkhilfe_3"), # Absolute steering angle - ("LH3_BLWSign", "Lenkhilfe_3"), # Steering angle sign - ("LH3_LM", "Lenkhilfe_3"), # Absolute driver torque input - ("LH3_LMSign", "Lenkhilfe_3"), # Driver torque input sign - ("LH2_Sta_HCA", "Lenkhilfe_2"), # Steering rack HCA status - ("Lenkradwinkel_Geschwindigkeit", "Lenkwinkel_1"), # Absolute steering rate - ("Lenkradwinkel_Geschwindigkeit_S", "Lenkwinkel_1"), # Steering rate sign - ("Geschwindigkeit_neu__Bremse_1_", "Bremse_1"), # Vehicle speed from ABS - ("Radgeschw__VL_4_1", "Bremse_3"), # ABS wheel speed, front left - ("Radgeschw__VR_4_1", "Bremse_3"), # ABS wheel speed, front right - ("Radgeschw__HL_4_1", "Bremse_3"), # ABS wheel speed, rear left - ("Radgeschw__HR_4_1", "Bremse_3"), # ABS wheel speed, rear right - ("Giergeschwindigkeit", "Bremse_5"), # Absolute yaw rate - ("Vorzeichen_der_Giergeschwindigk", "Bremse_5"), # Yaw rate sign - ("Gurtschalter_Fahrer", "Airbag_1"), # Seatbelt status, driver - ("Gurtschalter_Beifahrer", "Airbag_1"), # Seatbelt status, passenger - ("Bremstestschalter", "Motor_2"), # Brake pedal pressed (brake light test switch) - ("Bremslichtschalter", "Motor_2"), # Brakes applied (brake light switch) - ("Bremsdruck", "Bremse_5"), # Brake pressure applied - ("Vorzeichen_Bremsdruck", "Bremse_5"), # Brake pressure applied sign (???) - ("Fahrpedal_Rohsignal", "Motor_3"), # Accelerator pedal value - ("ESP_Passiv_getastet", "Bremse_1"), # Stability control disabled - ("GRA_Hauptschalter", "Motor_5"), # ACC main switch - ("GRA_Status", "Motor_2"), # ACC engagement status - ("GK1_Fa_Tuerkont", "Gate_Komf_1"), # Door open, driver - ("BSK_BT_geoeffnet", "Gate_Komf_1"), # Door open, passenger - ("BSK_HL_geoeffnet", "Gate_Komf_1"), # Door open, rear left - ("BSK_HR_geoeffnet", "Gate_Komf_1"), # Door open, rear right - ("BSK_HD_Hauptraste", "Gate_Komf_1"), # Trunk or hatch open - ("GK1_Blinker_li", "Gate_Komf_1"), # Left turn signal on - ("GK1_Blinker_re", "Gate_Komf_1"), # Right turn signal on - ("Bremsinfo", "Kombi_1"), # Manual handbrake applied - ("GRA_Hauptschalt", "GRA_Neu"), # ACC button, on/off - ("GRA_Typ_Hauptschalt", "GRA_Neu"), # ACC button, momentary vs latching - ("GRA_Kodierinfo", "GRA_Neu"), # ACC button, configuration - ("GRA_Abbrechen", "GRA_Neu"), # ACC button, cancel - ("GRA_Neu_Setzen", "GRA_Neu"), # ACC button, set - ("GRA_Up_lang", "GRA_Neu"), # ACC button, increase or accel, long press - ("GRA_Down_lang", "GRA_Neu"), # ACC button, decrease or decel, long press - ("GRA_Up_kurz", "GRA_Neu"), # ACC button, increase or accel, short press - ("GRA_Down_kurz", "GRA_Neu"), # ACC button, decrease or decel, short press - ("GRA_Recall", "GRA_Neu"), # ACC button, resume - ("GRA_Zeitluecke", "GRA_Neu"), # ACC button, time gap adj - ("COUNTER", "GRA_Neu"), # ACC button, message counter - ("GRA_Sender", "GRA_Neu"), # ACC button, CAN message originator - ] - - checks = [ + messages = [ # sig_address, frequency ("Bremse_1", 100), # From J104 ABS/ESP controller ("Bremse_3", 100), # From J104 ABS/ESP controller @@ -440,95 +326,55 @@ class CarState(CarStateBase): ] if CP.transmissionType == TransmissionType.automatic: - signals += [("Waehlhebelposition__Getriebe_1_", "Getriebe_1", 0)] # Auto trans gear selector position - checks += [("Getriebe_1", 100)] # From J743 Auto transmission control module + messages += [("Getriebe_1", 100)] # From J743 Auto transmission control module elif CP.transmissionType == TransmissionType.manual: - signals += [("Kupplungsschalter", "Motor_1", 0), # Clutch switch - ("GK1_Rueckfahr", "Gate_Komf_1", 0)] # Reverse light from BCM - checks += [("Motor_1", 100)] # From J623 Engine control module + messages += [("Motor_1", 100)] # From J623 Engine control module if CP.networkLocation == NetworkLocation.fwdCamera: # Extended CAN devices other than the camera are here on CANBUS.pt - signals += PqExtraSignals.fwd_radar_signals - checks += PqExtraSignals.fwd_radar_checks + messages += PqExtraSignals.fwd_radar_messages if CP.enableBsm: - signals += PqExtraSignals.bsm_radar_signals - checks += PqExtraSignals.bsm_radar_checks + messages += PqExtraSignals.bsm_radar_messages - return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, CANBUS.pt) + return CANParser(DBC[CP.carFingerprint]["pt"], messages, CANBUS.pt) @staticmethod def get_cam_can_parser_pq(CP): - signals = [] - checks = [] + messages = [] if CP.networkLocation == NetworkLocation.fwdCamera: - signals += [ - # sig_name, sig_address - ("LDW_SW_Warnung_links", "LDW_Status"), # Blind spot in warning mode on left side due to lane departure - ("LDW_SW_Warnung_rechts", "LDW_Status"), # Blind spot in warning mode on right side due to lane departure - ("LDW_Seite_DLCTLC", "LDW_Status"), # Direction of most likely lane departure (left or right) - ("LDW_DLC", "LDW_Status"), # Lane departure, distance to line crossing - ("LDW_TLC", "LDW_Status"), # Lane departure, time to line crossing - ] - checks += [ + messages += [ # sig_address, frequency ("LDW_Status", 10) # From R242 Driver assistance camera ] if CP.networkLocation == NetworkLocation.gateway: # Radars are here on CANBUS.cam - signals += PqExtraSignals.fwd_radar_signals - checks += PqExtraSignals.fwd_radar_checks + messages += PqExtraSignals.fwd_radar_messages if CP.enableBsm: - signals += PqExtraSignals.bsm_radar_signals - checks += PqExtraSignals.bsm_radar_checks + messages += PqExtraSignals.bsm_radar_messages - return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, CANBUS.cam) + return CANParser(DBC[CP.carFingerprint]["pt"], messages, CANBUS.cam) class MqbExtraSignals: # Additional signal and message lists for optional or bus-portable controllers - fwd_radar_signals = [ - ("ACC_Wunschgeschw_02", "ACC_02"), # ACC set speed - ("ACC_Typ", "ACC_06"), # Basic vs FtS vs SnG - ("AWV2_Freigabe", "ACC_10"), # FCW brake jerk release - ("ANB_Teilbremsung_Freigabe", "ACC_10"), # AEB partial braking release - ("ANB_Zielbremsung_Freigabe", "ACC_10"), # AEB target braking release - ] - fwd_radar_checks = [ + fwd_radar_messages = [ ("ACC_06", 50), # From J428 ACC radar control module ("ACC_10", 50), # From J428 ACC radar control module ("ACC_02", 17), # From J428 ACC radar control module ] - bsm_radar_signals = [ - ("SWA_Infostufe_SWA_li", "SWA_01"), # Blind spot object info, left - ("SWA_Warnung_SWA_li", "SWA_01"), # Blind spot object warning, left - ("SWA_Infostufe_SWA_re", "SWA_01"), # Blind spot object info, right - ("SWA_Warnung_SWA_re", "SWA_01"), # Blind spot object warning, right - ] - bsm_radar_checks = [ + bsm_radar_messages = [ ("SWA_01", 20), # From J1086 Lane Change Assist ] class PqExtraSignals: # Additional signal and message lists for optional or bus-portable controllers - fwd_radar_signals = [ - ("ACS_Typ_ACC", "ACC_System"), # Basic vs FtS (no SnG support on PQ) - ("ACA_StaACC", "ACC_GRA_Anzeige"), # ACC drivetrain coordinator status - ("ACA_V_Wunsch", "ACC_GRA_Anzeige"), # ACC set speed - ] - fwd_radar_checks = [ + fwd_radar_messages = [ ("ACC_System", 50), # From J428 ACC radar control module ("ACC_GRA_Anzeige", 25), # From J428 ACC radar control module ] - bsm_radar_signals = [ - ("SWA_Infostufe_SWA_li", "SWA_1"), # Blind spot object info, left - ("SWA_Warnung_SWA_li", "SWA_1"), # Blind spot object warning, left - ("SWA_Infostufe_SWA_re", "SWA_1"), # Blind spot object info, right - ("SWA_Warnung_SWA_re", "SWA_1"), # Blind spot object warning, right - ] - bsm_radar_checks = [ + bsm_radar_messages = [ ("SWA_1", 20), # From J1086 Lane Change Assist ] diff --git a/selfdrive/car/volkswagen/values.py b/selfdrive/car/volkswagen/values.py index 3a6ed0e30..bc129f79c 100755 --- a/selfdrive/car/volkswagen/values.py +++ b/selfdrive/car/volkswagen/values.py @@ -458,6 +458,7 @@ FW_VERSIONS = { b'\xf1\x878V0906259H \xf1\x890002', b'\xf1\x878V0906259J \xf1\x890003', b'\xf1\x878V0906259K \xf1\x890001', + b'\xf1\x878V0906259K \xf1\x890003', b'\xf1\x878V0906259P \xf1\x890001', b'\xf1\x878V0906259Q \xf1\x890002', b'\xf1\x878V0906264F \xf1\x890003', @@ -486,6 +487,7 @@ FW_VERSIONS = { b'\xf1\x870D9300012 \xf1\x894913', b'\xf1\x870D9300012 \xf1\x894937', b'\xf1\x870D9300012 \xf1\x895045', + b'\xf1\x870D9300012 \xf1\x895046', b'\xf1\x870D9300014M \xf1\x895004', b'\xf1\x870D9300014Q \xf1\x895006', b'\xf1\x870D9300020J \xf1\x894902', @@ -953,6 +955,7 @@ FW_VERSIONS = { b'\xf1\x875G0906259D \xf1\x890002', b'\xf1\x875G0906259L \xf1\x890002', b'\xf1\x875G0906259Q \xf1\x890002', + b'\xf1\x878V0906259E \xf1\x890001', b'\xf1\x878V0906259F \xf1\x890002', b'\xf1\x878V0906259H \xf1\x890002', b'\xf1\x878V0906259J \xf1\x890002', @@ -967,6 +970,7 @@ FW_VERSIONS = { b'\xf1\x870CW300048 \xf1\x895201', b'\xf1\x870D9300012 \xf1\x894912', b'\xf1\x870D9300012 \xf1\x894931', + b'\xf1\x870D9300012L \xf1\x894521', b'\xf1\x870D9300012K \xf1\x894513', b'\xf1\x870D9300013B \xf1\x894902', b'\xf1\x870D9300013B \xf1\x894931', @@ -997,6 +1001,7 @@ FW_VERSIONS = { b'\xf1\x875Q0959655N \xf1\x890361\xf1\x82\0211212001112111104110411111521159114', ], (Ecu.eps, 0x712, None): [ + b'\xf1\x873Q0909144F \xf1\x895043\xf1\x82\x0561G01A13A0', b'\xf1\x873Q0909144H \xf1\x895061\xf1\x82\00566G0HA14A1', b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566G0HA14A1', b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571G01A16A1', @@ -1012,6 +1017,7 @@ FW_VERSIONS = { b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\00521G00807A1', ], (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x875Q0907567M \xf1\x890398\xf1\x82\x0101', b'\xf1\x875Q0907567N \xf1\x890400\xf1\x82\x0101', b'\xf1\x875Q0907572F \xf1\x890400\xf1\x82\x0101', b'\xf1\x875Q0907572D \xf1\x890304\xf1\x82\x0101', diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 432e9c20a..5a2c9c97a 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -43,8 +43,6 @@ NOSENSOR = "NOSENSOR" in os.environ IGNORE_PROCESSES = {"loggerd", "encoderd", "statsd"} # dp related processes IGNORE_PROCESSES.update({"mapd", "otisserv", "fileserv", "gpxd", "gpx_uploader"}) -if dp_device_dm_unavailable: - IGNORE_PROCESSES.update({"dmonitoringd", "dmonitoringmodeld"}) ThermalStatus = log.DeviceState.ThermalStatus State = log.ControlsState.OpenpilotState @@ -103,8 +101,6 @@ class Controls: ignore = ['testJoystick'] if SIMULATION: ignore += ['driverCameraState', 'managerState'] - if dp_device_dm_unavailable: - ignore += ['driverMonitoringState'] self.sm = messaging.SubMaster(['deviceState', 'pandaStates', 'peripheralState', 'modelV2', 'liveCalibration', 'driverMonitoringState', 'longitudinalPlan', 'lateralPlan', 'liveLocationKalman', 'managerState', 'liveParameters', 'radarState', 'liveTorqueParameters', 'testJoystick', 'longitudinalPlanExt'] + self.camera_packets, @@ -304,7 +300,7 @@ class Controls: if CS.gasPressed: self.events.add(EventName.gasPressedOverride) - if not dp_device_dm_unavailable and not self.CP.notCar: + if not self.CP.notCar: self.events.add_from_msg(self.sm['driverMonitoringState'].events) # Add car events, ignore if CAN isn't valid @@ -410,7 +406,7 @@ class Controls: # generic catch-all. ideally, a more specific event should be added above instead can_rcv_timeout = self.can_rcv_timeout_counter >= 5 - has_disable_events = self.events.any(ET.NO_ENTRY) and (self.events.any(ET.SOFT_DISABLE) or self.events.any(ET.IMMEDIATE_DISABLE)) + has_disable_events = self.events.contains(ET.NO_ENTRY) and (self.events.contains(ET.SOFT_DISABLE) or self.events.contains(ET.IMMEDIATE_DISABLE)) no_system_errors = (not has_disable_events) or (len(self.events) == num_events) if (not self.sm.all_checks() or can_rcv_timeout) and no_system_errors: if not self.sm.all_alive(): @@ -546,29 +542,29 @@ class Controls: # ENABLED, SOFT DISABLING, PRE ENABLING, OVERRIDING if self.state != State.disabled: # user and immediate disable always have priority in a non-disabled state - if self.events.any(ET.USER_DISABLE): + if self.events.contains(ET.USER_DISABLE): self.state = State.disabled self.current_alert_types.append(ET.USER_DISABLE) - elif self.events.any(ET.IMMEDIATE_DISABLE): + elif self.events.contains(ET.IMMEDIATE_DISABLE): self.state = State.disabled self.current_alert_types.append(ET.IMMEDIATE_DISABLE) else: # ENABLED if self.state == State.enabled: - if self.events.any(ET.SOFT_DISABLE): + if self.events.contains(ET.SOFT_DISABLE): self.state = State.softDisabling self.soft_disable_timer = int(SOFT_DISABLE_TIME / DT_CTRL) self.current_alert_types.append(ET.SOFT_DISABLE) - elif self.events.any(ET.OVERRIDE_LATERAL) or self.events.any(ET.OVERRIDE_LONGITUDINAL): + elif self.events.contains(ET.OVERRIDE_LATERAL) or self.events.contains(ET.OVERRIDE_LONGITUDINAL): self.state = State.overriding self.current_alert_types += [ET.OVERRIDE_LATERAL, ET.OVERRIDE_LONGITUDINAL] # SOFT DISABLING elif self.state == State.softDisabling: - if not self.events.any(ET.SOFT_DISABLE): + if not self.events.contains(ET.SOFT_DISABLE): # no more soft disabling condition, so go back to ENABLED self.state = State.enabled @@ -580,32 +576,32 @@ class Controls: # PRE ENABLING elif self.state == State.preEnabled: - if not self.events.any(ET.PRE_ENABLE): + if not self.events.contains(ET.PRE_ENABLE): self.state = State.enabled else: self.current_alert_types.append(ET.PRE_ENABLE) # OVERRIDING elif self.state == State.overriding: - if self.events.any(ET.SOFT_DISABLE): + if self.events.contains(ET.SOFT_DISABLE): self.state = State.softDisabling self.soft_disable_timer = int(SOFT_DISABLE_TIME / DT_CTRL) self.current_alert_types.append(ET.SOFT_DISABLE) - elif not (self.events.any(ET.OVERRIDE_LATERAL) or self.events.any(ET.OVERRIDE_LONGITUDINAL)): + elif not (self.events.contains(ET.OVERRIDE_LATERAL) or self.events.contains(ET.OVERRIDE_LONGITUDINAL)): self.state = State.enabled else: self.current_alert_types += [ET.OVERRIDE_LATERAL, ET.OVERRIDE_LONGITUDINAL] # DISABLED elif self.state == State.disabled: - if self.events.any(ET.ENABLE): - if self.events.any(ET.NO_ENTRY): + if self.events.contains(ET.ENABLE): + if self.events.contains(ET.NO_ENTRY): self.current_alert_types.append(ET.NO_ENTRY) else: - if self.events.any(ET.PRE_ENABLE): + if self.events.contains(ET.PRE_ENABLE): self.state = State.preEnabled - elif self.events.any(ET.OVERRIDE_LATERAL) or self.events.any(ET.OVERRIDE_LONGITUDINAL): + elif self.events.contains(ET.OVERRIDE_LATERAL) or self.events.contains(ET.OVERRIDE_LONGITUDINAL): self.state = State.overriding else: self.state = State.enabled @@ -644,7 +640,7 @@ class Controls: standstill = CS.vEgo <= max(self.CP.minSteerSpeed, MIN_LATERAL_CONTROL_SPEED) or CS.standstill CC.latActive = self.active and not CS.steerFaultTemporary and not CS.steerFaultPermanent and \ (not standstill or self.joystick_mode) - CC.longActive = self.enabled and not self.events.any(ET.OVERRIDE_LONGITUDINAL) and self.CP.openpilotLongitudinalControl + CC.longActive = self.enabled and not self.events.contains(ET.OVERRIDE_LONGITUDINAL) and self.CP.openpilotLongitudinalControl if not self.read_only and self.initialized and self._dp_alka and self._dp_alka_active and not standstill and CS.cruiseState.available: if self.sm['liveCalibration'].calStatus != log.LiveCalibrationData.Status.calibrated: @@ -822,7 +818,7 @@ class Controls: else: self.steer_limited = abs(CC.actuators.steer - CC.actuatorsOutput.steer) > 1e-2 - force_decel = (not dp_device_dm_unavailable and self.sm['driverMonitoringState'].awarenessStatus < 0.) or \ + force_decel = (self.sm['driverMonitoringState'].awarenessStatus < 0.) or \ (self.state == State.softDisabling) # Curvature & Steering angle @@ -852,7 +848,7 @@ class Controls: controlsState.desiredCurvature = self.desired_curvature controlsState.desiredCurvatureRate = self.desired_curvature_rate controlsState.state = self.state - controlsState.engageable = not self.events.any(ET.NO_ENTRY) + controlsState.engageable = not self.events.contains(ET.NO_ENTRY) controlsState.longControlState = self.LoC.long_control_state controlsState.vPid = float(self.LoC.v_pid) controlsState.vCruise = float(self.v_cruise_helper.v_cruise_kph) diff --git a/selfdrive/controls/lib/desire_helper.py b/selfdrive/controls/lib/desire_helper.py index 4652b41c1..f4773a020 100644 --- a/selfdrive/controls/lib/desire_helper.py +++ b/selfdrive/controls/lib/desire_helper.py @@ -40,7 +40,7 @@ class DesireHelper: self.prev_one_blinker = False self.desire = log.LateralPlan.Desire.none - def update(self, carstate, lateral_active, lane_change_prob): + def update(self, carstate, lateral_active, lane_change_prob, edge_detected_left, edge_detected_right): v_ego = carstate.vEgo one_blinker = carstate.leftBlinker != carstate.rightBlinker below_lane_change_speed = v_ego < LANE_CHANGE_SPEED_MIN @@ -64,8 +64,8 @@ class DesireHelper: ((carstate.steeringTorque > 0 and self.lane_change_direction == LaneChangeDirection.left) or (carstate.steeringTorque < 0 and self.lane_change_direction == LaneChangeDirection.right)) - blindspot_detected = ((carstate.leftBlindspot and self.lane_change_direction == LaneChangeDirection.left) or - (carstate.rightBlindspot and self.lane_change_direction == LaneChangeDirection.right)) + blindspot_detected = (((edge_detected_left or carstate.leftBlindspot) and self.lane_change_direction == LaneChangeDirection.left) or + ((edge_detected_right or carstate.rightBlindspot) and self.lane_change_direction == LaneChangeDirection.right)) if not one_blinker or below_lane_change_speed: self.lane_change_state = LaneChangeState.off diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index ce8a74270..6cfdac1cc 100755 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -72,7 +72,7 @@ class Events: self.events_prev = {k: (v + 1 if k in self.events else 0) for k, v in self.events_prev.items()} self.events = self.static_events.copy() - def any(self, event_type: str) -> bool: + def contains(self, event_type: str) -> bool: return any(event_type in EVENTS.get(e, {}) for e in self.events) def create_alerts(self, event_types: List[str], callback_args=None): diff --git a/selfdrive/controls/lib/lateral_mpc_lib/acados_ocp_lat.json b/selfdrive/controls/lib/lateral_mpc_lib/acados_ocp_lat.json index 50634e948..4690040e2 100644 --- a/selfdrive/controls/lib/lateral_mpc_lib/acados_ocp_lat.json +++ b/selfdrive/controls/lib/lateral_mpc_lib/acados_ocp_lat.json @@ -91,124 +91,11 @@ "usphi_e": [] }, "cost": { - "Vu": [ - [ - 0.0 - ], - [ - 0.0 - ], - [ - 0.0 - ], - [ - 0.0 - ], - [ - 0.0 - ] - ], - "Vu_0": [ - [ - 0.0 - ], - [ - 0.0 - ], - [ - 0.0 - ], - [ - 0.0 - ], - [ - 0.0 - ] - ], - "Vx": [ - [ - 0.0, - 0.0, - 0.0, - 0.0 - ], - [ - 0.0, - 0.0, - 0.0, - 0.0 - ], - [ - 0.0, - 0.0, - 0.0, - 0.0 - ], - [ - 0.0, - 0.0, - 0.0, - 0.0 - ], - [ - 0.0, - 0.0, - 0.0, - 0.0 - ] - ], - "Vx_0": [ - [ - 0.0, - 0.0, - 0.0, - 0.0 - ], - [ - 0.0, - 0.0, - 0.0, - 0.0 - ], - [ - 0.0, - 0.0, - 0.0, - 0.0 - ], - [ - 0.0, - 0.0, - 0.0, - 0.0 - ], - [ - 0.0, - 0.0, - 0.0, - 0.0 - ] - ], - "Vx_e": [ - [ - 0.0, - 0.0, - 0.0, - 0.0 - ], - [ - 0.0, - 0.0, - 0.0, - 0.0 - ], - [ - 0.0, - 0.0, - 0.0, - 0.0 - ] - ], + "Vu": [], + "Vu_0": [], + "Vx": [], + "Vx_0": [], + "Vx_e": [], "Vz": [], "Vz_0": [], "W": [ @@ -336,7 +223,10 @@ "zu": [], "zu_e": [] }, - "cython_include_dirs": "/usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/core/include", + "cython_include_dirs": [ + "/usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/core/include", + "/usr/local/pyenv/versions/3.11.4/include/python3.11" + ], "dims": { "N": 32, "nbu": 0, @@ -371,73 +261,74 @@ "ny_e": 3, "nz": 0 }, + "json_file": "/data/openpilot/selfdrive/controls/lib/lateral_mpc_lib/acados_ocp_lat.json", "model": { + "con_h_expr": null, + "con_h_expr_e": null, + "con_phi_expr": null, + "con_phi_expr_e": null, + "con_r_expr": null, + "con_r_expr_e": null, + "con_r_in_phi": null, + "con_r_in_phi_e": null, + "cost_conl_custom_outer_hess": null, + "cost_conl_custom_outer_hess_0": null, + "cost_conl_custom_outer_hess_e": null, + "cost_expr_ext_cost": null, + "cost_expr_ext_cost_0": null, + "cost_expr_ext_cost_custom_hess": null, + "cost_expr_ext_cost_custom_hess_0": null, + "cost_expr_ext_cost_custom_hess_e": null, + "cost_expr_ext_cost_e": null, + "cost_psi_expr": null, + "cost_psi_expr_0": null, + "cost_psi_expr_e": null, + "cost_r_in_psi_expr": null, + "cost_r_in_psi_expr_0": null, + "cost_r_in_psi_expr_e": null, + "cost_y_expr": "jhpnnagiieahaaaadaaaaaaaaaaaaaaaaaegjaaaaaaaaaaaaaaafaaaaaaaaaaaaaaabaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaafaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaabaaaaaaaaaaaaaaacaaaaaaaaaaaaaaadaaaaaaaaaaaaaaaeaaaaaaaaaaaaaaafaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaafaaaaaaajhpffghgpgegdaaaaaaaaaaaaaaaegbaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaafaaaaaaaghpffghgpgegmcaaaaaaaaaaaaaajgkaaaaaaaegpcaaaaaaaaaaaaaahaaaaaaaahdhjgpffghgpgegdaaaaaaaaaaaaaaacheaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaamaaaaaaaahdhjgpfchbgehfgpffghgpgegdaaaaaaaaaaaaaaacheaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaanaaaaaaaahdhjgpfbgdgdgfgmgpffghgpgegeaaaaaaaaaaaaaaachjaaaaaaaaaaaaaaaegbaaaaaaaaaaaaaaachcaaaaaaaaaaaaaaaegmcaaaaaaaaaaaaaachkjjjjjjjjjjjjlpd", + "cost_y_expr_0": "jhpnnagiieahaaaadaaaaaaaaaaaaaaaaaegjaaaaaaaaaaaaaaafaaaaaaaaaaaaaaabaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaafaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaabaaaaaaaaaaaaaaacaaaaaaaaaaaaaaadaaaaaaaaaaaaaaaeaaaaaaaaaaaaaaafaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaafaaaaaaajhpffghgpgegdaaaaaaaaaaaaaaaegbaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaafaaaaaaaghpffghgpgegmcaaaaaaaaaaaaaajgkaaaaaaaegpcaaaaaaaaaaaaaahaaaaaaaahdhjgpffghgpgegdaaaaaaaaaaaaaaacheaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaamaaaaaaaahdhjgpfchbgehfgpffghgpgegdaaaaaaaaaaaaaaacheaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaanaaaaaaaahdhjgpfbgdgdgfgmgpffghgpgegeaaaaaaaaaaaaaaachjaaaaaaaaaaaaaaaegbaaaaaaaaaaaaaaachcaaaaaaaaaaaaaaaegmcaaaaaaaaaaaaaachkjjjjjjjjjjjjlpd", + "cost_y_expr_e": "jhpnnagiieahaaaadaaaaaaaaaaaaaaaaaeghaaaaaaaaaaaaaaadaaaaaaaaaaaaaaabaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaadaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaabaaaaaaaaaaaaaaacaaaaaaaaaaaaaaadaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaafaaaaaaajhpffghgpgegdaaaaaaaaaaaaaaaegbaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaafaaaaaaaghpffghgpgegmcaaaaaaaaaaaaaajgkaaaaaaaegpcaaaaaaaaaaaaaahaaaaaaaahdhjgpffghgpgegdaaaaaaaaaaaaaaacheaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaamaaaaaaaahdhjgpfchbgehfgpffghgpg", + "disc_dyn_expr": null, "dyn_disc_fun": null, "dyn_disc_fun_jac": null, "dyn_disc_fun_jac_hess": null, "dyn_ext_fun_type": "casadi", - "dyn_source_discrete": null, + "dyn_generic_source": null, + "f_expl_expr": "jhpnnagiieahaaaadaaaaaaaaaaaaaaaaaegiaaaaaaaaaaaaaaaeaaaaaaaaaaaaaaabaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaeaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaabaaaaaaaaaaaaaaacaaaaaaaaaaaaaaadaaaaaaaaaaaaaaaeaaaaaaaaaaaaaaaegcaaaaaaaaaaaaaaaegdaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaafaaaaaaaghpffghgpgegoaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaahaaaaaaaahdhjgpffghgpgegdaaaaaaaaaaaaaaaegdaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaapaaaaaaachpgehbgehjgpgogpfchbgegjgfhdhegnaaaaaaaaaaaaaaachcaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaamaaaaaaaahdhjgpfchbgehfgpffghgpgegbaaaaaaaaaaaaaaaegdaaaaaaaaaaaaaaachbaaaaaaaaaaaaaaaegnaaaaaaaaaaaaaaachcaaaaaaaaaaaaaaaegdaaaaaaaaaaaaaaaegdaaaaaaaaaaaaaaachfaaaaaaaaaaaaaaaegoaaaaaaaaaaaaaaachcaaaaaaaaaaaaaaachiaaaaaaaaaaaaaaachiaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaanaaaaaaaahdhjgpfbgdgdgfgmgpffghgpg", + "f_impl_expr": "jhpnnagiieahaaaadaaaaaaaaaaaaaaaaaegiaaaaaaaaaaaaaaaeaaaaaaaaaaaaaaabaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaeaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaabaaaaaaaaaaaaaaacaaaaaaaaaaaaaaadaaaaaaaaaaaaaaaeaaaaaaaaaaaaaaaegcaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaajaaaaaaaihpffghgpgpfegpgehegcaaaaaaaaaaaaaaaegdaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaafaaaaaaaghpffghgpgegoaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaahaaaaaaaahdhjgpffghgpgegdaaaaaaaaaaaaaaaegdaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaapaaaaaaachpgehbgehjgpgogpfchbgegjgfhdhegnaaaaaaaaaaaaaaachdaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaamaaaaaaaahdhjgpfchbgehfgpffghgpgegcaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaajaaaaaaajhpffghgpgpfegpgehegbaaaaaaaaaaaaaaaegdaaaaaaaaaaaaaaachcaaaaaaaaaaaaaaaegnaaaaaaaaaaaaaaachdaaaaaaaaaaaaaaaegdaaaaaaaaaaaaaaaegdaaaaaaaaaaaaaaachgaaaaaaaaaaaaaaaegoaaaaaaaaaaaaaaachdaaaaaaaaaaaaaaachjaaaaaaaaaaaaaaaegcaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaalaaaaaaaahdhjgpffghgpgpfegpgehchjaaaaaaaaaaaaaaaegcaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaaabaaaaaaahdhjgpfchbgehfgpffghgpgpfegpgehegpcaaaaaaaaaaaaaanaaaaaaaahdhjgpfbgdgdgfgmgpffghgpg", "gnsf": { "nontrivial_f_LO": 1, "purely_linear": 0 }, - "name": "lat" + "name": "lat", + "p": "jhpnnagiieahaaaadaaaaaaaaaaaaaaaaaeggaaaaaaaaaaaaaaacaaaaaaaaaaaaaaabaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaacaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaabaaaaaaaaaaaaaaacaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaafaaaaaaaghpffghgpgegpcaaaaaaaaaaaaaapaaaaaaachpgehbgehjgpgogpfchbgegjgfhdh", + "u": "jhpnnagiieahaaaadaaaaaaaaaaaaaaaaaegfaaaaaaaaaaaaaaabaaaaaaaaaaaaaaabaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaabaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaabaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaanaaaaaaaahdhjgpfbgdgdgfgmgpffghgpg", + "x": "jhpnnagiieahaaaadaaaaaaaaaaaaaaaaaegiaaaaaaaaaaaaaaaeaaaaaaaaaaaaaaabaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaeaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaabaaaaaaaaaaaaaaacaaaaaaaaaaaaaaadaaaaaaaaaaaaaaaeaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaafaaaaaaaihpffghgpgegpcaaaaaaaaaaaaaafaaaaaaajhpffghgpgegpcaaaaaaaaaaaaaahaaaaaaaahdhjgpffghgpgegpcaaaaaaaaaaaaaamaaaaaaaahdhjgpfchbgehfgpffghgpg", + "xdot": "jhpnnagiieahaaaadaaaaaaaaaaaaaaaaaegiaaaaaaaaaaaaaaaeaaaaaaaaaaaaaaabaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaeaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaabaaaaaaaaaaaaaaacaaaaaaaaaaaaaaadaaaaaaaaaaaaaaaeaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaajaaaaaaaihpffghgpgpfegpgehegpcaaaaaaaaaaaaaajaaaaaaajhpffghgpgpfegpgehegpcaaaaaaaaaaaaaalaaaaaaaahdhjgpffghgpgpfegpgehegpcaaaaaaaaaaaaaaabaaaaaaahdhjgpfchbgehfgpffghgpgpfegpgeh", + "z": "jhpnnagiieahaaaadaaaaaaaaaaaaaaaaaegdaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaa" }, "parameter_values": [ 0.0, 0.0 ], "problem_class": "OCP", - "simulink_opts": { - "inputs": { - "cost_W": 0, - "cost_W_0": 0, - "cost_W_e": 0, - "lbu": 1, - "lbx": 1, - "lbx_0": 1, - "lbx_e": 1, - "lg": 1, - "lh": 1, - "parameter_traj": 1, - "reset_solver": 0, - "u_init": 0, - "ubu": 1, - "ubx": 1, - "ubx_0": 1, - "ubx_e": 1, - "ug": 1, - "uh": 1, - "x_init": 0, - "y_ref": 1, - "y_ref_0": 1, - "y_ref_e": 1 - }, - "outputs": { - "CPU_time": 1, - "CPU_time_lin": 0, - "CPU_time_qp": 0, - "CPU_time_sim": 0, - "KKT_residual": 1, - "solver_status": 1, - "sqp_iter": 1, - "u0": 1, - "utraj": 0, - "x1": 1, - "xtraj": 0 - }, - "samplingtime": "t0" - }, + "shared_lib_ext": ".so", "solver_options": { "Tsim": 0.009765625, "alpha_min": 0.05, "alpha_reduction": 0.7, "collocation_type": "GAUSS_LEGENDRE", + "custom_templates": [], + "custom_update_copy": true, + "custom_update_filename": "", + "custom_update_header_filename": "", "eps_sufficient_descent": 0.0001, "exact_hess_constr": 1, "exact_hess_cost": 1, "exact_hess_dyn": 1, "ext_cost_num_hess": 0, + "ext_fun_compile_flags": "-O2", "full_step_dual": 0, "globalization": "FIXED_STEP", "globalization_use_SOC": 0, @@ -449,6 +340,7 @@ "line_search_use_sufficient_descent": 0, "model_external_shared_lib_dir": null, "model_external_shared_lib_name": null, + "nlp_solver_ext_qp_res": 0, "nlp_solver_max_iter": 100, "nlp_solver_step_length": 1.0, "nlp_solver_tol_comp": 1e-06, @@ -459,13 +351,50 @@ "print_level": 0, "qp_solver": "PARTIAL_CONDENSING_HPIPM", "qp_solver_cond_N": 1, + "qp_solver_cond_ric_alg": 1, "qp_solver_iter_max": 1, + "qp_solver_ric_alg": 1, "qp_solver_tol_comp": null, "qp_solver_tol_eq": null, "qp_solver_tol_ineq": null, "qp_solver_tol_stat": null, "qp_solver_warm_start": 0, "regularize_method": null, + "shooting_nodes": [ + 0.0, + 0.009765625, + 0.0390625, + 0.087890625, + 0.15625, + 0.244140625, + 0.3515625, + 0.478515625, + 0.625, + 0.791015625, + 0.9765625, + 1.181640625, + 1.40625, + 1.650390625, + 1.9140625, + 2.197265625, + 2.5, + 2.822265625, + 3.1640625, + 3.525390625, + 3.90625, + 4.306640625, + 4.7265625, + 5.166015625, + 5.625, + 6.103515625, + 6.6015625, + 7.119140625, + 7.65625, + 8.212890625, + 8.7890625, + 9.384765625, + 10.0 + ], "sim_method_jac_reuse": [ 0, 0, @@ -501,6 +430,7 @@ 0 ], "sim_method_newton_iter": 3, + "sim_method_newton_tol": 0.0, "sim_method_num_stages": [ 4, 4, diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/Makefile b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/Makefile index 86b79d437..7520bcda1 100644 --- a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/Makefile +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/Makefile @@ -1,8 +1,5 @@ # -# Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, -# Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, -# Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, -# Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl +# Copyright (c) The acados authors. # # This file is part of acados. # @@ -41,6 +38,7 @@ MODEL_SRC= MODEL_SRC+= lat_model/lat_expl_ode_fun.c MODEL_SRC+= lat_model/lat_expl_vde_forw.c +MODEL_SRC+= lat_model/lat_expl_vde_adj.c MODEL_OBJ := $(MODEL_SRC:.c=.o) # optimal control problem - mostly CasADi exports @@ -54,6 +52,7 @@ OCP_SRC+= lat_cost/lat_cost_y_hess.c OCP_SRC+= lat_cost/lat_cost_y_e_fun.c OCP_SRC+= lat_cost/lat_cost_y_e_fun_jac_ut_xt.c OCP_SRC+= lat_cost/lat_cost_y_e_hess.c + OCP_SRC+= acados_solver_lat.c OCP_OBJ := $(OCP_SRC:.c=.o) @@ -91,7 +90,7 @@ CPPFLAGS+= -I$(INCLUDE_PATH)/hpipm/include # define the c-compiler flags for make's implicit rules -CFLAGS = -fPIC -std=c99 #-fno-diagnostics-show-line-numbers -g +CFLAGS = -fPIC -std=c99 -O2#-fno-diagnostics-show-line-numbers -g # # Debugging # CFLAGS += -g3 @@ -148,11 +147,11 @@ ocp_cython_o: ocp_cython_c $(CC) $(ACADOS_FLAGS) -c -O2 \ -fPIC \ -o acados_ocp_solver_pyx.o \ - -I /usr/include/python3.8 \ -I $(INCLUDE_PATH)/blasfeo/include/ \ -I $(INCLUDE_PATH)/hpipm/include/ \ -I $(INCLUDE_PATH) \ -I /usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/core/include \ + -I /usr/local/pyenv/versions/3.11.4/include/python3.11 \ acados_ocp_solver_pyx.c \ ocp_cython: ocp_cython_o @@ -163,6 +162,33 @@ ocp_cython: ocp_cython_o $(abspath .)/libacados_ocp_solver_lat.so \ $(LDFLAGS) $(LDLIBS) +# Sim Cython targets +sim_cython_c: sim_shared_lib + cython \ + -o acados_sim_solver_pyx.c \ + -I $(INCLUDE_PATH)/../interfaces/acados_template/acados_template \ + $(INCLUDE_PATH)/../interfaces/acados_template/acados_template/acados_sim_solver_pyx.pyx \ + -I /data/openpilot/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code \ + +sim_cython_o: sim_cython_c + $(CC) $(ACADOS_FLAGS) -c -O2 \ + -fPIC \ + -o acados_sim_solver_pyx.o \ + -I $(INCLUDE_PATH)/blasfeo/include/ \ + -I $(INCLUDE_PATH)/hpipm/include/ \ + -I $(INCLUDE_PATH) \ + -I /usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/core/include \ + -I /usr/local/pyenv/versions/3.11.4/include/python3.11 \ + acados_sim_solver_pyx.c \ + +sim_cython: sim_cython_o + $(CC) $(ACADOS_FLAGS) -shared \ + -o acados_sim_solver_pyx.so \ + -Wl,-rpath=$(LIB_PATH) \ + acados_sim_solver_pyx.o \ + $(abspath .)/libacados_sim_solver_lat.so \ + $(LDFLAGS) $(LDLIBS) + clean: $(RM) $(OBJ) $(EX_OBJ) $(EX_SIM_OBJ) $(RM) $(LIBACADOS_SOLVER) $(LIBACADOS_OCP_SOLVER) $(LIBACADOS_SIM_SOLVER) @@ -177,3 +203,9 @@ clean_ocp_cython: $(RM) acados_solver_lat.o $(RM) acados_ocp_solver_pyx.so $(RM) acados_ocp_solver_pyx.o + +clean_sim_cython: + $(RM) libacados_sim_solver_lat.so + $(RM) acados_sim_solver_lat.o + $(RM) acados_sim_solver_pyx.so + $(RM) acados_sim_solver_pyx.o diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_ocp_solver_pyx.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_ocp_solver_pyx.c index d3fc080e2..09ac88d0c 100644 --- a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_ocp_solver_pyx.c +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_ocp_solver_pyx.c @@ -1781,7 +1781,7 @@ typedef npy_clongdouble __pyx_t_5numpy_clongdouble_t; */ typedef npy_cdouble __pyx_t_5numpy_complex_t; -/* "acados_template/acados_ocp_solver_pyx.pyx":52 +/* "acados_template/acados_ocp_solver_pyx.pyx":49 * * * cdef class AcadosOcpSolverCython: # <<<<<<<<<<<<<< @@ -1798,7 +1798,6 @@ struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython ocp_nlp_out *sens_out; ocp_nlp_in *nlp_in; ocp_nlp_solver *nlp_solver; - int status; int solver_created; PyObject *model_name; int N; @@ -2479,6 +2478,12 @@ static PyObject* __Pyx_ImportFrom(PyObject* module, PyObject* name); /* HasAttr.proto */ static CYTHON_INLINE int __Pyx_HasAttr(PyObject *, PyObject *); +/* PyIntCompare.proto */ +static CYTHON_INLINE int __Pyx_PyInt_BoolEqObjC(PyObject *op1, PyObject *op2, long intval, long inplace); + +/* PyIntCompare.proto */ +static CYTHON_INLINE int __Pyx_PyInt_BoolNeObjC(PyObject *op1, PyObject *op2, long intval, long inplace); + /* IsLittleEndian.proto */ static CYTHON_INLINE int __Pyx_Is_Little_Endian(void); @@ -2528,6 +2533,56 @@ static CYTHON_INLINE PyObject* __Pyx_PyObject_GetSlice( #define __Pyx_PyObject_Str(obj)\ (likely(PyString_CheckExact(obj)) ? __Pyx_NewRef(obj) : PyObject_Str(obj)) +/* PyObjectFormat.proto */ +#if CYTHON_USE_UNICODE_WRITER +static PyObject* __Pyx_PyObject_Format(PyObject* s, PyObject* f); +#else +#define __Pyx_PyObject_Format(s, f) PyObject_Format(s, f) +#endif + +/* py_dict_keys.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyDict_Keys(PyObject* d); + +/* UnpackUnboundCMethod.proto */ +typedef struct { + PyObject *type; + PyObject **method_name; + PyCFunction func; + PyObject *method; + int flag; +} __Pyx_CachedCFunction; + +/* CallUnboundCMethod0.proto */ +static PyObject* __Pyx__CallUnboundCMethod0(__Pyx_CachedCFunction* cfunc, PyObject* self); +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_CallUnboundCMethod0(cfunc, self)\ + (likely((cfunc)->func) ?\ + (likely((cfunc)->flag == METH_NOARGS) ? (*((cfunc)->func))(self, NULL) :\ + (PY_VERSION_HEX >= 0x030600B1 && likely((cfunc)->flag == METH_FASTCALL) ?\ + (PY_VERSION_HEX >= 0x030700A0 ?\ + (*(__Pyx_PyCFunctionFast)(void*)(PyCFunction)(cfunc)->func)(self, &__pyx_empty_tuple, 0) :\ + (*(__Pyx_PyCFunctionFastWithKeywords)(void*)(PyCFunction)(cfunc)->func)(self, &__pyx_empty_tuple, 0, NULL)) :\ + (PY_VERSION_HEX >= 0x030700A0 && (cfunc)->flag == (METH_FASTCALL | METH_KEYWORDS) ?\ + (*(__Pyx_PyCFunctionFastWithKeywords)(void*)(PyCFunction)(cfunc)->func)(self, &__pyx_empty_tuple, 0, NULL) :\ + (likely((cfunc)->flag == (METH_VARARGS | METH_KEYWORDS)) ? ((*(PyCFunctionWithKeywords)(void*)(PyCFunction)(cfunc)->func)(self, __pyx_empty_tuple, NULL)) :\ + ((cfunc)->flag == METH_VARARGS ? (*((cfunc)->func))(self, __pyx_empty_tuple) :\ + __Pyx__CallUnboundCMethod0(cfunc, self)))))) :\ + __Pyx__CallUnboundCMethod0(cfunc, self)) +#else +#define __Pyx_CallUnboundCMethod0(cfunc, self) __Pyx__CallUnboundCMethod0(cfunc, self) +#endif + +/* DictGetItem.proto */ +#if PY_MAJOR_VERSION >= 3 && !CYTHON_COMPILING_IN_PYPY +static PyObject *__Pyx_PyDict_GetItem(PyObject *d, PyObject* key); +#define __Pyx_PyObject_Dict_GetItem(obj, name)\ + (likely(PyDict_CheckExact(obj)) ?\ + __Pyx_PyDict_GetItem(obj, name) : PyObject_GetItem(obj, name)) +#else +#define __Pyx_PyDict_GetItem(d, key) PyObject_GetItem(d, key) +#define __Pyx_PyObject_Dict_GetItem(obj, name) PyObject_GetItem(obj, name) +#endif + /* PyObjectLookupSpecial.proto */ #if CYTHON_USE_PYTYPE_LOOKUP && CYTHON_USE_TYPE_SLOTS #define __Pyx_PyObject_LookupSpecialNoError(obj, attr_name) __Pyx__PyObject_LookupSpecial(obj, attr_name, 0) @@ -2987,15 +3042,15 @@ static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *); /* CIntToPy.proto */ static CYTHON_INLINE PyObject* __Pyx_PyInt_From_int(int value); +/* CIntFromPy.proto */ +static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *); + /* CIntToPy.proto */ static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value); /* CIntFromPy.proto */ static CYTHON_INLINE size_t __Pyx_PyInt_As_size_t(PyObject *); -/* CIntFromPy.proto */ -static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *); - /* CIntFromPy.proto */ static CYTHON_INLINE char __Pyx_PyInt_As_char(PyObject *); @@ -3116,6 +3171,7 @@ static void __pyx_memoryview__slice_assign_scalar(char *, Py_ssize_t *, Py_ssize static PyObject *__pyx_unpickle_Enum__set_state(struct __pyx_MemviewEnum_obj *, PyObject *); /*proto*/ /* #### Code section: typeinfo ### */ static __Pyx_TypeInfo __Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t = { "float64_t", NULL, sizeof(__pyx_t_5numpy_float64_t), { 0 }, 0, 'R', 0, 0 }; +static __Pyx_TypeInfo __Pyx_TypeInfo_nn___pyx_t_5numpy_int32_t = { "int32_t", NULL, sizeof(__pyx_t_5numpy_int32_t), { 0 }, 0, __PYX_IS_UNSIGNED(__pyx_t_5numpy_int32_t) ? 'U' : 'I', __PYX_IS_UNSIGNED(__pyx_t_5numpy_int32_t), 0 }; static __Pyx_TypeInfo __Pyx_TypeInfo_double = { "double", NULL, sizeof(double), { 0 }, 0, 'R', 0, 0 }; static __Pyx_TypeInfo __Pyx_TypeInfo_unsigned_char = { "unsigned char", NULL, sizeof(unsigned char), { 0 }, 0, __PYX_IS_UNSIGNED(unsigned char) ? 'U' : 'I', __PYX_IS_UNSIGNED(unsigned char), 0 }; /* #### Code section: before_global_var ### */ @@ -3126,10 +3182,10 @@ int __pyx_module_is_main_acados_template__acados_ocp_solver_pyx = 0; /* Implementation of "acados_template.acados_ocp_solver_pyx" */ /* #### Code section: global_var ### */ static PyObject *__pyx_builtin_AssertionError; +static PyObject *__pyx_builtin_print; static PyObject *__pyx_builtin_NotImplementedError; static PyObject *__pyx_builtin_range; static PyObject *__pyx_builtin_open; -static PyObject *__pyx_builtin_print; static PyObject *__pyx_builtin_TypeError; static PyObject *__pyx_builtin___import__; static PyObject *__pyx_builtin_ValueError; @@ -3141,12 +3197,15 @@ static PyObject *__pyx_builtin_IndexError; static PyObject *__pyx_builtin_ImportError; /* #### Code section: string_decls ### */ static const char __pyx_k_[] = ": "; +static const char __pyx_k_0[] = "0"; static const char __pyx_k_F[] = "F"; static const char __pyx_k_N[] = "N"; static const char __pyx_k_O[] = "O"; static const char __pyx_k_c[] = "c"; +static const char __pyx_k_d[] = "d"; static const char __pyx_k_f[] = "f"; static const char __pyx_k_i[] = "i"; +static const char __pyx_k_k[] = "k"; static const char __pyx_k_m[] = "m"; static const char __pyx_k_n[] = "n"; static const char __pyx_k_p[] = "p"; @@ -3163,21 +3222,24 @@ static const char __pyx_k__7[] = ")"; static const char __pyx_k_ex[] = "ex"; static const char __pyx_k_gc[] = "gc"; static const char __pyx_k_id[] = "id"; +static const char __pyx_k_lN[] = "lN"; static const char __pyx_k_np[] = "np"; static const char __pyx_k_nx[] = "nx"; static const char __pyx_k_os[] = "os"; static const char __pyx_k_pi[] = "pi"; static const char __pyx_k_sl[] = "sl"; static const char __pyx_k_su[] = "su"; +static const char __pyx_k_u0[] = "u0"; static const char __pyx_k_SQP[] = "SQP"; -static const char __pyx_k__14[] = ""; -static const char __pyx_k__15[] = "_"; -static const char __pyx_k__29[] = ", "; -static const char __pyx_k__84[] = "?"; +static const char __pyx_k__16[] = ""; +static const char __pyx_k__17[] = "_"; +static const char __pyx_k__31[] = ", "; +static const char __pyx_k__94[] = "?"; static const char __pyx_k_abc[] = "abc"; static const char __pyx_k_and[] = " and "; static const char __pyx_k_get[] = "get"; static const char __pyx_k_got[] = " (got "; +static const char __pyx_k_idx[] = "idx"; static const char __pyx_k_int[] = "int"; static const char __pyx_k_key[] = "key"; static const char __pyx_k_lam[] = "lam"; @@ -3198,6 +3260,7 @@ static const char __pyx_k_z_2[] = "z_"; static const char __pyx_k_None[] = "None"; static const char __pyx_k_TODO[] = "TODO!"; static const char __pyx_k_base[] = "base"; +static const char __pyx_k_data[] = "data_"; static const char __pyx_k_dict[] = "__dict__"; static const char __pyx_k_dims[] = "dims"; static const char __pyx_k_dump[] = "dump"; @@ -3234,6 +3297,7 @@ static const char __pyx_k_error[] = "error"; static const char __pyx_k_field[] = "field"; static const char __pyx_k_flags[] = "flags"; static const char __pyx_k_index[] = "index"; +static const char __pyx_k_int32[] = "int32"; static const char __pyx_k_lam_2[] = "lam_"; static const char __pyx_k_numpy[] = "numpy"; static const char __pyx_k_order[] = "order"; @@ -3249,6 +3313,7 @@ static const char __pyx_k_utf_8[] = "utf-8"; static const char __pyx_k_value[] = "value_"; static const char __pyx_k_y_ref[] = "y_ref"; static const char __pyx_k_zeros[] = "zeros"; +static const char __pyx_k_data_2[] = "data"; static const char __pyx_k_enable[] = "enable"; static const char __pyx_k_encode[] = "encode"; static const char __pyx_k_fields[] = "fields"; @@ -3265,12 +3330,14 @@ static const char __pyx_k_reduce[] = "__reduce__"; static const char __pyx_k_res_eq[] = "res_eq"; static const char __pyx_k_stat_m[] = "stat_m"; static const char __pyx_k_stat_n[] = "stat_n"; +static const char __pyx_k_status[] = "status"; static const char __pyx_k_struct[] = "struct"; static const char __pyx_k_tol_eq[] = "tol_eq"; static const char __pyx_k_tolist[] = "tolist"; static const char __pyx_k_unpack[] = "unpack"; static const char __pyx_k_update[] = "update"; static const char __pyx_k_utcnow[] = "utcnow"; +static const char __pyx_k_x0_bar[] = "x0_bar"; static const char __pyx_k_SQP_RTI[] = "SQP_RTI"; static const char __pyx_k_default[] = "default"; static const char __pyx_k_disable[] = "disable"; @@ -3279,6 +3346,7 @@ static const char __pyx_k_float64[] = "float64"; static const char __pyx_k_fortran[] = "fortran"; static const char __pyx_k_iterate[] = "iterate"; static const char __pyx_k_memview[] = "memview"; +static const char __pyx_k_ndarray[] = "ndarray"; static const char __pyx_k_out_mat[] = "out_mat"; static const char __pyx_k_qp_iter[] = "qp_iter"; static const char __pyx_k_time_qp[] = "time_qp"; @@ -3288,12 +3356,15 @@ static const char __pyx_k_Ellipsis[] = "Ellipsis"; static const char __pyx_k_Sequence[] = "Sequence"; static const char __pyx_k_at_stage[] = "\" at stage "; static const char __pyx_k_cost_set[] = "cost_set"; +static const char __pyx_k_data_len[] = "data_len"; static const char __pyx_k_datetime[] = "datetime"; static const char __pyx_k_filename[] = "filename"; static const char __pyx_k_get_cost[] = "get_cost"; static const char __pyx_k_getstate[] = "__getstate__"; +static const char __pyx_k_i_string[] = "i_string"; static const char __pyx_k_itemsize[] = "itemsize"; static const char __pyx_k_min_size[] = "min_size"; +static const char __pyx_k_n_update[] = "n_update"; static const char __pyx_k_pyx_type[] = "__pyx_type"; static const char __pyx_k_register[] = "register"; static const char __pyx_k_res_comp[] = "res_comp"; @@ -3330,6 +3401,7 @@ static const char __pyx_k_time_glob[] = "time_glob"; static const char __pyx_k_IndexError[] = "IndexError"; static const char __pyx_k_ValueError[] = "ValueError"; static const char __pyx_k_full_stats[] = "full_stats"; +static const char __pyx_k_idx_values[] = "idx_values_"; static const char __pyx_k_int_fields[] = "int_fields"; static const char __pyx_k_mem_fields[] = "mem_fields"; static const char __pyx_k_model_name[] = "model_name"; @@ -3354,17 +3426,20 @@ static const char __pyx_k_time_sim_ad[] = "time_sim_ad"; static const char __pyx_k_time_sim_la[] = "time_sim_la"; static const char __pyx_k_value_shape[] = "value_shape"; static const char __pyx_k_double_value[] = "double_value"; -static const char __pyx_k_dynamics_get[] = "dynamics_get"; static const char __pyx_k_get_stat_int[] = "__get_stat_int"; static const char __pyx_k_initializing[] = "_initializing"; static const char __pyx_k_is_coroutine[] = "_is_coroutine"; static const char __pyx_k_load_iterate[] = "load_iterate"; +static const char __pyx_k_param_values[] = "param_values_"; static const char __pyx_k_pyx_checksum[] = "__pyx_checksum"; +static const char __pyx_k_solve_for_x0[] = "solve_for_x0"; static const char __pyx_k_string_value[] = "string_value"; static const char __pyx_k_stringsource[] = ""; static const char __pyx_k_version_info[] = "version_info"; +static const char __pyx_k_Got_sizes_idx[] = " Got sizes idx "; static const char __pyx_k_Y_m_d_H_M_S_f[] = "%Y-%m-%d-%H:%M:%S.%f"; static const char __pyx_k_class_getitem[] = "__class_getitem__"; +static const char __pyx_k_custom_update[] = "custom_update"; static const char __pyx_k_double_fields[] = "double_fields"; static const char __pyx_k_get_residuals[] = "get_residuals"; static const char __pyx_k_globalization[] = "globalization"; @@ -3376,7 +3451,9 @@ static const char __pyx_k_time_qp_xcond[] = "time_qp_xcond"; static const char __pyx_k_AssertionError[] = "AssertionError"; static const char __pyx_k_asfortranarray[] = "asfortranarray"; static const char __pyx_k_full_step_dual[] = "full_step_dual"; +static const char __pyx_k_get_from_qp_in[] = "get_from_qp_in"; static const char __pyx_k_new_time_steps[] = "new_time_steps"; +static const char __pyx_k_param_values_2[] = ", param_values "; static const char __pyx_k_with_dimension[] = " with dimension "; static const char __pyx_k_View_MemoryView[] = "View.MemoryView"; static const char __pyx_k_allocate_buffer[] = "allocate_buffer"; @@ -3394,6 +3471,7 @@ static const char __pyx_k_print_statistics[] = "print_statistics"; static const char __pyx_k_qp_solver_cond_N[] = "qp_solver_cond_N"; static const char __pyx_k_ascontiguousarray[] = "ascontiguousarray"; static const char __pyx_k_pyx_unpickle_Enum[] = "__pyx_unpickle_Enum"; +static const char __pyx_k_set_params_sparse[] = "set_params_sparse"; static const char __pyx_k_asyncio_coroutines[] = "asyncio.coroutines"; static const char __pyx_k_cline_in_traceback[] = "cline_in_traceback"; static const char __pyx_k_constraints_fields[] = "constraints_fields"; @@ -3402,6 +3480,7 @@ static const char __pyx_k_strided_and_direct[] = ""; static const char __pyx_k_NotImplementedError[] = "NotImplementedError"; static const char __pyx_k_get_pointers_solver[] = "__get_pointers_solver"; static const char __pyx_k_initialize_t_slacks[] = "initialize_t_slacks"; +static const char __pyx_k_reset_qp_solver_mem[] = "reset_qp_solver_mem"; static const char __pyx_k_time_qp_solver_call[] = "time_qp_solver_call"; static const char __pyx_k_warm_start_first_qp[] = "warm_start_first_qp"; static const char __pyx_k_strided_and_indirect[] = ""; @@ -3430,13 +3509,15 @@ static const char __pyx_k_time_solution_sensitivities[] = "time_solution_sensiti static const char __pyx_k_unable_to_allocate_array_data[] = "unable to allocate array data."; static const char __pyx_k_AcadosOcpSolverCython_cost_set[] = "AcadosOcpSolverCython.cost_set"; static const char __pyx_k_AcadosOcpSolverCython_get_cost[] = "AcadosOcpSolverCython.get_cost"; +static const char __pyx_k_param_values__must_be_np_array[] = "param_values_ must be np.array."; static const char __pyx_k_strided_and_direct_or_indirect[] = ""; static const char __pyx_k_AcadosOcpSolverCython__get_poin[] = "_AcadosOcpSolverCython__get_pointers_solver"; static const char __pyx_k_AcadosOcpSolverCython__get_stat[] = "_AcadosOcpSolverCython__get_stat_int"; static const char __pyx_k_AcadosOcpSolverCython_get_field[] = "AcadosOcpSolverCython.get(): field {} does not exist at final stage {}."; -static const char __pyx_k_AcadosOcpSolverCython_get_is_an[] = "AcadosOcpSolverCython.get(): {} is an invalid argument. \n Possible values are {}. Exiting."; +static const char __pyx_k_AcadosOcpSolverCython_get_is_an[] = "AcadosOcpSolverCython.get(): {} is an invalid argument. \n Possible values are {}."; static const char __pyx_k_AcadosOcpSolverCython_get_stage[] = "AcadosOcpSolverCython.get(): stage index must be in [0, N], got: {}."; static const char __pyx_k_AcadosOcpSolverCython_get_stats[] = "AcadosOcpSolverCython.get_stats"; +static const char __pyx_k_AcadosOcpSolverCython_solve_for[] = "AcadosOcpSolverCython.solve_for_x0"; static const char __pyx_k_AcadosOcpSolverCython_update_qp[] = "AcadosOcpSolverCython.update_qp_solver_cond_N"; static const char __pyx_k_numpy_core_multiarray_failed_to[] = "numpy.core.multiarray failed to import"; static const char __pyx_k_AcadosOcpSolverCython___get_poin[] = "AcadosOcpSolverCython.__get_pointers_solver"; @@ -3445,16 +3526,18 @@ static const char __pyx_k_AcadosOcpSolverCython___reduce_c[] = "AcadosOcpSolverC static const char __pyx_k_AcadosOcpSolverCython___setstate[] = "AcadosOcpSolverCython.__setstate_cython__"; static const char __pyx_k_AcadosOcpSolverCython_constraint[] = "AcadosOcpSolverCython.constraints_set(): mismatching dimension"; static const char __pyx_k_AcadosOcpSolverCython_cost_set_m[] = "AcadosOcpSolverCython.cost_set(): mismatching dimension"; +static const char __pyx_k_AcadosOcpSolverCython_custom_upd[] = "AcadosOcpSolverCython.custom_update"; static const char __pyx_k_AcadosOcpSolverCython_does_not_s[] = "AcadosOcpSolverCython: does not support set_new_time_steps() since it is only a prototyping feature"; -static const char __pyx_k_AcadosOcpSolverCython_dynamics_g[] = "AcadosOcpSolverCython.dynamics_get"; static const char __pyx_k_AcadosOcpSolverCython_eval_param[] = "AcadosOcpSolverCython.eval_param_sens(): index must be Integer."; +static const char __pyx_k_AcadosOcpSolverCython_get_from_q[] = "AcadosOcpSolverCython.get_from_qp_in"; static const char __pyx_k_AcadosOcpSolverCython_get_residu[] = "AcadosOcpSolverCython.get_residuals"; static const char __pyx_k_AcadosOcpSolverCython_load_itera[] = "AcadosOcpSolverCython.load_iterate"; static const char __pyx_k_AcadosOcpSolverCython_options_se[] = "AcadosOcpSolverCython.options_set() does not support field {}.\n Possible values are {}."; static const char __pyx_k_AcadosOcpSolverCython_print_stat[] = "AcadosOcpSolverCython.print_statistics"; -static const char __pyx_k_AcadosOcpSolverCython_set_is_not[] = "AcadosOcpSolverCython.set(): {} is not a valid argument. \nPossible values are {}. Exiting."; +static const char __pyx_k_AcadosOcpSolverCython_set_is_not[] = "AcadosOcpSolverCython.set(): {} is not a valid argument. \nPossible values are {}."; static const char __pyx_k_AcadosOcpSolverCython_set_mismat[] = "AcadosOcpSolverCython.set(): mismatching dimension for field \"{}\" "; static const char __pyx_k_AcadosOcpSolverCython_set_new_ti[] = "AcadosOcpSolverCython.set_new_time_steps"; +static const char __pyx_k_AcadosOcpSolverCython_set_params[] = "AcadosOcpSolverCython.set_params_sparse"; static const char __pyx_k_AcadosOcpSolverCython_solve_argu[] = "AcadosOcpSolverCython.solve(): argument 'rti_phase' can take only values 0, 1, 2 for SQP-RTI-type solvers"; static const char __pyx_k_AcadosOcpSolverCython_store_iter[] = "AcadosOcpSolverCython.store_iterate"; static const char __pyx_k_All_dimensions_preceding_dimensi[] = "All dimensions preceding dimension %d must be indexed and not sliced"; @@ -3469,13 +3552,19 @@ static const char __pyx_k_Indirect_dimensions_not_supporte[] = "Indirect dimensi static const char __pyx_k_Invalid_mode_expected_c_or_fortr[] = "Invalid mode, expected 'c' or 'fortran', got "; static const char __pyx_k_Out_of_bounds_on_buffer_access_a[] = "Out of bounds on buffer access (axis "; static const char __pyx_k_Unable_to_convert_item_to_object[] = "Unable to convert item to object"; +static const char __pyx_k_Warning_acados_ocp_solver_reache[] = "Warning: acados_ocp_solver reached maximum iterations."; +static const char __pyx_k_acados_acados_ocp_solver_returne[] = "acados acados_ocp_solver returned status "; static const char __pyx_k_acados_template_acados_ocp_solve[] = "acados_template.acados_ocp_solver_pyx"; static const char __pyx_k_alpha_values_are_not_available_f[] = "alpha values are not available for SQP_RTI"; +static const char __pyx_k_constraints_set_value_must_be_nu[] = "constraints_set: value must be numpy array, got "; +static const char __pyx_k_cost_set_value_must_be_numpy_arr[] = "cost_set: value must be numpy array, got "; static const char __pyx_k_got_differing_extents_in_dimensi[] = "got differing extents in dimension "; static const char __pyx_k_line_search_use_sufficient_desce[] = "line_search_use_sufficient_descent"; static const char __pyx_k_load_iterate_failed_file_does_no[] = "load_iterate: failed, file does not exist: "; static const char __pyx_k_no_default___reduce___due_to_non[] = "no default __reduce__ due to non-trivial __cinit__"; static const char __pyx_k_numpy_core_umath_failed_to_impor[] = "numpy.core.umath failed to import"; +static const char __pyx_k_param_values__and_idx_values__mu[] = "param_values_ and idx_values_ must be of the same size."; +static const char __pyx_k_set_value_must_be_numpy_array_go[] = "set: value must be numpy array, got "; static const char __pyx_k_solver_option_must_be_of_type_fl[] = "solver option {} must be of type float. You have {}."; static const char __pyx_k_solver_option_must_be_of_type_in[] = "solver option {} must be of type int. You have {}."; static const char __pyx_k_solver_option_must_be_of_type_st[] = "solver option {} must be of type str. You have {}."; @@ -3535,35 +3624,39 @@ static PyObject *__pyx_pf___pyx_memoryviewslice_2__setstate_cython__(CYTHON_UNUS static PyObject *__pyx_pf_15View_dot_MemoryView___pyx_unpickle_Enum(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v___pyx_type, long __pyx_v___pyx_checksum, PyObject *__pyx_v___pyx_state); /* proto */ static int __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython___cinit__(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_model_name, PyObject *__pyx_v_nlp_solver_type, PyObject *__pyx_v_N); /* proto */ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_2__get_pointers_solver(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6reset(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8set_new_time_steps(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v_new_time_steps); /* proto */ -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10update_qp_solver_cond_N(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v_qp_solver_cond_N); /* proto */ -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12eval_param_sens(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_stage, PyObject *__pyx_v_field); /* proto */ -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14get(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_); /* proto */ -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16print_statistics(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve_for_x0(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_x0_bar); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6solve(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8reset(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_reset_qp_solver_mem); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10custom_update(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_data_); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12set_new_time_steps(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v_new_time_steps); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14update_qp_solver_cond_N(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v_qp_solver_cond_N); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16eval_param_sens(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_stage, PyObject *__pyx_v_field); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18get(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20print_statistics(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ static PyObject *__pyx_lambda_funcdef_lambda(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_x); /* proto */ -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18store_iterate(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_filename, PyObject *__pyx_v_overwrite); /* proto */ -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20load_iterate(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_filename); /* proto */ -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22get_stats(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field_); /* proto */ -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_24__get_stat_int(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field); /* proto */ -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_26__get_stat_double(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field); /* proto */ -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_28__get_stat_matrix(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field, PyObject *__pyx_v_n, PyObject *__pyx_v_m); /* proto */ -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_30get_cost(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_32get_residuals(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_recompute); /* proto */ -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_); /* proto */ -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36cost_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_); /* proto */ -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38constraints_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_); /* proto */ -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40dynamics_get(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_); /* proto */ -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42options_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_); /* proto */ -static void __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_44__del__(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_46__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_48__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22store_iterate(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_filename, PyObject *__pyx_v_overwrite); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_24load_iterate(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_filename); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_26get_stats(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field_); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_28__get_stat_int(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_30__get_stat_double(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_32__get_stat_matrix(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field, PyObject *__pyx_v_n, PyObject *__pyx_v_m); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34get_cost(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36get_residuals(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_recompute); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40cost_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42constraints_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_44get_from_qp_in(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_46options_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_48set_params_sparse(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_idx_values_, PyObject *__pyx_v_param_values_); /* proto */ +static void __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_50__del__(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_52__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_54__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ static PyObject *__pyx_tp_new_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ static PyObject *__pyx_tp_new_array(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ static PyObject *__pyx_tp_new_Enum(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ static PyObject *__pyx_tp_new_memoryview(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ static PyObject *__pyx_tp_new__memoryviewslice(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static __Pyx_CachedCFunction __pyx_umethod_PyDict_Type_keys = {0, 0, 0, 0, 0}; /* #### Code section: late_includes ### */ /* #### Code section: module_state ### */ typedef struct { @@ -3650,6 +3743,7 @@ typedef struct { PyTypeObject *__pyx_memoryview_type; PyTypeObject *__pyx_memoryviewslice_type; PyObject *__pyx_kp_u_; + PyObject *__pyx_kp_u_0; PyObject *__pyx_n_s_ASCII; PyObject *__pyx_n_s_AcadosOcpSolverCython; PyObject *__pyx_n_s_AcadosOcpSolverCython___get_poin; @@ -3666,15 +3760,16 @@ typedef struct { PyObject *__pyx_n_s_AcadosOcpSolverCython_constraint_2; PyObject *__pyx_n_s_AcadosOcpSolverCython_cost_set; PyObject *__pyx_kp_u_AcadosOcpSolverCython_cost_set_m; + PyObject *__pyx_n_s_AcadosOcpSolverCython_custom_upd; PyObject *__pyx_kp_u_AcadosOcpSolverCython_does_not_s; PyObject *__pyx_kp_u_AcadosOcpSolverCython_does_not_s_2; - PyObject *__pyx_n_s_AcadosOcpSolverCython_dynamics_g; PyObject *__pyx_kp_u_AcadosOcpSolverCython_eval_param; PyObject *__pyx_kp_u_AcadosOcpSolverCython_eval_param_2; PyObject *__pyx_n_s_AcadosOcpSolverCython_eval_param_3; PyObject *__pyx_n_s_AcadosOcpSolverCython_get; PyObject *__pyx_n_s_AcadosOcpSolverCython_get_cost; PyObject *__pyx_kp_u_AcadosOcpSolverCython_get_field; + PyObject *__pyx_n_s_AcadosOcpSolverCython_get_from_q; PyObject *__pyx_kp_u_AcadosOcpSolverCython_get_is_an; PyObject *__pyx_n_s_AcadosOcpSolverCython_get_residu; PyObject *__pyx_kp_u_AcadosOcpSolverCython_get_stage; @@ -3688,9 +3783,11 @@ typedef struct { PyObject *__pyx_kp_u_AcadosOcpSolverCython_set_is_not; PyObject *__pyx_kp_u_AcadosOcpSolverCython_set_mismat; PyObject *__pyx_n_s_AcadosOcpSolverCython_set_new_ti; + PyObject *__pyx_n_s_AcadosOcpSolverCython_set_params; PyObject *__pyx_n_s_AcadosOcpSolverCython_solve; PyObject *__pyx_kp_u_AcadosOcpSolverCython_solve_argu; PyObject *__pyx_kp_u_AcadosOcpSolverCython_solve_argu_2; + PyObject *__pyx_n_s_AcadosOcpSolverCython_solve_for; PyObject *__pyx_n_s_AcadosOcpSolverCython_store_iter; PyObject *__pyx_n_s_AcadosOcpSolverCython_update_qp; PyObject *__pyx_kp_s_All_dimensions_preceding_dimensi; @@ -3705,6 +3802,7 @@ typedef struct { PyObject *__pyx_n_s_Ellipsis; PyObject *__pyx_kp_s_Empty_shape_tuple_for_cython_arr; PyObject *__pyx_n_u_F; + PyObject *__pyx_kp_u_Got_sizes_idx; PyObject *__pyx_n_s_ImportError; PyObject *__pyx_kp_s_Incompatible_checksums_0x_x_vs_0; PyObject *__pyx_n_s_IndexError; @@ -3730,16 +3828,18 @@ typedef struct { PyObject *__pyx_kp_s_Unable_to_convert_item_to_object; PyObject *__pyx_n_s_ValueError; PyObject *__pyx_n_s_View_MemoryView; + PyObject *__pyx_kp_u_Warning_acados_ocp_solver_reache; PyObject *__pyx_kp_u_Y_m_d_H_M_S_f; - PyObject *__pyx_kp_u__14; - PyObject *__pyx_n_u__15; + PyObject *__pyx_kp_u__16; + PyObject *__pyx_n_u__17; PyObject *__pyx_kp_u__2; - PyObject *__pyx_kp_u__29; PyObject *__pyx_n_s__3; + PyObject *__pyx_kp_u__31; PyObject *__pyx_kp_u__6; PyObject *__pyx_kp_u__7; - PyObject *__pyx_n_s__84; + PyObject *__pyx_n_s__94; PyObject *__pyx_n_s_abc; + PyObject *__pyx_kp_u_acados_acados_ocp_solver_returne; PyObject *__pyx_n_s_acados_template_acados_ocp_solve; PyObject *__pyx_n_s_allocate_buffer; PyObject *__pyx_n_u_alpha; @@ -3762,11 +3862,18 @@ typedef struct { PyObject *__pyx_kp_s_collections_abc; PyObject *__pyx_n_s_constraints_fields; PyObject *__pyx_n_s_constraints_set; + PyObject *__pyx_kp_u_constraints_set_value_must_be_nu; PyObject *__pyx_kp_s_contiguous_and_direct; PyObject *__pyx_kp_s_contiguous_and_indirect; PyObject *__pyx_n_s_cost_fields; PyObject *__pyx_n_s_cost_set; + PyObject *__pyx_kp_u_cost_set_value_must_be_numpy_arr; PyObject *__pyx_n_s_count; + PyObject *__pyx_n_s_custom_update; + PyObject *__pyx_n_u_d; + PyObject *__pyx_n_s_data; + PyObject *__pyx_n_s_data_2; + PyObject *__pyx_n_s_data_len; PyObject *__pyx_n_s_datetime; PyObject *__pyx_n_s_default; PyObject *__pyx_n_s_dict; @@ -3777,7 +3884,6 @@ typedef struct { PyObject *__pyx_n_s_dtype; PyObject *__pyx_n_s_dtype_is_object; PyObject *__pyx_n_s_dump; - PyObject *__pyx_n_s_dynamics_get; PyObject *__pyx_kp_u_enable; PyObject *__pyx_n_s_encode; PyObject *__pyx_n_s_enter; @@ -3803,6 +3909,7 @@ typedef struct { PyObject *__pyx_kp_u_gc; PyObject *__pyx_n_s_get; PyObject *__pyx_n_s_get_cost; + PyObject *__pyx_n_s_get_from_qp_in; PyObject *__pyx_n_s_get_pointers_solver; PyObject *__pyx_n_s_get_residuals; PyObject *__pyx_n_s_get_stat_double; @@ -3816,13 +3923,17 @@ typedef struct { PyObject *__pyx_kp_u_got; PyObject *__pyx_kp_u_got_differing_extents_in_dimensi; PyObject *__pyx_n_s_i; + PyObject *__pyx_n_s_i_string; PyObject *__pyx_n_s_id; + PyObject *__pyx_n_s_idx; + PyObject *__pyx_n_s_idx_values; PyObject *__pyx_n_s_import; PyObject *__pyx_n_s_indent; PyObject *__pyx_n_s_index; PyObject *__pyx_n_u_initialize_t_slacks; PyObject *__pyx_n_s_initializing; PyObject *__pyx_n_s_int; + PyObject *__pyx_n_s_int32; PyObject *__pyx_n_s_int_fields; PyObject *__pyx_n_s_int_value; PyObject *__pyx_n_s_is_coroutine; @@ -3834,8 +3945,10 @@ typedef struct { PyObject *__pyx_n_s_join; PyObject *__pyx_n_s_json; PyObject *__pyx_kp_u_json_2; + PyObject *__pyx_n_s_k; PyObject *__pyx_n_s_key; PyObject *__pyx_n_s_keys; + PyObject *__pyx_n_s_lN; PyObject *__pyx_n_u_lam; PyObject *__pyx_n_u_lam_2; PyObject *__pyx_n_u_lbu; @@ -3853,8 +3966,10 @@ typedef struct { PyObject *__pyx_n_s_model_name; PyObject *__pyx_n_s_msg; PyObject *__pyx_n_s_n; + PyObject *__pyx_n_s_n_update; PyObject *__pyx_n_s_name; PyObject *__pyx_n_s_name_2; + PyObject *__pyx_n_s_ndarray; PyObject *__pyx_n_s_ndim; PyObject *__pyx_n_s_new; PyObject *__pyx_n_s_new_time_steps; @@ -3876,6 +3991,10 @@ typedef struct { PyObject *__pyx_n_s_overwrite; PyObject *__pyx_n_u_p; PyObject *__pyx_n_s_pack; + PyObject *__pyx_n_s_param_values; + PyObject *__pyx_kp_u_param_values_2; + PyObject *__pyx_kp_u_param_values__and_idx_values__mu; + PyObject *__pyx_kp_u_param_values__must_be_np_array; PyObject *__pyx_n_s_path; PyObject *__pyx_n_u_pi; PyObject *__pyx_n_u_pi_2; @@ -3911,11 +4030,14 @@ typedef struct { PyObject *__pyx_n_b_res_ineq; PyObject *__pyx_n_b_res_stat; PyObject *__pyx_n_s_reset; + PyObject *__pyx_n_s_reset_qp_solver_mem; PyObject *__pyx_n_u_residuals; PyObject *__pyx_n_u_rti_phase; PyObject *__pyx_n_s_self; PyObject *__pyx_n_s_set; PyObject *__pyx_n_s_set_new_time_steps; + PyObject *__pyx_n_s_set_params_sparse; + PyObject *__pyx_kp_u_set_value_must_be_numpy_array_go; PyObject *__pyx_n_s_setstate; PyObject *__pyx_n_s_setstate_cython; PyObject *__pyx_n_s_shape; @@ -3924,6 +4046,7 @@ typedef struct { PyObject *__pyx_n_u_sl_2; PyObject *__pyx_n_s_solution; PyObject *__pyx_n_s_solve; + PyObject *__pyx_n_s_solve_for_x0; PyObject *__pyx_kp_u_solver_option_must_be_of_type_fl; PyObject *__pyx_kp_u_solver_option_must_be_of_type_in; PyObject *__pyx_kp_u_solver_option_must_be_of_type_st; @@ -3939,6 +4062,7 @@ typedef struct { PyObject *__pyx_n_s_stat_n; PyObject *__pyx_n_u_stat_n; PyObject *__pyx_n_u_statistics; + PyObject *__pyx_n_s_status; PyObject *__pyx_n_s_step; PyObject *__pyx_n_u_step_length; PyObject *__pyx_n_s_stop; @@ -3977,6 +4101,7 @@ typedef struct { PyObject *__pyx_n_u_tol_stat; PyObject *__pyx_n_s_tolist; PyObject *__pyx_n_u_u; + PyObject *__pyx_n_s_u0; PyObject *__pyx_n_u_u_2; PyObject *__pyx_n_u_ubu; PyObject *__pyx_n_u_ubx; @@ -3998,6 +4123,7 @@ typedef struct { PyObject *__pyx_n_b_x; PyObject *__pyx_n_s_x; PyObject *__pyx_n_u_x; + PyObject *__pyx_n_s_x0_bar; PyObject *__pyx_n_u_x_2; PyObject *__pyx_n_u_xdot_guess; PyObject *__pyx_n_u_y_ref; @@ -4005,6 +4131,7 @@ typedef struct { PyObject *__pyx_n_u_yref; PyObject *__pyx_n_u_z; PyObject *__pyx_n_u_z_2; + PyObject *__pyx_n_b_z_guess; PyObject *__pyx_n_u_z_guess; PyObject *__pyx_n_s_zeros; PyObject *__pyx_int_0; @@ -4023,13 +4150,13 @@ typedef struct { PyObject *__pyx_tuple__4; PyObject *__pyx_tuple__8; PyObject *__pyx_tuple__9; - PyObject *__pyx_slice__16; + PyObject *__pyx_slice__18; PyObject *__pyx_tuple__10; PyObject *__pyx_tuple__11; PyObject *__pyx_tuple__12; PyObject *__pyx_tuple__13; - PyObject *__pyx_tuple__17; - PyObject *__pyx_tuple__18; + PyObject *__pyx_tuple__14; + PyObject *__pyx_tuple__15; PyObject *__pyx_tuple__19; PyObject *__pyx_tuple__20; PyObject *__pyx_tuple__21; @@ -4040,8 +4167,8 @@ typedef struct { PyObject *__pyx_tuple__26; PyObject *__pyx_tuple__27; PyObject *__pyx_tuple__28; + PyObject *__pyx_tuple__29; PyObject *__pyx_tuple__30; - PyObject *__pyx_tuple__31; PyObject *__pyx_tuple__32; PyObject *__pyx_tuple__33; PyObject *__pyx_tuple__34; @@ -4050,50 +4177,60 @@ typedef struct { PyObject *__pyx_tuple__37; PyObject *__pyx_tuple__38; PyObject *__pyx_tuple__39; + PyObject *__pyx_tuple__40; PyObject *__pyx_tuple__41; - PyObject *__pyx_tuple__45; - PyObject *__pyx_tuple__47; + PyObject *__pyx_tuple__42; + PyObject *__pyx_tuple__44; + PyObject *__pyx_tuple__46; PyObject *__pyx_tuple__49; PyObject *__pyx_tuple__51; - PyObject *__pyx_tuple__52; + PyObject *__pyx_tuple__53; PyObject *__pyx_tuple__55; PyObject *__pyx_tuple__57; - PyObject *__pyx_tuple__58; + PyObject *__pyx_tuple__59; PyObject *__pyx_tuple__60; - PyObject *__pyx_tuple__62; + PyObject *__pyx_tuple__63; PyObject *__pyx_tuple__65; - PyObject *__pyx_tuple__67; - PyObject *__pyx_tuple__69; - PyObject *__pyx_tuple__71; - PyObject *__pyx_tuple__72; - PyObject *__pyx_tuple__74; + PyObject *__pyx_tuple__66; + PyObject *__pyx_tuple__68; + PyObject *__pyx_tuple__70; + PyObject *__pyx_tuple__73; + PyObject *__pyx_tuple__75; PyObject *__pyx_tuple__77; PyObject *__pyx_tuple__79; + PyObject *__pyx_tuple__80; PyObject *__pyx_tuple__82; - PyObject *__pyx_codeobj__40; - PyObject *__pyx_codeobj__42; + PyObject *__pyx_tuple__85; + PyObject *__pyx_tuple__87; + PyObject *__pyx_tuple__89; + PyObject *__pyx_tuple__92; PyObject *__pyx_codeobj__43; - PyObject *__pyx_codeobj__44; - PyObject *__pyx_codeobj__46; + PyObject *__pyx_codeobj__45; + PyObject *__pyx_codeobj__47; PyObject *__pyx_codeobj__48; PyObject *__pyx_codeobj__50; - PyObject *__pyx_codeobj__53; + PyObject *__pyx_codeobj__52; PyObject *__pyx_codeobj__54; PyObject *__pyx_codeobj__56; - PyObject *__pyx_codeobj__59; + PyObject *__pyx_codeobj__58; PyObject *__pyx_codeobj__61; - PyObject *__pyx_codeobj__63; + PyObject *__pyx_codeobj__62; PyObject *__pyx_codeobj__64; - PyObject *__pyx_codeobj__66; - PyObject *__pyx_codeobj__68; - PyObject *__pyx_codeobj__70; - PyObject *__pyx_codeobj__73; - PyObject *__pyx_codeobj__75; + PyObject *__pyx_codeobj__67; + PyObject *__pyx_codeobj__69; + PyObject *__pyx_codeobj__71; + PyObject *__pyx_codeobj__72; + PyObject *__pyx_codeobj__74; PyObject *__pyx_codeobj__76; PyObject *__pyx_codeobj__78; - PyObject *__pyx_codeobj__80; PyObject *__pyx_codeobj__81; PyObject *__pyx_codeobj__83; + PyObject *__pyx_codeobj__84; + PyObject *__pyx_codeobj__86; + PyObject *__pyx_codeobj__88; + PyObject *__pyx_codeobj__90; + PyObject *__pyx_codeobj__91; + PyObject *__pyx_codeobj__93; } __pyx_mstate; #if CYTHON_USE_MODULE_STATE @@ -4163,6 +4300,7 @@ static int __pyx_m_clear(PyObject *m) { Py_CLEAR(clear_module_state->__pyx_memoryviewslice_type); Py_CLEAR(clear_module_state->__pyx_type___pyx_memoryviewslice); Py_CLEAR(clear_module_state->__pyx_kp_u_); + Py_CLEAR(clear_module_state->__pyx_kp_u_0); Py_CLEAR(clear_module_state->__pyx_n_s_ASCII); Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython); Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython___get_poin); @@ -4179,15 +4317,16 @@ static int __pyx_m_clear(PyObject *m) { Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_constraint_2); Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_cost_set); Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_cost_set_m); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_custom_upd); Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_does_not_s); Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_does_not_s_2); - Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_dynamics_g); Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_eval_param); Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_eval_param_2); Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_eval_param_3); Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_get); Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_get_cost); Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_get_field); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_get_from_q); Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_get_is_an); Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_get_residu); Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_get_stage); @@ -4201,9 +4340,11 @@ static int __pyx_m_clear(PyObject *m) { Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_set_is_not); Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_set_mismat); Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_set_new_ti); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_set_params); Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_solve); Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_solve_argu); Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_solve_argu_2); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_solve_for); Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_store_iter); Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_update_qp); Py_CLEAR(clear_module_state->__pyx_kp_s_All_dimensions_preceding_dimensi); @@ -4218,6 +4359,7 @@ static int __pyx_m_clear(PyObject *m) { Py_CLEAR(clear_module_state->__pyx_n_s_Ellipsis); Py_CLEAR(clear_module_state->__pyx_kp_s_Empty_shape_tuple_for_cython_arr); Py_CLEAR(clear_module_state->__pyx_n_u_F); + Py_CLEAR(clear_module_state->__pyx_kp_u_Got_sizes_idx); Py_CLEAR(clear_module_state->__pyx_n_s_ImportError); Py_CLEAR(clear_module_state->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0); Py_CLEAR(clear_module_state->__pyx_n_s_IndexError); @@ -4243,16 +4385,18 @@ static int __pyx_m_clear(PyObject *m) { Py_CLEAR(clear_module_state->__pyx_kp_s_Unable_to_convert_item_to_object); Py_CLEAR(clear_module_state->__pyx_n_s_ValueError); Py_CLEAR(clear_module_state->__pyx_n_s_View_MemoryView); + Py_CLEAR(clear_module_state->__pyx_kp_u_Warning_acados_ocp_solver_reache); Py_CLEAR(clear_module_state->__pyx_kp_u_Y_m_d_H_M_S_f); - Py_CLEAR(clear_module_state->__pyx_kp_u__14); - Py_CLEAR(clear_module_state->__pyx_n_u__15); + Py_CLEAR(clear_module_state->__pyx_kp_u__16); + Py_CLEAR(clear_module_state->__pyx_n_u__17); Py_CLEAR(clear_module_state->__pyx_kp_u__2); - Py_CLEAR(clear_module_state->__pyx_kp_u__29); Py_CLEAR(clear_module_state->__pyx_n_s__3); + Py_CLEAR(clear_module_state->__pyx_kp_u__31); Py_CLEAR(clear_module_state->__pyx_kp_u__6); Py_CLEAR(clear_module_state->__pyx_kp_u__7); - Py_CLEAR(clear_module_state->__pyx_n_s__84); + Py_CLEAR(clear_module_state->__pyx_n_s__94); Py_CLEAR(clear_module_state->__pyx_n_s_abc); + Py_CLEAR(clear_module_state->__pyx_kp_u_acados_acados_ocp_solver_returne); Py_CLEAR(clear_module_state->__pyx_n_s_acados_template_acados_ocp_solve); Py_CLEAR(clear_module_state->__pyx_n_s_allocate_buffer); Py_CLEAR(clear_module_state->__pyx_n_u_alpha); @@ -4275,11 +4419,18 @@ static int __pyx_m_clear(PyObject *m) { Py_CLEAR(clear_module_state->__pyx_kp_s_collections_abc); Py_CLEAR(clear_module_state->__pyx_n_s_constraints_fields); Py_CLEAR(clear_module_state->__pyx_n_s_constraints_set); + Py_CLEAR(clear_module_state->__pyx_kp_u_constraints_set_value_must_be_nu); Py_CLEAR(clear_module_state->__pyx_kp_s_contiguous_and_direct); Py_CLEAR(clear_module_state->__pyx_kp_s_contiguous_and_indirect); Py_CLEAR(clear_module_state->__pyx_n_s_cost_fields); Py_CLEAR(clear_module_state->__pyx_n_s_cost_set); + Py_CLEAR(clear_module_state->__pyx_kp_u_cost_set_value_must_be_numpy_arr); Py_CLEAR(clear_module_state->__pyx_n_s_count); + Py_CLEAR(clear_module_state->__pyx_n_s_custom_update); + Py_CLEAR(clear_module_state->__pyx_n_u_d); + Py_CLEAR(clear_module_state->__pyx_n_s_data); + Py_CLEAR(clear_module_state->__pyx_n_s_data_2); + Py_CLEAR(clear_module_state->__pyx_n_s_data_len); Py_CLEAR(clear_module_state->__pyx_n_s_datetime); Py_CLEAR(clear_module_state->__pyx_n_s_default); Py_CLEAR(clear_module_state->__pyx_n_s_dict); @@ -4290,7 +4441,6 @@ static int __pyx_m_clear(PyObject *m) { Py_CLEAR(clear_module_state->__pyx_n_s_dtype); Py_CLEAR(clear_module_state->__pyx_n_s_dtype_is_object); Py_CLEAR(clear_module_state->__pyx_n_s_dump); - Py_CLEAR(clear_module_state->__pyx_n_s_dynamics_get); Py_CLEAR(clear_module_state->__pyx_kp_u_enable); Py_CLEAR(clear_module_state->__pyx_n_s_encode); Py_CLEAR(clear_module_state->__pyx_n_s_enter); @@ -4316,6 +4466,7 @@ static int __pyx_m_clear(PyObject *m) { Py_CLEAR(clear_module_state->__pyx_kp_u_gc); Py_CLEAR(clear_module_state->__pyx_n_s_get); Py_CLEAR(clear_module_state->__pyx_n_s_get_cost); + Py_CLEAR(clear_module_state->__pyx_n_s_get_from_qp_in); Py_CLEAR(clear_module_state->__pyx_n_s_get_pointers_solver); Py_CLEAR(clear_module_state->__pyx_n_s_get_residuals); Py_CLEAR(clear_module_state->__pyx_n_s_get_stat_double); @@ -4329,13 +4480,17 @@ static int __pyx_m_clear(PyObject *m) { Py_CLEAR(clear_module_state->__pyx_kp_u_got); Py_CLEAR(clear_module_state->__pyx_kp_u_got_differing_extents_in_dimensi); Py_CLEAR(clear_module_state->__pyx_n_s_i); + Py_CLEAR(clear_module_state->__pyx_n_s_i_string); Py_CLEAR(clear_module_state->__pyx_n_s_id); + Py_CLEAR(clear_module_state->__pyx_n_s_idx); + Py_CLEAR(clear_module_state->__pyx_n_s_idx_values); Py_CLEAR(clear_module_state->__pyx_n_s_import); Py_CLEAR(clear_module_state->__pyx_n_s_indent); Py_CLEAR(clear_module_state->__pyx_n_s_index); Py_CLEAR(clear_module_state->__pyx_n_u_initialize_t_slacks); Py_CLEAR(clear_module_state->__pyx_n_s_initializing); Py_CLEAR(clear_module_state->__pyx_n_s_int); + Py_CLEAR(clear_module_state->__pyx_n_s_int32); Py_CLEAR(clear_module_state->__pyx_n_s_int_fields); Py_CLEAR(clear_module_state->__pyx_n_s_int_value); Py_CLEAR(clear_module_state->__pyx_n_s_is_coroutine); @@ -4347,8 +4502,10 @@ static int __pyx_m_clear(PyObject *m) { Py_CLEAR(clear_module_state->__pyx_n_s_join); Py_CLEAR(clear_module_state->__pyx_n_s_json); Py_CLEAR(clear_module_state->__pyx_kp_u_json_2); + Py_CLEAR(clear_module_state->__pyx_n_s_k); Py_CLEAR(clear_module_state->__pyx_n_s_key); Py_CLEAR(clear_module_state->__pyx_n_s_keys); + Py_CLEAR(clear_module_state->__pyx_n_s_lN); Py_CLEAR(clear_module_state->__pyx_n_u_lam); Py_CLEAR(clear_module_state->__pyx_n_u_lam_2); Py_CLEAR(clear_module_state->__pyx_n_u_lbu); @@ -4366,8 +4523,10 @@ static int __pyx_m_clear(PyObject *m) { Py_CLEAR(clear_module_state->__pyx_n_s_model_name); Py_CLEAR(clear_module_state->__pyx_n_s_msg); Py_CLEAR(clear_module_state->__pyx_n_s_n); + Py_CLEAR(clear_module_state->__pyx_n_s_n_update); Py_CLEAR(clear_module_state->__pyx_n_s_name); Py_CLEAR(clear_module_state->__pyx_n_s_name_2); + Py_CLEAR(clear_module_state->__pyx_n_s_ndarray); Py_CLEAR(clear_module_state->__pyx_n_s_ndim); Py_CLEAR(clear_module_state->__pyx_n_s_new); Py_CLEAR(clear_module_state->__pyx_n_s_new_time_steps); @@ -4389,6 +4548,10 @@ static int __pyx_m_clear(PyObject *m) { Py_CLEAR(clear_module_state->__pyx_n_s_overwrite); Py_CLEAR(clear_module_state->__pyx_n_u_p); Py_CLEAR(clear_module_state->__pyx_n_s_pack); + Py_CLEAR(clear_module_state->__pyx_n_s_param_values); + Py_CLEAR(clear_module_state->__pyx_kp_u_param_values_2); + Py_CLEAR(clear_module_state->__pyx_kp_u_param_values__and_idx_values__mu); + Py_CLEAR(clear_module_state->__pyx_kp_u_param_values__must_be_np_array); Py_CLEAR(clear_module_state->__pyx_n_s_path); Py_CLEAR(clear_module_state->__pyx_n_u_pi); Py_CLEAR(clear_module_state->__pyx_n_u_pi_2); @@ -4424,11 +4587,14 @@ static int __pyx_m_clear(PyObject *m) { Py_CLEAR(clear_module_state->__pyx_n_b_res_ineq); Py_CLEAR(clear_module_state->__pyx_n_b_res_stat); Py_CLEAR(clear_module_state->__pyx_n_s_reset); + Py_CLEAR(clear_module_state->__pyx_n_s_reset_qp_solver_mem); Py_CLEAR(clear_module_state->__pyx_n_u_residuals); Py_CLEAR(clear_module_state->__pyx_n_u_rti_phase); Py_CLEAR(clear_module_state->__pyx_n_s_self); Py_CLEAR(clear_module_state->__pyx_n_s_set); Py_CLEAR(clear_module_state->__pyx_n_s_set_new_time_steps); + Py_CLEAR(clear_module_state->__pyx_n_s_set_params_sparse); + Py_CLEAR(clear_module_state->__pyx_kp_u_set_value_must_be_numpy_array_go); Py_CLEAR(clear_module_state->__pyx_n_s_setstate); Py_CLEAR(clear_module_state->__pyx_n_s_setstate_cython); Py_CLEAR(clear_module_state->__pyx_n_s_shape); @@ -4437,6 +4603,7 @@ static int __pyx_m_clear(PyObject *m) { Py_CLEAR(clear_module_state->__pyx_n_u_sl_2); Py_CLEAR(clear_module_state->__pyx_n_s_solution); Py_CLEAR(clear_module_state->__pyx_n_s_solve); + Py_CLEAR(clear_module_state->__pyx_n_s_solve_for_x0); Py_CLEAR(clear_module_state->__pyx_kp_u_solver_option_must_be_of_type_fl); Py_CLEAR(clear_module_state->__pyx_kp_u_solver_option_must_be_of_type_in); Py_CLEAR(clear_module_state->__pyx_kp_u_solver_option_must_be_of_type_st); @@ -4452,6 +4619,7 @@ static int __pyx_m_clear(PyObject *m) { Py_CLEAR(clear_module_state->__pyx_n_s_stat_n); Py_CLEAR(clear_module_state->__pyx_n_u_stat_n); Py_CLEAR(clear_module_state->__pyx_n_u_statistics); + Py_CLEAR(clear_module_state->__pyx_n_s_status); Py_CLEAR(clear_module_state->__pyx_n_s_step); Py_CLEAR(clear_module_state->__pyx_n_u_step_length); Py_CLEAR(clear_module_state->__pyx_n_s_stop); @@ -4490,6 +4658,7 @@ static int __pyx_m_clear(PyObject *m) { Py_CLEAR(clear_module_state->__pyx_n_u_tol_stat); Py_CLEAR(clear_module_state->__pyx_n_s_tolist); Py_CLEAR(clear_module_state->__pyx_n_u_u); + Py_CLEAR(clear_module_state->__pyx_n_s_u0); Py_CLEAR(clear_module_state->__pyx_n_u_u_2); Py_CLEAR(clear_module_state->__pyx_n_u_ubu); Py_CLEAR(clear_module_state->__pyx_n_u_ubx); @@ -4511,6 +4680,7 @@ static int __pyx_m_clear(PyObject *m) { Py_CLEAR(clear_module_state->__pyx_n_b_x); Py_CLEAR(clear_module_state->__pyx_n_s_x); Py_CLEAR(clear_module_state->__pyx_n_u_x); + Py_CLEAR(clear_module_state->__pyx_n_s_x0_bar); Py_CLEAR(clear_module_state->__pyx_n_u_x_2); Py_CLEAR(clear_module_state->__pyx_n_u_xdot_guess); Py_CLEAR(clear_module_state->__pyx_n_u_y_ref); @@ -4518,6 +4688,7 @@ static int __pyx_m_clear(PyObject *m) { Py_CLEAR(clear_module_state->__pyx_n_u_yref); Py_CLEAR(clear_module_state->__pyx_n_u_z); Py_CLEAR(clear_module_state->__pyx_n_u_z_2); + Py_CLEAR(clear_module_state->__pyx_n_b_z_guess); Py_CLEAR(clear_module_state->__pyx_n_u_z_guess); Py_CLEAR(clear_module_state->__pyx_n_s_zeros); Py_CLEAR(clear_module_state->__pyx_int_0); @@ -4536,13 +4707,13 @@ static int __pyx_m_clear(PyObject *m) { Py_CLEAR(clear_module_state->__pyx_tuple__4); Py_CLEAR(clear_module_state->__pyx_tuple__8); Py_CLEAR(clear_module_state->__pyx_tuple__9); - Py_CLEAR(clear_module_state->__pyx_slice__16); + Py_CLEAR(clear_module_state->__pyx_slice__18); Py_CLEAR(clear_module_state->__pyx_tuple__10); Py_CLEAR(clear_module_state->__pyx_tuple__11); Py_CLEAR(clear_module_state->__pyx_tuple__12); Py_CLEAR(clear_module_state->__pyx_tuple__13); - Py_CLEAR(clear_module_state->__pyx_tuple__17); - Py_CLEAR(clear_module_state->__pyx_tuple__18); + Py_CLEAR(clear_module_state->__pyx_tuple__14); + Py_CLEAR(clear_module_state->__pyx_tuple__15); Py_CLEAR(clear_module_state->__pyx_tuple__19); Py_CLEAR(clear_module_state->__pyx_tuple__20); Py_CLEAR(clear_module_state->__pyx_tuple__21); @@ -4553,8 +4724,8 @@ static int __pyx_m_clear(PyObject *m) { Py_CLEAR(clear_module_state->__pyx_tuple__26); Py_CLEAR(clear_module_state->__pyx_tuple__27); Py_CLEAR(clear_module_state->__pyx_tuple__28); + Py_CLEAR(clear_module_state->__pyx_tuple__29); Py_CLEAR(clear_module_state->__pyx_tuple__30); - Py_CLEAR(clear_module_state->__pyx_tuple__31); Py_CLEAR(clear_module_state->__pyx_tuple__32); Py_CLEAR(clear_module_state->__pyx_tuple__33); Py_CLEAR(clear_module_state->__pyx_tuple__34); @@ -4563,50 +4734,60 @@ static int __pyx_m_clear(PyObject *m) { Py_CLEAR(clear_module_state->__pyx_tuple__37); Py_CLEAR(clear_module_state->__pyx_tuple__38); Py_CLEAR(clear_module_state->__pyx_tuple__39); + Py_CLEAR(clear_module_state->__pyx_tuple__40); Py_CLEAR(clear_module_state->__pyx_tuple__41); - Py_CLEAR(clear_module_state->__pyx_tuple__45); - Py_CLEAR(clear_module_state->__pyx_tuple__47); + Py_CLEAR(clear_module_state->__pyx_tuple__42); + Py_CLEAR(clear_module_state->__pyx_tuple__44); + Py_CLEAR(clear_module_state->__pyx_tuple__46); Py_CLEAR(clear_module_state->__pyx_tuple__49); Py_CLEAR(clear_module_state->__pyx_tuple__51); - Py_CLEAR(clear_module_state->__pyx_tuple__52); + Py_CLEAR(clear_module_state->__pyx_tuple__53); Py_CLEAR(clear_module_state->__pyx_tuple__55); Py_CLEAR(clear_module_state->__pyx_tuple__57); - Py_CLEAR(clear_module_state->__pyx_tuple__58); + Py_CLEAR(clear_module_state->__pyx_tuple__59); Py_CLEAR(clear_module_state->__pyx_tuple__60); - Py_CLEAR(clear_module_state->__pyx_tuple__62); + Py_CLEAR(clear_module_state->__pyx_tuple__63); Py_CLEAR(clear_module_state->__pyx_tuple__65); - Py_CLEAR(clear_module_state->__pyx_tuple__67); - Py_CLEAR(clear_module_state->__pyx_tuple__69); - Py_CLEAR(clear_module_state->__pyx_tuple__71); - Py_CLEAR(clear_module_state->__pyx_tuple__72); - Py_CLEAR(clear_module_state->__pyx_tuple__74); + Py_CLEAR(clear_module_state->__pyx_tuple__66); + Py_CLEAR(clear_module_state->__pyx_tuple__68); + Py_CLEAR(clear_module_state->__pyx_tuple__70); + Py_CLEAR(clear_module_state->__pyx_tuple__73); + Py_CLEAR(clear_module_state->__pyx_tuple__75); Py_CLEAR(clear_module_state->__pyx_tuple__77); Py_CLEAR(clear_module_state->__pyx_tuple__79); + Py_CLEAR(clear_module_state->__pyx_tuple__80); Py_CLEAR(clear_module_state->__pyx_tuple__82); - Py_CLEAR(clear_module_state->__pyx_codeobj__40); - Py_CLEAR(clear_module_state->__pyx_codeobj__42); + Py_CLEAR(clear_module_state->__pyx_tuple__85); + Py_CLEAR(clear_module_state->__pyx_tuple__87); + Py_CLEAR(clear_module_state->__pyx_tuple__89); + Py_CLEAR(clear_module_state->__pyx_tuple__92); Py_CLEAR(clear_module_state->__pyx_codeobj__43); - Py_CLEAR(clear_module_state->__pyx_codeobj__44); - Py_CLEAR(clear_module_state->__pyx_codeobj__46); + Py_CLEAR(clear_module_state->__pyx_codeobj__45); + Py_CLEAR(clear_module_state->__pyx_codeobj__47); Py_CLEAR(clear_module_state->__pyx_codeobj__48); Py_CLEAR(clear_module_state->__pyx_codeobj__50); - Py_CLEAR(clear_module_state->__pyx_codeobj__53); + Py_CLEAR(clear_module_state->__pyx_codeobj__52); Py_CLEAR(clear_module_state->__pyx_codeobj__54); Py_CLEAR(clear_module_state->__pyx_codeobj__56); - Py_CLEAR(clear_module_state->__pyx_codeobj__59); + Py_CLEAR(clear_module_state->__pyx_codeobj__58); Py_CLEAR(clear_module_state->__pyx_codeobj__61); - Py_CLEAR(clear_module_state->__pyx_codeobj__63); + Py_CLEAR(clear_module_state->__pyx_codeobj__62); Py_CLEAR(clear_module_state->__pyx_codeobj__64); - Py_CLEAR(clear_module_state->__pyx_codeobj__66); - Py_CLEAR(clear_module_state->__pyx_codeobj__68); - Py_CLEAR(clear_module_state->__pyx_codeobj__70); - Py_CLEAR(clear_module_state->__pyx_codeobj__73); - Py_CLEAR(clear_module_state->__pyx_codeobj__75); + Py_CLEAR(clear_module_state->__pyx_codeobj__67); + Py_CLEAR(clear_module_state->__pyx_codeobj__69); + Py_CLEAR(clear_module_state->__pyx_codeobj__71); + Py_CLEAR(clear_module_state->__pyx_codeobj__72); + Py_CLEAR(clear_module_state->__pyx_codeobj__74); Py_CLEAR(clear_module_state->__pyx_codeobj__76); Py_CLEAR(clear_module_state->__pyx_codeobj__78); - Py_CLEAR(clear_module_state->__pyx_codeobj__80); Py_CLEAR(clear_module_state->__pyx_codeobj__81); Py_CLEAR(clear_module_state->__pyx_codeobj__83); + Py_CLEAR(clear_module_state->__pyx_codeobj__84); + Py_CLEAR(clear_module_state->__pyx_codeobj__86); + Py_CLEAR(clear_module_state->__pyx_codeobj__88); + Py_CLEAR(clear_module_state->__pyx_codeobj__90); + Py_CLEAR(clear_module_state->__pyx_codeobj__91); + Py_CLEAR(clear_module_state->__pyx_codeobj__93); return 0; } #endif @@ -4654,6 +4835,7 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { Py_VISIT(traverse_module_state->__pyx_memoryviewslice_type); Py_VISIT(traverse_module_state->__pyx_type___pyx_memoryviewslice); Py_VISIT(traverse_module_state->__pyx_kp_u_); + Py_VISIT(traverse_module_state->__pyx_kp_u_0); Py_VISIT(traverse_module_state->__pyx_n_s_ASCII); Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython); Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython___get_poin); @@ -4670,15 +4852,16 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_constraint_2); Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_cost_set); Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_cost_set_m); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_custom_upd); Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_does_not_s); Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_does_not_s_2); - Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_dynamics_g); Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_eval_param); Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_eval_param_2); Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_eval_param_3); Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_get); Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_get_cost); Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_get_field); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_get_from_q); Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_get_is_an); Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_get_residu); Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_get_stage); @@ -4692,9 +4875,11 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_set_is_not); Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_set_mismat); Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_set_new_ti); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_set_params); Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_solve); Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_solve_argu); Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_solve_argu_2); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_solve_for); Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_store_iter); Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_update_qp); Py_VISIT(traverse_module_state->__pyx_kp_s_All_dimensions_preceding_dimensi); @@ -4709,6 +4894,7 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { Py_VISIT(traverse_module_state->__pyx_n_s_Ellipsis); Py_VISIT(traverse_module_state->__pyx_kp_s_Empty_shape_tuple_for_cython_arr); Py_VISIT(traverse_module_state->__pyx_n_u_F); + Py_VISIT(traverse_module_state->__pyx_kp_u_Got_sizes_idx); Py_VISIT(traverse_module_state->__pyx_n_s_ImportError); Py_VISIT(traverse_module_state->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0); Py_VISIT(traverse_module_state->__pyx_n_s_IndexError); @@ -4734,16 +4920,18 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { Py_VISIT(traverse_module_state->__pyx_kp_s_Unable_to_convert_item_to_object); Py_VISIT(traverse_module_state->__pyx_n_s_ValueError); Py_VISIT(traverse_module_state->__pyx_n_s_View_MemoryView); + Py_VISIT(traverse_module_state->__pyx_kp_u_Warning_acados_ocp_solver_reache); Py_VISIT(traverse_module_state->__pyx_kp_u_Y_m_d_H_M_S_f); - Py_VISIT(traverse_module_state->__pyx_kp_u__14); - Py_VISIT(traverse_module_state->__pyx_n_u__15); + Py_VISIT(traverse_module_state->__pyx_kp_u__16); + Py_VISIT(traverse_module_state->__pyx_n_u__17); Py_VISIT(traverse_module_state->__pyx_kp_u__2); - Py_VISIT(traverse_module_state->__pyx_kp_u__29); Py_VISIT(traverse_module_state->__pyx_n_s__3); + Py_VISIT(traverse_module_state->__pyx_kp_u__31); Py_VISIT(traverse_module_state->__pyx_kp_u__6); Py_VISIT(traverse_module_state->__pyx_kp_u__7); - Py_VISIT(traverse_module_state->__pyx_n_s__84); + Py_VISIT(traverse_module_state->__pyx_n_s__94); Py_VISIT(traverse_module_state->__pyx_n_s_abc); + Py_VISIT(traverse_module_state->__pyx_kp_u_acados_acados_ocp_solver_returne); Py_VISIT(traverse_module_state->__pyx_n_s_acados_template_acados_ocp_solve); Py_VISIT(traverse_module_state->__pyx_n_s_allocate_buffer); Py_VISIT(traverse_module_state->__pyx_n_u_alpha); @@ -4766,11 +4954,18 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { Py_VISIT(traverse_module_state->__pyx_kp_s_collections_abc); Py_VISIT(traverse_module_state->__pyx_n_s_constraints_fields); Py_VISIT(traverse_module_state->__pyx_n_s_constraints_set); + Py_VISIT(traverse_module_state->__pyx_kp_u_constraints_set_value_must_be_nu); Py_VISIT(traverse_module_state->__pyx_kp_s_contiguous_and_direct); Py_VISIT(traverse_module_state->__pyx_kp_s_contiguous_and_indirect); Py_VISIT(traverse_module_state->__pyx_n_s_cost_fields); Py_VISIT(traverse_module_state->__pyx_n_s_cost_set); + Py_VISIT(traverse_module_state->__pyx_kp_u_cost_set_value_must_be_numpy_arr); Py_VISIT(traverse_module_state->__pyx_n_s_count); + Py_VISIT(traverse_module_state->__pyx_n_s_custom_update); + Py_VISIT(traverse_module_state->__pyx_n_u_d); + Py_VISIT(traverse_module_state->__pyx_n_s_data); + Py_VISIT(traverse_module_state->__pyx_n_s_data_2); + Py_VISIT(traverse_module_state->__pyx_n_s_data_len); Py_VISIT(traverse_module_state->__pyx_n_s_datetime); Py_VISIT(traverse_module_state->__pyx_n_s_default); Py_VISIT(traverse_module_state->__pyx_n_s_dict); @@ -4781,7 +4976,6 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { Py_VISIT(traverse_module_state->__pyx_n_s_dtype); Py_VISIT(traverse_module_state->__pyx_n_s_dtype_is_object); Py_VISIT(traverse_module_state->__pyx_n_s_dump); - Py_VISIT(traverse_module_state->__pyx_n_s_dynamics_get); Py_VISIT(traverse_module_state->__pyx_kp_u_enable); Py_VISIT(traverse_module_state->__pyx_n_s_encode); Py_VISIT(traverse_module_state->__pyx_n_s_enter); @@ -4807,6 +5001,7 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { Py_VISIT(traverse_module_state->__pyx_kp_u_gc); Py_VISIT(traverse_module_state->__pyx_n_s_get); Py_VISIT(traverse_module_state->__pyx_n_s_get_cost); + Py_VISIT(traverse_module_state->__pyx_n_s_get_from_qp_in); Py_VISIT(traverse_module_state->__pyx_n_s_get_pointers_solver); Py_VISIT(traverse_module_state->__pyx_n_s_get_residuals); Py_VISIT(traverse_module_state->__pyx_n_s_get_stat_double); @@ -4820,13 +5015,17 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { Py_VISIT(traverse_module_state->__pyx_kp_u_got); Py_VISIT(traverse_module_state->__pyx_kp_u_got_differing_extents_in_dimensi); Py_VISIT(traverse_module_state->__pyx_n_s_i); + Py_VISIT(traverse_module_state->__pyx_n_s_i_string); Py_VISIT(traverse_module_state->__pyx_n_s_id); + Py_VISIT(traverse_module_state->__pyx_n_s_idx); + Py_VISIT(traverse_module_state->__pyx_n_s_idx_values); Py_VISIT(traverse_module_state->__pyx_n_s_import); Py_VISIT(traverse_module_state->__pyx_n_s_indent); Py_VISIT(traverse_module_state->__pyx_n_s_index); Py_VISIT(traverse_module_state->__pyx_n_u_initialize_t_slacks); Py_VISIT(traverse_module_state->__pyx_n_s_initializing); Py_VISIT(traverse_module_state->__pyx_n_s_int); + Py_VISIT(traverse_module_state->__pyx_n_s_int32); Py_VISIT(traverse_module_state->__pyx_n_s_int_fields); Py_VISIT(traverse_module_state->__pyx_n_s_int_value); Py_VISIT(traverse_module_state->__pyx_n_s_is_coroutine); @@ -4838,8 +5037,10 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { Py_VISIT(traverse_module_state->__pyx_n_s_join); Py_VISIT(traverse_module_state->__pyx_n_s_json); Py_VISIT(traverse_module_state->__pyx_kp_u_json_2); + Py_VISIT(traverse_module_state->__pyx_n_s_k); Py_VISIT(traverse_module_state->__pyx_n_s_key); Py_VISIT(traverse_module_state->__pyx_n_s_keys); + Py_VISIT(traverse_module_state->__pyx_n_s_lN); Py_VISIT(traverse_module_state->__pyx_n_u_lam); Py_VISIT(traverse_module_state->__pyx_n_u_lam_2); Py_VISIT(traverse_module_state->__pyx_n_u_lbu); @@ -4857,8 +5058,10 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { Py_VISIT(traverse_module_state->__pyx_n_s_model_name); Py_VISIT(traverse_module_state->__pyx_n_s_msg); Py_VISIT(traverse_module_state->__pyx_n_s_n); + Py_VISIT(traverse_module_state->__pyx_n_s_n_update); Py_VISIT(traverse_module_state->__pyx_n_s_name); Py_VISIT(traverse_module_state->__pyx_n_s_name_2); + Py_VISIT(traverse_module_state->__pyx_n_s_ndarray); Py_VISIT(traverse_module_state->__pyx_n_s_ndim); Py_VISIT(traverse_module_state->__pyx_n_s_new); Py_VISIT(traverse_module_state->__pyx_n_s_new_time_steps); @@ -4880,6 +5083,10 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { Py_VISIT(traverse_module_state->__pyx_n_s_overwrite); Py_VISIT(traverse_module_state->__pyx_n_u_p); Py_VISIT(traverse_module_state->__pyx_n_s_pack); + Py_VISIT(traverse_module_state->__pyx_n_s_param_values); + Py_VISIT(traverse_module_state->__pyx_kp_u_param_values_2); + Py_VISIT(traverse_module_state->__pyx_kp_u_param_values__and_idx_values__mu); + Py_VISIT(traverse_module_state->__pyx_kp_u_param_values__must_be_np_array); Py_VISIT(traverse_module_state->__pyx_n_s_path); Py_VISIT(traverse_module_state->__pyx_n_u_pi); Py_VISIT(traverse_module_state->__pyx_n_u_pi_2); @@ -4915,11 +5122,14 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { Py_VISIT(traverse_module_state->__pyx_n_b_res_ineq); Py_VISIT(traverse_module_state->__pyx_n_b_res_stat); Py_VISIT(traverse_module_state->__pyx_n_s_reset); + Py_VISIT(traverse_module_state->__pyx_n_s_reset_qp_solver_mem); Py_VISIT(traverse_module_state->__pyx_n_u_residuals); Py_VISIT(traverse_module_state->__pyx_n_u_rti_phase); Py_VISIT(traverse_module_state->__pyx_n_s_self); Py_VISIT(traverse_module_state->__pyx_n_s_set); Py_VISIT(traverse_module_state->__pyx_n_s_set_new_time_steps); + Py_VISIT(traverse_module_state->__pyx_n_s_set_params_sparse); + Py_VISIT(traverse_module_state->__pyx_kp_u_set_value_must_be_numpy_array_go); Py_VISIT(traverse_module_state->__pyx_n_s_setstate); Py_VISIT(traverse_module_state->__pyx_n_s_setstate_cython); Py_VISIT(traverse_module_state->__pyx_n_s_shape); @@ -4928,6 +5138,7 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { Py_VISIT(traverse_module_state->__pyx_n_u_sl_2); Py_VISIT(traverse_module_state->__pyx_n_s_solution); Py_VISIT(traverse_module_state->__pyx_n_s_solve); + Py_VISIT(traverse_module_state->__pyx_n_s_solve_for_x0); Py_VISIT(traverse_module_state->__pyx_kp_u_solver_option_must_be_of_type_fl); Py_VISIT(traverse_module_state->__pyx_kp_u_solver_option_must_be_of_type_in); Py_VISIT(traverse_module_state->__pyx_kp_u_solver_option_must_be_of_type_st); @@ -4943,6 +5154,7 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { Py_VISIT(traverse_module_state->__pyx_n_s_stat_n); Py_VISIT(traverse_module_state->__pyx_n_u_stat_n); Py_VISIT(traverse_module_state->__pyx_n_u_statistics); + Py_VISIT(traverse_module_state->__pyx_n_s_status); Py_VISIT(traverse_module_state->__pyx_n_s_step); Py_VISIT(traverse_module_state->__pyx_n_u_step_length); Py_VISIT(traverse_module_state->__pyx_n_s_stop); @@ -4981,6 +5193,7 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { Py_VISIT(traverse_module_state->__pyx_n_u_tol_stat); Py_VISIT(traverse_module_state->__pyx_n_s_tolist); Py_VISIT(traverse_module_state->__pyx_n_u_u); + Py_VISIT(traverse_module_state->__pyx_n_s_u0); Py_VISIT(traverse_module_state->__pyx_n_u_u_2); Py_VISIT(traverse_module_state->__pyx_n_u_ubu); Py_VISIT(traverse_module_state->__pyx_n_u_ubx); @@ -5002,6 +5215,7 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { Py_VISIT(traverse_module_state->__pyx_n_b_x); Py_VISIT(traverse_module_state->__pyx_n_s_x); Py_VISIT(traverse_module_state->__pyx_n_u_x); + Py_VISIT(traverse_module_state->__pyx_n_s_x0_bar); Py_VISIT(traverse_module_state->__pyx_n_u_x_2); Py_VISIT(traverse_module_state->__pyx_n_u_xdot_guess); Py_VISIT(traverse_module_state->__pyx_n_u_y_ref); @@ -5009,6 +5223,7 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { Py_VISIT(traverse_module_state->__pyx_n_u_yref); Py_VISIT(traverse_module_state->__pyx_n_u_z); Py_VISIT(traverse_module_state->__pyx_n_u_z_2); + Py_VISIT(traverse_module_state->__pyx_n_b_z_guess); Py_VISIT(traverse_module_state->__pyx_n_u_z_guess); Py_VISIT(traverse_module_state->__pyx_n_s_zeros); Py_VISIT(traverse_module_state->__pyx_int_0); @@ -5027,13 +5242,13 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { Py_VISIT(traverse_module_state->__pyx_tuple__4); Py_VISIT(traverse_module_state->__pyx_tuple__8); Py_VISIT(traverse_module_state->__pyx_tuple__9); - Py_VISIT(traverse_module_state->__pyx_slice__16); + Py_VISIT(traverse_module_state->__pyx_slice__18); Py_VISIT(traverse_module_state->__pyx_tuple__10); Py_VISIT(traverse_module_state->__pyx_tuple__11); Py_VISIT(traverse_module_state->__pyx_tuple__12); Py_VISIT(traverse_module_state->__pyx_tuple__13); - Py_VISIT(traverse_module_state->__pyx_tuple__17); - Py_VISIT(traverse_module_state->__pyx_tuple__18); + Py_VISIT(traverse_module_state->__pyx_tuple__14); + Py_VISIT(traverse_module_state->__pyx_tuple__15); Py_VISIT(traverse_module_state->__pyx_tuple__19); Py_VISIT(traverse_module_state->__pyx_tuple__20); Py_VISIT(traverse_module_state->__pyx_tuple__21); @@ -5044,8 +5259,8 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { Py_VISIT(traverse_module_state->__pyx_tuple__26); Py_VISIT(traverse_module_state->__pyx_tuple__27); Py_VISIT(traverse_module_state->__pyx_tuple__28); + Py_VISIT(traverse_module_state->__pyx_tuple__29); Py_VISIT(traverse_module_state->__pyx_tuple__30); - Py_VISIT(traverse_module_state->__pyx_tuple__31); Py_VISIT(traverse_module_state->__pyx_tuple__32); Py_VISIT(traverse_module_state->__pyx_tuple__33); Py_VISIT(traverse_module_state->__pyx_tuple__34); @@ -5054,50 +5269,60 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { Py_VISIT(traverse_module_state->__pyx_tuple__37); Py_VISIT(traverse_module_state->__pyx_tuple__38); Py_VISIT(traverse_module_state->__pyx_tuple__39); + Py_VISIT(traverse_module_state->__pyx_tuple__40); Py_VISIT(traverse_module_state->__pyx_tuple__41); - Py_VISIT(traverse_module_state->__pyx_tuple__45); - Py_VISIT(traverse_module_state->__pyx_tuple__47); + Py_VISIT(traverse_module_state->__pyx_tuple__42); + Py_VISIT(traverse_module_state->__pyx_tuple__44); + Py_VISIT(traverse_module_state->__pyx_tuple__46); Py_VISIT(traverse_module_state->__pyx_tuple__49); Py_VISIT(traverse_module_state->__pyx_tuple__51); - Py_VISIT(traverse_module_state->__pyx_tuple__52); + Py_VISIT(traverse_module_state->__pyx_tuple__53); Py_VISIT(traverse_module_state->__pyx_tuple__55); Py_VISIT(traverse_module_state->__pyx_tuple__57); - Py_VISIT(traverse_module_state->__pyx_tuple__58); + Py_VISIT(traverse_module_state->__pyx_tuple__59); Py_VISIT(traverse_module_state->__pyx_tuple__60); - Py_VISIT(traverse_module_state->__pyx_tuple__62); + Py_VISIT(traverse_module_state->__pyx_tuple__63); Py_VISIT(traverse_module_state->__pyx_tuple__65); - Py_VISIT(traverse_module_state->__pyx_tuple__67); - Py_VISIT(traverse_module_state->__pyx_tuple__69); - Py_VISIT(traverse_module_state->__pyx_tuple__71); - Py_VISIT(traverse_module_state->__pyx_tuple__72); - Py_VISIT(traverse_module_state->__pyx_tuple__74); + Py_VISIT(traverse_module_state->__pyx_tuple__66); + Py_VISIT(traverse_module_state->__pyx_tuple__68); + Py_VISIT(traverse_module_state->__pyx_tuple__70); + Py_VISIT(traverse_module_state->__pyx_tuple__73); + Py_VISIT(traverse_module_state->__pyx_tuple__75); Py_VISIT(traverse_module_state->__pyx_tuple__77); Py_VISIT(traverse_module_state->__pyx_tuple__79); + Py_VISIT(traverse_module_state->__pyx_tuple__80); Py_VISIT(traverse_module_state->__pyx_tuple__82); - Py_VISIT(traverse_module_state->__pyx_codeobj__40); - Py_VISIT(traverse_module_state->__pyx_codeobj__42); + Py_VISIT(traverse_module_state->__pyx_tuple__85); + Py_VISIT(traverse_module_state->__pyx_tuple__87); + Py_VISIT(traverse_module_state->__pyx_tuple__89); + Py_VISIT(traverse_module_state->__pyx_tuple__92); Py_VISIT(traverse_module_state->__pyx_codeobj__43); - Py_VISIT(traverse_module_state->__pyx_codeobj__44); - Py_VISIT(traverse_module_state->__pyx_codeobj__46); + Py_VISIT(traverse_module_state->__pyx_codeobj__45); + Py_VISIT(traverse_module_state->__pyx_codeobj__47); Py_VISIT(traverse_module_state->__pyx_codeobj__48); Py_VISIT(traverse_module_state->__pyx_codeobj__50); - Py_VISIT(traverse_module_state->__pyx_codeobj__53); + Py_VISIT(traverse_module_state->__pyx_codeobj__52); Py_VISIT(traverse_module_state->__pyx_codeobj__54); Py_VISIT(traverse_module_state->__pyx_codeobj__56); - Py_VISIT(traverse_module_state->__pyx_codeobj__59); + Py_VISIT(traverse_module_state->__pyx_codeobj__58); Py_VISIT(traverse_module_state->__pyx_codeobj__61); - Py_VISIT(traverse_module_state->__pyx_codeobj__63); + Py_VISIT(traverse_module_state->__pyx_codeobj__62); Py_VISIT(traverse_module_state->__pyx_codeobj__64); - Py_VISIT(traverse_module_state->__pyx_codeobj__66); - Py_VISIT(traverse_module_state->__pyx_codeobj__68); - Py_VISIT(traverse_module_state->__pyx_codeobj__70); - Py_VISIT(traverse_module_state->__pyx_codeobj__73); - Py_VISIT(traverse_module_state->__pyx_codeobj__75); + Py_VISIT(traverse_module_state->__pyx_codeobj__67); + Py_VISIT(traverse_module_state->__pyx_codeobj__69); + Py_VISIT(traverse_module_state->__pyx_codeobj__71); + Py_VISIT(traverse_module_state->__pyx_codeobj__72); + Py_VISIT(traverse_module_state->__pyx_codeobj__74); Py_VISIT(traverse_module_state->__pyx_codeobj__76); Py_VISIT(traverse_module_state->__pyx_codeobj__78); - Py_VISIT(traverse_module_state->__pyx_codeobj__80); Py_VISIT(traverse_module_state->__pyx_codeobj__81); Py_VISIT(traverse_module_state->__pyx_codeobj__83); + Py_VISIT(traverse_module_state->__pyx_codeobj__84); + Py_VISIT(traverse_module_state->__pyx_codeobj__86); + Py_VISIT(traverse_module_state->__pyx_codeobj__88); + Py_VISIT(traverse_module_state->__pyx_codeobj__90); + Py_VISIT(traverse_module_state->__pyx_codeobj__91); + Py_VISIT(traverse_module_state->__pyx_codeobj__93); return 0; } #endif @@ -5185,6 +5410,7 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #define __pyx_memoryview_type __pyx_mstate_global->__pyx_memoryview_type #define __pyx_memoryviewslice_type __pyx_mstate_global->__pyx_memoryviewslice_type #define __pyx_kp_u_ __pyx_mstate_global->__pyx_kp_u_ +#define __pyx_kp_u_0 __pyx_mstate_global->__pyx_kp_u_0 #define __pyx_n_s_ASCII __pyx_mstate_global->__pyx_n_s_ASCII #define __pyx_n_s_AcadosOcpSolverCython __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython #define __pyx_n_s_AcadosOcpSolverCython___get_poin __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython___get_poin @@ -5201,15 +5427,16 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #define __pyx_n_s_AcadosOcpSolverCython_constraint_2 __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_constraint_2 #define __pyx_n_s_AcadosOcpSolverCython_cost_set __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_cost_set #define __pyx_kp_u_AcadosOcpSolverCython_cost_set_m __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_cost_set_m +#define __pyx_n_s_AcadosOcpSolverCython_custom_upd __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_custom_upd #define __pyx_kp_u_AcadosOcpSolverCython_does_not_s __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_does_not_s #define __pyx_kp_u_AcadosOcpSolverCython_does_not_s_2 __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_does_not_s_2 -#define __pyx_n_s_AcadosOcpSolverCython_dynamics_g __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_dynamics_g #define __pyx_kp_u_AcadosOcpSolverCython_eval_param __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_eval_param #define __pyx_kp_u_AcadosOcpSolverCython_eval_param_2 __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_eval_param_2 #define __pyx_n_s_AcadosOcpSolverCython_eval_param_3 __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_eval_param_3 #define __pyx_n_s_AcadosOcpSolverCython_get __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_get #define __pyx_n_s_AcadosOcpSolverCython_get_cost __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_get_cost #define __pyx_kp_u_AcadosOcpSolverCython_get_field __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_get_field +#define __pyx_n_s_AcadosOcpSolverCython_get_from_q __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_get_from_q #define __pyx_kp_u_AcadosOcpSolverCython_get_is_an __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_get_is_an #define __pyx_n_s_AcadosOcpSolverCython_get_residu __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_get_residu #define __pyx_kp_u_AcadosOcpSolverCython_get_stage __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_get_stage @@ -5223,9 +5450,11 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #define __pyx_kp_u_AcadosOcpSolverCython_set_is_not __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_set_is_not #define __pyx_kp_u_AcadosOcpSolverCython_set_mismat __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_set_mismat #define __pyx_n_s_AcadosOcpSolverCython_set_new_ti __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_set_new_ti +#define __pyx_n_s_AcadosOcpSolverCython_set_params __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_set_params #define __pyx_n_s_AcadosOcpSolverCython_solve __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_solve #define __pyx_kp_u_AcadosOcpSolverCython_solve_argu __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_solve_argu #define __pyx_kp_u_AcadosOcpSolverCython_solve_argu_2 __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_solve_argu_2 +#define __pyx_n_s_AcadosOcpSolverCython_solve_for __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_solve_for #define __pyx_n_s_AcadosOcpSolverCython_store_iter __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_store_iter #define __pyx_n_s_AcadosOcpSolverCython_update_qp __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_update_qp #define __pyx_kp_s_All_dimensions_preceding_dimensi __pyx_mstate_global->__pyx_kp_s_All_dimensions_preceding_dimensi @@ -5240,6 +5469,7 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #define __pyx_n_s_Ellipsis __pyx_mstate_global->__pyx_n_s_Ellipsis #define __pyx_kp_s_Empty_shape_tuple_for_cython_arr __pyx_mstate_global->__pyx_kp_s_Empty_shape_tuple_for_cython_arr #define __pyx_n_u_F __pyx_mstate_global->__pyx_n_u_F +#define __pyx_kp_u_Got_sizes_idx __pyx_mstate_global->__pyx_kp_u_Got_sizes_idx #define __pyx_n_s_ImportError __pyx_mstate_global->__pyx_n_s_ImportError #define __pyx_kp_s_Incompatible_checksums_0x_x_vs_0 __pyx_mstate_global->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0 #define __pyx_n_s_IndexError __pyx_mstate_global->__pyx_n_s_IndexError @@ -5265,16 +5495,18 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #define __pyx_kp_s_Unable_to_convert_item_to_object __pyx_mstate_global->__pyx_kp_s_Unable_to_convert_item_to_object #define __pyx_n_s_ValueError __pyx_mstate_global->__pyx_n_s_ValueError #define __pyx_n_s_View_MemoryView __pyx_mstate_global->__pyx_n_s_View_MemoryView +#define __pyx_kp_u_Warning_acados_ocp_solver_reache __pyx_mstate_global->__pyx_kp_u_Warning_acados_ocp_solver_reache #define __pyx_kp_u_Y_m_d_H_M_S_f __pyx_mstate_global->__pyx_kp_u_Y_m_d_H_M_S_f -#define __pyx_kp_u__14 __pyx_mstate_global->__pyx_kp_u__14 -#define __pyx_n_u__15 __pyx_mstate_global->__pyx_n_u__15 +#define __pyx_kp_u__16 __pyx_mstate_global->__pyx_kp_u__16 +#define __pyx_n_u__17 __pyx_mstate_global->__pyx_n_u__17 #define __pyx_kp_u__2 __pyx_mstate_global->__pyx_kp_u__2 -#define __pyx_kp_u__29 __pyx_mstate_global->__pyx_kp_u__29 #define __pyx_n_s__3 __pyx_mstate_global->__pyx_n_s__3 +#define __pyx_kp_u__31 __pyx_mstate_global->__pyx_kp_u__31 #define __pyx_kp_u__6 __pyx_mstate_global->__pyx_kp_u__6 #define __pyx_kp_u__7 __pyx_mstate_global->__pyx_kp_u__7 -#define __pyx_n_s__84 __pyx_mstate_global->__pyx_n_s__84 +#define __pyx_n_s__94 __pyx_mstate_global->__pyx_n_s__94 #define __pyx_n_s_abc __pyx_mstate_global->__pyx_n_s_abc +#define __pyx_kp_u_acados_acados_ocp_solver_returne __pyx_mstate_global->__pyx_kp_u_acados_acados_ocp_solver_returne #define __pyx_n_s_acados_template_acados_ocp_solve __pyx_mstate_global->__pyx_n_s_acados_template_acados_ocp_solve #define __pyx_n_s_allocate_buffer __pyx_mstate_global->__pyx_n_s_allocate_buffer #define __pyx_n_u_alpha __pyx_mstate_global->__pyx_n_u_alpha @@ -5297,11 +5529,18 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #define __pyx_kp_s_collections_abc __pyx_mstate_global->__pyx_kp_s_collections_abc #define __pyx_n_s_constraints_fields __pyx_mstate_global->__pyx_n_s_constraints_fields #define __pyx_n_s_constraints_set __pyx_mstate_global->__pyx_n_s_constraints_set +#define __pyx_kp_u_constraints_set_value_must_be_nu __pyx_mstate_global->__pyx_kp_u_constraints_set_value_must_be_nu #define __pyx_kp_s_contiguous_and_direct __pyx_mstate_global->__pyx_kp_s_contiguous_and_direct #define __pyx_kp_s_contiguous_and_indirect __pyx_mstate_global->__pyx_kp_s_contiguous_and_indirect #define __pyx_n_s_cost_fields __pyx_mstate_global->__pyx_n_s_cost_fields #define __pyx_n_s_cost_set __pyx_mstate_global->__pyx_n_s_cost_set +#define __pyx_kp_u_cost_set_value_must_be_numpy_arr __pyx_mstate_global->__pyx_kp_u_cost_set_value_must_be_numpy_arr #define __pyx_n_s_count __pyx_mstate_global->__pyx_n_s_count +#define __pyx_n_s_custom_update __pyx_mstate_global->__pyx_n_s_custom_update +#define __pyx_n_u_d __pyx_mstate_global->__pyx_n_u_d +#define __pyx_n_s_data __pyx_mstate_global->__pyx_n_s_data +#define __pyx_n_s_data_2 __pyx_mstate_global->__pyx_n_s_data_2 +#define __pyx_n_s_data_len __pyx_mstate_global->__pyx_n_s_data_len #define __pyx_n_s_datetime __pyx_mstate_global->__pyx_n_s_datetime #define __pyx_n_s_default __pyx_mstate_global->__pyx_n_s_default #define __pyx_n_s_dict __pyx_mstate_global->__pyx_n_s_dict @@ -5312,7 +5551,6 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #define __pyx_n_s_dtype __pyx_mstate_global->__pyx_n_s_dtype #define __pyx_n_s_dtype_is_object __pyx_mstate_global->__pyx_n_s_dtype_is_object #define __pyx_n_s_dump __pyx_mstate_global->__pyx_n_s_dump -#define __pyx_n_s_dynamics_get __pyx_mstate_global->__pyx_n_s_dynamics_get #define __pyx_kp_u_enable __pyx_mstate_global->__pyx_kp_u_enable #define __pyx_n_s_encode __pyx_mstate_global->__pyx_n_s_encode #define __pyx_n_s_enter __pyx_mstate_global->__pyx_n_s_enter @@ -5338,6 +5576,7 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #define __pyx_kp_u_gc __pyx_mstate_global->__pyx_kp_u_gc #define __pyx_n_s_get __pyx_mstate_global->__pyx_n_s_get #define __pyx_n_s_get_cost __pyx_mstate_global->__pyx_n_s_get_cost +#define __pyx_n_s_get_from_qp_in __pyx_mstate_global->__pyx_n_s_get_from_qp_in #define __pyx_n_s_get_pointers_solver __pyx_mstate_global->__pyx_n_s_get_pointers_solver #define __pyx_n_s_get_residuals __pyx_mstate_global->__pyx_n_s_get_residuals #define __pyx_n_s_get_stat_double __pyx_mstate_global->__pyx_n_s_get_stat_double @@ -5351,13 +5590,17 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #define __pyx_kp_u_got __pyx_mstate_global->__pyx_kp_u_got #define __pyx_kp_u_got_differing_extents_in_dimensi __pyx_mstate_global->__pyx_kp_u_got_differing_extents_in_dimensi #define __pyx_n_s_i __pyx_mstate_global->__pyx_n_s_i +#define __pyx_n_s_i_string __pyx_mstate_global->__pyx_n_s_i_string #define __pyx_n_s_id __pyx_mstate_global->__pyx_n_s_id +#define __pyx_n_s_idx __pyx_mstate_global->__pyx_n_s_idx +#define __pyx_n_s_idx_values __pyx_mstate_global->__pyx_n_s_idx_values #define __pyx_n_s_import __pyx_mstate_global->__pyx_n_s_import #define __pyx_n_s_indent __pyx_mstate_global->__pyx_n_s_indent #define __pyx_n_s_index __pyx_mstate_global->__pyx_n_s_index #define __pyx_n_u_initialize_t_slacks __pyx_mstate_global->__pyx_n_u_initialize_t_slacks #define __pyx_n_s_initializing __pyx_mstate_global->__pyx_n_s_initializing #define __pyx_n_s_int __pyx_mstate_global->__pyx_n_s_int +#define __pyx_n_s_int32 __pyx_mstate_global->__pyx_n_s_int32 #define __pyx_n_s_int_fields __pyx_mstate_global->__pyx_n_s_int_fields #define __pyx_n_s_int_value __pyx_mstate_global->__pyx_n_s_int_value #define __pyx_n_s_is_coroutine __pyx_mstate_global->__pyx_n_s_is_coroutine @@ -5369,8 +5612,10 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #define __pyx_n_s_join __pyx_mstate_global->__pyx_n_s_join #define __pyx_n_s_json __pyx_mstate_global->__pyx_n_s_json #define __pyx_kp_u_json_2 __pyx_mstate_global->__pyx_kp_u_json_2 +#define __pyx_n_s_k __pyx_mstate_global->__pyx_n_s_k #define __pyx_n_s_key __pyx_mstate_global->__pyx_n_s_key #define __pyx_n_s_keys __pyx_mstate_global->__pyx_n_s_keys +#define __pyx_n_s_lN __pyx_mstate_global->__pyx_n_s_lN #define __pyx_n_u_lam __pyx_mstate_global->__pyx_n_u_lam #define __pyx_n_u_lam_2 __pyx_mstate_global->__pyx_n_u_lam_2 #define __pyx_n_u_lbu __pyx_mstate_global->__pyx_n_u_lbu @@ -5388,8 +5633,10 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #define __pyx_n_s_model_name __pyx_mstate_global->__pyx_n_s_model_name #define __pyx_n_s_msg __pyx_mstate_global->__pyx_n_s_msg #define __pyx_n_s_n __pyx_mstate_global->__pyx_n_s_n +#define __pyx_n_s_n_update __pyx_mstate_global->__pyx_n_s_n_update #define __pyx_n_s_name __pyx_mstate_global->__pyx_n_s_name #define __pyx_n_s_name_2 __pyx_mstate_global->__pyx_n_s_name_2 +#define __pyx_n_s_ndarray __pyx_mstate_global->__pyx_n_s_ndarray #define __pyx_n_s_ndim __pyx_mstate_global->__pyx_n_s_ndim #define __pyx_n_s_new __pyx_mstate_global->__pyx_n_s_new #define __pyx_n_s_new_time_steps __pyx_mstate_global->__pyx_n_s_new_time_steps @@ -5411,6 +5658,10 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #define __pyx_n_s_overwrite __pyx_mstate_global->__pyx_n_s_overwrite #define __pyx_n_u_p __pyx_mstate_global->__pyx_n_u_p #define __pyx_n_s_pack __pyx_mstate_global->__pyx_n_s_pack +#define __pyx_n_s_param_values __pyx_mstate_global->__pyx_n_s_param_values +#define __pyx_kp_u_param_values_2 __pyx_mstate_global->__pyx_kp_u_param_values_2 +#define __pyx_kp_u_param_values__and_idx_values__mu __pyx_mstate_global->__pyx_kp_u_param_values__and_idx_values__mu +#define __pyx_kp_u_param_values__must_be_np_array __pyx_mstate_global->__pyx_kp_u_param_values__must_be_np_array #define __pyx_n_s_path __pyx_mstate_global->__pyx_n_s_path #define __pyx_n_u_pi __pyx_mstate_global->__pyx_n_u_pi #define __pyx_n_u_pi_2 __pyx_mstate_global->__pyx_n_u_pi_2 @@ -5446,11 +5697,14 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #define __pyx_n_b_res_ineq __pyx_mstate_global->__pyx_n_b_res_ineq #define __pyx_n_b_res_stat __pyx_mstate_global->__pyx_n_b_res_stat #define __pyx_n_s_reset __pyx_mstate_global->__pyx_n_s_reset +#define __pyx_n_s_reset_qp_solver_mem __pyx_mstate_global->__pyx_n_s_reset_qp_solver_mem #define __pyx_n_u_residuals __pyx_mstate_global->__pyx_n_u_residuals #define __pyx_n_u_rti_phase __pyx_mstate_global->__pyx_n_u_rti_phase #define __pyx_n_s_self __pyx_mstate_global->__pyx_n_s_self #define __pyx_n_s_set __pyx_mstate_global->__pyx_n_s_set #define __pyx_n_s_set_new_time_steps __pyx_mstate_global->__pyx_n_s_set_new_time_steps +#define __pyx_n_s_set_params_sparse __pyx_mstate_global->__pyx_n_s_set_params_sparse +#define __pyx_kp_u_set_value_must_be_numpy_array_go __pyx_mstate_global->__pyx_kp_u_set_value_must_be_numpy_array_go #define __pyx_n_s_setstate __pyx_mstate_global->__pyx_n_s_setstate #define __pyx_n_s_setstate_cython __pyx_mstate_global->__pyx_n_s_setstate_cython #define __pyx_n_s_shape __pyx_mstate_global->__pyx_n_s_shape @@ -5459,6 +5713,7 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #define __pyx_n_u_sl_2 __pyx_mstate_global->__pyx_n_u_sl_2 #define __pyx_n_s_solution __pyx_mstate_global->__pyx_n_s_solution #define __pyx_n_s_solve __pyx_mstate_global->__pyx_n_s_solve +#define __pyx_n_s_solve_for_x0 __pyx_mstate_global->__pyx_n_s_solve_for_x0 #define __pyx_kp_u_solver_option_must_be_of_type_fl __pyx_mstate_global->__pyx_kp_u_solver_option_must_be_of_type_fl #define __pyx_kp_u_solver_option_must_be_of_type_in __pyx_mstate_global->__pyx_kp_u_solver_option_must_be_of_type_in #define __pyx_kp_u_solver_option_must_be_of_type_st __pyx_mstate_global->__pyx_kp_u_solver_option_must_be_of_type_st @@ -5474,6 +5729,7 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #define __pyx_n_s_stat_n __pyx_mstate_global->__pyx_n_s_stat_n #define __pyx_n_u_stat_n __pyx_mstate_global->__pyx_n_u_stat_n #define __pyx_n_u_statistics __pyx_mstate_global->__pyx_n_u_statistics +#define __pyx_n_s_status __pyx_mstate_global->__pyx_n_s_status #define __pyx_n_s_step __pyx_mstate_global->__pyx_n_s_step #define __pyx_n_u_step_length __pyx_mstate_global->__pyx_n_u_step_length #define __pyx_n_s_stop __pyx_mstate_global->__pyx_n_s_stop @@ -5512,6 +5768,7 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #define __pyx_n_u_tol_stat __pyx_mstate_global->__pyx_n_u_tol_stat #define __pyx_n_s_tolist __pyx_mstate_global->__pyx_n_s_tolist #define __pyx_n_u_u __pyx_mstate_global->__pyx_n_u_u +#define __pyx_n_s_u0 __pyx_mstate_global->__pyx_n_s_u0 #define __pyx_n_u_u_2 __pyx_mstate_global->__pyx_n_u_u_2 #define __pyx_n_u_ubu __pyx_mstate_global->__pyx_n_u_ubu #define __pyx_n_u_ubx __pyx_mstate_global->__pyx_n_u_ubx @@ -5533,6 +5790,7 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #define __pyx_n_b_x __pyx_mstate_global->__pyx_n_b_x #define __pyx_n_s_x __pyx_mstate_global->__pyx_n_s_x #define __pyx_n_u_x __pyx_mstate_global->__pyx_n_u_x +#define __pyx_n_s_x0_bar __pyx_mstate_global->__pyx_n_s_x0_bar #define __pyx_n_u_x_2 __pyx_mstate_global->__pyx_n_u_x_2 #define __pyx_n_u_xdot_guess __pyx_mstate_global->__pyx_n_u_xdot_guess #define __pyx_n_u_y_ref __pyx_mstate_global->__pyx_n_u_y_ref @@ -5540,6 +5798,7 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #define __pyx_n_u_yref __pyx_mstate_global->__pyx_n_u_yref #define __pyx_n_u_z __pyx_mstate_global->__pyx_n_u_z #define __pyx_n_u_z_2 __pyx_mstate_global->__pyx_n_u_z_2 +#define __pyx_n_b_z_guess __pyx_mstate_global->__pyx_n_b_z_guess #define __pyx_n_u_z_guess __pyx_mstate_global->__pyx_n_u_z_guess #define __pyx_n_s_zeros __pyx_mstate_global->__pyx_n_s_zeros #define __pyx_int_0 __pyx_mstate_global->__pyx_int_0 @@ -5558,13 +5817,13 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #define __pyx_tuple__4 __pyx_mstate_global->__pyx_tuple__4 #define __pyx_tuple__8 __pyx_mstate_global->__pyx_tuple__8 #define __pyx_tuple__9 __pyx_mstate_global->__pyx_tuple__9 -#define __pyx_slice__16 __pyx_mstate_global->__pyx_slice__16 +#define __pyx_slice__18 __pyx_mstate_global->__pyx_slice__18 #define __pyx_tuple__10 __pyx_mstate_global->__pyx_tuple__10 #define __pyx_tuple__11 __pyx_mstate_global->__pyx_tuple__11 #define __pyx_tuple__12 __pyx_mstate_global->__pyx_tuple__12 #define __pyx_tuple__13 __pyx_mstate_global->__pyx_tuple__13 -#define __pyx_tuple__17 __pyx_mstate_global->__pyx_tuple__17 -#define __pyx_tuple__18 __pyx_mstate_global->__pyx_tuple__18 +#define __pyx_tuple__14 __pyx_mstate_global->__pyx_tuple__14 +#define __pyx_tuple__15 __pyx_mstate_global->__pyx_tuple__15 #define __pyx_tuple__19 __pyx_mstate_global->__pyx_tuple__19 #define __pyx_tuple__20 __pyx_mstate_global->__pyx_tuple__20 #define __pyx_tuple__21 __pyx_mstate_global->__pyx_tuple__21 @@ -5575,8 +5834,8 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #define __pyx_tuple__26 __pyx_mstate_global->__pyx_tuple__26 #define __pyx_tuple__27 __pyx_mstate_global->__pyx_tuple__27 #define __pyx_tuple__28 __pyx_mstate_global->__pyx_tuple__28 +#define __pyx_tuple__29 __pyx_mstate_global->__pyx_tuple__29 #define __pyx_tuple__30 __pyx_mstate_global->__pyx_tuple__30 -#define __pyx_tuple__31 __pyx_mstate_global->__pyx_tuple__31 #define __pyx_tuple__32 __pyx_mstate_global->__pyx_tuple__32 #define __pyx_tuple__33 __pyx_mstate_global->__pyx_tuple__33 #define __pyx_tuple__34 __pyx_mstate_global->__pyx_tuple__34 @@ -5585,50 +5844,60 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #define __pyx_tuple__37 __pyx_mstate_global->__pyx_tuple__37 #define __pyx_tuple__38 __pyx_mstate_global->__pyx_tuple__38 #define __pyx_tuple__39 __pyx_mstate_global->__pyx_tuple__39 +#define __pyx_tuple__40 __pyx_mstate_global->__pyx_tuple__40 #define __pyx_tuple__41 __pyx_mstate_global->__pyx_tuple__41 -#define __pyx_tuple__45 __pyx_mstate_global->__pyx_tuple__45 -#define __pyx_tuple__47 __pyx_mstate_global->__pyx_tuple__47 +#define __pyx_tuple__42 __pyx_mstate_global->__pyx_tuple__42 +#define __pyx_tuple__44 __pyx_mstate_global->__pyx_tuple__44 +#define __pyx_tuple__46 __pyx_mstate_global->__pyx_tuple__46 #define __pyx_tuple__49 __pyx_mstate_global->__pyx_tuple__49 #define __pyx_tuple__51 __pyx_mstate_global->__pyx_tuple__51 -#define __pyx_tuple__52 __pyx_mstate_global->__pyx_tuple__52 +#define __pyx_tuple__53 __pyx_mstate_global->__pyx_tuple__53 #define __pyx_tuple__55 __pyx_mstate_global->__pyx_tuple__55 #define __pyx_tuple__57 __pyx_mstate_global->__pyx_tuple__57 -#define __pyx_tuple__58 __pyx_mstate_global->__pyx_tuple__58 +#define __pyx_tuple__59 __pyx_mstate_global->__pyx_tuple__59 #define __pyx_tuple__60 __pyx_mstate_global->__pyx_tuple__60 -#define __pyx_tuple__62 __pyx_mstate_global->__pyx_tuple__62 +#define __pyx_tuple__63 __pyx_mstate_global->__pyx_tuple__63 #define __pyx_tuple__65 __pyx_mstate_global->__pyx_tuple__65 -#define __pyx_tuple__67 __pyx_mstate_global->__pyx_tuple__67 -#define __pyx_tuple__69 __pyx_mstate_global->__pyx_tuple__69 -#define __pyx_tuple__71 __pyx_mstate_global->__pyx_tuple__71 -#define __pyx_tuple__72 __pyx_mstate_global->__pyx_tuple__72 -#define __pyx_tuple__74 __pyx_mstate_global->__pyx_tuple__74 +#define __pyx_tuple__66 __pyx_mstate_global->__pyx_tuple__66 +#define __pyx_tuple__68 __pyx_mstate_global->__pyx_tuple__68 +#define __pyx_tuple__70 __pyx_mstate_global->__pyx_tuple__70 +#define __pyx_tuple__73 __pyx_mstate_global->__pyx_tuple__73 +#define __pyx_tuple__75 __pyx_mstate_global->__pyx_tuple__75 #define __pyx_tuple__77 __pyx_mstate_global->__pyx_tuple__77 #define __pyx_tuple__79 __pyx_mstate_global->__pyx_tuple__79 +#define __pyx_tuple__80 __pyx_mstate_global->__pyx_tuple__80 #define __pyx_tuple__82 __pyx_mstate_global->__pyx_tuple__82 -#define __pyx_codeobj__40 __pyx_mstate_global->__pyx_codeobj__40 -#define __pyx_codeobj__42 __pyx_mstate_global->__pyx_codeobj__42 +#define __pyx_tuple__85 __pyx_mstate_global->__pyx_tuple__85 +#define __pyx_tuple__87 __pyx_mstate_global->__pyx_tuple__87 +#define __pyx_tuple__89 __pyx_mstate_global->__pyx_tuple__89 +#define __pyx_tuple__92 __pyx_mstate_global->__pyx_tuple__92 #define __pyx_codeobj__43 __pyx_mstate_global->__pyx_codeobj__43 -#define __pyx_codeobj__44 __pyx_mstate_global->__pyx_codeobj__44 -#define __pyx_codeobj__46 __pyx_mstate_global->__pyx_codeobj__46 +#define __pyx_codeobj__45 __pyx_mstate_global->__pyx_codeobj__45 +#define __pyx_codeobj__47 __pyx_mstate_global->__pyx_codeobj__47 #define __pyx_codeobj__48 __pyx_mstate_global->__pyx_codeobj__48 #define __pyx_codeobj__50 __pyx_mstate_global->__pyx_codeobj__50 -#define __pyx_codeobj__53 __pyx_mstate_global->__pyx_codeobj__53 +#define __pyx_codeobj__52 __pyx_mstate_global->__pyx_codeobj__52 #define __pyx_codeobj__54 __pyx_mstate_global->__pyx_codeobj__54 #define __pyx_codeobj__56 __pyx_mstate_global->__pyx_codeobj__56 -#define __pyx_codeobj__59 __pyx_mstate_global->__pyx_codeobj__59 +#define __pyx_codeobj__58 __pyx_mstate_global->__pyx_codeobj__58 #define __pyx_codeobj__61 __pyx_mstate_global->__pyx_codeobj__61 -#define __pyx_codeobj__63 __pyx_mstate_global->__pyx_codeobj__63 +#define __pyx_codeobj__62 __pyx_mstate_global->__pyx_codeobj__62 #define __pyx_codeobj__64 __pyx_mstate_global->__pyx_codeobj__64 -#define __pyx_codeobj__66 __pyx_mstate_global->__pyx_codeobj__66 -#define __pyx_codeobj__68 __pyx_mstate_global->__pyx_codeobj__68 -#define __pyx_codeobj__70 __pyx_mstate_global->__pyx_codeobj__70 -#define __pyx_codeobj__73 __pyx_mstate_global->__pyx_codeobj__73 -#define __pyx_codeobj__75 __pyx_mstate_global->__pyx_codeobj__75 +#define __pyx_codeobj__67 __pyx_mstate_global->__pyx_codeobj__67 +#define __pyx_codeobj__69 __pyx_mstate_global->__pyx_codeobj__69 +#define __pyx_codeobj__71 __pyx_mstate_global->__pyx_codeobj__71 +#define __pyx_codeobj__72 __pyx_mstate_global->__pyx_codeobj__72 +#define __pyx_codeobj__74 __pyx_mstate_global->__pyx_codeobj__74 #define __pyx_codeobj__76 __pyx_mstate_global->__pyx_codeobj__76 #define __pyx_codeobj__78 __pyx_mstate_global->__pyx_codeobj__78 -#define __pyx_codeobj__80 __pyx_mstate_global->__pyx_codeobj__80 #define __pyx_codeobj__81 __pyx_mstate_global->__pyx_codeobj__81 #define __pyx_codeobj__83 __pyx_mstate_global->__pyx_codeobj__83 +#define __pyx_codeobj__84 __pyx_mstate_global->__pyx_codeobj__84 +#define __pyx_codeobj__86 __pyx_mstate_global->__pyx_codeobj__86 +#define __pyx_codeobj__88 __pyx_mstate_global->__pyx_codeobj__88 +#define __pyx_codeobj__90 __pyx_mstate_global->__pyx_codeobj__90 +#define __pyx_codeobj__91 __pyx_mstate_global->__pyx_codeobj__91 +#define __pyx_codeobj__93 __pyx_mstate_global->__pyx_codeobj__93 /* #### Code section: module_code ### */ /* "carray.to_py":114 @@ -20419,7 +20688,7 @@ static CYTHON_INLINE NPY_DATETIMEUNIT __pyx_f_5numpy_get_datetime64_unit(PyObjec return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":74 +/* "acados_template/acados_ocp_solver_pyx.pyx":70 * cdef str nlp_solver_type * * def __cinit__(self, model_name, nlp_solver_type, N): # <<<<<<<<<<<<<< @@ -20460,26 +20729,26 @@ static int __pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverC switch (__pyx_nargs) { case 0: if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_model_name)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 74, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 70, __pyx_L3_error) else goto __pyx_L5_argtuple_error; CYTHON_FALLTHROUGH; case 1: if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_nlp_solver_type)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 74, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 70, __pyx_L3_error) else { - __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 3, 3, 1); __PYX_ERR(0, 74, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 3, 3, 1); __PYX_ERR(0, 70, __pyx_L3_error) } CYTHON_FALLTHROUGH; case 2: if (likely((values[2] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_N)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 74, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 70, __pyx_L3_error) else { - __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 3, 3, 2); __PYX_ERR(0, 74, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 3, 3, 2); __PYX_ERR(0, 70, __pyx_L3_error) } } if (unlikely(kw_args > 0)) { const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__cinit__") < 0)) __PYX_ERR(0, 74, __pyx_L3_error) + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__cinit__") < 0)) __PYX_ERR(0, 70, __pyx_L3_error) } } else if (unlikely(__pyx_nargs != 3)) { goto __pyx_L5_argtuple_error; @@ -20494,7 +20763,7 @@ static int __pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverC } goto __pyx_L4_argument_unpacking_done; __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 74, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 70, __pyx_L3_error) __pyx_L3_error:; __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); __Pyx_RefNannyFinishContext(); @@ -20520,7 +20789,7 @@ static int __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverC int __pyx_clineno = 0; __Pyx_RefNannySetupContext("__cinit__", 0); - /* "acados_template/acados_ocp_solver_pyx.pyx":76 + /* "acados_template/acados_ocp_solver_pyx.pyx":72 * def __cinit__(self, model_name, nlp_solver_type, N): * * self.solver_created = False # <<<<<<<<<<<<<< @@ -20529,24 +20798,24 @@ static int __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverC */ __pyx_v_self->solver_created = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":78 + /* "acados_template/acados_ocp_solver_pyx.pyx":74 * self.solver_created = False * * self.N = N # <<<<<<<<<<<<<< * self.model_name = model_name * self.nlp_solver_type = nlp_solver_type */ - __pyx_t_1 = __Pyx_PyInt_As_int(__pyx_v_N); if (unlikely((__pyx_t_1 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 78, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyInt_As_int(__pyx_v_N); if (unlikely((__pyx_t_1 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 74, __pyx_L1_error) __pyx_v_self->N = __pyx_t_1; - /* "acados_template/acados_ocp_solver_pyx.pyx":79 + /* "acados_template/acados_ocp_solver_pyx.pyx":75 * * self.N = N * self.model_name = model_name # <<<<<<<<<<<<<< * self.nlp_solver_type = nlp_solver_type * */ - if (!(likely(PyUnicode_CheckExact(__pyx_v_model_name))||((__pyx_v_model_name) == Py_None) || __Pyx_RaiseUnexpectedTypeError("unicode", __pyx_v_model_name))) __PYX_ERR(0, 79, __pyx_L1_error) + if (!(likely(PyUnicode_CheckExact(__pyx_v_model_name))||((__pyx_v_model_name) == Py_None) || __Pyx_RaiseUnexpectedTypeError("unicode", __pyx_v_model_name))) __PYX_ERR(0, 75, __pyx_L1_error) __pyx_t_2 = __pyx_v_model_name; __Pyx_INCREF(__pyx_t_2); __Pyx_GIVEREF(__pyx_t_2); @@ -20555,14 +20824,14 @@ static int __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverC __pyx_v_self->model_name = ((PyObject*)__pyx_t_2); __pyx_t_2 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":80 + /* "acados_template/acados_ocp_solver_pyx.pyx":76 * self.N = N * self.model_name = model_name * self.nlp_solver_type = nlp_solver_type # <<<<<<<<<<<<<< * * # create capsule */ - if (!(likely(PyUnicode_CheckExact(__pyx_v_nlp_solver_type))||((__pyx_v_nlp_solver_type) == Py_None) || __Pyx_RaiseUnexpectedTypeError("unicode", __pyx_v_nlp_solver_type))) __PYX_ERR(0, 80, __pyx_L1_error) + if (!(likely(PyUnicode_CheckExact(__pyx_v_nlp_solver_type))||((__pyx_v_nlp_solver_type) == Py_None) || __Pyx_RaiseUnexpectedTypeError("unicode", __pyx_v_nlp_solver_type))) __PYX_ERR(0, 76, __pyx_L1_error) __pyx_t_2 = __pyx_v_nlp_solver_type; __Pyx_INCREF(__pyx_t_2); __Pyx_GIVEREF(__pyx_t_2); @@ -20571,7 +20840,7 @@ static int __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverC __pyx_v_self->nlp_solver_type = ((PyObject*)__pyx_t_2); __pyx_t_2 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":83 + /* "acados_template/acados_ocp_solver_pyx.pyx":79 * * # create capsule * self.capsule = acados_solver.acados_create_capsule() # <<<<<<<<<<<<<< @@ -20580,7 +20849,7 @@ static int __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverC */ __pyx_v_self->capsule = lat_acados_create_capsule(); - /* "acados_template/acados_ocp_solver_pyx.pyx":86 + /* "acados_template/acados_ocp_solver_pyx.pyx":82 * * # create solver * assert acados_solver.acados_create(self.capsule) == 0 # <<<<<<<<<<<<<< @@ -20592,14 +20861,14 @@ static int __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverC __pyx_t_3 = (lat_acados_create(__pyx_v_self->capsule) == 0); if (unlikely(!__pyx_t_3)) { __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); - __PYX_ERR(0, 86, __pyx_L1_error) + __PYX_ERR(0, 82, __pyx_L1_error) } } #else - if ((1)); else __PYX_ERR(0, 86, __pyx_L1_error) + if ((1)); else __PYX_ERR(0, 82, __pyx_L1_error) #endif - /* "acados_template/acados_ocp_solver_pyx.pyx":87 + /* "acados_template/acados_ocp_solver_pyx.pyx":83 * # create solver * assert acados_solver.acados_create(self.capsule) == 0 * self.solver_created = True # <<<<<<<<<<<<<< @@ -20608,14 +20877,14 @@ static int __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverC */ __pyx_v_self->solver_created = 1; - /* "acados_template/acados_ocp_solver_pyx.pyx":90 + /* "acados_template/acados_ocp_solver_pyx.pyx":86 * * # get pointers solver * self.__get_pointers_solver() # <<<<<<<<<<<<<< - * self.status = 0 + * * */ - __pyx_t_4 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_AcadosOcpSolverCython__get_poin); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 90, __pyx_L1_error) + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_AcadosOcpSolverCython__get_poin); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 86, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); __pyx_t_5 = NULL; __pyx_t_1 = 0; @@ -20633,22 +20902,13 @@ static int __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverC PyObject *__pyx_callargs[1] = {__pyx_t_5, }; __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_1, 0+__pyx_t_1); __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; - if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 90, __pyx_L1_error) + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 86, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; } __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":91 - * # get pointers solver - * self.__get_pointers_solver() - * self.status = 0 # <<<<<<<<<<<<<< - * - * - */ - __pyx_v_self->status = 0; - - /* "acados_template/acados_ocp_solver_pyx.pyx":74 + /* "acados_template/acados_ocp_solver_pyx.pyx":70 * cdef str nlp_solver_type * * def __cinit__(self, model_name, nlp_solver_type, N): # <<<<<<<<<<<<<< @@ -20670,7 +20930,7 @@ static int __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverC return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":94 +/* "acados_template/acados_ocp_solver_pyx.pyx":89 * * * def __get_pointers_solver(self): # <<<<<<<<<<<<<< @@ -20717,7 +20977,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __Pyx_RefNannyDeclarations __Pyx_RefNannySetupContext("_AcadosOcpSolverCython__get_pointers_solver", 0); - /* "acados_template/acados_ocp_solver_pyx.pyx":99 + /* "acados_template/acados_ocp_solver_pyx.pyx":94 * """ * # get pointers solver * self.nlp_opts = acados_solver.acados_get_nlp_opts(self.capsule) # <<<<<<<<<<<<<< @@ -20726,7 +20986,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ __pyx_v_self->nlp_opts = lat_acados_get_nlp_opts(__pyx_v_self->capsule); - /* "acados_template/acados_ocp_solver_pyx.pyx":100 + /* "acados_template/acados_ocp_solver_pyx.pyx":95 * # get pointers solver * self.nlp_opts = acados_solver.acados_get_nlp_opts(self.capsule) * self.nlp_dims = acados_solver.acados_get_nlp_dims(self.capsule) # <<<<<<<<<<<<<< @@ -20735,7 +20995,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ __pyx_v_self->nlp_dims = lat_acados_get_nlp_dims(__pyx_v_self->capsule); - /* "acados_template/acados_ocp_solver_pyx.pyx":101 + /* "acados_template/acados_ocp_solver_pyx.pyx":96 * self.nlp_opts = acados_solver.acados_get_nlp_opts(self.capsule) * self.nlp_dims = acados_solver.acados_get_nlp_dims(self.capsule) * self.nlp_config = acados_solver.acados_get_nlp_config(self.capsule) # <<<<<<<<<<<<<< @@ -20744,7 +21004,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ __pyx_v_self->nlp_config = lat_acados_get_nlp_config(__pyx_v_self->capsule); - /* "acados_template/acados_ocp_solver_pyx.pyx":102 + /* "acados_template/acados_ocp_solver_pyx.pyx":97 * self.nlp_dims = acados_solver.acados_get_nlp_dims(self.capsule) * self.nlp_config = acados_solver.acados_get_nlp_config(self.capsule) * self.nlp_out = acados_solver.acados_get_nlp_out(self.capsule) # <<<<<<<<<<<<<< @@ -20753,7 +21013,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ __pyx_v_self->nlp_out = lat_acados_get_nlp_out(__pyx_v_self->capsule); - /* "acados_template/acados_ocp_solver_pyx.pyx":103 + /* "acados_template/acados_ocp_solver_pyx.pyx":98 * self.nlp_config = acados_solver.acados_get_nlp_config(self.capsule) * self.nlp_out = acados_solver.acados_get_nlp_out(self.capsule) * self.sens_out = acados_solver.acados_get_sens_out(self.capsule) # <<<<<<<<<<<<<< @@ -20762,7 +21022,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ __pyx_v_self->sens_out = lat_acados_get_sens_out(__pyx_v_self->capsule); - /* "acados_template/acados_ocp_solver_pyx.pyx":104 + /* "acados_template/acados_ocp_solver_pyx.pyx":99 * self.nlp_out = acados_solver.acados_get_nlp_out(self.capsule) * self.sens_out = acados_solver.acados_get_sens_out(self.capsule) * self.nlp_in = acados_solver.acados_get_nlp_in(self.capsule) # <<<<<<<<<<<<<< @@ -20771,7 +21031,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ __pyx_v_self->nlp_in = lat_acados_get_nlp_in(__pyx_v_self->capsule); - /* "acados_template/acados_ocp_solver_pyx.pyx":105 + /* "acados_template/acados_ocp_solver_pyx.pyx":100 * self.sens_out = acados_solver.acados_get_sens_out(self.capsule) * self.nlp_in = acados_solver.acados_get_nlp_in(self.capsule) * self.nlp_solver = acados_solver.acados_get_nlp_solver(self.capsule) # <<<<<<<<<<<<<< @@ -20780,7 +21040,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ __pyx_v_self->nlp_solver = lat_acados_get_nlp_solver(__pyx_v_self->capsule); - /* "acados_template/acados_ocp_solver_pyx.pyx":94 + /* "acados_template/acados_ocp_solver_pyx.pyx":89 * * * def __get_pointers_solver(self): # <<<<<<<<<<<<<< @@ -20795,7 +21055,316 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":108 +/* "acados_template/acados_ocp_solver_pyx.pyx":103 + * + * + * def solve_for_x0(self, x0_bar): # <<<<<<<<<<<<<< + * """ + * Wrapper around `solve()` which sets initial state constraint, solves the OCP, and returns u0. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve_for_x0(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve_for_x0, "\n Wrapper around `solve()` which sets initial state constraint, solves the OCP, and returns u0.\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve_for_x0 = {"solve_for_x0", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve_for_x0, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve_for_x0}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve_for_x0(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_x0_bar = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("solve_for_x0 (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_x0_bar,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_x0_bar)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 103, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "solve_for_x0") < 0)) __PYX_ERR(0, 103, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_x0_bar = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("solve_for_x0", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 103, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.solve_for_x0", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve_for_x0(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_x0_bar); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve_for_x0(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_x0_bar) { + PyObject *__pyx_v_status = NULL; + PyObject *__pyx_v_u0 = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("solve_for_x0", 0); + + /* "acados_template/acados_ocp_solver_pyx.pyx":107 + * Wrapper around `solve()` which sets initial state constraint, solves the OCP, and returns u0. + * """ + * self.set(0, "lbx", x0_bar) # <<<<<<<<<<<<<< + * self.set(0, "ubx", x0_bar) + * + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_set); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 107, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[4] = {__pyx_t_3, __pyx_int_0, __pyx_n_u_lbx, __pyx_v_x0_bar}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 3+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 107, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":108 + * """ + * self.set(0, "lbx", x0_bar) + * self.set(0, "ubx", x0_bar) # <<<<<<<<<<<<<< + * + * status = self.solve() + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_set); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 108, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[4] = {__pyx_t_3, __pyx_int_0, __pyx_n_u_ubx, __pyx_v_x0_bar}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 3+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 108, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":110 + * self.set(0, "ubx", x0_bar) + * + * status = self.solve() # <<<<<<<<<<<<<< + * + * if status == 2: + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_solve); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 110, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[1] = {__pyx_t_3, }; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 0+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 110, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_v_status = __pyx_t_1; + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":112 + * status = self.solve() + * + * if status == 2: # <<<<<<<<<<<<<< + * print("Warning: acados_ocp_solver reached maximum iterations.") + * elif status != 0: + */ + __pyx_t_5 = (__Pyx_PyInt_BoolEqObjC(__pyx_v_status, __pyx_int_2, 2, 0)); if (unlikely((__pyx_t_5 < 0))) __PYX_ERR(0, 112, __pyx_L1_error) + if (__pyx_t_5) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":113 + * + * if status == 2: + * print("Warning: acados_ocp_solver reached maximum iterations.") # <<<<<<<<<<<<<< + * elif status != 0: + * raise Exception(f'acados acados_ocp_solver returned status {status}') + */ + __pyx_t_1 = __Pyx_PyObject_Call(__pyx_builtin_print, __pyx_tuple__11, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 113, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":112 + * status = self.solve() + * + * if status == 2: # <<<<<<<<<<<<<< + * print("Warning: acados_ocp_solver reached maximum iterations.") + * elif status != 0: + */ + goto __pyx_L3; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":114 + * if status == 2: + * print("Warning: acados_ocp_solver reached maximum iterations.") + * elif status != 0: # <<<<<<<<<<<<<< + * raise Exception(f'acados acados_ocp_solver returned status {status}') + * + */ + __pyx_t_5 = (__Pyx_PyInt_BoolNeObjC(__pyx_v_status, __pyx_int_0, 0, 0)); if (unlikely((__pyx_t_5 < 0))) __PYX_ERR(0, 114, __pyx_L1_error) + if (unlikely(__pyx_t_5)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":115 + * print("Warning: acados_ocp_solver reached maximum iterations.") + * elif status != 0: + * raise Exception(f'acados acados_ocp_solver returned status {status}') # <<<<<<<<<<<<<< + * + * u0 = self.get(0, "u") + */ + __pyx_t_1 = __Pyx_PyObject_FormatSimple(__pyx_v_status, __pyx_empty_unicode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 115, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyUnicode_Concat(__pyx_kp_u_acados_acados_ocp_solver_returne, __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 115, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 115, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 115, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":114 + * if status == 2: + * print("Warning: acados_ocp_solver reached maximum iterations.") + * elif status != 0: # <<<<<<<<<<<<<< + * raise Exception(f'acados acados_ocp_solver returned status {status}') + * + */ + } + __pyx_L3:; + + /* "acados_template/acados_ocp_solver_pyx.pyx":117 + * raise Exception(f'acados acados_ocp_solver returned status {status}') + * + * u0 = self.get(0, "u") # <<<<<<<<<<<<<< + * return u0 + * + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 117, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_Call(__pyx_t_1, __pyx_tuple__12, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 117, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_u0 = __pyx_t_2; + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":118 + * + * u0 = self.get(0, "u") + * return u0 # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_u0); + __pyx_r = __pyx_v_u0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":103 + * + * + * def solve_for_x0(self, x0_bar): # <<<<<<<<<<<<<< + * """ + * Wrapper around `solve()` which sets initial state constraint, solves the OCP, and returns u0. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.solve_for_x0", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_status); + __Pyx_XDECREF(__pyx_v_u0); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":121 * * * def solve(self): # <<<<<<<<<<<<<< @@ -20804,16 +21373,16 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ /* Python wrapper */ -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve(PyObject *__pyx_v_self, +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7solve(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else PyObject *__pyx_args, PyObject *__pyx_kwds #endif ); /*proto*/ -PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve, "\n Solve the ocp with current input.\n "); -static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve = {"solve", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve}; -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve(PyObject *__pyx_v_self, +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6solve, "\n Solve the ocp with current input.\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7solve = {"solve", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7solve, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6solve}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7solve(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else @@ -20830,14 +21399,14 @@ PyObject *__pyx_args, PyObject *__pyx_kwds if (unlikely(__pyx_nargs > 0)) { __Pyx_RaiseArgtupleInvalid("solve", 1, 0, 0, __pyx_nargs); return NULL;} if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "solve", 0))) return NULL; - __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6solve(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); /* function exit code */ __Pyx_RefNannyFinishContext(); return __pyx_r; } -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6solve(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { PyObject *__pyx_r = NULL; __Pyx_RefNannyDeclarations PyObject *__pyx_t_1 = NULL; @@ -20846,7 +21415,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS int __pyx_clineno = 0; __Pyx_RefNannySetupContext("solve", 0); - /* "acados_template/acados_ocp_solver_pyx.pyx":112 + /* "acados_template/acados_ocp_solver_pyx.pyx":125 * Solve the ocp with current input. * """ * return acados_solver.acados_solve(self.capsule) # <<<<<<<<<<<<<< @@ -20854,13 +21423,13 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS * */ __Pyx_XDECREF(__pyx_r); - __pyx_t_1 = __Pyx_PyInt_From_int(lat_acados_solve(__pyx_v_self->capsule)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 112, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyInt_From_int(lat_acados_solve(__pyx_v_self->capsule)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 125, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __pyx_r = __pyx_t_1; __pyx_t_1 = 0; goto __pyx_L0; - /* "acados_template/acados_ocp_solver_pyx.pyx":108 + /* "acados_template/acados_ocp_solver_pyx.pyx":121 * * * def solve(self): # <<<<<<<<<<<<<< @@ -20879,82 +21448,128 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":115 +/* "acados_template/acados_ocp_solver_pyx.pyx":128 * * - * def reset(self): # <<<<<<<<<<<<<< + * def reset(self, reset_qp_solver_mem=1): # <<<<<<<<<<<<<< * """ * Sets current iterate to all zeros. */ /* Python wrapper */ -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7reset(PyObject *__pyx_v_self, +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9reset(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else PyObject *__pyx_args, PyObject *__pyx_kwds #endif ); /*proto*/ -PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6reset, "\n Sets current iterate to all zeros.\n "); -static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7reset = {"reset", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7reset, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6reset}; -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7reset(PyObject *__pyx_v_self, +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8reset, "\n Sets current iterate to all zeros.\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9reset = {"reset", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9reset, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8reset}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9reset(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else PyObject *__pyx_args, PyObject *__pyx_kwds #endif ) { + PyObject *__pyx_v_reset_qp_solver_mem = 0; #if !CYTHON_METH_FASTCALL CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); #endif CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; PyObject *__pyx_r = 0; __Pyx_RefNannyDeclarations __Pyx_RefNannySetupContext("reset (wrapper)", 0); - if (unlikely(__pyx_nargs > 0)) { - __Pyx_RaiseArgtupleInvalid("reset", 1, 0, 0, __pyx_nargs); return NULL;} - if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "reset", 0))) return NULL; - __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6reset(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_reset_qp_solver_mem,0}; + PyObject* values[1] = {0}; + values[0] = ((PyObject *)__pyx_int_1); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_reset_qp_solver_mem); + if (value) { values[0] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 128, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "reset") < 0)) __PYX_ERR(0, 128, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_reset_qp_solver_mem = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("reset", 0, 0, 1, __pyx_nargs); __PYX_ERR(0, 128, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.reset", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8reset(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_reset_qp_solver_mem); /* function exit code */ __Pyx_RefNannyFinishContext(); return __pyx_r; } -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6reset(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8reset(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_reset_qp_solver_mem) { PyObject *__pyx_r = NULL; __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; int __pyx_lineno = 0; const char *__pyx_filename = NULL; int __pyx_clineno = 0; __Pyx_RefNannySetupContext("reset", 0); - /* "acados_template/acados_ocp_solver_pyx.pyx":119 + /* "acados_template/acados_ocp_solver_pyx.pyx":132 * Sets current iterate to all zeros. * """ - * return acados_solver.acados_reset(self.capsule) # <<<<<<<<<<<<<< + * return acados_solver.acados_reset(self.capsule, reset_qp_solver_mem) # <<<<<<<<<<<<<< * * */ __Pyx_XDECREF(__pyx_r); - __pyx_t_1 = __Pyx_PyInt_From_int(lat_acados_reset(__pyx_v_self->capsule)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 119, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_r = __pyx_t_1; - __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyInt_As_int(__pyx_v_reset_qp_solver_mem); if (unlikely((__pyx_t_1 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 132, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyInt_From_int(lat_acados_reset(__pyx_v_self->capsule, __pyx_t_1)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 132, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; goto __pyx_L0; - /* "acados_template/acados_ocp_solver_pyx.pyx":115 + /* "acados_template/acados_ocp_solver_pyx.pyx":128 * * - * def reset(self): # <<<<<<<<<<<<<< + * def reset(self, reset_qp_solver_mem=1): # <<<<<<<<<<<<<< * """ * Sets current iterate to all zeros. */ /* function exit code */ __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.reset", __pyx_clineno, __pyx_lineno, __pyx_filename); __pyx_r = NULL; __pyx_L0:; @@ -20963,7 +21578,214 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":122 +/* "acados_template/acados_ocp_solver_pyx.pyx":135 + * + * + * def custom_update(self, data_): # <<<<<<<<<<<<<< + * """ + * A custom function that can be implemented by a user to be called between solver calls. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11custom_update(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10custom_update, "\n A custom function that can be implemented by a user to be called between solver calls.\n By default this does nothing.\n The idea is to have a convenient wrapper to do complex updates of parameters and numerical data efficiently in C,\n in a function that is compiled into the solver library and can be conveniently used in the Python environment.\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11custom_update = {"custom_update", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11custom_update, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10custom_update}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11custom_update(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_data_ = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("custom_update (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_data,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_data)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 135, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "custom_update") < 0)) __PYX_ERR(0, 135, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_data_ = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("custom_update", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 135, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.custom_update", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10custom_update(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_data_); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10custom_update(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_data_) { + Py_ssize_t __pyx_v_data_len; + PyArrayObject *__pyx_v_data = 0; + __Pyx_LocalBuf_ND __pyx_pybuffernd_data; + __Pyx_Buffer __pyx_pybuffer_data; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyArrayObject *__pyx_t_7 = NULL; + char *__pyx_t_8; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("custom_update", 0); + __pyx_pybuffer_data.pybuffer.buf = NULL; + __pyx_pybuffer_data.refcount = 0; + __pyx_pybuffernd_data.data = NULL; + __pyx_pybuffernd_data.rcbuffer = &__pyx_pybuffer_data; + + /* "acados_template/acados_ocp_solver_pyx.pyx":142 + * in a function that is compiled into the solver library and can be conveniently used in the Python environment. + * """ + * data_len = len(data_) # <<<<<<<<<<<<<< + * cdef cnp.ndarray[cnp.float64_t, ndim=1] data = np.ascontiguousarray(data_, dtype=np.float64) + * + */ + __pyx_t_1 = PyObject_Length(__pyx_v_data_); if (unlikely(__pyx_t_1 == ((Py_ssize_t)-1))) __PYX_ERR(0, 142, __pyx_L1_error) + __pyx_v_data_len = __pyx_t_1; + + /* "acados_template/acados_ocp_solver_pyx.pyx":143 + * """ + * data_len = len(data_) + * cdef cnp.ndarray[cnp.float64_t, ndim=1] data = np.ascontiguousarray(data_, dtype=np.float64) # <<<<<<<<<<<<<< + * + * return acados_solver.acados_custom_update(self.capsule, data.data, data_len) + */ + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_np); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = PyTuple_New(1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_INCREF(__pyx_v_data_); + __Pyx_GIVEREF(__pyx_v_data_); + PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_v_data_); + __pyx_t_4 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GetModuleGlobalName(__pyx_t_5, __pyx_n_s_np); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_float64); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (PyDict_SetItem(__pyx_t_4, __pyx_n_s_dtype, __pyx_t_6) < 0) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __pyx_t_6 = __Pyx_PyObject_Call(__pyx_t_3, __pyx_t_2, __pyx_t_4); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (!(likely(((__pyx_t_6) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_6, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 143, __pyx_L1_error) + __pyx_t_7 = ((PyArrayObject *)__pyx_t_6); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_data.rcbuffer->pybuffer, (PyObject*)__pyx_t_7, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 1, 0, __pyx_stack) == -1)) { + __pyx_v_data = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_data.rcbuffer->pybuffer.buf = NULL; + __PYX_ERR(0, 143, __pyx_L1_error) + } else {__pyx_pybuffernd_data.diminfo[0].strides = __pyx_pybuffernd_data.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_data.diminfo[0].shape = __pyx_pybuffernd_data.rcbuffer->pybuffer.shape[0]; + } + } + __pyx_t_7 = 0; + __pyx_v_data = ((PyArrayObject *)__pyx_t_6); + __pyx_t_6 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":145 + * cdef cnp.ndarray[cnp.float64_t, ndim=1] data = np.ascontiguousarray(data_, dtype=np.float64) + * + * return acados_solver.acados_custom_update(self.capsule, data.data, data_len) # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_8 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_data)); if (unlikely(__pyx_t_8 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 145, __pyx_L1_error) + __pyx_t_6 = __Pyx_PyInt_From_int(lat_acados_custom_update(__pyx_v_self->capsule, ((double *)__pyx_t_8), __pyx_v_data_len)); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 145, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_r = __pyx_t_6; + __pyx_t_6 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":135 + * + * + * def custom_update(self, data_): # <<<<<<<<<<<<<< + * """ + * A custom function that can be implemented by a user to be called between solver calls. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + { PyObject *__pyx_type, *__pyx_value, *__pyx_tb; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&__pyx_type, &__pyx_value, &__pyx_tb); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_data.rcbuffer->pybuffer); + __Pyx_ErrRestore(__pyx_type, __pyx_value, __pyx_tb);} + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.custom_update", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + goto __pyx_L2; + __pyx_L0:; + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_data.rcbuffer->pybuffer); + __pyx_L2:; + __Pyx_XDECREF((PyObject *)__pyx_v_data); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":148 * * * def set_new_time_steps(self, new_time_steps): # <<<<<<<<<<<<<< @@ -20972,16 +21794,16 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ /* Python wrapper */ -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9set_new_time_steps(PyObject *__pyx_v_self, +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13set_new_time_steps(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else PyObject *__pyx_args, PyObject *__pyx_kwds #endif ); /*proto*/ -PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8set_new_time_steps, "\n Set new time steps.\n Recreates the solver if N changes.\n\n :param new_time_steps: 1 dimensional np array of new time steps for the solver\n\n .. note:: This allows for different use-cases: either set a new size of time-steps or a new distribution of\n the shooting nodes without changing the number, e.g., to reach a different final time. Both cases\n do not require a new code export and compilation.\n "); -static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9set_new_time_steps = {"set_new_time_steps", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9set_new_time_steps, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8set_new_time_steps}; -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9set_new_time_steps(PyObject *__pyx_v_self, +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12set_new_time_steps, "\n Set new time steps.\n Recreates the solver if N changes.\n\n :param new_time_steps: 1 dimensional np array of new time steps for the solver\n\n .. note:: This allows for different use-cases: either set a new size of time-steps or a new distribution of\n the shooting nodes without changing the number, e.g., to reach a different final time. Both cases\n do not require a new code export and compilation.\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13set_new_time_steps = {"set_new_time_steps", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13set_new_time_steps, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12set_new_time_steps}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13set_new_time_steps(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else @@ -21014,12 +21836,12 @@ PyObject *__pyx_args, PyObject *__pyx_kwds switch (__pyx_nargs) { case 0: if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_new_time_steps)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 122, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 148, __pyx_L3_error) else goto __pyx_L5_argtuple_error; } if (unlikely(kw_args > 0)) { const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "set_new_time_steps") < 0)) __PYX_ERR(0, 122, __pyx_L3_error) + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "set_new_time_steps") < 0)) __PYX_ERR(0, 148, __pyx_L3_error) } } else if (unlikely(__pyx_nargs != 1)) { goto __pyx_L5_argtuple_error; @@ -21030,20 +21852,20 @@ PyObject *__pyx_args, PyObject *__pyx_kwds } goto __pyx_L4_argument_unpacking_done; __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("set_new_time_steps", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 122, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("set_new_time_steps", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 148, __pyx_L3_error) __pyx_L3_error:; __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.set_new_time_steps", __pyx_clineno, __pyx_lineno, __pyx_filename); __Pyx_RefNannyFinishContext(); return NULL; __pyx_L4_argument_unpacking_done:; - __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8set_new_time_steps(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_new_time_steps); + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12set_new_time_steps(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_new_time_steps); /* function exit code */ __Pyx_RefNannyFinishContext(); return __pyx_r; } -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8set_new_time_steps(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v_new_time_steps) { +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12set_new_time_steps(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v_new_time_steps) { PyObject *__pyx_r = NULL; __Pyx_RefNannyDeclarations PyObject *__pyx_t_1 = NULL; @@ -21052,20 +21874,20 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS int __pyx_clineno = 0; __Pyx_RefNannySetupContext("set_new_time_steps", 0); - /* "acados_template/acados_ocp_solver_pyx.pyx":134 + /* "acados_template/acados_ocp_solver_pyx.pyx":160 * """ * * raise NotImplementedError("AcadosOcpSolverCython: does not support set_new_time_steps() since it is only a prototyping feature") # <<<<<<<<<<<<<< * # # unlikely but still possible * # if not self.solver_created: */ - __pyx_t_1 = __Pyx_PyObject_Call(__pyx_builtin_NotImplementedError, __pyx_tuple__11, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 134, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_Call(__pyx_builtin_NotImplementedError, __pyx_tuple__13, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 160, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_Raise(__pyx_t_1, 0, 0, 0); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __PYX_ERR(0, 134, __pyx_L1_error) + __PYX_ERR(0, 160, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":122 + /* "acados_template/acados_ocp_solver_pyx.pyx":148 * * * def set_new_time_steps(self, new_time_steps): # <<<<<<<<<<<<<< @@ -21083,7 +21905,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":173 +/* "acados_template/acados_ocp_solver_pyx.pyx":199 * * * def update_qp_solver_cond_N(self, qp_solver_cond_N: int): # <<<<<<<<<<<<<< @@ -21092,16 +21914,16 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ /* Python wrapper */ -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11update_qp_solver_cond_N(PyObject *__pyx_v_self, +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15update_qp_solver_cond_N(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else PyObject *__pyx_args, PyObject *__pyx_kwds #endif ); /*proto*/ -PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10update_qp_solver_cond_N, "\n Recreate solver with new value `qp_solver_cond_N` with a partial condensing QP solver.\n This function is relevant for code reuse, i.e., if either `set_new_time_steps(...)` is used or\n the influence of a different `qp_solver_cond_N` is studied without code export and compilation.\n :param qp_solver_cond_N: new number of condensing stages for the solver\n\n .. note:: This function can only be used in combination with a partial condensing QP solver.\n\n .. note:: After `set_new_time_steps(...)` is used and depending on the new number of time steps it might be\n necessary to change `qp_solver_cond_N` as well (using this function), i.e., typically\n `qp_solver_cond_N < N`.\n "); -static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11update_qp_solver_cond_N = {"update_qp_solver_cond_N", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11update_qp_solver_cond_N, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10update_qp_solver_cond_N}; -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11update_qp_solver_cond_N(PyObject *__pyx_v_self, +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14update_qp_solver_cond_N, "\n Recreate solver with new value `qp_solver_cond_N` with a partial condensing QP solver.\n This function is relevant for code reuse, i.e., if either `set_new_time_steps(...)` is used or\n the influence of a different `qp_solver_cond_N` is studied without code export and compilation.\n :param qp_solver_cond_N: new number of condensing stages for the solver\n\n .. note:: This function can only be used in combination with a partial condensing QP solver.\n\n .. note:: After `set_new_time_steps(...)` is used and depending on the new number of time steps it might be\n necessary to change `qp_solver_cond_N` as well (using this function), i.e., typically\n `qp_solver_cond_N < N`.\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15update_qp_solver_cond_N = {"update_qp_solver_cond_N", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15update_qp_solver_cond_N, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14update_qp_solver_cond_N}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15update_qp_solver_cond_N(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else @@ -21134,12 +21956,12 @@ PyObject *__pyx_args, PyObject *__pyx_kwds switch (__pyx_nargs) { case 0: if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_qp_solver_cond_N)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 173, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 199, __pyx_L3_error) else goto __pyx_L5_argtuple_error; } if (unlikely(kw_args > 0)) { const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "update_qp_solver_cond_N") < 0)) __PYX_ERR(0, 173, __pyx_L3_error) + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "update_qp_solver_cond_N") < 0)) __PYX_ERR(0, 199, __pyx_L3_error) } } else if (unlikely(__pyx_nargs != 1)) { goto __pyx_L5_argtuple_error; @@ -21150,14 +21972,14 @@ PyObject *__pyx_args, PyObject *__pyx_kwds } goto __pyx_L4_argument_unpacking_done; __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("update_qp_solver_cond_N", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 173, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("update_qp_solver_cond_N", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 199, __pyx_L3_error) __pyx_L3_error:; __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.update_qp_solver_cond_N", __pyx_clineno, __pyx_lineno, __pyx_filename); __Pyx_RefNannyFinishContext(); return NULL; __pyx_L4_argument_unpacking_done:; - if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_qp_solver_cond_N), (&PyInt_Type), 0, "qp_solver_cond_N", 1))) __PYX_ERR(0, 173, __pyx_L1_error) - __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10update_qp_solver_cond_N(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_qp_solver_cond_N); + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_qp_solver_cond_N), (&PyInt_Type), 0, "qp_solver_cond_N", 1))) __PYX_ERR(0, 199, __pyx_L1_error) + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14update_qp_solver_cond_N(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_qp_solver_cond_N); /* function exit code */ goto __pyx_L0; @@ -21168,7 +21990,7 @@ PyObject *__pyx_args, PyObject *__pyx_kwds return __pyx_r; } -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10update_qp_solver_cond_N(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v_qp_solver_cond_N) { +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14update_qp_solver_cond_N(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v_qp_solver_cond_N) { PyObject *__pyx_r = NULL; __Pyx_RefNannyDeclarations PyObject *__pyx_t_1 = NULL; @@ -21177,20 +21999,20 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS int __pyx_clineno = 0; __Pyx_RefNannySetupContext("update_qp_solver_cond_N", 0); - /* "acados_template/acados_ocp_solver_pyx.pyx":186 + /* "acados_template/acados_ocp_solver_pyx.pyx":212 * `qp_solver_cond_N < N`. * """ * raise NotImplementedError("AcadosOcpSolverCython: does not support update_qp_solver_cond_N() since it is only a prototyping feature") # <<<<<<<<<<<<<< * * # # unlikely but still possible */ - __pyx_t_1 = __Pyx_PyObject_Call(__pyx_builtin_NotImplementedError, __pyx_tuple__12, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 186, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_Call(__pyx_builtin_NotImplementedError, __pyx_tuple__14, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 212, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_Raise(__pyx_t_1, 0, 0, 0); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __PYX_ERR(0, 186, __pyx_L1_error) + __PYX_ERR(0, 212, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":173 + /* "acados_template/acados_ocp_solver_pyx.pyx":199 * * * def update_qp_solver_cond_N(self, qp_solver_cond_N: int): # <<<<<<<<<<<<<< @@ -21208,7 +22030,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":207 +/* "acados_template/acados_ocp_solver_pyx.pyx":233 * * * def eval_param_sens(self, index, stage=0, field="ex"): # <<<<<<<<<<<<<< @@ -21217,16 +22039,16 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ /* Python wrapper */ -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13eval_param_sens(PyObject *__pyx_v_self, +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17eval_param_sens(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else PyObject *__pyx_args, PyObject *__pyx_kwds #endif ); /*proto*/ -PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12eval_param_sens, "\n Calculate the sensitivity of the curent solution with respect to the initial state component of index\n\n :param index: integer corresponding to initial state index in range(nx)\n "); -static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13eval_param_sens = {"eval_param_sens", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13eval_param_sens, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12eval_param_sens}; -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13eval_param_sens(PyObject *__pyx_v_self, +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16eval_param_sens, "\n Calculate the sensitivity of the curent solution with respect to the initial state component of index\n\n :param index: integer corresponding to initial state index in range(nx)\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17eval_param_sens = {"eval_param_sens", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17eval_param_sens, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16eval_param_sens}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17eval_param_sens(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else @@ -21267,26 +22089,26 @@ PyObject *__pyx_args, PyObject *__pyx_kwds switch (__pyx_nargs) { case 0: if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_index)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 207, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 233, __pyx_L3_error) else goto __pyx_L5_argtuple_error; CYTHON_FALLTHROUGH; case 1: if (kw_args > 0) { PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_stage); if (value) { values[1] = value; kw_args--; } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 207, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 233, __pyx_L3_error) } CYTHON_FALLTHROUGH; case 2: if (kw_args > 0) { PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field); if (value) { values[2] = value; kw_args--; } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 207, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 233, __pyx_L3_error) } } if (unlikely(kw_args > 0)) { const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "eval_param_sens") < 0)) __PYX_ERR(0, 207, __pyx_L3_error) + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "eval_param_sens") < 0)) __PYX_ERR(0, 233, __pyx_L3_error) } } else { switch (__pyx_nargs) { @@ -21305,20 +22127,20 @@ PyObject *__pyx_args, PyObject *__pyx_kwds } goto __pyx_L4_argument_unpacking_done; __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("eval_param_sens", 0, 1, 3, __pyx_nargs); __PYX_ERR(0, 207, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("eval_param_sens", 0, 1, 3, __pyx_nargs); __PYX_ERR(0, 233, __pyx_L3_error) __pyx_L3_error:; __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.eval_param_sens", __pyx_clineno, __pyx_lineno, __pyx_filename); __Pyx_RefNannyFinishContext(); return NULL; __pyx_L4_argument_unpacking_done:; - __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12eval_param_sens(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_index, __pyx_v_stage, __pyx_v_field); + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16eval_param_sens(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_index, __pyx_v_stage, __pyx_v_field); /* function exit code */ __Pyx_RefNannyFinishContext(); return __pyx_r; } -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12eval_param_sens(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_stage, PyObject *__pyx_v_field) { +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16eval_param_sens(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_stage, PyObject *__pyx_v_field) { PyObject *__pyx_v_field_ = NULL; int __pyx_v_nx; PyObject *__pyx_r = NULL; @@ -21340,7 +22162,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __Pyx_RefNannySetupContext("eval_param_sens", 0); __Pyx_INCREF(__pyx_v_field); - /* "acados_template/acados_ocp_solver_pyx.pyx":214 + /* "acados_template/acados_ocp_solver_pyx.pyx":240 * """ * * field_ = field # <<<<<<<<<<<<<< @@ -21350,14 +22172,14 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __Pyx_INCREF(__pyx_v_field); __pyx_v_field_ = __pyx_v_field; - /* "acados_template/acados_ocp_solver_pyx.pyx":215 + /* "acados_template/acados_ocp_solver_pyx.pyx":241 * * field_ = field * field = field_.encode('utf-8') # <<<<<<<<<<<<<< * * # checks */ - __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_field_, __pyx_n_s_encode); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 215, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_field_, __pyx_n_s_encode); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 241, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __pyx_t_3 = NULL; __pyx_t_4 = 0; @@ -21375,14 +22197,14 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_kp_u_utf_8}; __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; - if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 215, __pyx_L1_error) + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 241, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; } __Pyx_DECREF_SET(__pyx_v_field, __pyx_t_1); __pyx_t_1 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":218 + /* "acados_template/acados_ocp_solver_pyx.pyx":244 * * # checks * if not isinstance(index, int): # <<<<<<<<<<<<<< @@ -21393,20 +22215,20 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_t_6 = (!__pyx_t_5); if (unlikely(__pyx_t_6)) { - /* "acados_template/acados_ocp_solver_pyx.pyx":219 + /* "acados_template/acados_ocp_solver_pyx.pyx":245 * # checks * if not isinstance(index, int): * raise Exception('AcadosOcpSolverCython.eval_param_sens(): index must be Integer.') # <<<<<<<<<<<<<< * * cdef int nx = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, self.nlp_dims, self.nlp_out, 0, "x".encode('utf-8')) */ - __pyx_t_1 = __Pyx_PyObject_Call(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_tuple__13, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 219, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_Call(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_tuple__15, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 245, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_Raise(__pyx_t_1, 0, 0, 0); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __PYX_ERR(0, 219, __pyx_L1_error) + __PYX_ERR(0, 245, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":218 + /* "acados_template/acados_ocp_solver_pyx.pyx":244 * * # checks * if not isinstance(index, int): # <<<<<<<<<<<<<< @@ -21415,49 +22237,49 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":221 + /* "acados_template/acados_ocp_solver_pyx.pyx":247 * raise Exception('AcadosOcpSolverCython.eval_param_sens(): index must be Integer.') * * cdef int nx = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, self.nlp_dims, self.nlp_out, 0, "x".encode('utf-8')) # <<<<<<<<<<<<<< * * if index < 0 or index > nx: */ - __pyx_t_7 = __Pyx_PyBytes_AsString(__pyx_n_b_x); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 221, __pyx_L1_error) + __pyx_t_7 = __Pyx_PyBytes_AsString(__pyx_n_b_x); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 247, __pyx_L1_error) __pyx_v_nx = ocp_nlp_dims_get_from_attr(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, 0, __pyx_t_7); - /* "acados_template/acados_ocp_solver_pyx.pyx":223 + /* "acados_template/acados_ocp_solver_pyx.pyx":249 * cdef int nx = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, self.nlp_dims, self.nlp_out, 0, "x".encode('utf-8')) * * if index < 0 or index > nx: # <<<<<<<<<<<<<< * raise Exception(f'AcadosOcpSolverCython.eval_param_sens(): index must be in [0, nx-1], got: {index}.') * */ - __pyx_t_1 = PyObject_RichCompare(__pyx_v_index, __pyx_int_0, Py_LT); __Pyx_XGOTREF(__pyx_t_1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 223, __pyx_L1_error) - __pyx_t_5 = __Pyx_PyObject_IsTrue(__pyx_t_1); if (unlikely((__pyx_t_5 < 0))) __PYX_ERR(0, 223, __pyx_L1_error) + __pyx_t_1 = PyObject_RichCompare(__pyx_v_index, __pyx_int_0, Py_LT); __Pyx_XGOTREF(__pyx_t_1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 249, __pyx_L1_error) + __pyx_t_5 = __Pyx_PyObject_IsTrue(__pyx_t_1); if (unlikely((__pyx_t_5 < 0))) __PYX_ERR(0, 249, __pyx_L1_error) __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; if (!__pyx_t_5) { } else { __pyx_t_6 = __pyx_t_5; goto __pyx_L5_bool_binop_done; } - __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_nx); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 223, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_nx); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 249, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); - __pyx_t_2 = PyObject_RichCompare(__pyx_v_index, __pyx_t_1, Py_GT); __Pyx_XGOTREF(__pyx_t_2); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 223, __pyx_L1_error) + __pyx_t_2 = PyObject_RichCompare(__pyx_v_index, __pyx_t_1, Py_GT); __Pyx_XGOTREF(__pyx_t_2); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 249, __pyx_L1_error) __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_5 = __Pyx_PyObject_IsTrue(__pyx_t_2); if (unlikely((__pyx_t_5 < 0))) __PYX_ERR(0, 223, __pyx_L1_error) + __pyx_t_5 = __Pyx_PyObject_IsTrue(__pyx_t_2); if (unlikely((__pyx_t_5 < 0))) __PYX_ERR(0, 249, __pyx_L1_error) __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; __pyx_t_6 = __pyx_t_5; __pyx_L5_bool_binop_done:; if (unlikely(__pyx_t_6)) { - /* "acados_template/acados_ocp_solver_pyx.pyx":224 + /* "acados_template/acados_ocp_solver_pyx.pyx":250 * * if index < 0 or index > nx: * raise Exception(f'AcadosOcpSolverCython.eval_param_sens(): index must be in [0, nx-1], got: {index}.') # <<<<<<<<<<<<<< * * # actual eval_param */ - __pyx_t_2 = PyTuple_New(3); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 224, __pyx_L1_error) + __pyx_t_2 = PyTuple_New(3); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 250, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __pyx_t_8 = 0; __pyx_t_9 = 127; @@ -21465,7 +22287,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_t_8 += 74; __Pyx_GIVEREF(__pyx_kp_u_AcadosOcpSolverCython_eval_param_2); PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_kp_u_AcadosOcpSolverCython_eval_param_2); - __pyx_t_1 = __Pyx_PyObject_FormatSimple(__pyx_v_index, __pyx_empty_unicode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 224, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_FormatSimple(__pyx_v_index, __pyx_empty_unicode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 250, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __pyx_t_9 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) > __pyx_t_9) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) : __pyx_t_9; __pyx_t_8 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); @@ -21476,17 +22298,17 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_t_8 += 1; __Pyx_GIVEREF(__pyx_kp_u__2); PyTuple_SET_ITEM(__pyx_t_2, 2, __pyx_kp_u__2); - __pyx_t_1 = __Pyx_PyUnicode_Join(__pyx_t_2, 3, __pyx_t_8, __pyx_t_9); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 224, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyUnicode_Join(__pyx_t_2, 3, __pyx_t_8, __pyx_t_9); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 250, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - __pyx_t_2 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 224, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 250, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; __Pyx_Raise(__pyx_t_2, 0, 0, 0); __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - __PYX_ERR(0, 224, __pyx_L1_error) + __PYX_ERR(0, 250, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":223 + /* "acados_template/acados_ocp_solver_pyx.pyx":249 * cdef int nx = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, self.nlp_dims, self.nlp_out, 0, "x".encode('utf-8')) * * if index < 0 or index > nx: # <<<<<<<<<<<<<< @@ -21495,19 +22317,19 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":227 + /* "acados_template/acados_ocp_solver_pyx.pyx":253 * * # actual eval_param * acados_solver_common.ocp_nlp_eval_param_sens(self.nlp_solver, field, stage, index, self.sens_out) # <<<<<<<<<<<<<< * * return */ - __pyx_t_10 = __Pyx_PyObject_AsWritableString(__pyx_v_field); if (unlikely((!__pyx_t_10) && PyErr_Occurred())) __PYX_ERR(0, 227, __pyx_L1_error) - __pyx_t_4 = __Pyx_PyInt_As_int(__pyx_v_stage); if (unlikely((__pyx_t_4 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 227, __pyx_L1_error) - __pyx_t_11 = __Pyx_PyInt_As_int(__pyx_v_index); if (unlikely((__pyx_t_11 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 227, __pyx_L1_error) + __pyx_t_10 = __Pyx_PyObject_AsWritableString(__pyx_v_field); if (unlikely((!__pyx_t_10) && PyErr_Occurred())) __PYX_ERR(0, 253, __pyx_L1_error) + __pyx_t_4 = __Pyx_PyInt_As_int(__pyx_v_stage); if (unlikely((__pyx_t_4 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 253, __pyx_L1_error) + __pyx_t_11 = __Pyx_PyInt_As_int(__pyx_v_index); if (unlikely((__pyx_t_11 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 253, __pyx_L1_error) ocp_nlp_eval_param_sens(__pyx_v_self->nlp_solver, __pyx_t_10, __pyx_t_4, __pyx_t_11, __pyx_v_self->sens_out); - /* "acados_template/acados_ocp_solver_pyx.pyx":229 + /* "acados_template/acados_ocp_solver_pyx.pyx":255 * acados_solver_common.ocp_nlp_eval_param_sens(self.nlp_solver, field, stage, index, self.sens_out) * * return # <<<<<<<<<<<<<< @@ -21518,7 +22340,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_r = Py_None; __Pyx_INCREF(Py_None); goto __pyx_L0; - /* "acados_template/acados_ocp_solver_pyx.pyx":207 + /* "acados_template/acados_ocp_solver_pyx.pyx":233 * * * def eval_param_sens(self, index, stage=0, field="ex"): # <<<<<<<<<<<<<< @@ -21541,7 +22363,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":232 +/* "acados_template/acados_ocp_solver_pyx.pyx":258 * * * def get(self, int stage, str field_): # <<<<<<<<<<<<<< @@ -21550,16 +22372,16 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ /* Python wrapper */ -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15get(PyObject *__pyx_v_self, +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19get(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else PyObject *__pyx_args, PyObject *__pyx_kwds #endif ); /*proto*/ -PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14get, "\n Get the last solution of the solver:\n\n :param stage: integer corresponding to shooting node\n :param field: string in ['x', 'u', 'z', 'pi', 'lam', 't', 'sl', 'su',]\n\n .. note:: regarding lam, t: \n\n the inequalities are internally organized in the following order: \n\n [ lbu lbx lg lh lphi ubu ubx ug uh uphi; \n\n lsbu lsbx lsg lsh lsphi usbu usbx usg ush usphi]\n\n .. note:: pi: multipliers for dynamics equality constraints \n\n lam: multipliers for inequalities \n\n t: slack variables corresponding to evaluation of all inequalities (at the solution) \n\n sl: slack variables of soft lower inequality constraints \n\n su: slack variables of soft upper inequality constraints \n\n "); -static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15get = {"get", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15get, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14get}; -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15get(PyObject *__pyx_v_self, +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18get, "\n Get the last solution of the solver:\n\n :param stage: integer corresponding to shooting node\n :param field: string in ['x', 'u', 'z', 'pi', 'lam', 't', 'sl', 'su',]\n\n .. note:: regarding lam, t: \n\n the inequalities are internally organized in the following order: \n\n [ lbu lbx lg lh lphi ubu ubx ug uh uphi; \n\n lsbu lsbx lsg lsh lsphi usbu usbx usg ush usphi]\n\n .. note:: pi: multipliers for dynamics equality constraints \n\n lam: multipliers for inequalities \n\n t: slack variables corresponding to evaluation of all inequalities (at the solution) \n\n sl: slack variables of soft lower inequality constraints \n\n su: slack variables of soft upper inequality constraints \n\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19get = {"get", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19get, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18get}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19get(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else @@ -21595,19 +22417,19 @@ PyObject *__pyx_args, PyObject *__pyx_kwds switch (__pyx_nargs) { case 0: if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_stage)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 232, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 258, __pyx_L3_error) else goto __pyx_L5_argtuple_error; CYTHON_FALLTHROUGH; case 1: if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field_2)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 232, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 258, __pyx_L3_error) else { - __Pyx_RaiseArgtupleInvalid("get", 1, 2, 2, 1); __PYX_ERR(0, 232, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("get", 1, 2, 2, 1); __PYX_ERR(0, 258, __pyx_L3_error) } } if (unlikely(kw_args > 0)) { const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "get") < 0)) __PYX_ERR(0, 232, __pyx_L3_error) + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "get") < 0)) __PYX_ERR(0, 258, __pyx_L3_error) } } else if (unlikely(__pyx_nargs != 2)) { goto __pyx_L5_argtuple_error; @@ -21615,19 +22437,19 @@ PyObject *__pyx_args, PyObject *__pyx_kwds values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); } - __pyx_v_stage = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_stage == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 232, __pyx_L3_error) + __pyx_v_stage = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_stage == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 258, __pyx_L3_error) __pyx_v_field_ = ((PyObject*)values[1]); } goto __pyx_L4_argument_unpacking_done; __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("get", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 232, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("get", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 258, __pyx_L3_error) __pyx_L3_error:; __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.get", __pyx_clineno, __pyx_lineno, __pyx_filename); __Pyx_RefNannyFinishContext(); return NULL; __pyx_L4_argument_unpacking_done:; - if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 232, __pyx_L1_error) - __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14get(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_stage, __pyx_v_field_); + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 258, __pyx_L1_error) + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18get(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_stage, __pyx_v_field_); /* function exit code */ goto __pyx_L0; @@ -21638,7 +22460,7 @@ PyObject *__pyx_args, PyObject *__pyx_kwds return __pyx_r; } -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14get(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_) { +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18get(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_) { PyObject *__pyx_v_out_fields = NULL; PyObject *__pyx_v_field = NULL; int __pyx_v_dims; @@ -21667,14 +22489,14 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_pybuffernd_out.data = NULL; __pyx_pybuffernd_out.rcbuffer = &__pyx_pybuffer_out; - /* "acados_template/acados_ocp_solver_pyx.pyx":251 + /* "acados_template/acados_ocp_solver_pyx.pyx":277 * """ * * out_fields = ['x', 'u', 'z', 'pi', 'lam', 't', 'sl', 'su'] # <<<<<<<<<<<<<< * field = field_.encode('utf-8') * */ - __pyx_t_1 = PyList_New(8); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 251, __pyx_L1_error) + __pyx_t_1 = PyList_New(8); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 277, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_INCREF(__pyx_n_u_x); __Pyx_GIVEREF(__pyx_n_u_x); @@ -21703,7 +22525,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_v_out_fields = ((PyObject*)__pyx_t_1); __pyx_t_1 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":252 + /* "acados_template/acados_ocp_solver_pyx.pyx":278 * * out_fields = ['x', 'u', 'z', 'pi', 'lam', 't', 'sl', 'su'] * field = field_.encode('utf-8') # <<<<<<<<<<<<<< @@ -21712,31 +22534,31 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ if (unlikely(__pyx_v_field_ == Py_None)) { PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "encode"); - __PYX_ERR(0, 252, __pyx_L1_error) + __PYX_ERR(0, 278, __pyx_L1_error) } - __pyx_t_1 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 252, __pyx_L1_error) + __pyx_t_1 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 278, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __pyx_v_field = __pyx_t_1; __pyx_t_1 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":254 + /* "acados_template/acados_ocp_solver_pyx.pyx":280 * field = field_.encode('utf-8') * * if field_ not in out_fields: # <<<<<<<<<<<<<< * raise Exception('AcadosOcpSolverCython.get(): {} is an invalid argument.\ - * \n Possible values are {}. Exiting.'.format(field_, out_fields)) + * \n Possible values are {}.'.format(field_, out_fields)) */ - __pyx_t_2 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_out_fields, Py_NE)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 254, __pyx_L1_error) + __pyx_t_2 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_out_fields, Py_NE)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 280, __pyx_L1_error) if (unlikely(__pyx_t_2)) { - /* "acados_template/acados_ocp_solver_pyx.pyx":256 + /* "acados_template/acados_ocp_solver_pyx.pyx":282 * if field_ not in out_fields: * raise Exception('AcadosOcpSolverCython.get(): {} is an invalid argument.\ - * \n Possible values are {}. Exiting.'.format(field_, out_fields)) # <<<<<<<<<<<<<< + * \n Possible values are {}.'.format(field_, out_fields)) # <<<<<<<<<<<<<< * * if stage < 0 or stage > self.N: */ - __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_get_is_an, __pyx_n_s_format); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 256, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_get_is_an, __pyx_n_s_format); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 282, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __pyx_t_4 = NULL; __pyx_t_5 = 0; @@ -21754,36 +22576,36 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_callargs[3] = {__pyx_t_4, __pyx_v_field_, __pyx_v_out_fields}; __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_5, 2+__pyx_t_5); __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; - if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 256, __pyx_L1_error) + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 282, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; } - /* "acados_template/acados_ocp_solver_pyx.pyx":255 + /* "acados_template/acados_ocp_solver_pyx.pyx":281 * * if field_ not in out_fields: * raise Exception('AcadosOcpSolverCython.get(): {} is an invalid argument.\ # <<<<<<<<<<<<<< - * \n Possible values are {}. Exiting.'.format(field_, out_fields)) + * \n Possible values are {}.'.format(field_, out_fields)) * */ - __pyx_t_3 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 255, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 281, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; __Pyx_Raise(__pyx_t_3, 0, 0, 0); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - __PYX_ERR(0, 255, __pyx_L1_error) + __PYX_ERR(0, 281, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":254 + /* "acados_template/acados_ocp_solver_pyx.pyx":280 * field = field_.encode('utf-8') * * if field_ not in out_fields: # <<<<<<<<<<<<<< * raise Exception('AcadosOcpSolverCython.get(): {} is an invalid argument.\ - * \n Possible values are {}. Exiting.'.format(field_, out_fields)) + * \n Possible values are {}.'.format(field_, out_fields)) */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":258 - * \n Possible values are {}. Exiting.'.format(field_, out_fields)) + /* "acados_template/acados_ocp_solver_pyx.pyx":284 + * \n Possible values are {}.'.format(field_, out_fields)) * * if stage < 0 or stage > self.N: # <<<<<<<<<<<<<< * raise Exception('AcadosOcpSolverCython.get(): stage index must be in [0, N], got: {}.'.format(self.N)) @@ -21800,16 +22622,16 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_L5_bool_binop_done:; if (unlikely(__pyx_t_2)) { - /* "acados_template/acados_ocp_solver_pyx.pyx":259 + /* "acados_template/acados_ocp_solver_pyx.pyx":285 * * if stage < 0 or stage > self.N: * raise Exception('AcadosOcpSolverCython.get(): stage index must be in [0, N], got: {}.'.format(self.N)) # <<<<<<<<<<<<<< * * if stage == self.N and field_ == 'pi': */ - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_get_stage, __pyx_n_s_format); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 259, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_get_stage, __pyx_n_s_format); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 285, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); - __pyx_t_4 = __Pyx_PyInt_From_int(__pyx_v_self->N); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 259, __pyx_L1_error) + __pyx_t_4 = __Pyx_PyInt_From_int(__pyx_v_self->N); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 285, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); __pyx_t_7 = NULL; __pyx_t_5 = 0; @@ -21828,19 +22650,19 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_5, 1+__pyx_t_5); __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 259, __pyx_L1_error) + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 285, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; } - __pyx_t_1 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 259, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 285, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; __Pyx_Raise(__pyx_t_1, 0, 0, 0); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __PYX_ERR(0, 259, __pyx_L1_error) + __PYX_ERR(0, 285, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":258 - * \n Possible values are {}. Exiting.'.format(field_, out_fields)) + /* "acados_template/acados_ocp_solver_pyx.pyx":284 + * \n Possible values are {}.'.format(field_, out_fields)) * * if stage < 0 or stage > self.N: # <<<<<<<<<<<<<< * raise Exception('AcadosOcpSolverCython.get(): stage index must be in [0, N], got: {}.'.format(self.N)) @@ -21848,7 +22670,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":261 + /* "acados_template/acados_ocp_solver_pyx.pyx":287 * raise Exception('AcadosOcpSolverCython.get(): stage index must be in [0, N], got: {}.'.format(self.N)) * * if stage == self.N and field_ == 'pi': # <<<<<<<<<<<<<< @@ -21861,21 +22683,21 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_t_2 = __pyx_t_6; goto __pyx_L8_bool_binop_done; } - __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_pi, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 261, __pyx_L1_error) + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_pi, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 287, __pyx_L1_error) __pyx_t_2 = __pyx_t_6; __pyx_L8_bool_binop_done:; if (unlikely(__pyx_t_2)) { - /* "acados_template/acados_ocp_solver_pyx.pyx":263 + /* "acados_template/acados_ocp_solver_pyx.pyx":289 * if stage == self.N and field_ == 'pi': * raise Exception('AcadosOcpSolverCython.get(): field {} does not exist at final stage {}.'\ * .format(field_, stage)) # <<<<<<<<<<<<<< * * cdef int dims = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, */ - __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_get_field, __pyx_n_s_format); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 263, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_get_field, __pyx_n_s_format); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 289, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); - __pyx_t_4 = __Pyx_PyInt_From_int(__pyx_v_stage); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 263, __pyx_L1_error) + __pyx_t_4 = __Pyx_PyInt_From_int(__pyx_v_stage); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 289, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); __pyx_t_7 = NULL; __pyx_t_5 = 0; @@ -21894,26 +22716,26 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_5, 2+__pyx_t_5); __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 263, __pyx_L1_error) + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 289, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; } - /* "acados_template/acados_ocp_solver_pyx.pyx":262 + /* "acados_template/acados_ocp_solver_pyx.pyx":288 * * if stage == self.N and field_ == 'pi': * raise Exception('AcadosOcpSolverCython.get(): field {} does not exist at final stage {}.'\ # <<<<<<<<<<<<<< * .format(field_, stage)) * */ - __pyx_t_3 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 262, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 288, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; __Pyx_Raise(__pyx_t_3, 0, 0, 0); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - __PYX_ERR(0, 262, __pyx_L1_error) + __PYX_ERR(0, 288, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":261 + /* "acados_template/acados_ocp_solver_pyx.pyx":287 * raise Exception('AcadosOcpSolverCython.get(): stage index must be in [0, N], got: {}.'.format(self.N)) * * if stage == self.N and field_ == 'pi': # <<<<<<<<<<<<<< @@ -21922,16 +22744,16 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":266 + /* "acados_template/acados_ocp_solver_pyx.pyx":292 * * cdef int dims = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, * self.nlp_dims, self.nlp_out, stage, field) # <<<<<<<<<<<<<< * * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((dims,)) */ - __pyx_t_8 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_8) && PyErr_Occurred())) __PYX_ERR(0, 266, __pyx_L1_error) + __pyx_t_8 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_8) && PyErr_Occurred())) __PYX_ERR(0, 292, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":265 + /* "acados_template/acados_ocp_solver_pyx.pyx":291 * .format(field_, stage)) * * cdef int dims = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, # <<<<<<<<<<<<<< @@ -21940,21 +22762,21 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ __pyx_v_dims = ocp_nlp_dims_get_from_attr(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_8); - /* "acados_template/acados_ocp_solver_pyx.pyx":268 + /* "acados_template/acados_ocp_solver_pyx.pyx":294 * self.nlp_dims, self.nlp_out, stage, field) * * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((dims,)) # <<<<<<<<<<<<<< * acados_solver_common.ocp_nlp_out_get(self.nlp_config, \ * self.nlp_dims, self.nlp_out, stage, field, out.data) */ - __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 268, __pyx_L1_error) + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 294, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); - __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_zeros); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 268, __pyx_L1_error) + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_zeros); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 294, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_dims); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 268, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_dims); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 294, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); - __pyx_t_7 = PyTuple_New(1); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 268, __pyx_L1_error) + __pyx_t_7 = PyTuple_New(1); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 294, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); __Pyx_GIVEREF(__pyx_t_1); PyTuple_SET_ITEM(__pyx_t_7, 0, __pyx_t_1); @@ -21976,17 +22798,17 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_5, 1+__pyx_t_5); __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 268, __pyx_L1_error) + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 294, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; } - if (!(likely(((__pyx_t_3) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_3, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 268, __pyx_L1_error) + if (!(likely(((__pyx_t_3) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_3, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 294, __pyx_L1_error) __pyx_t_9 = ((PyArrayObject *)__pyx_t_3); { __Pyx_BufFmt_StackElem __pyx_stack[1]; if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_out.rcbuffer->pybuffer, (PyObject*)__pyx_t_9, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 1, 0, __pyx_stack) == -1)) { __pyx_v_out = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_out.rcbuffer->pybuffer.buf = NULL; - __PYX_ERR(0, 268, __pyx_L1_error) + __PYX_ERR(0, 294, __pyx_L1_error) } else {__pyx_pybuffernd_out.diminfo[0].strides = __pyx_pybuffernd_out.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_out.diminfo[0].shape = __pyx_pybuffernd_out.rcbuffer->pybuffer.shape[0]; } } @@ -21994,17 +22816,17 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_v_out = ((PyArrayObject *)__pyx_t_3); __pyx_t_3 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":270 + /* "acados_template/acados_ocp_solver_pyx.pyx":296 * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((dims,)) * acados_solver_common.ocp_nlp_out_get(self.nlp_config, \ * self.nlp_dims, self.nlp_out, stage, field, out.data) # <<<<<<<<<<<<<< * * return out */ - __pyx_t_10 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_10) && PyErr_Occurred())) __PYX_ERR(0, 270, __pyx_L1_error) - __pyx_t_11 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_out)); if (unlikely(__pyx_t_11 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 270, __pyx_L1_error) + __pyx_t_10 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_10) && PyErr_Occurred())) __PYX_ERR(0, 296, __pyx_L1_error) + __pyx_t_11 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_out)); if (unlikely(__pyx_t_11 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 296, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":269 + /* "acados_template/acados_ocp_solver_pyx.pyx":295 * * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((dims,)) * acados_solver_common.ocp_nlp_out_get(self.nlp_config, \ # <<<<<<<<<<<<<< @@ -22013,7 +22835,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ ocp_nlp_out_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_10, ((void *)__pyx_t_11)); - /* "acados_template/acados_ocp_solver_pyx.pyx":272 + /* "acados_template/acados_ocp_solver_pyx.pyx":298 * self.nlp_dims, self.nlp_out, stage, field, out.data) * * return out # <<<<<<<<<<<<<< @@ -22025,7 +22847,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_r = ((PyObject *)__pyx_v_out); goto __pyx_L0; - /* "acados_template/acados_ocp_solver_pyx.pyx":232 + /* "acados_template/acados_ocp_solver_pyx.pyx":258 * * * def get(self, int stage, str field_): # <<<<<<<<<<<<<< @@ -22059,7 +22881,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":275 +/* "acados_template/acados_ocp_solver_pyx.pyx":301 * * * def print_statistics(self): # <<<<<<<<<<<<<< @@ -22068,16 +22890,16 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ /* Python wrapper */ -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17print_statistics(PyObject *__pyx_v_self, +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21print_statistics(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else PyObject *__pyx_args, PyObject *__pyx_kwds #endif ); /*proto*/ -PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16print_statistics, "\n prints statistics of previous solver run as a table:\n - iter: iteration number\n - res_stat: stationarity residual\n - res_eq: residual wrt equality constraints (dynamics)\n - res_ineq: residual wrt inequality constraints (constraints)\n - res_comp: residual wrt complementarity conditions\n - qp_stat: status of QP solver\n - qp_iter: number of QP iterations\n - qp_res_stat: stationarity residual of the last QP solution\n - qp_res_eq: residual wrt equality constraints (dynamics) of the last QP solution\n - qp_res_ineq: residual wrt inequality constraints (constraints) of the last QP solution\n - qp_res_comp: residual wrt complementarity conditions of the last QP solution\n "); -static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17print_statistics = {"print_statistics", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17print_statistics, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16print_statistics}; -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17print_statistics(PyObject *__pyx_v_self, +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20print_statistics, "\n prints statistics of previous solver run as a table:\n - iter: iteration number\n - res_stat: stationarity residual\n - res_eq: residual wrt equality constraints (dynamics)\n - res_ineq: residual wrt inequality constraints (constraints)\n - res_comp: residual wrt complementarity conditions\n - qp_stat: status of QP solver\n - qp_iter: number of QP iterations\n - qp_res_stat: stationarity residual of the last QP solution\n - qp_res_eq: residual wrt equality constraints (dynamics) of the last QP solution\n - qp_res_ineq: residual wrt inequality constraints (constraints) of the last QP solution\n - qp_res_comp: residual wrt complementarity conditions of the last QP solution\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21print_statistics = {"print_statistics", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21print_statistics, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20print_statistics}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21print_statistics(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else @@ -22094,19 +22916,19 @@ PyObject *__pyx_args, PyObject *__pyx_kwds if (unlikely(__pyx_nargs > 0)) { __Pyx_RaiseArgtupleInvalid("print_statistics", 1, 0, 0, __pyx_nargs); return NULL;} if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "print_statistics", 0))) return NULL; - __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16print_statistics(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20print_statistics(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); /* function exit code */ __Pyx_RefNannyFinishContext(); return __pyx_r; } -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16print_statistics(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20print_statistics(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { PyObject *__pyx_r = NULL; __Pyx_RefNannyDeclarations __Pyx_RefNannySetupContext("print_statistics", 0); - /* "acados_template/acados_ocp_solver_pyx.pyx":290 + /* "acados_template/acados_ocp_solver_pyx.pyx":316 * - qp_res_comp: residual wrt complementarity conditions of the last QP solution * """ * acados_solver.acados_print_stats(self.capsule) # <<<<<<<<<<<<<< @@ -22115,7 +22937,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ lat_acados_print_stats(__pyx_v_self->capsule); - /* "acados_template/acados_ocp_solver_pyx.pyx":275 + /* "acados_template/acados_ocp_solver_pyx.pyx":301 * * * def print_statistics(self): # <<<<<<<<<<<<<< @@ -22130,7 +22952,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":293 +/* "acados_template/acados_ocp_solver_pyx.pyx":319 * * * def store_iterate(self, filename='', overwrite=False): # <<<<<<<<<<<<<< @@ -22139,16 +22961,16 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ /* Python wrapper */ -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19store_iterate(PyObject *__pyx_v_self, +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23store_iterate(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else PyObject *__pyx_args, PyObject *__pyx_kwds #endif ); /*proto*/ -PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18store_iterate, "\n Stores the current iterate of the ocp solver in a json file.\n\n :param filename: if not set, use model_name + timestamp + '.json'\n :param overwrite: if false and filename exists add timestamp to filename\n "); -static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19store_iterate = {"store_iterate", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19store_iterate, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18store_iterate}; -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19store_iterate(PyObject *__pyx_v_self, +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22store_iterate, "\n Stores the current iterate of the ocp solver in a json file.\n\n :param filename: if not set, use model_name + timestamp + '.json'\n :param overwrite: if false and filename exists add timestamp to filename\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23store_iterate = {"store_iterate", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23store_iterate, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22store_iterate}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23store_iterate(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else @@ -22170,7 +22992,7 @@ PyObject *__pyx_args, PyObject *__pyx_kwds { PyObject **__pyx_pyargnames[] = {&__pyx_n_s_filename,&__pyx_n_s_overwrite,0}; PyObject* values[2] = {0,0}; - values[0] = ((PyObject *)__pyx_kp_u__14); + values[0] = ((PyObject *)__pyx_kp_u__16); values[1] = ((PyObject *)Py_False); if (__pyx_kwds) { Py_ssize_t kw_args; @@ -22188,19 +23010,19 @@ PyObject *__pyx_args, PyObject *__pyx_kwds if (kw_args > 0) { PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_filename); if (value) { values[0] = value; kw_args--; } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 293, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 319, __pyx_L3_error) } CYTHON_FALLTHROUGH; case 1: if (kw_args > 0) { PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_overwrite); if (value) { values[1] = value; kw_args--; } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 293, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 319, __pyx_L3_error) } } if (unlikely(kw_args > 0)) { const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "store_iterate") < 0)) __PYX_ERR(0, 293, __pyx_L3_error) + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "store_iterate") < 0)) __PYX_ERR(0, 319, __pyx_L3_error) } } else { switch (__pyx_nargs) { @@ -22217,20 +23039,20 @@ PyObject *__pyx_args, PyObject *__pyx_kwds } goto __pyx_L4_argument_unpacking_done; __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("store_iterate", 0, 0, 2, __pyx_nargs); __PYX_ERR(0, 293, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("store_iterate", 0, 0, 2, __pyx_nargs); __PYX_ERR(0, 319, __pyx_L3_error) __pyx_L3_error:; __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.store_iterate", __pyx_clineno, __pyx_lineno, __pyx_filename); __Pyx_RefNannyFinishContext(); return NULL; __pyx_L4_argument_unpacking_done:; - __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18store_iterate(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_filename, __pyx_v_overwrite); + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22store_iterate(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_filename, __pyx_v_overwrite); /* function exit code */ __Pyx_RefNannyFinishContext(); return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":326 +/* "acados_template/acados_ocp_solver_pyx.pyx":358 * # save * with open(filename, 'w') as f: * json.dump(solution, f, default=lambda x: x.tolist(), indent=4, sort_keys=True) # <<<<<<<<<<<<<< @@ -22280,12 +23102,12 @@ PyObject *__pyx_args, PyObject *__pyx_kwds switch (__pyx_nargs) { case 0: if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_x)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 326, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 358, __pyx_L3_error) else goto __pyx_L5_argtuple_error; } if (unlikely(kw_args > 0)) { const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "lambda") < 0)) __PYX_ERR(0, 326, __pyx_L3_error) + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "lambda") < 0)) __PYX_ERR(0, 358, __pyx_L3_error) } } else if (unlikely(__pyx_nargs != 1)) { goto __pyx_L5_argtuple_error; @@ -22296,7 +23118,7 @@ PyObject *__pyx_args, PyObject *__pyx_kwds } goto __pyx_L4_argument_unpacking_done; __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("lambda", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 326, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("lambda", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 358, __pyx_L3_error) __pyx_L3_error:; __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.store_iterate.lambda", __pyx_clineno, __pyx_lineno, __pyx_filename); __Pyx_RefNannyFinishContext(); @@ -22321,7 +23143,7 @@ static PyObject *__pyx_lambda_funcdef_lambda(CYTHON_UNUSED PyObject *__pyx_self, int __pyx_clineno = 0; __Pyx_RefNannySetupContext("lambda", 0); __Pyx_XDECREF(__pyx_r); - __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_x, __pyx_n_s_tolist); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 326, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_x, __pyx_n_s_tolist); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 358, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __pyx_t_3 = NULL; __pyx_t_4 = 0; @@ -22339,7 +23161,7 @@ static PyObject *__pyx_lambda_funcdef_lambda(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_callargs[1] = {__pyx_t_3, }; __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 0+__pyx_t_4); __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; - if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 326, __pyx_L1_error) + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 358, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; } @@ -22360,7 +23182,7 @@ static PyObject *__pyx_lambda_funcdef_lambda(CYTHON_UNUSED PyObject *__pyx_self, return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":293 +/* "acados_template/acados_ocp_solver_pyx.pyx":319 * * * def store_iterate(self, filename='', overwrite=False): # <<<<<<<<<<<<<< @@ -22368,10 +23190,13 @@ static PyObject *__pyx_lambda_funcdef_lambda(CYTHON_UNUSED PyObject *__pyx_self, * Stores the current iterate of the ocp solver in a json file. */ -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18store_iterate(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_filename, PyObject *__pyx_v_overwrite) { +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22store_iterate(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_filename, PyObject *__pyx_v_overwrite) { PyObject *__pyx_v_json = NULL; PyObject *__pyx_v_solution = NULL; - PyObject *__pyx_v_i = NULL; + Py_ssize_t __pyx_v_lN; + long __pyx_v_i; + PyObject *__pyx_v_i_string = NULL; + PyObject *__pyx_v_k = NULL; PyObject *__pyx_v_f = NULL; PyObject *__pyx_r = NULL; __Pyx_RefNannyDeclarations @@ -22383,63 +23208,67 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS int __pyx_t_6; PyObject *__pyx_t_7 = NULL; Py_ssize_t __pyx_t_8; - PyObject *(*__pyx_t_9)(PyObject *); - PyObject *__pyx_t_10 = NULL; - PyObject *__pyx_t_11 = NULL; - PyObject *__pyx_t_12 = NULL; - PyObject *__pyx_t_13 = NULL; + long __pyx_t_9; + long __pyx_t_10; + long __pyx_t_11; + Py_UCS4 __pyx_t_12; + Py_ssize_t __pyx_t_13; PyObject *__pyx_t_14 = NULL; PyObject *__pyx_t_15 = NULL; + PyObject *__pyx_t_16 = NULL; + PyObject *__pyx_t_17 = NULL; + PyObject *__pyx_t_18 = NULL; + PyObject *__pyx_t_19 = NULL; int __pyx_lineno = 0; const char *__pyx_filename = NULL; int __pyx_clineno = 0; __Pyx_RefNannySetupContext("store_iterate", 0); __Pyx_INCREF(__pyx_v_filename); - /* "acados_template/acados_ocp_solver_pyx.pyx":300 + /* "acados_template/acados_ocp_solver_pyx.pyx":326 * :param overwrite: if false and filename exists add timestamp to filename * """ * import json # <<<<<<<<<<<<<< * if filename == '': * filename += self.model_name + '_' + 'iterate' + '.json' */ - __pyx_t_1 = __Pyx_ImportDottedModule(__pyx_n_s_json, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 300, __pyx_L1_error) + __pyx_t_1 = __Pyx_ImportDottedModule(__pyx_n_s_json, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 326, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __pyx_v_json = __pyx_t_1; __pyx_t_1 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":301 + /* "acados_template/acados_ocp_solver_pyx.pyx":327 * """ * import json * if filename == '': # <<<<<<<<<<<<<< * filename += self.model_name + '_' + 'iterate' + '.json' * */ - __pyx_t_2 = (__Pyx_PyUnicode_Equals(__pyx_v_filename, __pyx_kp_u__14, Py_EQ)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 301, __pyx_L1_error) + __pyx_t_2 = (__Pyx_PyUnicode_Equals(__pyx_v_filename, __pyx_kp_u__16, Py_EQ)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 327, __pyx_L1_error) if (__pyx_t_2) { - /* "acados_template/acados_ocp_solver_pyx.pyx":302 + /* "acados_template/acados_ocp_solver_pyx.pyx":328 * import json * if filename == '': * filename += self.model_name + '_' + 'iterate' + '.json' # <<<<<<<<<<<<<< * * if not overwrite: */ - __pyx_t_1 = __Pyx_PyUnicode_ConcatSafe(__pyx_v_self->model_name, __pyx_n_u__15); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 302, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyUnicode_ConcatSafe(__pyx_v_self->model_name, __pyx_n_u__17); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 328, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); - __pyx_t_3 = __Pyx_PyUnicode_ConcatInPlace(__pyx_t_1, __pyx_n_u_iterate); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 302, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyUnicode_ConcatInPlace(__pyx_t_1, __pyx_n_u_iterate); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 328, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_1 = __Pyx_PyUnicode_ConcatInPlace(__pyx_t_3, __pyx_kp_u_json_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 302, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyUnicode_ConcatInPlace(__pyx_t_3, __pyx_kp_u_json_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 328, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - __pyx_t_3 = PyNumber_InPlaceAdd(__pyx_v_filename, __pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 302, __pyx_L1_error) + __pyx_t_3 = PyNumber_InPlaceAdd(__pyx_v_filename, __pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 328, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; __Pyx_DECREF_SET(__pyx_v_filename, __pyx_t_3); __pyx_t_3 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":301 + /* "acados_template/acados_ocp_solver_pyx.pyx":327 * """ * import json * if filename == '': # <<<<<<<<<<<<<< @@ -22448,30 +23277,30 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":304 + /* "acados_template/acados_ocp_solver_pyx.pyx":330 * filename += self.model_name + '_' + 'iterate' + '.json' * * if not overwrite: # <<<<<<<<<<<<<< * # append timestamp * if os.path.isfile(filename): */ - __pyx_t_2 = __Pyx_PyObject_IsTrue(__pyx_v_overwrite); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 304, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_IsTrue(__pyx_v_overwrite); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 330, __pyx_L1_error) __pyx_t_4 = (!__pyx_t_2); if (__pyx_t_4) { - /* "acados_template/acados_ocp_solver_pyx.pyx":306 + /* "acados_template/acados_ocp_solver_pyx.pyx":332 * if not overwrite: * # append timestamp * if os.path.isfile(filename): # <<<<<<<<<<<<<< * filename = filename[:-5] * filename += datetime.utcnow().strftime('%Y-%m-%d-%H:%M:%S.%f') + '.json' */ - __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_os); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 306, __pyx_L1_error) + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_os); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 332, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); - __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_path); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 306, __pyx_L1_error) + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_path); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 332, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_5); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_isfile); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 306, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_isfile); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 332, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; __pyx_t_5 = NULL; @@ -22490,36 +23319,36 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_callargs[2] = {__pyx_t_5, __pyx_v_filename}; __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 1+__pyx_t_6); __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; - if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 306, __pyx_L1_error) + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 332, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; } - __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_t_3); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 306, __pyx_L1_error) + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_t_3); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 332, __pyx_L1_error) __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; if (__pyx_t_4) { - /* "acados_template/acados_ocp_solver_pyx.pyx":307 + /* "acados_template/acados_ocp_solver_pyx.pyx":333 * # append timestamp * if os.path.isfile(filename): * filename = filename[:-5] # <<<<<<<<<<<<<< * filename += datetime.utcnow().strftime('%Y-%m-%d-%H:%M:%S.%f') + '.json' * */ - __pyx_t_3 = __Pyx_PyObject_GetSlice(__pyx_v_filename, 0, -5L, NULL, NULL, &__pyx_slice__16, 0, 1, 1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 307, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyObject_GetSlice(__pyx_v_filename, 0, -5L, NULL, NULL, &__pyx_slice__18, 0, 1, 1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 333, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_DECREF_SET(__pyx_v_filename, __pyx_t_3); __pyx_t_3 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":308 + /* "acados_template/acados_ocp_solver_pyx.pyx":334 * if os.path.isfile(filename): * filename = filename[:-5] * filename += datetime.utcnow().strftime('%Y-%m-%d-%H:%M:%S.%f') + '.json' # <<<<<<<<<<<<<< * * # get iterate: */ - __Pyx_GetModuleGlobalName(__pyx_t_5, __pyx_n_s_datetime); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 308, __pyx_L1_error) + __Pyx_GetModuleGlobalName(__pyx_t_5, __pyx_n_s_datetime); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 334, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_5); - __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_utcnow); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 308, __pyx_L1_error) + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_utcnow); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 334, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; __pyx_t_5 = NULL; @@ -22538,11 +23367,11 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_callargs[1] = {__pyx_t_5, }; __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_7, __pyx_callargs+1-__pyx_t_6, 0+__pyx_t_6); __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; - if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 308, __pyx_L1_error) + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 334, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; } - __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_strftime); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 308, __pyx_L1_error) + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_strftime); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 334, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; __pyx_t_1 = NULL; @@ -22561,20 +23390,20 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_callargs[2] = {__pyx_t_1, __pyx_kp_u_Y_m_d_H_M_S_f}; __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_7, __pyx_callargs+1-__pyx_t_6, 1+__pyx_t_6); __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; - if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 308, __pyx_L1_error) + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 334, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; } - __pyx_t_7 = PyNumber_Add(__pyx_t_3, __pyx_kp_u_json_2); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 308, __pyx_L1_error) + __pyx_t_7 = PyNumber_Add(__pyx_t_3, __pyx_kp_u_json_2); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 334, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - __pyx_t_3 = PyNumber_InPlaceAdd(__pyx_v_filename, __pyx_t_7); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 308, __pyx_L1_error) + __pyx_t_3 = PyNumber_InPlaceAdd(__pyx_v_filename, __pyx_t_7); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 334, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; __Pyx_DECREF_SET(__pyx_v_filename, __pyx_t_3); __pyx_t_3 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":306 + /* "acados_template/acados_ocp_solver_pyx.pyx":332 * if not overwrite: * # append timestamp * if os.path.isfile(filename): # <<<<<<<<<<<<<< @@ -22583,7 +23412,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":304 + /* "acados_template/acados_ocp_solver_pyx.pyx":330 * filename += self.model_name + '_' + 'iterate' + '.json' * * if not overwrite: # <<<<<<<<<<<<<< @@ -22592,453 +23421,475 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":311 + /* "acados_template/acados_ocp_solver_pyx.pyx":337 * * # get iterate: * solution = dict() # <<<<<<<<<<<<<< * - * for i in range(self.N+1): + * lN = len(str(self.N+1)) */ - __pyx_t_3 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 311, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 337, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __pyx_v_solution = ((PyObject*)__pyx_t_3); __pyx_t_3 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":313 + /* "acados_template/acados_ocp_solver_pyx.pyx":339 * solution = dict() * - * for i in range(self.N+1): # <<<<<<<<<<<<<< - * solution['x_'+str(i)] = self.get(i,'x') - * solution['u_'+str(i)] = self.get(i,'u') + * lN = len(str(self.N+1)) # <<<<<<<<<<<<<< + * for i in range(self.N+1): + * i_string = f'{i:0{lN}d}' */ - __pyx_t_3 = __Pyx_PyInt_From_long((__pyx_v_self->N + 1)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 313, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyInt_From_long((__pyx_v_self->N + 1)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 339, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); - __pyx_t_7 = __Pyx_PyObject_CallOneArg(__pyx_builtin_range, __pyx_t_3); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 313, __pyx_L1_error) + __pyx_t_7 = __Pyx_PyObject_Str(__pyx_t_3); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 339, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - if (likely(PyList_CheckExact(__pyx_t_7)) || PyTuple_CheckExact(__pyx_t_7)) { - __pyx_t_3 = __pyx_t_7; __Pyx_INCREF(__pyx_t_3); __pyx_t_8 = 0; - __pyx_t_9 = NULL; - } else { - __pyx_t_8 = -1; __pyx_t_3 = PyObject_GetIter(__pyx_t_7); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 313, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __pyx_t_9 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_3); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 313, __pyx_L1_error) - } + __pyx_t_8 = PyObject_Length(__pyx_t_7); if (unlikely(__pyx_t_8 == ((Py_ssize_t)-1))) __PYX_ERR(0, 339, __pyx_L1_error) __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - for (;;) { - if (likely(!__pyx_t_9)) { - if (likely(PyList_CheckExact(__pyx_t_3))) { - if (__pyx_t_8 >= PyList_GET_SIZE(__pyx_t_3)) break; - #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - __pyx_t_7 = PyList_GET_ITEM(__pyx_t_3, __pyx_t_8); __Pyx_INCREF(__pyx_t_7); __pyx_t_8++; if (unlikely((0 < 0))) __PYX_ERR(0, 313, __pyx_L1_error) - #else - __pyx_t_7 = PySequence_ITEM(__pyx_t_3, __pyx_t_8); __pyx_t_8++; if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 313, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - #endif - } else { - if (__pyx_t_8 >= PyTuple_GET_SIZE(__pyx_t_3)) break; - #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - __pyx_t_7 = PyTuple_GET_ITEM(__pyx_t_3, __pyx_t_8); __Pyx_INCREF(__pyx_t_7); __pyx_t_8++; if (unlikely((0 < 0))) __PYX_ERR(0, 313, __pyx_L1_error) - #else - __pyx_t_7 = PySequence_ITEM(__pyx_t_3, __pyx_t_8); __pyx_t_8++; if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 313, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - #endif - } - } else { - __pyx_t_7 = __pyx_t_9(__pyx_t_3); - if (unlikely(!__pyx_t_7)) { - PyObject* exc_type = PyErr_Occurred(); - if (exc_type) { - if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); - else __PYX_ERR(0, 313, __pyx_L1_error) - } - break; - } - __Pyx_GOTREF(__pyx_t_7); - } - __Pyx_XDECREF_SET(__pyx_v_i, __pyx_t_7); - __pyx_t_7 = 0; + __pyx_v_lN = __pyx_t_8; - /* "acados_template/acados_ocp_solver_pyx.pyx":314 - * - * for i in range(self.N+1): - * solution['x_'+str(i)] = self.get(i,'x') # <<<<<<<<<<<<<< - * solution['u_'+str(i)] = self.get(i,'u') - * solution['z_'+str(i)] = self.get(i,'z') - */ - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 314, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_5 = NULL; - __pyx_t_6 = 0; - if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { - __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); - if (likely(__pyx_t_5)) { - PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); - __Pyx_INCREF(__pyx_t_5); - __Pyx_INCREF(function); - __Pyx_DECREF_SET(__pyx_t_1, function); - __pyx_t_6 = 1; - } - } - { - PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_v_i, __pyx_n_u_x}; - __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); - __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; - if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 314, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - } - __pyx_t_1 = __Pyx_PyObject_Str(__pyx_v_i); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 314, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_5 = PyNumber_Add(__pyx_n_u_x_2, __pyx_t_1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 314, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_5, __pyx_t_7) < 0))) __PYX_ERR(0, 314, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - - /* "acados_template/acados_ocp_solver_pyx.pyx":315 - * for i in range(self.N+1): - * solution['x_'+str(i)] = self.get(i,'x') - * solution['u_'+str(i)] = self.get(i,'u') # <<<<<<<<<<<<<< - * solution['z_'+str(i)] = self.get(i,'z') - * solution['lam_'+str(i)] = self.get(i,'lam') - */ - __pyx_t_5 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 315, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __pyx_t_1 = NULL; - __pyx_t_6 = 0; - if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_5))) { - __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_5); - if (likely(__pyx_t_1)) { - PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); - __Pyx_INCREF(__pyx_t_1); - __Pyx_INCREF(function); - __Pyx_DECREF_SET(__pyx_t_5, function); - __pyx_t_6 = 1; - } - } - { - PyObject *__pyx_callargs[3] = {__pyx_t_1, __pyx_v_i, __pyx_n_u_u}; - __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); - __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; - if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 315, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - } - __pyx_t_5 = __Pyx_PyObject_Str(__pyx_v_i); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 315, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __pyx_t_1 = PyNumber_Add(__pyx_n_u_u_2, __pyx_t_5); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 315, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_7) < 0))) __PYX_ERR(0, 315, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - - /* "acados_template/acados_ocp_solver_pyx.pyx":316 - * solution['x_'+str(i)] = self.get(i,'x') - * solution['u_'+str(i)] = self.get(i,'u') - * solution['z_'+str(i)] = self.get(i,'z') # <<<<<<<<<<<<<< - * solution['lam_'+str(i)] = self.get(i,'lam') - * solution['t_'+str(i)] = self.get(i, 't') - */ - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 316, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_5 = NULL; - __pyx_t_6 = 0; - if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { - __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); - if (likely(__pyx_t_5)) { - PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); - __Pyx_INCREF(__pyx_t_5); - __Pyx_INCREF(function); - __Pyx_DECREF_SET(__pyx_t_1, function); - __pyx_t_6 = 1; - } - } - { - PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_v_i, __pyx_n_u_z}; - __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); - __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; - if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 316, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - } - __pyx_t_1 = __Pyx_PyObject_Str(__pyx_v_i); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 316, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_5 = PyNumber_Add(__pyx_n_u_z_2, __pyx_t_1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 316, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_5, __pyx_t_7) < 0))) __PYX_ERR(0, 316, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - - /* "acados_template/acados_ocp_solver_pyx.pyx":317 - * solution['u_'+str(i)] = self.get(i,'u') - * solution['z_'+str(i)] = self.get(i,'z') - * solution['lam_'+str(i)] = self.get(i,'lam') # <<<<<<<<<<<<<< - * solution['t_'+str(i)] = self.get(i, 't') - * solution['sl_'+str(i)] = self.get(i, 'sl') - */ - __pyx_t_5 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 317, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __pyx_t_1 = NULL; - __pyx_t_6 = 0; - if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_5))) { - __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_5); - if (likely(__pyx_t_1)) { - PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); - __Pyx_INCREF(__pyx_t_1); - __Pyx_INCREF(function); - __Pyx_DECREF_SET(__pyx_t_5, function); - __pyx_t_6 = 1; - } - } - { - PyObject *__pyx_callargs[3] = {__pyx_t_1, __pyx_v_i, __pyx_n_u_lam}; - __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); - __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; - if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 317, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - } - __pyx_t_5 = __Pyx_PyObject_Str(__pyx_v_i); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 317, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __pyx_t_1 = PyNumber_Add(__pyx_n_u_lam_2, __pyx_t_5); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 317, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_7) < 0))) __PYX_ERR(0, 317, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - - /* "acados_template/acados_ocp_solver_pyx.pyx":318 - * solution['z_'+str(i)] = self.get(i,'z') - * solution['lam_'+str(i)] = self.get(i,'lam') - * solution['t_'+str(i)] = self.get(i, 't') # <<<<<<<<<<<<<< - * solution['sl_'+str(i)] = self.get(i, 'sl') - * solution['su_'+str(i)] = self.get(i, 'su') - */ - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 318, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_5 = NULL; - __pyx_t_6 = 0; - if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { - __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); - if (likely(__pyx_t_5)) { - PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); - __Pyx_INCREF(__pyx_t_5); - __Pyx_INCREF(function); - __Pyx_DECREF_SET(__pyx_t_1, function); - __pyx_t_6 = 1; - } - } - { - PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_v_i, __pyx_n_u_t}; - __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); - __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; - if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 318, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - } - __pyx_t_1 = __Pyx_PyObject_Str(__pyx_v_i); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 318, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_5 = PyNumber_Add(__pyx_n_u_t_2, __pyx_t_1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 318, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_5, __pyx_t_7) < 0))) __PYX_ERR(0, 318, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - - /* "acados_template/acados_ocp_solver_pyx.pyx":319 - * solution['lam_'+str(i)] = self.get(i,'lam') - * solution['t_'+str(i)] = self.get(i, 't') - * solution['sl_'+str(i)] = self.get(i, 'sl') # <<<<<<<<<<<<<< - * solution['su_'+str(i)] = self.get(i, 'su') - * for i in range(self.N): - */ - __pyx_t_5 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 319, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __pyx_t_1 = NULL; - __pyx_t_6 = 0; - if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_5))) { - __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_5); - if (likely(__pyx_t_1)) { - PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); - __Pyx_INCREF(__pyx_t_1); - __Pyx_INCREF(function); - __Pyx_DECREF_SET(__pyx_t_5, function); - __pyx_t_6 = 1; - } - } - { - PyObject *__pyx_callargs[3] = {__pyx_t_1, __pyx_v_i, __pyx_n_u_sl}; - __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); - __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; - if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 319, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - } - __pyx_t_5 = __Pyx_PyObject_Str(__pyx_v_i); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 319, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __pyx_t_1 = PyNumber_Add(__pyx_n_u_sl_2, __pyx_t_5); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 319, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_7) < 0))) __PYX_ERR(0, 319, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - - /* "acados_template/acados_ocp_solver_pyx.pyx":320 - * solution['t_'+str(i)] = self.get(i, 't') - * solution['sl_'+str(i)] = self.get(i, 'sl') - * solution['su_'+str(i)] = self.get(i, 'su') # <<<<<<<<<<<<<< - * for i in range(self.N): - * solution['pi_'+str(i)] = self.get(i,'pi') - */ - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 320, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_5 = NULL; - __pyx_t_6 = 0; - if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { - __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); - if (likely(__pyx_t_5)) { - PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); - __Pyx_INCREF(__pyx_t_5); - __Pyx_INCREF(function); - __Pyx_DECREF_SET(__pyx_t_1, function); - __pyx_t_6 = 1; - } - } - { - PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_v_i, __pyx_n_u_su}; - __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); - __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; - if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 320, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - } - __pyx_t_1 = __Pyx_PyObject_Str(__pyx_v_i); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 320, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_5 = PyNumber_Add(__pyx_n_u_su_2, __pyx_t_1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 320, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_5, __pyx_t_7) < 0))) __PYX_ERR(0, 320, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - - /* "acados_template/acados_ocp_solver_pyx.pyx":313 - * solution = dict() + /* "acados_template/acados_ocp_solver_pyx.pyx":340 * + * lN = len(str(self.N+1)) * for i in range(self.N+1): # <<<<<<<<<<<<<< - * solution['x_'+str(i)] = self.get(i,'x') - * solution['u_'+str(i)] = self.get(i,'u') + * i_string = f'{i:0{lN}d}' + * solution['x_'+i_string] = self.get(i,'x') */ - } - __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_9 = (__pyx_v_self->N + 1); + __pyx_t_10 = __pyx_t_9; + for (__pyx_t_11 = 0; __pyx_t_11 < __pyx_t_10; __pyx_t_11+=1) { + __pyx_v_i = __pyx_t_11; - /* "acados_template/acados_ocp_solver_pyx.pyx":321 - * solution['sl_'+str(i)] = self.get(i, 'sl') - * solution['su_'+str(i)] = self.get(i, 'su') - * for i in range(self.N): # <<<<<<<<<<<<<< - * solution['pi_'+str(i)] = self.get(i,'pi') + /* "acados_template/acados_ocp_solver_pyx.pyx":341 + * lN = len(str(self.N+1)) + * for i in range(self.N+1): + * i_string = f'{i:0{lN}d}' # <<<<<<<<<<<<<< + * solution['x_'+i_string] = self.get(i,'x') + * solution['u_'+i_string] = self.get(i,'u') + */ + __pyx_t_7 = __Pyx_PyInt_From_long(__pyx_v_i); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 341, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 341, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_8 = 0; + __pyx_t_12 = 127; + __Pyx_INCREF(__pyx_kp_u_0); + __pyx_t_8 += 1; + __Pyx_GIVEREF(__pyx_kp_u_0); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_kp_u_0); + __pyx_t_1 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_lN, 0, ' ', 'd'); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 341, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_8 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1); + __pyx_t_1 = 0; + __Pyx_INCREF(__pyx_n_u_d); + __pyx_t_8 += 1; + __Pyx_GIVEREF(__pyx_n_u_d); + PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_n_u_d); + __pyx_t_1 = __Pyx_PyUnicode_Join(__pyx_t_3, 3, __pyx_t_8, __pyx_t_12); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 341, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PyObject_Format(__pyx_t_7, __pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 341, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF_SET(__pyx_v_i_string, ((PyObject*)__pyx_t_3)); + __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":342 + * for i in range(self.N+1): + * i_string = f'{i:0{lN}d}' + * solution['x_'+i_string] = self.get(i,'x') # <<<<<<<<<<<<<< + * solution['u_'+i_string] = self.get(i,'u') + * solution['z_'+i_string] = self.get(i,'z') + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 342, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = __Pyx_PyInt_From_long(__pyx_v_i); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 342, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_t_7, __pyx_n_u_x}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 342, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyUnicode_Concat(__pyx_n_u_x_2, __pyx_v_i_string); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 342, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_3) < 0))) __PYX_ERR(0, 342, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":343 + * i_string = f'{i:0{lN}d}' + * solution['x_'+i_string] = self.get(i,'x') + * solution['u_'+i_string] = self.get(i,'u') # <<<<<<<<<<<<<< + * solution['z_'+i_string] = self.get(i,'z') + * solution['lam_'+i_string] = self.get(i,'lam') + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 343, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = __Pyx_PyInt_From_long(__pyx_v_i); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 343, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_t_7, __pyx_n_u_u}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 343, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyUnicode_Concat(__pyx_n_u_u_2, __pyx_v_i_string); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 343, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_3) < 0))) __PYX_ERR(0, 343, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":344 + * solution['x_'+i_string] = self.get(i,'x') + * solution['u_'+i_string] = self.get(i,'u') + * solution['z_'+i_string] = self.get(i,'z') # <<<<<<<<<<<<<< + * solution['lam_'+i_string] = self.get(i,'lam') + * solution['t_'+i_string] = self.get(i, 't') + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 344, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = __Pyx_PyInt_From_long(__pyx_v_i); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 344, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_t_7, __pyx_n_u_z}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 344, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyUnicode_Concat(__pyx_n_u_z_2, __pyx_v_i_string); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 344, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_3) < 0))) __PYX_ERR(0, 344, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":345 + * solution['u_'+i_string] = self.get(i,'u') + * solution['z_'+i_string] = self.get(i,'z') + * solution['lam_'+i_string] = self.get(i,'lam') # <<<<<<<<<<<<<< + * solution['t_'+i_string] = self.get(i, 't') + * solution['sl_'+i_string] = self.get(i, 'sl') + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 345, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = __Pyx_PyInt_From_long(__pyx_v_i); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 345, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_t_7, __pyx_n_u_lam}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 345, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyUnicode_Concat(__pyx_n_u_lam_2, __pyx_v_i_string); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 345, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_3) < 0))) __PYX_ERR(0, 345, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":346 + * solution['z_'+i_string] = self.get(i,'z') + * solution['lam_'+i_string] = self.get(i,'lam') + * solution['t_'+i_string] = self.get(i, 't') # <<<<<<<<<<<<<< + * solution['sl_'+i_string] = self.get(i, 'sl') + * solution['su_'+i_string] = self.get(i, 'su') + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 346, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = __Pyx_PyInt_From_long(__pyx_v_i); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 346, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_t_7, __pyx_n_u_t}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 346, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyUnicode_Concat(__pyx_n_u_t_2, __pyx_v_i_string); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 346, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_3) < 0))) __PYX_ERR(0, 346, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":347 + * solution['lam_'+i_string] = self.get(i,'lam') + * solution['t_'+i_string] = self.get(i, 't') + * solution['sl_'+i_string] = self.get(i, 'sl') # <<<<<<<<<<<<<< + * solution['su_'+i_string] = self.get(i, 'su') + * if i < self.N: + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 347, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = __Pyx_PyInt_From_long(__pyx_v_i); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 347, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_t_7, __pyx_n_u_sl}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 347, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyUnicode_Concat(__pyx_n_u_sl_2, __pyx_v_i_string); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 347, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_3) < 0))) __PYX_ERR(0, 347, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":348 + * solution['t_'+i_string] = self.get(i, 't') + * solution['sl_'+i_string] = self.get(i, 'sl') + * solution['su_'+i_string] = self.get(i, 'su') # <<<<<<<<<<<<<< + * if i < self.N: + * solution['pi_'+i_string] = self.get(i,'pi') + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 348, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = __Pyx_PyInt_From_long(__pyx_v_i); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 348, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_t_7, __pyx_n_u_su}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 348, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyUnicode_Concat(__pyx_n_u_su_2, __pyx_v_i_string); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 348, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_3) < 0))) __PYX_ERR(0, 348, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":349 + * solution['sl_'+i_string] = self.get(i, 'sl') + * solution['su_'+i_string] = self.get(i, 'su') + * if i < self.N: # <<<<<<<<<<<<<< + * solution['pi_'+i_string] = self.get(i,'pi') * */ - __pyx_t_3 = __Pyx_PyInt_From_int(__pyx_v_self->N); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 321, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __pyx_t_7 = __Pyx_PyObject_CallOneArg(__pyx_builtin_range, __pyx_t_3); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 321, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - if (likely(PyList_CheckExact(__pyx_t_7)) || PyTuple_CheckExact(__pyx_t_7)) { - __pyx_t_3 = __pyx_t_7; __Pyx_INCREF(__pyx_t_3); __pyx_t_8 = 0; - __pyx_t_9 = NULL; - } else { - __pyx_t_8 = -1; __pyx_t_3 = PyObject_GetIter(__pyx_t_7); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 321, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __pyx_t_9 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_3); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 321, __pyx_L1_error) - } - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - for (;;) { - if (likely(!__pyx_t_9)) { - if (likely(PyList_CheckExact(__pyx_t_3))) { - if (__pyx_t_8 >= PyList_GET_SIZE(__pyx_t_3)) break; - #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - __pyx_t_7 = PyList_GET_ITEM(__pyx_t_3, __pyx_t_8); __Pyx_INCREF(__pyx_t_7); __pyx_t_8++; if (unlikely((0 < 0))) __PYX_ERR(0, 321, __pyx_L1_error) - #else - __pyx_t_7 = PySequence_ITEM(__pyx_t_3, __pyx_t_8); __pyx_t_8++; if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 321, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - #endif - } else { - if (__pyx_t_8 >= PyTuple_GET_SIZE(__pyx_t_3)) break; - #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - __pyx_t_7 = PyTuple_GET_ITEM(__pyx_t_3, __pyx_t_8); __Pyx_INCREF(__pyx_t_7); __pyx_t_8++; if (unlikely((0 < 0))) __PYX_ERR(0, 321, __pyx_L1_error) - #else - __pyx_t_7 = PySequence_ITEM(__pyx_t_3, __pyx_t_8); __pyx_t_8++; if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 321, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - #endif - } - } else { - __pyx_t_7 = __pyx_t_9(__pyx_t_3); - if (unlikely(!__pyx_t_7)) { - PyObject* exc_type = PyErr_Occurred(); - if (exc_type) { - if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); - else __PYX_ERR(0, 321, __pyx_L1_error) - } - break; - } - __Pyx_GOTREF(__pyx_t_7); - } - __Pyx_XDECREF_SET(__pyx_v_i, __pyx_t_7); - __pyx_t_7 = 0; + __pyx_t_4 = (__pyx_v_i < __pyx_v_self->N); + if (__pyx_t_4) { - /* "acados_template/acados_ocp_solver_pyx.pyx":322 - * solution['su_'+str(i)] = self.get(i, 'su') - * for i in range(self.N): - * solution['pi_'+str(i)] = self.get(i,'pi') # <<<<<<<<<<<<<< + /* "acados_template/acados_ocp_solver_pyx.pyx":350 + * solution['su_'+i_string] = self.get(i, 'su') + * if i < self.N: + * solution['pi_'+i_string] = self.get(i,'pi') # <<<<<<<<<<<<<< + * + * for k in list(solution.keys()): + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 350, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = __Pyx_PyInt_From_long(__pyx_v_i); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 350, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_t_7, __pyx_n_u_pi}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 350, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyUnicode_Concat(__pyx_n_u_pi_2, __pyx_v_i_string); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 350, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_3) < 0))) __PYX_ERR(0, 350, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":349 + * solution['sl_'+i_string] = self.get(i, 'sl') + * solution['su_'+i_string] = self.get(i, 'su') + * if i < self.N: # <<<<<<<<<<<<<< + * solution['pi_'+i_string] = self.get(i,'pi') + * + */ + } + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":352 + * solution['pi_'+i_string] = self.get(i,'pi') + * + * for k in list(solution.keys()): # <<<<<<<<<<<<<< + * if len(solution[k]) == 0: + * del solution[k] + */ + __pyx_t_3 = __Pyx_PyDict_Keys(__pyx_v_solution); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 352, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = __Pyx_PySequence_ListKeepNew(__pyx_t_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 352, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __pyx_t_1; __Pyx_INCREF(__pyx_t_3); __pyx_t_8 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + for (;;) { + if (__pyx_t_8 >= PyList_GET_SIZE(__pyx_t_3)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_1 = PyList_GET_ITEM(__pyx_t_3, __pyx_t_8); __Pyx_INCREF(__pyx_t_1); __pyx_t_8++; if (unlikely((0 < 0))) __PYX_ERR(0, 352, __pyx_L1_error) + #else + __pyx_t_1 = PySequence_ITEM(__pyx_t_3, __pyx_t_8); __pyx_t_8++; if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 352, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + #endif + __Pyx_XDECREF_SET(__pyx_v_k, __pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":353 + * + * for k in list(solution.keys()): + * if len(solution[k]) == 0: # <<<<<<<<<<<<<< + * del solution[k] + * + */ + __pyx_t_1 = __Pyx_PyDict_GetItem(__pyx_v_solution, __pyx_v_k); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 353, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_13 = PyObject_Length(__pyx_t_1); if (unlikely(__pyx_t_13 == ((Py_ssize_t)-1))) __PYX_ERR(0, 353, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_4 = (__pyx_t_13 == 0); + if (__pyx_t_4) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":354 + * for k in list(solution.keys()): + * if len(solution[k]) == 0: + * del solution[k] # <<<<<<<<<<<<<< * * # save */ - __pyx_t_5 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 322, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __pyx_t_1 = NULL; - __pyx_t_6 = 0; - if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_5))) { - __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_5); - if (likely(__pyx_t_1)) { - PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); - __Pyx_INCREF(__pyx_t_1); - __Pyx_INCREF(function); - __Pyx_DECREF_SET(__pyx_t_5, function); - __pyx_t_6 = 1; - } - } - { - PyObject *__pyx_callargs[3] = {__pyx_t_1, __pyx_v_i, __pyx_n_u_pi}; - __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); - __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; - if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 322, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - } - __pyx_t_5 = __Pyx_PyObject_Str(__pyx_v_i); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 322, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __pyx_t_1 = PyNumber_Add(__pyx_n_u_pi_2, __pyx_t_5); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 322, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_7) < 0))) __PYX_ERR(0, 322, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely((PyDict_DelItem(__pyx_v_solution, __pyx_v_k) < 0))) __PYX_ERR(0, 354, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":321 - * solution['sl_'+str(i)] = self.get(i, 'sl') - * solution['su_'+str(i)] = self.get(i, 'su') - * for i in range(self.N): # <<<<<<<<<<<<<< - * solution['pi_'+str(i)] = self.get(i,'pi') + /* "acados_template/acados_ocp_solver_pyx.pyx":353 * + * for k in list(solution.keys()): + * if len(solution[k]) == 0: # <<<<<<<<<<<<<< + * del solution[k] + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":352 + * solution['pi_'+i_string] = self.get(i,'pi') + * + * for k in list(solution.keys()): # <<<<<<<<<<<<<< + * if len(solution[k]) == 0: + * del solution[k] */ } __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":325 + /* "acados_template/acados_ocp_solver_pyx.pyx":357 * * # save * with open(filename, 'w') as f: # <<<<<<<<<<<<<< @@ -23046,7 +23897,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS * print("stored current iterate in ", os.path.join(os.getcwd(), filename)) */ /*with:*/ { - __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 325, __pyx_L1_error) + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 357, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_INCREF(__pyx_v_filename); __Pyx_GIVEREF(__pyx_v_filename); @@ -23054,81 +23905,81 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __Pyx_INCREF(__pyx_n_u_w); __Pyx_GIVEREF(__pyx_n_u_w); PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_n_u_w); - __pyx_t_7 = __Pyx_PyObject_Call(__pyx_builtin_open, __pyx_t_3, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 325, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - __pyx_t_10 = __Pyx_PyObject_LookupSpecial(__pyx_t_7, __pyx_n_s_exit); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 325, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_10); - __pyx_t_1 = __Pyx_PyObject_LookupSpecial(__pyx_t_7, __pyx_n_s_enter); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 325, __pyx_L12_error) + __pyx_t_1 = __Pyx_PyObject_Call(__pyx_builtin_open, __pyx_t_3, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 357, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_14 = __Pyx_PyObject_LookupSpecial(__pyx_t_1, __pyx_n_s_exit); if (unlikely(!__pyx_t_14)) __PYX_ERR(0, 357, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_14); + __pyx_t_7 = __Pyx_PyObject_LookupSpecial(__pyx_t_1, __pyx_n_s_enter); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 357, __pyx_L13_error) + __Pyx_GOTREF(__pyx_t_7); __pyx_t_5 = NULL; __pyx_t_6 = 0; - if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { - __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_7))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_7); if (likely(__pyx_t_5)) { - PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_7); __Pyx_INCREF(__pyx_t_5); __Pyx_INCREF(function); - __Pyx_DECREF_SET(__pyx_t_1, function); + __Pyx_DECREF_SET(__pyx_t_7, function); __pyx_t_6 = 1; } } { PyObject *__pyx_callargs[1] = {__pyx_t_5, }; - __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 0+__pyx_t_6); + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_7, __pyx_callargs+1-__pyx_t_6, 0+__pyx_t_6); __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; - if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 325, __pyx_L12_error) + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 357, __pyx_L13_error) __Pyx_GOTREF(__pyx_t_3); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; } - __pyx_t_1 = __pyx_t_3; + __pyx_t_7 = __pyx_t_3; __pyx_t_3 = 0; - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; /*try:*/ { { __Pyx_PyThreadState_declare __Pyx_PyThreadState_assign - __Pyx_ExceptionSave(&__pyx_t_11, &__pyx_t_12, &__pyx_t_13); - __Pyx_XGOTREF(__pyx_t_11); - __Pyx_XGOTREF(__pyx_t_12); - __Pyx_XGOTREF(__pyx_t_13); + __Pyx_ExceptionSave(&__pyx_t_15, &__pyx_t_16, &__pyx_t_17); + __Pyx_XGOTREF(__pyx_t_15); + __Pyx_XGOTREF(__pyx_t_16); + __Pyx_XGOTREF(__pyx_t_17); /*try:*/ { - __pyx_v_f = __pyx_t_1; - __pyx_t_1 = 0; + __pyx_v_f = __pyx_t_7; + __pyx_t_7 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":326 + /* "acados_template/acados_ocp_solver_pyx.pyx":358 * # save * with open(filename, 'w') as f: * json.dump(solution, f, default=lambda x: x.tolist(), indent=4, sort_keys=True) # <<<<<<<<<<<<<< * print("stored current iterate in ", os.path.join(os.getcwd(), filename)) * */ - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_json, __pyx_n_s_dump); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 326, __pyx_L16_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_7 = PyTuple_New(2); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 326, __pyx_L16_error) + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_v_json, __pyx_n_s_dump); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 358, __pyx_L17_error) __Pyx_GOTREF(__pyx_t_7); + __pyx_t_1 = PyTuple_New(2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 358, __pyx_L17_error) + __Pyx_GOTREF(__pyx_t_1); __Pyx_INCREF(__pyx_v_solution); __Pyx_GIVEREF(__pyx_v_solution); - PyTuple_SET_ITEM(__pyx_t_7, 0, __pyx_v_solution); + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v_solution); __Pyx_INCREF(__pyx_v_f); __Pyx_GIVEREF(__pyx_v_f); - PyTuple_SET_ITEM(__pyx_t_7, 1, __pyx_v_f); - __pyx_t_3 = __Pyx_PyDict_NewPresized(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 326, __pyx_L16_error) + PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_v_f); + __pyx_t_3 = __Pyx_PyDict_NewPresized(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 358, __pyx_L17_error) __Pyx_GOTREF(__pyx_t_3); - __pyx_t_5 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13store_iterate_lambda, 0, __pyx_n_s_store_iterate_locals_lambda, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, NULL); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 326, __pyx_L16_error) + __pyx_t_5 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13store_iterate_lambda, 0, __pyx_n_s_store_iterate_locals_lambda, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, NULL); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 358, __pyx_L17_error) __Pyx_GOTREF(__pyx_t_5); - if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_default, __pyx_t_5) < 0) __PYX_ERR(0, 326, __pyx_L16_error) + if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_default, __pyx_t_5) < 0) __PYX_ERR(0, 358, __pyx_L17_error) __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_indent, __pyx_int_4) < 0) __PYX_ERR(0, 326, __pyx_L16_error) - if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_sort_keys, Py_True) < 0) __PYX_ERR(0, 326, __pyx_L16_error) - __pyx_t_5 = __Pyx_PyObject_Call(__pyx_t_1, __pyx_t_7, __pyx_t_3); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 326, __pyx_L16_error) + if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_indent, __pyx_int_4) < 0) __PYX_ERR(0, 358, __pyx_L17_error) + if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_sort_keys, Py_True) < 0) __PYX_ERR(0, 358, __pyx_L17_error) + __pyx_t_5 = __Pyx_PyObject_Call(__pyx_t_7, __pyx_t_1, __pyx_t_3); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 358, __pyx_L17_error) __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":325 + /* "acados_template/acados_ocp_solver_pyx.pyx":357 * * # save * with open(filename, 'w') as f: # <<<<<<<<<<<<<< @@ -23136,154 +23987,154 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS * print("stored current iterate in ", os.path.join(os.getcwd(), filename)) */ } - __Pyx_XDECREF(__pyx_t_11); __pyx_t_11 = 0; - __Pyx_XDECREF(__pyx_t_12); __pyx_t_12 = 0; - __Pyx_XDECREF(__pyx_t_13); __pyx_t_13 = 0; - goto __pyx_L21_try_end; - __pyx_L16_error:; + __Pyx_XDECREF(__pyx_t_15); __pyx_t_15 = 0; + __Pyx_XDECREF(__pyx_t_16); __pyx_t_16 = 0; + __Pyx_XDECREF(__pyx_t_17); __pyx_t_17 = 0; + goto __pyx_L22_try_end; + __pyx_L17_error:; __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; /*except:*/ { __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.store_iterate", __pyx_clineno, __pyx_lineno, __pyx_filename); - if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_3, &__pyx_t_7) < 0) __PYX_ERR(0, 325, __pyx_L18_except_error) + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_3, &__pyx_t_1) < 0) __PYX_ERR(0, 357, __pyx_L19_except_error) __Pyx_XGOTREF(__pyx_t_5); __Pyx_XGOTREF(__pyx_t_3); - __Pyx_XGOTREF(__pyx_t_7); - __pyx_t_1 = PyTuple_Pack(3, __pyx_t_5, __pyx_t_3, __pyx_t_7); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 325, __pyx_L18_except_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_14 = __Pyx_PyObject_Call(__pyx_t_10, __pyx_t_1, NULL); - __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - if (unlikely(!__pyx_t_14)) __PYX_ERR(0, 325, __pyx_L18_except_error) - __Pyx_GOTREF(__pyx_t_14); - __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_t_14); + __Pyx_XGOTREF(__pyx_t_1); + __pyx_t_7 = PyTuple_Pack(3, __pyx_t_5, __pyx_t_3, __pyx_t_1); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 357, __pyx_L19_except_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_18 = __Pyx_PyObject_Call(__pyx_t_14, __pyx_t_7, NULL); __Pyx_DECREF(__pyx_t_14); __pyx_t_14 = 0; - if (__pyx_t_4 < 0) __PYX_ERR(0, 325, __pyx_L18_except_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_18)) __PYX_ERR(0, 357, __pyx_L19_except_error) + __Pyx_GOTREF(__pyx_t_18); + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_t_18); + __Pyx_DECREF(__pyx_t_18); __pyx_t_18 = 0; + if (__pyx_t_4 < 0) __PYX_ERR(0, 357, __pyx_L19_except_error) __pyx_t_2 = (!__pyx_t_4); if (unlikely(__pyx_t_2)) { __Pyx_GIVEREF(__pyx_t_5); __Pyx_GIVEREF(__pyx_t_3); - __Pyx_XGIVEREF(__pyx_t_7); - __Pyx_ErrRestoreWithState(__pyx_t_5, __pyx_t_3, __pyx_t_7); - __pyx_t_5 = 0; __pyx_t_3 = 0; __pyx_t_7 = 0; - __PYX_ERR(0, 325, __pyx_L18_except_error) + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_ErrRestoreWithState(__pyx_t_5, __pyx_t_3, __pyx_t_1); + __pyx_t_5 = 0; __pyx_t_3 = 0; __pyx_t_1 = 0; + __PYX_ERR(0, 357, __pyx_L19_except_error) } __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; - __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; - goto __pyx_L17_exception_handled; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + goto __pyx_L18_exception_handled; } - __pyx_L18_except_error:; - __Pyx_XGIVEREF(__pyx_t_11); - __Pyx_XGIVEREF(__pyx_t_12); - __Pyx_XGIVEREF(__pyx_t_13); - __Pyx_ExceptionReset(__pyx_t_11, __pyx_t_12, __pyx_t_13); + __pyx_L19_except_error:; + __Pyx_XGIVEREF(__pyx_t_15); + __Pyx_XGIVEREF(__pyx_t_16); + __Pyx_XGIVEREF(__pyx_t_17); + __Pyx_ExceptionReset(__pyx_t_15, __pyx_t_16, __pyx_t_17); goto __pyx_L1_error; - __pyx_L17_exception_handled:; - __Pyx_XGIVEREF(__pyx_t_11); - __Pyx_XGIVEREF(__pyx_t_12); - __Pyx_XGIVEREF(__pyx_t_13); - __Pyx_ExceptionReset(__pyx_t_11, __pyx_t_12, __pyx_t_13); - __pyx_L21_try_end:; + __pyx_L18_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_15); + __Pyx_XGIVEREF(__pyx_t_16); + __Pyx_XGIVEREF(__pyx_t_17); + __Pyx_ExceptionReset(__pyx_t_15, __pyx_t_16, __pyx_t_17); + __pyx_L22_try_end:; } } /*finally:*/ { /*normal exit:*/{ - if (__pyx_t_10) { - __pyx_t_13 = __Pyx_PyObject_Call(__pyx_t_10, __pyx_tuple__17, NULL); - __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; - if (unlikely(!__pyx_t_13)) __PYX_ERR(0, 325, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_13); - __Pyx_DECREF(__pyx_t_13); __pyx_t_13 = 0; + if (__pyx_t_14) { + __pyx_t_17 = __Pyx_PyObject_Call(__pyx_t_14, __pyx_tuple__19, NULL); + __Pyx_DECREF(__pyx_t_14); __pyx_t_14 = 0; + if (unlikely(!__pyx_t_17)) __PYX_ERR(0, 357, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_17); + __Pyx_DECREF(__pyx_t_17); __pyx_t_17 = 0; } - goto __pyx_L15; + goto __pyx_L16; } - __pyx_L15:; + __pyx_L16:; } - goto __pyx_L25; - __pyx_L12_error:; - __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + goto __pyx_L26; + __pyx_L13_error:; + __Pyx_DECREF(__pyx_t_14); __pyx_t_14 = 0; goto __pyx_L1_error; - __pyx_L25:; + __pyx_L26:; } - /* "acados_template/acados_ocp_solver_pyx.pyx":327 + /* "acados_template/acados_ocp_solver_pyx.pyx":359 * with open(filename, 'w') as f: * json.dump(solution, f, default=lambda x: x.tolist(), indent=4, sort_keys=True) * print("stored current iterate in ", os.path.join(os.getcwd(), filename)) # <<<<<<<<<<<<<< * * */ - __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_os); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 327, __pyx_L1_error) + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_os); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 359, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); - __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_path); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 327, __pyx_L1_error) + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_path); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 359, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_5); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_join); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 327, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_join); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 359, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_os); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 327, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_15 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_getcwd); if (unlikely(!__pyx_t_15)) __PYX_ERR(0, 327, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_15); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_1 = NULL; + __Pyx_GetModuleGlobalName(__pyx_t_7, __pyx_n_s_os); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 359, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_19 = __Pyx_PyObject_GetAttrStr(__pyx_t_7, __pyx_n_s_getcwd); if (unlikely(!__pyx_t_19)) __PYX_ERR(0, 359, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_19); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __pyx_t_7 = NULL; __pyx_t_6 = 0; - if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_15))) { - __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_15); - if (likely(__pyx_t_1)) { - PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_15); - __Pyx_INCREF(__pyx_t_1); + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_19))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_19); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_19); + __Pyx_INCREF(__pyx_t_7); __Pyx_INCREF(function); - __Pyx_DECREF_SET(__pyx_t_15, function); + __Pyx_DECREF_SET(__pyx_t_19, function); __pyx_t_6 = 1; } } { - PyObject *__pyx_callargs[1] = {__pyx_t_1, }; - __pyx_t_5 = __Pyx_PyObject_FastCall(__pyx_t_15, __pyx_callargs+1-__pyx_t_6, 0+__pyx_t_6); - __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; - if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 327, __pyx_L1_error) + PyObject *__pyx_callargs[1] = {__pyx_t_7, }; + __pyx_t_5 = __Pyx_PyObject_FastCall(__pyx_t_19, __pyx_callargs+1-__pyx_t_6, 0+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 359, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_15); __pyx_t_15 = 0; + __Pyx_DECREF(__pyx_t_19); __pyx_t_19 = 0; } - __pyx_t_15 = NULL; + __pyx_t_19 = NULL; __pyx_t_6 = 0; if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_3))) { - __pyx_t_15 = PyMethod_GET_SELF(__pyx_t_3); - if (likely(__pyx_t_15)) { + __pyx_t_19 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_19)) { PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); - __Pyx_INCREF(__pyx_t_15); + __Pyx_INCREF(__pyx_t_19); __Pyx_INCREF(function); __Pyx_DECREF_SET(__pyx_t_3, function); __pyx_t_6 = 1; } } { - PyObject *__pyx_callargs[3] = {__pyx_t_15, __pyx_t_5, __pyx_v_filename}; - __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); - __Pyx_XDECREF(__pyx_t_15); __pyx_t_15 = 0; + PyObject *__pyx_callargs[3] = {__pyx_t_19, __pyx_t_5, __pyx_v_filename}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_19); __pyx_t_19 = 0; __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 327, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 359, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; } - __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 327, __pyx_L1_error) + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 359, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_INCREF(__pyx_kp_u_stored_current_iterate_in); __Pyx_GIVEREF(__pyx_kp_u_stored_current_iterate_in); PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_kp_u_stored_current_iterate_in); - __Pyx_GIVEREF(__pyx_t_7); - PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_7); - __pyx_t_7 = 0; - __pyx_t_7 = __Pyx_PyObject_Call(__pyx_builtin_print, __pyx_t_3, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 327, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1); + __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_Call(__pyx_builtin_print, __pyx_t_3, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 359, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":293 + /* "acados_template/acados_ocp_solver_pyx.pyx":319 * * * def store_iterate(self, filename='', overwrite=False): # <<<<<<<<<<<<<< @@ -23299,13 +24150,14 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __Pyx_XDECREF(__pyx_t_3); __Pyx_XDECREF(__pyx_t_5); __Pyx_XDECREF(__pyx_t_7); - __Pyx_XDECREF(__pyx_t_15); + __Pyx_XDECREF(__pyx_t_19); __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.store_iterate", __pyx_clineno, __pyx_lineno, __pyx_filename); __pyx_r = NULL; __pyx_L0:; __Pyx_XDECREF(__pyx_v_json); __Pyx_XDECREF(__pyx_v_solution); - __Pyx_XDECREF(__pyx_v_i); + __Pyx_XDECREF(__pyx_v_i_string); + __Pyx_XDECREF(__pyx_v_k); __Pyx_XDECREF(__pyx_v_f); __Pyx_XDECREF(__pyx_v_filename); __Pyx_XGIVEREF(__pyx_r); @@ -23313,7 +24165,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":330 +/* "acados_template/acados_ocp_solver_pyx.pyx":362 * * * def load_iterate(self, filename): # <<<<<<<<<<<<<< @@ -23322,16 +24174,16 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ /* Python wrapper */ -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21load_iterate(PyObject *__pyx_v_self, +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25load_iterate(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else PyObject *__pyx_args, PyObject *__pyx_kwds #endif ); /*proto*/ -PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20load_iterate, "\n Loads the iterate stored in json file with filename into the ocp solver.\n "); -static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21load_iterate = {"load_iterate", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21load_iterate, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20load_iterate}; -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21load_iterate(PyObject *__pyx_v_self, +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_24load_iterate, "\n Loads the iterate stored in json file with filename into the ocp solver.\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25load_iterate = {"load_iterate", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25load_iterate, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_24load_iterate}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25load_iterate(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else @@ -23364,12 +24216,12 @@ PyObject *__pyx_args, PyObject *__pyx_kwds switch (__pyx_nargs) { case 0: if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_filename)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 330, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 362, __pyx_L3_error) else goto __pyx_L5_argtuple_error; } if (unlikely(kw_args > 0)) { const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "load_iterate") < 0)) __PYX_ERR(0, 330, __pyx_L3_error) + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "load_iterate") < 0)) __PYX_ERR(0, 362, __pyx_L3_error) } } else if (unlikely(__pyx_nargs != 1)) { goto __pyx_L5_argtuple_error; @@ -23380,20 +24232,20 @@ PyObject *__pyx_args, PyObject *__pyx_kwds } goto __pyx_L4_argument_unpacking_done; __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("load_iterate", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 330, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("load_iterate", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 362, __pyx_L3_error) __pyx_L3_error:; __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.load_iterate", __pyx_clineno, __pyx_lineno, __pyx_filename); __Pyx_RefNannyFinishContext(); return NULL; __pyx_L4_argument_unpacking_done:; - __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20load_iterate(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_filename); + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_24load_iterate(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_filename); /* function exit code */ __Pyx_RefNannyFinishContext(); return __pyx_r; } -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20load_iterate(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_filename) { +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_24load_iterate(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_filename) { PyObject *__pyx_v_json = NULL; PyObject *__pyx_v_f = NULL; PyObject *__pyx_v_solution = NULL; @@ -23427,31 +24279,31 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS int __pyx_clineno = 0; __Pyx_RefNannySetupContext("load_iterate", 0); - /* "acados_template/acados_ocp_solver_pyx.pyx":334 + /* "acados_template/acados_ocp_solver_pyx.pyx":366 * Loads the iterate stored in json file with filename into the ocp solver. * """ * import json # <<<<<<<<<<<<<< * if not os.path.isfile(filename): * raise Exception('load_iterate: failed, file does not exist: ' + os.path.join(os.getcwd(), filename)) */ - __pyx_t_1 = __Pyx_ImportDottedModule(__pyx_n_s_json, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 334, __pyx_L1_error) + __pyx_t_1 = __Pyx_ImportDottedModule(__pyx_n_s_json, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 366, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __pyx_v_json = __pyx_t_1; __pyx_t_1 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":335 + /* "acados_template/acados_ocp_solver_pyx.pyx":367 * """ * import json * if not os.path.isfile(filename): # <<<<<<<<<<<<<< * raise Exception('load_iterate: failed, file does not exist: ' + os.path.join(os.getcwd(), filename)) * */ - __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_os); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 335, __pyx_L1_error) + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_os); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 367, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); - __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_path); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 335, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_path); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 367, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_isfile); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 335, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_isfile); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 367, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; __pyx_t_3 = NULL; @@ -23470,33 +24322,33 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_filename}; __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; - if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 335, __pyx_L1_error) + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 367, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; } - __pyx_t_5 = __Pyx_PyObject_IsTrue(__pyx_t_1); if (unlikely((__pyx_t_5 < 0))) __PYX_ERR(0, 335, __pyx_L1_error) + __pyx_t_5 = __Pyx_PyObject_IsTrue(__pyx_t_1); if (unlikely((__pyx_t_5 < 0))) __PYX_ERR(0, 367, __pyx_L1_error) __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; __pyx_t_6 = (!__pyx_t_5); if (unlikely(__pyx_t_6)) { - /* "acados_template/acados_ocp_solver_pyx.pyx":336 + /* "acados_template/acados_ocp_solver_pyx.pyx":368 * import json * if not os.path.isfile(filename): * raise Exception('load_iterate: failed, file does not exist: ' + os.path.join(os.getcwd(), filename)) # <<<<<<<<<<<<<< * * with open(filename, 'r') as f: */ - __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_os); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 336, __pyx_L1_error) + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_os); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 368, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); - __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_path); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 336, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_path); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 368, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_join); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 336, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_join); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 368, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - __Pyx_GetModuleGlobalName(__pyx_t_7, __pyx_n_s_os); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 336, __pyx_L1_error) + __Pyx_GetModuleGlobalName(__pyx_t_7, __pyx_n_s_os); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 368, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); - __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_t_7, __pyx_n_s_getcwd); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 336, __pyx_L1_error) + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_t_7, __pyx_n_s_getcwd); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 368, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_8); __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; __pyx_t_7 = NULL; @@ -23515,7 +24367,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_callargs[1] = {__pyx_t_7, }; __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_8, __pyx_callargs+1-__pyx_t_4, 0+__pyx_t_4); __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; - if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 336, __pyx_L1_error) + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 368, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; } @@ -23536,21 +24388,21 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 2+__pyx_t_4); __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 336, __pyx_L1_error) + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 368, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; } - __pyx_t_2 = PyNumber_Add(__pyx_kp_u_load_iterate_failed_file_does_no, __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 336, __pyx_L1_error) + __pyx_t_2 = PyNumber_Add(__pyx_kp_u_load_iterate_failed_file_does_no, __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 368, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_1 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 336, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 368, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; __Pyx_Raise(__pyx_t_1, 0, 0, 0); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __PYX_ERR(0, 336, __pyx_L1_error) + __PYX_ERR(0, 368, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":335 + /* "acados_template/acados_ocp_solver_pyx.pyx":367 * """ * import json * if not os.path.isfile(filename): # <<<<<<<<<<<<<< @@ -23559,7 +24411,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":338 + /* "acados_template/acados_ocp_solver_pyx.pyx":370 * raise Exception('load_iterate: failed, file does not exist: ' + os.path.join(os.getcwd(), filename)) * * with open(filename, 'r') as f: # <<<<<<<<<<<<<< @@ -23567,7 +24419,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS * */ /*with:*/ { - __pyx_t_1 = PyTuple_New(2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 338, __pyx_L1_error) + __pyx_t_1 = PyTuple_New(2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 370, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_INCREF(__pyx_v_filename); __Pyx_GIVEREF(__pyx_v_filename); @@ -23575,12 +24427,12 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __Pyx_INCREF(__pyx_n_u_r); __Pyx_GIVEREF(__pyx_n_u_r); PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_n_u_r); - __pyx_t_2 = __Pyx_PyObject_Call(__pyx_builtin_open, __pyx_t_1, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 338, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_Call(__pyx_builtin_open, __pyx_t_1, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 370, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_9 = __Pyx_PyObject_LookupSpecial(__pyx_t_2, __pyx_n_s_exit); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 338, __pyx_L1_error) + __pyx_t_9 = __Pyx_PyObject_LookupSpecial(__pyx_t_2, __pyx_n_s_exit); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 370, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_9); - __pyx_t_3 = __Pyx_PyObject_LookupSpecial(__pyx_t_2, __pyx_n_s_enter); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 338, __pyx_L4_error) + __pyx_t_3 = __Pyx_PyObject_LookupSpecial(__pyx_t_2, __pyx_n_s_enter); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 370, __pyx_L4_error) __Pyx_GOTREF(__pyx_t_3); __pyx_t_8 = NULL; __pyx_t_4 = 0; @@ -23598,7 +24450,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_callargs[1] = {__pyx_t_8, }; __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_4, 0+__pyx_t_4); __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; - if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 338, __pyx_L4_error) + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 370, __pyx_L4_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; } @@ -23617,14 +24469,14 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_v_f = __pyx_t_3; __pyx_t_3 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":339 + /* "acados_template/acados_ocp_solver_pyx.pyx":371 * * with open(filename, 'r') as f: * solution = json.load(f) # <<<<<<<<<<<<<< * * for key in solution.keys(): */ - __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_json, __pyx_n_s_load); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 339, __pyx_L8_error) + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_json, __pyx_n_s_load); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 371, __pyx_L8_error) __Pyx_GOTREF(__pyx_t_2); __pyx_t_1 = NULL; __pyx_t_4 = 0; @@ -23642,14 +24494,14 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_callargs[2] = {__pyx_t_1, __pyx_v_f}; __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; - if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 339, __pyx_L8_error) + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 371, __pyx_L8_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; } __pyx_v_solution = __pyx_t_3; __pyx_t_3 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":338 + /* "acados_template/acados_ocp_solver_pyx.pyx":370 * raise Exception('load_iterate: failed, file does not exist: ' + os.path.join(os.getcwd(), filename)) * * with open(filename, 'r') as f: # <<<<<<<<<<<<<< @@ -23669,20 +24521,20 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; /*except:*/ { __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.load_iterate", __pyx_clineno, __pyx_lineno, __pyx_filename); - if (__Pyx_GetException(&__pyx_t_3, &__pyx_t_2, &__pyx_t_1) < 0) __PYX_ERR(0, 338, __pyx_L10_except_error) + if (__Pyx_GetException(&__pyx_t_3, &__pyx_t_2, &__pyx_t_1) < 0) __PYX_ERR(0, 370, __pyx_L10_except_error) __Pyx_XGOTREF(__pyx_t_3); __Pyx_XGOTREF(__pyx_t_2); __Pyx_XGOTREF(__pyx_t_1); - __pyx_t_8 = PyTuple_Pack(3, __pyx_t_3, __pyx_t_2, __pyx_t_1); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 338, __pyx_L10_except_error) + __pyx_t_8 = PyTuple_Pack(3, __pyx_t_3, __pyx_t_2, __pyx_t_1); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 370, __pyx_L10_except_error) __Pyx_GOTREF(__pyx_t_8); __pyx_t_13 = __Pyx_PyObject_Call(__pyx_t_9, __pyx_t_8, NULL); __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; - if (unlikely(!__pyx_t_13)) __PYX_ERR(0, 338, __pyx_L10_except_error) + if (unlikely(!__pyx_t_13)) __PYX_ERR(0, 370, __pyx_L10_except_error) __Pyx_GOTREF(__pyx_t_13); __pyx_t_6 = __Pyx_PyObject_IsTrue(__pyx_t_13); __Pyx_DECREF(__pyx_t_13); __pyx_t_13 = 0; - if (__pyx_t_6 < 0) __PYX_ERR(0, 338, __pyx_L10_except_error) + if (__pyx_t_6 < 0) __PYX_ERR(0, 370, __pyx_L10_except_error) __pyx_t_5 = (!__pyx_t_6); if (unlikely(__pyx_t_5)) { __Pyx_GIVEREF(__pyx_t_3); @@ -23690,7 +24542,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __Pyx_XGIVEREF(__pyx_t_1); __Pyx_ErrRestoreWithState(__pyx_t_3, __pyx_t_2, __pyx_t_1); __pyx_t_3 = 0; __pyx_t_2 = 0; __pyx_t_1 = 0; - __PYX_ERR(0, 338, __pyx_L10_except_error) + __PYX_ERR(0, 370, __pyx_L10_except_error) } __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; @@ -23714,9 +24566,9 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS /*finally:*/ { /*normal exit:*/{ if (__pyx_t_9) { - __pyx_t_12 = __Pyx_PyObject_Call(__pyx_t_9, __pyx_tuple__17, NULL); + __pyx_t_12 = __Pyx_PyObject_Call(__pyx_t_9, __pyx_tuple__19, NULL); __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; - if (unlikely(!__pyx_t_12)) __PYX_ERR(0, 338, __pyx_L1_error) + if (unlikely(!__pyx_t_12)) __PYX_ERR(0, 370, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_12); __Pyx_DECREF(__pyx_t_12); __pyx_t_12 = 0; } @@ -23731,7 +24583,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_L17:; } - /* "acados_template/acados_ocp_solver_pyx.pyx":341 + /* "acados_template/acados_ocp_solver_pyx.pyx":373 * solution = json.load(f) * * for key in solution.keys(): # <<<<<<<<<<<<<< @@ -23739,12 +24591,12 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS * self.set(int(stage), field, np.array(solution[key])) */ __pyx_t_14 = 0; - if (unlikely(!__pyx_v_solution)) { __Pyx_RaiseUnboundLocalError("solution"); __PYX_ERR(0, 341, __pyx_L1_error) } + if (unlikely(!__pyx_v_solution)) { __Pyx_RaiseUnboundLocalError("solution"); __PYX_ERR(0, 373, __pyx_L1_error) } if (unlikely(__pyx_v_solution == Py_None)) { PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "keys"); - __PYX_ERR(0, 341, __pyx_L1_error) + __PYX_ERR(0, 373, __pyx_L1_error) } - __pyx_t_2 = __Pyx_dict_iterator(__pyx_v_solution, 0, __pyx_n_s_keys, (&__pyx_t_15), (&__pyx_t_4)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 341, __pyx_L1_error) + __pyx_t_2 = __Pyx_dict_iterator(__pyx_v_solution, 0, __pyx_n_s_keys, (&__pyx_t_15), (&__pyx_t_4)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 373, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = __pyx_t_2; @@ -23752,19 +24604,19 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS while (1) { __pyx_t_16 = __Pyx_dict_iter_next(__pyx_t_1, __pyx_t_15, &__pyx_t_14, &__pyx_t_2, NULL, NULL, __pyx_t_4); if (unlikely(__pyx_t_16 == 0)) break; - if (unlikely(__pyx_t_16 == -1)) __PYX_ERR(0, 341, __pyx_L1_error) + if (unlikely(__pyx_t_16 == -1)) __PYX_ERR(0, 373, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_XDECREF_SET(__pyx_v_key, __pyx_t_2); __pyx_t_2 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":342 + /* "acados_template/acados_ocp_solver_pyx.pyx":374 * * for key in solution.keys(): * (field, stage) = key.split('_') # <<<<<<<<<<<<<< * self.set(int(stage), field, np.array(solution[key])) * */ - __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_v_key, __pyx_n_s_split); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 342, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_v_key, __pyx_n_s_split); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 374, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __pyx_t_8 = NULL; __pyx_t_16 = 0; @@ -23779,10 +24631,10 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS } } { - PyObject *__pyx_callargs[2] = {__pyx_t_8, __pyx_n_u__15}; + PyObject *__pyx_callargs[2] = {__pyx_t_8, __pyx_n_u__17}; __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_16, 1+__pyx_t_16); __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; - if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 342, __pyx_L1_error) + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 374, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; } @@ -23792,7 +24644,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS if (unlikely(size != 2)) { if (size > 2) __Pyx_RaiseTooManyValuesError(2); else if (size >= 0) __Pyx_RaiseNeedMoreValuesError(size); - __PYX_ERR(0, 342, __pyx_L1_error) + __PYX_ERR(0, 374, __pyx_L1_error) } #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS if (likely(PyTuple_CheckExact(sequence))) { @@ -23805,15 +24657,15 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __Pyx_INCREF(__pyx_t_3); __Pyx_INCREF(__pyx_t_8); #else - __pyx_t_3 = PySequence_ITEM(sequence, 0); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 342, __pyx_L1_error) + __pyx_t_3 = PySequence_ITEM(sequence, 0); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 374, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); - __pyx_t_8 = PySequence_ITEM(sequence, 1); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 342, __pyx_L1_error) + __pyx_t_8 = PySequence_ITEM(sequence, 1); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 374, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_8); #endif __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; } else { Py_ssize_t index = -1; - __pyx_t_7 = PyObject_GetIter(__pyx_t_2); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 342, __pyx_L1_error) + __pyx_t_7 = PyObject_GetIter(__pyx_t_2); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 374, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; __pyx_t_17 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_7); @@ -23821,7 +24673,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __Pyx_GOTREF(__pyx_t_3); index = 1; __pyx_t_8 = __pyx_t_17(__pyx_t_7); if (unlikely(!__pyx_t_8)) goto __pyx_L20_unpacking_failed; __Pyx_GOTREF(__pyx_t_8); - if (__Pyx_IternextUnpackEndCheck(__pyx_t_17(__pyx_t_7), 2) < 0) __PYX_ERR(0, 342, __pyx_L1_error) + if (__Pyx_IternextUnpackEndCheck(__pyx_t_17(__pyx_t_7), 2) < 0) __PYX_ERR(0, 374, __pyx_L1_error) __pyx_t_17 = NULL; __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; goto __pyx_L21_unpacking_done; @@ -23829,7 +24681,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; __pyx_t_17 = NULL; if (__Pyx_IterFinish() == 0) __Pyx_RaiseNeedMoreValuesError(index); - __PYX_ERR(0, 342, __pyx_L1_error) + __PYX_ERR(0, 374, __pyx_L1_error) __pyx_L21_unpacking_done:; } __Pyx_XDECREF_SET(__pyx_v_field, __pyx_t_3); @@ -23837,24 +24689,24 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __Pyx_XDECREF_SET(__pyx_v_stage, __pyx_t_8); __pyx_t_8 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":343 + /* "acados_template/acados_ocp_solver_pyx.pyx":375 * for key in solution.keys(): * (field, stage) = key.split('_') * self.set(int(stage), field, np.array(solution[key])) # <<<<<<<<<<<<<< * * */ - __pyx_t_8 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_set); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 343, __pyx_L1_error) + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_set); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 375, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_8); - __pyx_t_3 = __Pyx_PyNumber_Int(__pyx_v_stage); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 343, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyNumber_Int(__pyx_v_stage); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 375, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); - __Pyx_GetModuleGlobalName(__pyx_t_18, __pyx_n_s_np); if (unlikely(!__pyx_t_18)) __PYX_ERR(0, 343, __pyx_L1_error) + __Pyx_GetModuleGlobalName(__pyx_t_18, __pyx_n_s_np); if (unlikely(!__pyx_t_18)) __PYX_ERR(0, 375, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_18); - __pyx_t_19 = __Pyx_PyObject_GetAttrStr(__pyx_t_18, __pyx_n_s_array); if (unlikely(!__pyx_t_19)) __PYX_ERR(0, 343, __pyx_L1_error) + __pyx_t_19 = __Pyx_PyObject_GetAttrStr(__pyx_t_18, __pyx_n_s_array); if (unlikely(!__pyx_t_19)) __PYX_ERR(0, 375, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_19); __Pyx_DECREF(__pyx_t_18); __pyx_t_18 = 0; - if (unlikely(!__pyx_v_solution)) { __Pyx_RaiseUnboundLocalError("solution"); __PYX_ERR(0, 343, __pyx_L1_error) } - __pyx_t_18 = __Pyx_PyObject_GetItem(__pyx_v_solution, __pyx_v_key); if (unlikely(!__pyx_t_18)) __PYX_ERR(0, 343, __pyx_L1_error) + if (unlikely(!__pyx_v_solution)) { __Pyx_RaiseUnboundLocalError("solution"); __PYX_ERR(0, 375, __pyx_L1_error) } + __pyx_t_18 = __Pyx_PyObject_GetItem(__pyx_v_solution, __pyx_v_key); if (unlikely(!__pyx_t_18)) __PYX_ERR(0, 375, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_18); __pyx_t_20 = NULL; __pyx_t_16 = 0; @@ -23873,7 +24725,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_19, __pyx_callargs+1-__pyx_t_16, 1+__pyx_t_16); __Pyx_XDECREF(__pyx_t_20); __pyx_t_20 = 0; __Pyx_DECREF(__pyx_t_18); __pyx_t_18 = 0; - if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 343, __pyx_L1_error) + if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 375, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); __Pyx_DECREF(__pyx_t_19); __pyx_t_19 = 0; } @@ -23895,7 +24747,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __Pyx_XDECREF(__pyx_t_19); __pyx_t_19 = 0; __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 343, __pyx_L1_error) + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 375, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; } @@ -23903,7 +24755,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS } __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":330 + /* "acados_template/acados_ocp_solver_pyx.pyx":362 * * * def load_iterate(self, filename): # <<<<<<<<<<<<<< @@ -23937,7 +24789,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":346 +/* "acados_template/acados_ocp_solver_pyx.pyx":378 * * * def get_stats(self, field_): # <<<<<<<<<<<<<< @@ -23946,16 +24798,16 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ /* Python wrapper */ -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23get_stats(PyObject *__pyx_v_self, +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27get_stats(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else PyObject *__pyx_args, PyObject *__pyx_kwds #endif ); /*proto*/ -PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22get_stats, "\n Get the information of the last solver call.\n\n :param field: string in ['statistics', 'time_tot', 'time_lin', 'time_sim', 'time_sim_ad', 'time_sim_la', 'time_qp', 'time_qp_solver_call', 'time_reg', 'sqp_iter']\n Available fileds:\n - time_tot: total CPU time previous call\n - time_lin: CPU time for linearization\n - time_sim: CPU time for integrator\n - time_sim_ad: CPU time for integrator contribution of external function calls\n - time_sim_la: CPU time for integrator contribution of linear algebra\n - time_qp: CPU time qp solution\n - time_qp_solver_call: CPU time inside qp solver (without converting the QP)\n - time_qp_xcond: time_glob: CPU time globalization\n - time_solution_sensitivities: CPU time for previous call to eval_param_sens\n - time_reg: CPU time regularization\n - sqp_iter: number of SQP iterations\n - qp_iter: vector of QP iterations for last SQP call\n - statistics: table with info about last iteration\n - stat_m: number of rows in statistics matrix\n - stat_n: number of columns in statistics matrix\n - residuals: residuals of last iterate\n - alpha: step sizes of SQP iterations\n "); -static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23get_stats = {"get_stats", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23get_stats, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22get_stats}; -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23get_stats(PyObject *__pyx_v_self, +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_26get_stats, "\n Get the information of the last solver call.\n\n :param field: string in ['statistics', 'time_tot', 'time_lin', 'time_sim', 'time_sim_ad', 'time_sim_la', 'time_qp', 'time_qp_solver_call', 'time_reg', 'sqp_iter']\n Available fileds:\n - time_tot: total CPU time previous call\n - time_lin: CPU time for linearization\n - time_sim: CPU time for integrator\n - time_sim_ad: CPU time for integrator contribution of external function calls\n - time_sim_la: CPU time for integrator contribution of linear algebra\n - time_qp: CPU time qp solution\n - time_qp_solver_call: CPU time inside qp solver (without converting the QP)\n - time_qp_xcond: time_glob: CPU time globalization\n - time_solution_sensitivities: CPU time for previous call to eval_param_sens\n - time_reg: CPU time regularization\n - sqp_iter: number of SQP iterations\n - qp_iter: vector of QP iterations for last SQP call\n - statistics: table with info about last iteration\n - stat_m: number of rows in statistics matrix\n - stat_n: number of columns in statistics matrix\n - residuals: residuals of last iterate\n - alpha: step sizes of SQP iterations\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27get_stats = {"get_stats", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27get_stats, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_26get_stats}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27get_stats(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else @@ -23988,12 +24840,12 @@ PyObject *__pyx_args, PyObject *__pyx_kwds switch (__pyx_nargs) { case 0: if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field_2)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 346, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 378, __pyx_L3_error) else goto __pyx_L5_argtuple_error; } if (unlikely(kw_args > 0)) { const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "get_stats") < 0)) __PYX_ERR(0, 346, __pyx_L3_error) + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "get_stats") < 0)) __PYX_ERR(0, 378, __pyx_L3_error) } } else if (unlikely(__pyx_nargs != 1)) { goto __pyx_L5_argtuple_error; @@ -24004,20 +24856,20 @@ PyObject *__pyx_args, PyObject *__pyx_kwds } goto __pyx_L4_argument_unpacking_done; __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("get_stats", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 346, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("get_stats", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 378, __pyx_L3_error) __pyx_L3_error:; __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.get_stats", __pyx_clineno, __pyx_lineno, __pyx_filename); __Pyx_RefNannyFinishContext(); return NULL; __pyx_L4_argument_unpacking_done:; - __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22get_stats(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_field_); + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_26get_stats(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_field_); /* function exit code */ __Pyx_RefNannyFinishContext(); return __pyx_r; } -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22get_stats(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field_) { +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_26get_stats(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field_) { PyObject *__pyx_v_double_fields = NULL; CYTHON_UNUSED PyObject *__pyx_v_fields = NULL; PyObject *__pyx_v_field = NULL; @@ -24040,14 +24892,14 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS int __pyx_clineno = 0; __Pyx_RefNannySetupContext("get_stats", 0); - /* "acados_template/acados_ocp_solver_pyx.pyx":371 + /* "acados_template/acados_ocp_solver_pyx.pyx":403 * """ * * double_fields = ['time_tot', # <<<<<<<<<<<<<< * 'time_lin', * 'time_sim', */ - __pyx_t_1 = PyList_New(11); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 371, __pyx_L1_error) + __pyx_t_1 = PyList_New(11); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 403, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_INCREF(__pyx_n_u_time_tot); __Pyx_GIVEREF(__pyx_n_u_time_tot); @@ -24085,14 +24937,14 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_v_double_fields = ((PyObject*)__pyx_t_1); __pyx_t_1 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":383 + /* "acados_template/acados_ocp_solver_pyx.pyx":415 * 'time_reg' * ] * fields = double_fields + [ # <<<<<<<<<<<<<< * 'sqp_iter', * 'qp_iter', */ - __pyx_t_1 = PyList_New(7); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 383, __pyx_L1_error) + __pyx_t_1 = PyList_New(7); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 415, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_INCREF(__pyx_n_u_sqp_iter); __Pyx_GIVEREF(__pyx_n_u_sqp_iter); @@ -24115,20 +24967,20 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __Pyx_INCREF(__pyx_n_u_alpha); __Pyx_GIVEREF(__pyx_n_u_alpha); PyList_SET_ITEM(__pyx_t_1, 6, __pyx_n_u_alpha); - __pyx_t_2 = PyNumber_Add(__pyx_v_double_fields, __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 383, __pyx_L1_error) + __pyx_t_2 = PyNumber_Add(__pyx_v_double_fields, __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 415, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; __pyx_v_fields = ((PyObject*)__pyx_t_2); __pyx_t_2 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":392 + /* "acados_template/acados_ocp_solver_pyx.pyx":424 * 'alpha', * ] * field = field_.encode('utf-8') # <<<<<<<<<<<<<< * * if field_ in ['sqp_iter', 'stat_m', 'stat_n']: */ - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_field_, __pyx_n_s_encode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 392, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_field_, __pyx_n_s_encode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 424, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __pyx_t_3 = NULL; __pyx_t_4 = 0; @@ -24146,14 +24998,14 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_kp_u_utf_8}; __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; - if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 392, __pyx_L1_error) + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 424, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; } __pyx_v_field = __pyx_t_2; __pyx_t_2 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":394 + /* "acados_template/acados_ocp_solver_pyx.pyx":426 * field = field_.encode('utf-8') * * if field_ in ['sqp_iter', 'stat_m', 'stat_n']: # <<<<<<<<<<<<<< @@ -24162,26 +25014,26 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ __Pyx_INCREF(__pyx_v_field_); __pyx_t_2 = __pyx_v_field_; - __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_t_2, __pyx_n_u_sqp_iter, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 394, __pyx_L1_error) + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_t_2, __pyx_n_u_sqp_iter, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 426, __pyx_L1_error) if (!__pyx_t_6) { } else { __pyx_t_5 = __pyx_t_6; goto __pyx_L4_bool_binop_done; } - __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_t_2, __pyx_n_u_stat_m, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 394, __pyx_L1_error) + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_t_2, __pyx_n_u_stat_m, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 426, __pyx_L1_error) if (!__pyx_t_6) { } else { __pyx_t_5 = __pyx_t_6; goto __pyx_L4_bool_binop_done; } - __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_t_2, __pyx_n_u_stat_n, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 394, __pyx_L1_error) + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_t_2, __pyx_n_u_stat_n, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 426, __pyx_L1_error) __pyx_t_5 = __pyx_t_6; __pyx_L4_bool_binop_done:; __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; __pyx_t_6 = __pyx_t_5; if (__pyx_t_6) { - /* "acados_template/acados_ocp_solver_pyx.pyx":395 + /* "acados_template/acados_ocp_solver_pyx.pyx":427 * * if field_ in ['sqp_iter', 'stat_m', 'stat_n']: * return self.__get_stat_int(field) # <<<<<<<<<<<<<< @@ -24189,7 +25041,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS * elif field_ in double_fields: */ __Pyx_XDECREF(__pyx_r); - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_AcadosOcpSolverCython__get_stat); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 395, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_AcadosOcpSolverCython__get_stat); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 427, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __pyx_t_3 = NULL; __pyx_t_4 = 0; @@ -24207,7 +25059,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_field}; __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; - if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 395, __pyx_L1_error) + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 427, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; } @@ -24215,7 +25067,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_t_2 = 0; goto __pyx_L0; - /* "acados_template/acados_ocp_solver_pyx.pyx":394 + /* "acados_template/acados_ocp_solver_pyx.pyx":426 * field = field_.encode('utf-8') * * if field_ in ['sqp_iter', 'stat_m', 'stat_n']: # <<<<<<<<<<<<<< @@ -24224,17 +25076,17 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":397 + /* "acados_template/acados_ocp_solver_pyx.pyx":429 * return self.__get_stat_int(field) * * elif field_ in double_fields: # <<<<<<<<<<<<<< * return self.__get_stat_double(field) * */ - __pyx_t_6 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_double_fields, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 397, __pyx_L1_error) + __pyx_t_6 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_double_fields, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 429, __pyx_L1_error) if (__pyx_t_6) { - /* "acados_template/acados_ocp_solver_pyx.pyx":398 + /* "acados_template/acados_ocp_solver_pyx.pyx":430 * * elif field_ in double_fields: * return self.__get_stat_double(field) # <<<<<<<<<<<<<< @@ -24242,7 +25094,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS * elif field_ == 'statistics': */ __Pyx_XDECREF(__pyx_r); - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_AcadosOcpSolverCython__get_stat_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 398, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_AcadosOcpSolverCython__get_stat_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 430, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __pyx_t_3 = NULL; __pyx_t_4 = 0; @@ -24260,7 +25112,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_field}; __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; - if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 398, __pyx_L1_error) + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 430, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; } @@ -24268,7 +25120,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_t_2 = 0; goto __pyx_L0; - /* "acados_template/acados_ocp_solver_pyx.pyx":397 + /* "acados_template/acados_ocp_solver_pyx.pyx":429 * return self.__get_stat_int(field) * * elif field_ in double_fields: # <<<<<<<<<<<<<< @@ -24277,24 +25129,24 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":400 + /* "acados_template/acados_ocp_solver_pyx.pyx":432 * return self.__get_stat_double(field) * * elif field_ == 'statistics': # <<<<<<<<<<<<<< * sqp_iter = self.get_stats("sqp_iter") * stat_m = self.get_stats("stat_m") */ - __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_statistics, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 400, __pyx_L1_error) + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_statistics, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 432, __pyx_L1_error) if (__pyx_t_6) { - /* "acados_template/acados_ocp_solver_pyx.pyx":401 + /* "acados_template/acados_ocp_solver_pyx.pyx":433 * * elif field_ == 'statistics': * sqp_iter = self.get_stats("sqp_iter") # <<<<<<<<<<<<<< * stat_m = self.get_stats("stat_m") * stat_n = self.get_stats("stat_n") */ - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_stats); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 401, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_stats); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 433, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __pyx_t_3 = NULL; __pyx_t_4 = 0; @@ -24312,21 +25164,21 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_n_u_sqp_iter}; __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; - if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 401, __pyx_L1_error) + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 433, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; } __pyx_v_sqp_iter = __pyx_t_2; __pyx_t_2 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":402 + /* "acados_template/acados_ocp_solver_pyx.pyx":434 * elif field_ == 'statistics': * sqp_iter = self.get_stats("sqp_iter") * stat_m = self.get_stats("stat_m") # <<<<<<<<<<<<<< * stat_n = self.get_stats("stat_n") * min_size = min([stat_m, sqp_iter+1]) */ - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_stats); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 402, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_stats); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 434, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __pyx_t_3 = NULL; __pyx_t_4 = 0; @@ -24344,21 +25196,21 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_n_u_stat_m}; __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; - if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 402, __pyx_L1_error) + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 434, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; } __pyx_v_stat_m = __pyx_t_2; __pyx_t_2 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":403 + /* "acados_template/acados_ocp_solver_pyx.pyx":435 * sqp_iter = self.get_stats("sqp_iter") * stat_m = self.get_stats("stat_m") * stat_n = self.get_stats("stat_n") # <<<<<<<<<<<<<< * min_size = min([stat_m, sqp_iter+1]) * return self.__get_stat_matrix(field, stat_n+1, min_size) */ - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_stats); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 403, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_stats); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 435, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __pyx_t_3 = NULL; __pyx_t_4 = 0; @@ -24376,26 +25228,26 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_n_u_stat_n}; __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; - if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 403, __pyx_L1_error) + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 435, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; } __pyx_v_stat_n = __pyx_t_2; __pyx_t_2 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":404 + /* "acados_template/acados_ocp_solver_pyx.pyx":436 * stat_m = self.get_stats("stat_m") * stat_n = self.get_stats("stat_n") * min_size = min([stat_m, sqp_iter+1]) # <<<<<<<<<<<<<< * return self.__get_stat_matrix(field, stat_n+1, min_size) * */ - __pyx_t_2 = __Pyx_PyInt_AddObjC(__pyx_v_sqp_iter, __pyx_int_1, 1, 0, 0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 404, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyInt_AddObjC(__pyx_v_sqp_iter, __pyx_int_1, 1, 0, 0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 436, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_INCREF(__pyx_v_stat_m); __pyx_t_1 = __pyx_v_stat_m; - __pyx_t_7 = PyObject_RichCompare(__pyx_t_2, __pyx_t_1, Py_LT); __Pyx_XGOTREF(__pyx_t_7); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 404, __pyx_L1_error) - __pyx_t_6 = __Pyx_PyObject_IsTrue(__pyx_t_7); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 404, __pyx_L1_error) + __pyx_t_7 = PyObject_RichCompare(__pyx_t_2, __pyx_t_1, Py_LT); __Pyx_XGOTREF(__pyx_t_7); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 436, __pyx_L1_error) + __pyx_t_6 = __Pyx_PyObject_IsTrue(__pyx_t_7); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 436, __pyx_L1_error) __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; if (__pyx_t_6) { __Pyx_INCREF(__pyx_t_2); @@ -24412,7 +25264,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_v_min_size = __pyx_t_2; __pyx_t_2 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":405 + /* "acados_template/acados_ocp_solver_pyx.pyx":437 * stat_n = self.get_stats("stat_n") * min_size = min([stat_m, sqp_iter+1]) * return self.__get_stat_matrix(field, stat_n+1, min_size) # <<<<<<<<<<<<<< @@ -24420,9 +25272,9 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS * elif field_ == 'qp_iter': */ __Pyx_XDECREF(__pyx_r); - __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_AcadosOcpSolverCython__get_stat_3); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 405, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_AcadosOcpSolverCython__get_stat_3); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 437, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); - __pyx_t_1 = __Pyx_PyInt_AddObjC(__pyx_v_stat_n, __pyx_int_1, 1, 0, 0); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 405, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyInt_AddObjC(__pyx_v_stat_n, __pyx_int_1, 1, 0, 0); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 437, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __pyx_t_7 = NULL; __pyx_t_4 = 0; @@ -24441,7 +25293,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_4, 3+__pyx_t_4); __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 405, __pyx_L1_error) + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 437, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; } @@ -24449,7 +25301,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_t_2 = 0; goto __pyx_L0; - /* "acados_template/acados_ocp_solver_pyx.pyx":400 + /* "acados_template/acados_ocp_solver_pyx.pyx":432 * return self.__get_stat_double(field) * * elif field_ == 'statistics': # <<<<<<<<<<<<<< @@ -24458,24 +25310,24 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":407 + /* "acados_template/acados_ocp_solver_pyx.pyx":439 * return self.__get_stat_matrix(field, stat_n+1, min_size) * * elif field_ == 'qp_iter': # <<<<<<<<<<<<<< * full_stats = self.get_stats('statistics') * if self.nlp_solver_type == 'SQP': */ - __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_qp_iter, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 407, __pyx_L1_error) + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_qp_iter, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 439, __pyx_L1_error) if (__pyx_t_6) { - /* "acados_template/acados_ocp_solver_pyx.pyx":408 + /* "acados_template/acados_ocp_solver_pyx.pyx":440 * * elif field_ == 'qp_iter': * full_stats = self.get_stats('statistics') # <<<<<<<<<<<<<< * if self.nlp_solver_type == 'SQP': * return full_stats[6, :] */ - __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_stats); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 408, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_stats); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 440, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __pyx_t_1 = NULL; __pyx_t_4 = 0; @@ -24493,24 +25345,24 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_callargs[2] = {__pyx_t_1, __pyx_n_u_statistics}; __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; - if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 408, __pyx_L1_error) + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 440, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; } __pyx_v_full_stats = __pyx_t_2; __pyx_t_2 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":409 + /* "acados_template/acados_ocp_solver_pyx.pyx":441 * elif field_ == 'qp_iter': * full_stats = self.get_stats('statistics') * if self.nlp_solver_type == 'SQP': # <<<<<<<<<<<<<< * return full_stats[6, :] * elif self.nlp_solver_type == 'SQP_RTI': */ - __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_self->nlp_solver_type, __pyx_n_u_SQP, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 409, __pyx_L1_error) + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_self->nlp_solver_type, __pyx_n_u_SQP, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 441, __pyx_L1_error) if (__pyx_t_6) { - /* "acados_template/acados_ocp_solver_pyx.pyx":410 + /* "acados_template/acados_ocp_solver_pyx.pyx":442 * full_stats = self.get_stats('statistics') * if self.nlp_solver_type == 'SQP': * return full_stats[6, :] # <<<<<<<<<<<<<< @@ -24518,13 +25370,13 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS * return full_stats[2, :] */ __Pyx_XDECREF(__pyx_r); - __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_v_full_stats, __pyx_tuple__18); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 410, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_v_full_stats, __pyx_tuple__20); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 442, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __pyx_r = __pyx_t_2; __pyx_t_2 = 0; goto __pyx_L0; - /* "acados_template/acados_ocp_solver_pyx.pyx":409 + /* "acados_template/acados_ocp_solver_pyx.pyx":441 * elif field_ == 'qp_iter': * full_stats = self.get_stats('statistics') * if self.nlp_solver_type == 'SQP': # <<<<<<<<<<<<<< @@ -24533,17 +25385,17 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":411 + /* "acados_template/acados_ocp_solver_pyx.pyx":443 * if self.nlp_solver_type == 'SQP': * return full_stats[6, :] * elif self.nlp_solver_type == 'SQP_RTI': # <<<<<<<<<<<<<< * return full_stats[2, :] * */ - __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_self->nlp_solver_type, __pyx_n_u_SQP_RTI, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 411, __pyx_L1_error) + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_self->nlp_solver_type, __pyx_n_u_SQP_RTI, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 443, __pyx_L1_error) if (__pyx_t_6) { - /* "acados_template/acados_ocp_solver_pyx.pyx":412 + /* "acados_template/acados_ocp_solver_pyx.pyx":444 * return full_stats[6, :] * elif self.nlp_solver_type == 'SQP_RTI': * return full_stats[2, :] # <<<<<<<<<<<<<< @@ -24551,13 +25403,13 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS * elif field_ == 'alpha': */ __Pyx_XDECREF(__pyx_r); - __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_v_full_stats, __pyx_tuple__19); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 412, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_v_full_stats, __pyx_tuple__21); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 444, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __pyx_r = __pyx_t_2; __pyx_t_2 = 0; goto __pyx_L0; - /* "acados_template/acados_ocp_solver_pyx.pyx":411 + /* "acados_template/acados_ocp_solver_pyx.pyx":443 * if self.nlp_solver_type == 'SQP': * return full_stats[6, :] * elif self.nlp_solver_type == 'SQP_RTI': # <<<<<<<<<<<<<< @@ -24566,7 +25418,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":407 + /* "acados_template/acados_ocp_solver_pyx.pyx":439 * return self.__get_stat_matrix(field, stat_n+1, min_size) * * elif field_ == 'qp_iter': # <<<<<<<<<<<<<< @@ -24576,24 +25428,24 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS goto __pyx_L3; } - /* "acados_template/acados_ocp_solver_pyx.pyx":414 + /* "acados_template/acados_ocp_solver_pyx.pyx":446 * return full_stats[2, :] * * elif field_ == 'alpha': # <<<<<<<<<<<<<< * full_stats = self.get_stats('statistics') * if self.nlp_solver_type == 'SQP': */ - __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_alpha, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 414, __pyx_L1_error) + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_alpha, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 446, __pyx_L1_error) if (__pyx_t_6) { - /* "acados_template/acados_ocp_solver_pyx.pyx":415 + /* "acados_template/acados_ocp_solver_pyx.pyx":447 * * elif field_ == 'alpha': * full_stats = self.get_stats('statistics') # <<<<<<<<<<<<<< * if self.nlp_solver_type == 'SQP': * return full_stats[7, :] */ - __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_stats); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 415, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_stats); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 447, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __pyx_t_1 = NULL; __pyx_t_4 = 0; @@ -24611,24 +25463,24 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_callargs[2] = {__pyx_t_1, __pyx_n_u_statistics}; __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; - if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 415, __pyx_L1_error) + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 447, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; } __pyx_v_full_stats = __pyx_t_2; __pyx_t_2 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":416 + /* "acados_template/acados_ocp_solver_pyx.pyx":448 * elif field_ == 'alpha': * full_stats = self.get_stats('statistics') * if self.nlp_solver_type == 'SQP': # <<<<<<<<<<<<<< * return full_stats[7, :] * else: # self.nlp_solver_type == 'SQP_RTI': */ - __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_self->nlp_solver_type, __pyx_n_u_SQP, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 416, __pyx_L1_error) + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_self->nlp_solver_type, __pyx_n_u_SQP, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 448, __pyx_L1_error) if (likely(__pyx_t_6)) { - /* "acados_template/acados_ocp_solver_pyx.pyx":417 + /* "acados_template/acados_ocp_solver_pyx.pyx":449 * full_stats = self.get_stats('statistics') * if self.nlp_solver_type == 'SQP': * return full_stats[7, :] # <<<<<<<<<<<<<< @@ -24636,13 +25488,13 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS * raise Exception("alpha values are not available for SQP_RTI") */ __Pyx_XDECREF(__pyx_r); - __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_v_full_stats, __pyx_tuple__20); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 417, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_v_full_stats, __pyx_tuple__22); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 449, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __pyx_r = __pyx_t_2; __pyx_t_2 = 0; goto __pyx_L0; - /* "acados_template/acados_ocp_solver_pyx.pyx":416 + /* "acados_template/acados_ocp_solver_pyx.pyx":448 * elif field_ == 'alpha': * full_stats = self.get_stats('statistics') * if self.nlp_solver_type == 'SQP': # <<<<<<<<<<<<<< @@ -24651,7 +25503,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":419 + /* "acados_template/acados_ocp_solver_pyx.pyx":451 * return full_stats[7, :] * else: # self.nlp_solver_type == 'SQP_RTI': * raise Exception("alpha values are not available for SQP_RTI") # <<<<<<<<<<<<<< @@ -24659,14 +25511,14 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS * elif field_ == 'residuals': */ /*else*/ { - __pyx_t_2 = __Pyx_PyObject_Call(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_tuple__21, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 419, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_Call(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_tuple__23, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 451, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_Raise(__pyx_t_2, 0, 0, 0); __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - __PYX_ERR(0, 419, __pyx_L1_error) + __PYX_ERR(0, 451, __pyx_L1_error) } - /* "acados_template/acados_ocp_solver_pyx.pyx":414 + /* "acados_template/acados_ocp_solver_pyx.pyx":446 * return full_stats[2, :] * * elif field_ == 'alpha': # <<<<<<<<<<<<<< @@ -24675,17 +25527,17 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":421 + /* "acados_template/acados_ocp_solver_pyx.pyx":453 * raise Exception("alpha values are not available for SQP_RTI") * * elif field_ == 'residuals': # <<<<<<<<<<<<<< * return self.get_residuals() * */ - __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_residuals, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 421, __pyx_L1_error) + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_residuals, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 453, __pyx_L1_error) if (likely(__pyx_t_6)) { - /* "acados_template/acados_ocp_solver_pyx.pyx":422 + /* "acados_template/acados_ocp_solver_pyx.pyx":454 * * elif field_ == 'residuals': * return self.get_residuals() # <<<<<<<<<<<<<< @@ -24693,7 +25545,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS * else: */ __Pyx_XDECREF(__pyx_r); - __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_residuals); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 422, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_residuals); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 454, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __pyx_t_1 = NULL; __pyx_t_4 = 0; @@ -24711,7 +25563,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_callargs[1] = {__pyx_t_1, }; __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_4, 0+__pyx_t_4); __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; - if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 422, __pyx_L1_error) + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 454, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; } @@ -24719,7 +25571,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_t_2 = 0; goto __pyx_L0; - /* "acados_template/acados_ocp_solver_pyx.pyx":421 + /* "acados_template/acados_ocp_solver_pyx.pyx":453 * raise Exception("alpha values are not available for SQP_RTI") * * elif field_ == 'residuals': # <<<<<<<<<<<<<< @@ -24728,7 +25580,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":425 + /* "acados_template/acados_ocp_solver_pyx.pyx":457 * * else: * raise NotImplementedError("TODO!") # <<<<<<<<<<<<<< @@ -24736,15 +25588,15 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS * */ /*else*/ { - __pyx_t_2 = __Pyx_PyObject_Call(__pyx_builtin_NotImplementedError, __pyx_tuple__22, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 425, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_Call(__pyx_builtin_NotImplementedError, __pyx_tuple__24, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 457, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_Raise(__pyx_t_2, 0, 0, 0); __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - __PYX_ERR(0, 425, __pyx_L1_error) + __PYX_ERR(0, 457, __pyx_L1_error) } __pyx_L3:; - /* "acados_template/acados_ocp_solver_pyx.pyx":346 + /* "acados_template/acados_ocp_solver_pyx.pyx":378 * * * def get_stats(self, field_): # <<<<<<<<<<<<<< @@ -24776,7 +25628,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":428 +/* "acados_template/acados_ocp_solver_pyx.pyx":460 * * * def __get_stat_int(self, field): # <<<<<<<<<<<<<< @@ -24785,15 +25637,15 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ /* Python wrapper */ -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25_AcadosOcpSolverCython__get_stat_int(PyObject *__pyx_v_self, +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_int(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else PyObject *__pyx_args, PyObject *__pyx_kwds #endif ); /*proto*/ -static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25_AcadosOcpSolverCython__get_stat_int = {"_AcadosOcpSolverCython__get_stat_int", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25_AcadosOcpSolverCython__get_stat_int, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25_AcadosOcpSolverCython__get_stat_int(PyObject *__pyx_v_self, +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_int = {"_AcadosOcpSolverCython__get_stat_int", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_int, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_int(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else @@ -24826,12 +25678,12 @@ PyObject *__pyx_args, PyObject *__pyx_kwds switch (__pyx_nargs) { case 0: if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 428, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 460, __pyx_L3_error) else goto __pyx_L5_argtuple_error; } if (unlikely(kw_args > 0)) { const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "_AcadosOcpSolverCython__get_stat_int") < 0)) __PYX_ERR(0, 428, __pyx_L3_error) + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "_AcadosOcpSolverCython__get_stat_int") < 0)) __PYX_ERR(0, 460, __pyx_L3_error) } } else if (unlikely(__pyx_nargs != 1)) { goto __pyx_L5_argtuple_error; @@ -24842,20 +25694,20 @@ PyObject *__pyx_args, PyObject *__pyx_kwds } goto __pyx_L4_argument_unpacking_done; __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("_AcadosOcpSolverCython__get_stat_int", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 428, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("_AcadosOcpSolverCython__get_stat_int", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 460, __pyx_L3_error) __pyx_L3_error:; __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython._AcadosOcpSolverCython__get_stat_int", __pyx_clineno, __pyx_lineno, __pyx_filename); __Pyx_RefNannyFinishContext(); return NULL; __pyx_L4_argument_unpacking_done:; - __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_24__get_stat_int(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_field); + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_28__get_stat_int(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_field); /* function exit code */ __Pyx_RefNannyFinishContext(); return __pyx_r; } -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_24__get_stat_int(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field) { +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_28__get_stat_int(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field) { int __pyx_v_out; PyObject *__pyx_r = NULL; __Pyx_RefNannyDeclarations @@ -24866,17 +25718,17 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS int __pyx_clineno = 0; __Pyx_RefNannySetupContext("_AcadosOcpSolverCython__get_stat_int", 0); - /* "acados_template/acados_ocp_solver_pyx.pyx":430 + /* "acados_template/acados_ocp_solver_pyx.pyx":462 * def __get_stat_int(self, field): * cdef int out * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &out) # <<<<<<<<<<<<<< * return out * */ - __pyx_t_1 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_1) && PyErr_Occurred())) __PYX_ERR(0, 430, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_1) && PyErr_Occurred())) __PYX_ERR(0, 462, __pyx_L1_error) ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_t_1, ((void *)(&__pyx_v_out))); - /* "acados_template/acados_ocp_solver_pyx.pyx":431 + /* "acados_template/acados_ocp_solver_pyx.pyx":463 * cdef int out * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &out) * return out # <<<<<<<<<<<<<< @@ -24884,13 +25736,13 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS * def __get_stat_double(self, field): */ __Pyx_XDECREF(__pyx_r); - __pyx_t_2 = __Pyx_PyInt_From_int(__pyx_v_out); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 431, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyInt_From_int(__pyx_v_out); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 463, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __pyx_r = __pyx_t_2; __pyx_t_2 = 0; goto __pyx_L0; - /* "acados_template/acados_ocp_solver_pyx.pyx":428 + /* "acados_template/acados_ocp_solver_pyx.pyx":460 * * * def __get_stat_int(self, field): # <<<<<<<<<<<<<< @@ -24909,7 +25761,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":433 +/* "acados_template/acados_ocp_solver_pyx.pyx":465 * return out * * def __get_stat_double(self, field): # <<<<<<<<<<<<<< @@ -24918,15 +25770,15 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ /* Python wrapper */ -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27_AcadosOcpSolverCython__get_stat_double(PyObject *__pyx_v_self, +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31_AcadosOcpSolverCython__get_stat_double(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else PyObject *__pyx_args, PyObject *__pyx_kwds #endif ); /*proto*/ -static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27_AcadosOcpSolverCython__get_stat_double = {"_AcadosOcpSolverCython__get_stat_double", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27_AcadosOcpSolverCython__get_stat_double, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27_AcadosOcpSolverCython__get_stat_double(PyObject *__pyx_v_self, +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31_AcadosOcpSolverCython__get_stat_double = {"_AcadosOcpSolverCython__get_stat_double", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31_AcadosOcpSolverCython__get_stat_double, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31_AcadosOcpSolverCython__get_stat_double(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else @@ -24959,12 +25811,12 @@ PyObject *__pyx_args, PyObject *__pyx_kwds switch (__pyx_nargs) { case 0: if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 433, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 465, __pyx_L3_error) else goto __pyx_L5_argtuple_error; } if (unlikely(kw_args > 0)) { const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "_AcadosOcpSolverCython__get_stat_double") < 0)) __PYX_ERR(0, 433, __pyx_L3_error) + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "_AcadosOcpSolverCython__get_stat_double") < 0)) __PYX_ERR(0, 465, __pyx_L3_error) } } else if (unlikely(__pyx_nargs != 1)) { goto __pyx_L5_argtuple_error; @@ -24975,20 +25827,20 @@ PyObject *__pyx_args, PyObject *__pyx_kwds } goto __pyx_L4_argument_unpacking_done; __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("_AcadosOcpSolverCython__get_stat_double", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 433, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("_AcadosOcpSolverCython__get_stat_double", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 465, __pyx_L3_error) __pyx_L3_error:; __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython._AcadosOcpSolverCython__get_stat_double", __pyx_clineno, __pyx_lineno, __pyx_filename); __Pyx_RefNannyFinishContext(); return NULL; __pyx_L4_argument_unpacking_done:; - __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_26__get_stat_double(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_field); + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_30__get_stat_double(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_field); /* function exit code */ __Pyx_RefNannyFinishContext(); return __pyx_r; } -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_26__get_stat_double(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field) { +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_30__get_stat_double(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field) { PyArrayObject *__pyx_v_out = 0; __Pyx_LocalBuf_ND __pyx_pybuffernd_out; __Pyx_Buffer __pyx_pybuffer_out; @@ -25010,16 +25862,16 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_pybuffernd_out.data = NULL; __pyx_pybuffernd_out.rcbuffer = &__pyx_pybuffer_out; - /* "acados_template/acados_ocp_solver_pyx.pyx":434 + /* "acados_template/acados_ocp_solver_pyx.pyx":466 * * def __get_stat_double(self, field): * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) # <<<<<<<<<<<<<< * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) * return out */ - __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_np); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 434, __pyx_L1_error) + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_np); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 466, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); - __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_zeros); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 434, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_zeros); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 466, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; __pyx_t_2 = NULL; @@ -25035,20 +25887,20 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS } } { - PyObject *__pyx_callargs[2] = {__pyx_t_2, __pyx_tuple__23}; + PyObject *__pyx_callargs[2] = {__pyx_t_2, __pyx_tuple__25}; __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; - if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 434, __pyx_L1_error) + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 466, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; } - if (!(likely(((__pyx_t_1) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_1, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 434, __pyx_L1_error) + if (!(likely(((__pyx_t_1) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_1, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 466, __pyx_L1_error) __pyx_t_5 = ((PyArrayObject *)__pyx_t_1); { __Pyx_BufFmt_StackElem __pyx_stack[1]; if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_out.rcbuffer->pybuffer, (PyObject*)__pyx_t_5, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 1, 0, __pyx_stack) == -1)) { __pyx_v_out = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_out.rcbuffer->pybuffer.buf = NULL; - __PYX_ERR(0, 434, __pyx_L1_error) + __PYX_ERR(0, 466, __pyx_L1_error) } else {__pyx_pybuffernd_out.diminfo[0].strides = __pyx_pybuffernd_out.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_out.diminfo[0].shape = __pyx_pybuffernd_out.rcbuffer->pybuffer.shape[0]; } } @@ -25056,18 +25908,18 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_v_out = ((PyArrayObject *)__pyx_t_1); __pyx_t_1 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":435 + /* "acados_template/acados_ocp_solver_pyx.pyx":467 * def __get_stat_double(self, field): * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) # <<<<<<<<<<<<<< * return out * */ - __pyx_t_6 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_6) && PyErr_Occurred())) __PYX_ERR(0, 435, __pyx_L1_error) - __pyx_t_7 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_out)); if (unlikely(__pyx_t_7 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 435, __pyx_L1_error) + __pyx_t_6 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_6) && PyErr_Occurred())) __PYX_ERR(0, 467, __pyx_L1_error) + __pyx_t_7 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_out)); if (unlikely(__pyx_t_7 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 467, __pyx_L1_error) ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_t_6, ((void *)__pyx_t_7)); - /* "acados_template/acados_ocp_solver_pyx.pyx":436 + /* "acados_template/acados_ocp_solver_pyx.pyx":468 * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) * return out # <<<<<<<<<<<<<< @@ -25079,7 +25931,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_r = ((PyObject *)__pyx_v_out); goto __pyx_L0; - /* "acados_template/acados_ocp_solver_pyx.pyx":433 + /* "acados_template/acados_ocp_solver_pyx.pyx":465 * return out * * def __get_stat_double(self, field): # <<<<<<<<<<<<<< @@ -25110,7 +25962,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":438 +/* "acados_template/acados_ocp_solver_pyx.pyx":470 * return out * * def __get_stat_matrix(self, field, n, m): # <<<<<<<<<<<<<< @@ -25119,15 +25971,15 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ /* Python wrapper */ -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_matrix(PyObject *__pyx_v_self, +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33_AcadosOcpSolverCython__get_stat_matrix(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else PyObject *__pyx_args, PyObject *__pyx_kwds #endif ); /*proto*/ -static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_matrix = {"_AcadosOcpSolverCython__get_stat_matrix", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_matrix, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_matrix(PyObject *__pyx_v_self, +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33_AcadosOcpSolverCython__get_stat_matrix = {"_AcadosOcpSolverCython__get_stat_matrix", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33_AcadosOcpSolverCython__get_stat_matrix, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33_AcadosOcpSolverCython__get_stat_matrix(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else @@ -25166,26 +26018,26 @@ PyObject *__pyx_args, PyObject *__pyx_kwds switch (__pyx_nargs) { case 0: if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 438, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 470, __pyx_L3_error) else goto __pyx_L5_argtuple_error; CYTHON_FALLTHROUGH; case 1: if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_n)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 438, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 470, __pyx_L3_error) else { - __Pyx_RaiseArgtupleInvalid("_AcadosOcpSolverCython__get_stat_matrix", 1, 3, 3, 1); __PYX_ERR(0, 438, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("_AcadosOcpSolverCython__get_stat_matrix", 1, 3, 3, 1); __PYX_ERR(0, 470, __pyx_L3_error) } CYTHON_FALLTHROUGH; case 2: if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_m)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 438, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 470, __pyx_L3_error) else { - __Pyx_RaiseArgtupleInvalid("_AcadosOcpSolverCython__get_stat_matrix", 1, 3, 3, 2); __PYX_ERR(0, 438, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("_AcadosOcpSolverCython__get_stat_matrix", 1, 3, 3, 2); __PYX_ERR(0, 470, __pyx_L3_error) } } if (unlikely(kw_args > 0)) { const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "_AcadosOcpSolverCython__get_stat_matrix") < 0)) __PYX_ERR(0, 438, __pyx_L3_error) + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "_AcadosOcpSolverCython__get_stat_matrix") < 0)) __PYX_ERR(0, 470, __pyx_L3_error) } } else if (unlikely(__pyx_nargs != 3)) { goto __pyx_L5_argtuple_error; @@ -25200,20 +26052,20 @@ PyObject *__pyx_args, PyObject *__pyx_kwds } goto __pyx_L4_argument_unpacking_done; __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("_AcadosOcpSolverCython__get_stat_matrix", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 438, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("_AcadosOcpSolverCython__get_stat_matrix", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 470, __pyx_L3_error) __pyx_L3_error:; __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython._AcadosOcpSolverCython__get_stat_matrix", __pyx_clineno, __pyx_lineno, __pyx_filename); __Pyx_RefNannyFinishContext(); return NULL; __pyx_L4_argument_unpacking_done:; - __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_28__get_stat_matrix(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_field, __pyx_v_n, __pyx_v_m); + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_32__get_stat_matrix(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_field, __pyx_v_n, __pyx_v_m); /* function exit code */ __Pyx_RefNannyFinishContext(); return __pyx_r; } -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_28__get_stat_matrix(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field, PyObject *__pyx_v_n, PyObject *__pyx_v_m) { +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_32__get_stat_matrix(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field, PyObject *__pyx_v_n, PyObject *__pyx_v_m) { PyArrayObject *__pyx_v_out_mat = 0; __Pyx_LocalBuf_ND __pyx_pybuffernd_out_mat; __Pyx_Buffer __pyx_pybuffer_out_mat; @@ -25237,24 +26089,24 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_pybuffernd_out_mat.data = NULL; __pyx_pybuffernd_out_mat.rcbuffer = &__pyx_pybuffer_out_mat; - /* "acados_template/acados_ocp_solver_pyx.pyx":439 + /* "acados_template/acados_ocp_solver_pyx.pyx":471 * * def __get_stat_matrix(self, field, n, m): * cdef cnp.ndarray[cnp.float64_t, ndim=2] out_mat = np.ascontiguousarray(np.zeros((n, m)), dtype=np.float64) # <<<<<<<<<<<<<< * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_mat.data) * return out_mat */ - __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 439, __pyx_L1_error) + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 471, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); - __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 439, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 471, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_np); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 439, __pyx_L1_error) + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_np); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 471, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); - __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_zeros); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 439, __pyx_L1_error) + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_zeros); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 471, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 439, __pyx_L1_error) + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 471, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_INCREF(__pyx_v_n); __Pyx_GIVEREF(__pyx_v_n); @@ -25279,36 +26131,36 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_6, 1+__pyx_t_6); __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 439, __pyx_L1_error) + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 471, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; } - __pyx_t_4 = PyTuple_New(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 439, __pyx_L1_error) + __pyx_t_4 = PyTuple_New(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 471, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); __Pyx_GIVEREF(__pyx_t_1); PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_1); __pyx_t_1 = 0; - __pyx_t_1 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 439, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 471, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); - __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_np); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 439, __pyx_L1_error) + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_np); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 471, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); - __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_float64); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 439, __pyx_L1_error) + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_float64); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 471, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_5); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - if (PyDict_SetItem(__pyx_t_1, __pyx_n_s_dtype, __pyx_t_5) < 0) __PYX_ERR(0, 439, __pyx_L1_error) + if (PyDict_SetItem(__pyx_t_1, __pyx_n_s_dtype, __pyx_t_5) < 0) __PYX_ERR(0, 471, __pyx_L1_error) __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __pyx_t_5 = __Pyx_PyObject_Call(__pyx_t_2, __pyx_t_4, __pyx_t_1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 439, __pyx_L1_error) + __pyx_t_5 = __Pyx_PyObject_Call(__pyx_t_2, __pyx_t_4, __pyx_t_1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 471, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_5); __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - if (!(likely(((__pyx_t_5) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_5, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 439, __pyx_L1_error) + if (!(likely(((__pyx_t_5) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_5, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 471, __pyx_L1_error) __pyx_t_7 = ((PyArrayObject *)__pyx_t_5); { __Pyx_BufFmt_StackElem __pyx_stack[1]; if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_out_mat.rcbuffer->pybuffer, (PyObject*)__pyx_t_7, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 2, 0, __pyx_stack) == -1)) { __pyx_v_out_mat = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_out_mat.rcbuffer->pybuffer.buf = NULL; - __PYX_ERR(0, 439, __pyx_L1_error) + __PYX_ERR(0, 471, __pyx_L1_error) } else {__pyx_pybuffernd_out_mat.diminfo[0].strides = __pyx_pybuffernd_out_mat.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_out_mat.diminfo[0].shape = __pyx_pybuffernd_out_mat.rcbuffer->pybuffer.shape[0]; __pyx_pybuffernd_out_mat.diminfo[1].strides = __pyx_pybuffernd_out_mat.rcbuffer->pybuffer.strides[1]; __pyx_pybuffernd_out_mat.diminfo[1].shape = __pyx_pybuffernd_out_mat.rcbuffer->pybuffer.shape[1]; } } @@ -25316,18 +26168,18 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_v_out_mat = ((PyArrayObject *)__pyx_t_5); __pyx_t_5 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":440 + /* "acados_template/acados_ocp_solver_pyx.pyx":472 * def __get_stat_matrix(self, field, n, m): * cdef cnp.ndarray[cnp.float64_t, ndim=2] out_mat = np.ascontiguousarray(np.zeros((n, m)), dtype=np.float64) * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_mat.data) # <<<<<<<<<<<<<< * return out_mat * */ - __pyx_t_8 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_8) && PyErr_Occurred())) __PYX_ERR(0, 440, __pyx_L1_error) - __pyx_t_9 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_out_mat)); if (unlikely(__pyx_t_9 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 440, __pyx_L1_error) + __pyx_t_8 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_8) && PyErr_Occurred())) __PYX_ERR(0, 472, __pyx_L1_error) + __pyx_t_9 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_out_mat)); if (unlikely(__pyx_t_9 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 472, __pyx_L1_error) ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_t_8, ((void *)__pyx_t_9)); - /* "acados_template/acados_ocp_solver_pyx.pyx":441 + /* "acados_template/acados_ocp_solver_pyx.pyx":473 * cdef cnp.ndarray[cnp.float64_t, ndim=2] out_mat = np.ascontiguousarray(np.zeros((n, m)), dtype=np.float64) * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_mat.data) * return out_mat # <<<<<<<<<<<<<< @@ -25339,7 +26191,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_r = ((PyObject *)__pyx_v_out_mat); goto __pyx_L0; - /* "acados_template/acados_ocp_solver_pyx.pyx":438 + /* "acados_template/acados_ocp_solver_pyx.pyx":470 * return out * * def __get_stat_matrix(self, field, n, m): # <<<<<<<<<<<<<< @@ -25372,7 +26224,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":444 +/* "acados_template/acados_ocp_solver_pyx.pyx":476 * * * def get_cost(self): # <<<<<<<<<<<<<< @@ -25381,16 +26233,16 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ /* Python wrapper */ -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31get_cost(PyObject *__pyx_v_self, +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35get_cost(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else PyObject *__pyx_args, PyObject *__pyx_kwds #endif ); /*proto*/ -PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_30get_cost, "\n Returns the cost value of the current solution.\n "); -static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31get_cost = {"get_cost", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31get_cost, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_30get_cost}; -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31get_cost(PyObject *__pyx_v_self, +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34get_cost, "\n Returns the cost value of the current solution.\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35get_cost = {"get_cost", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35get_cost, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34get_cost}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35get_cost(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else @@ -25407,14 +26259,14 @@ PyObject *__pyx_args, PyObject *__pyx_kwds if (unlikely(__pyx_nargs > 0)) { __Pyx_RaiseArgtupleInvalid("get_cost", 1, 0, 0, __pyx_nargs); return NULL;} if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "get_cost", 0))) return NULL; - __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_30get_cost(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34get_cost(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); /* function exit code */ __Pyx_RefNannyFinishContext(); return __pyx_r; } -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_30get_cost(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34get_cost(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { double __pyx_v_out; PyObject *__pyx_r = NULL; __Pyx_RefNannyDeclarations @@ -25424,7 +26276,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS int __pyx_clineno = 0; __Pyx_RefNannySetupContext("get_cost", 0); - /* "acados_template/acados_ocp_solver_pyx.pyx":449 + /* "acados_template/acados_ocp_solver_pyx.pyx":481 * """ * # compute cost internally * acados_solver_common.ocp_nlp_eval_cost(self.nlp_solver, self.nlp_in, self.nlp_out) # <<<<<<<<<<<<<< @@ -25433,7 +26285,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ ocp_nlp_eval_cost(__pyx_v_self->nlp_solver, __pyx_v_self->nlp_in, __pyx_v_self->nlp_out); - /* "acados_template/acados_ocp_solver_pyx.pyx":455 + /* "acados_template/acados_ocp_solver_pyx.pyx":487 * * # call getter * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, "cost_value", &out) # <<<<<<<<<<<<<< @@ -25442,7 +26294,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, ((char const *)"cost_value"), ((void *)(&__pyx_v_out))); - /* "acados_template/acados_ocp_solver_pyx.pyx":457 + /* "acados_template/acados_ocp_solver_pyx.pyx":489 * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, "cost_value", &out) * * return out # <<<<<<<<<<<<<< @@ -25450,13 +26302,13 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS * */ __Pyx_XDECREF(__pyx_r); - __pyx_t_1 = PyFloat_FromDouble(__pyx_v_out); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 457, __pyx_L1_error) + __pyx_t_1 = PyFloat_FromDouble(__pyx_v_out); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 489, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __pyx_r = __pyx_t_1; __pyx_t_1 = 0; goto __pyx_L0; - /* "acados_template/acados_ocp_solver_pyx.pyx":444 + /* "acados_template/acados_ocp_solver_pyx.pyx":476 * * * def get_cost(self): # <<<<<<<<<<<<<< @@ -25475,7 +26327,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":460 +/* "acados_template/acados_ocp_solver_pyx.pyx":492 * * * def get_residuals(self, recompute=False): # <<<<<<<<<<<<<< @@ -25484,16 +26336,16 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ /* Python wrapper */ -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33get_residuals(PyObject *__pyx_v_self, +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37get_residuals(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else PyObject *__pyx_args, PyObject *__pyx_kwds #endif ); /*proto*/ -PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_32get_residuals, "\n Returns an array of the form [res_stat, res_eq, res_ineq, res_comp].\n "); -static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33get_residuals = {"get_residuals", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33get_residuals, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_32get_residuals}; -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33get_residuals(PyObject *__pyx_v_self, +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36get_residuals, "\n Returns an array of the form [res_stat, res_eq, res_ineq, res_comp].\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37get_residuals = {"get_residuals", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37get_residuals, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36get_residuals}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37get_residuals(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else @@ -25529,12 +26381,12 @@ PyObject *__pyx_args, PyObject *__pyx_kwds if (kw_args > 0) { PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_recompute); if (value) { values[0] = value; kw_args--; } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 460, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 492, __pyx_L3_error) } } if (unlikely(kw_args > 0)) { const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "get_residuals") < 0)) __PYX_ERR(0, 460, __pyx_L3_error) + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "get_residuals") < 0)) __PYX_ERR(0, 492, __pyx_L3_error) } } else { switch (__pyx_nargs) { @@ -25548,20 +26400,20 @@ PyObject *__pyx_args, PyObject *__pyx_kwds } goto __pyx_L4_argument_unpacking_done; __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("get_residuals", 0, 0, 1, __pyx_nargs); __PYX_ERR(0, 460, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("get_residuals", 0, 0, 1, __pyx_nargs); __PYX_ERR(0, 492, __pyx_L3_error) __pyx_L3_error:; __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.get_residuals", __pyx_clineno, __pyx_lineno, __pyx_filename); __Pyx_RefNannyFinishContext(); return NULL; __pyx_L4_argument_unpacking_done:; - __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_32get_residuals(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_recompute); + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36get_residuals(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_recompute); /* function exit code */ __Pyx_RefNannyFinishContext(); return __pyx_r; } -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_32get_residuals(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_recompute) { +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36get_residuals(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_recompute) { PyArrayObject *__pyx_v_out = 0; double __pyx_v_double_value; PyObject *__pyx_v_field = NULL; @@ -25590,25 +26442,25 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_pybuffernd_out.data = NULL; __pyx_pybuffernd_out.rcbuffer = &__pyx_pybuffer_out; - /* "acados_template/acados_ocp_solver_pyx.pyx":465 + /* "acados_template/acados_ocp_solver_pyx.pyx":497 * """ * # compute residuals if RTI * if self.nlp_solver_type == 'SQP_RTI' or recompute: # <<<<<<<<<<<<<< * acados_solver_common.ocp_nlp_eval_residuals(self.nlp_solver, self.nlp_in, self.nlp_out) * */ - __pyx_t_2 = (__Pyx_PyUnicode_Equals(__pyx_v_self->nlp_solver_type, __pyx_n_u_SQP_RTI, Py_EQ)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 465, __pyx_L1_error) + __pyx_t_2 = (__Pyx_PyUnicode_Equals(__pyx_v_self->nlp_solver_type, __pyx_n_u_SQP_RTI, Py_EQ)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 497, __pyx_L1_error) if (!__pyx_t_2) { } else { __pyx_t_1 = __pyx_t_2; goto __pyx_L4_bool_binop_done; } - __pyx_t_2 = __Pyx_PyObject_IsTrue(__pyx_v_recompute); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 465, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_IsTrue(__pyx_v_recompute); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 497, __pyx_L1_error) __pyx_t_1 = __pyx_t_2; __pyx_L4_bool_binop_done:; if (__pyx_t_1) { - /* "acados_template/acados_ocp_solver_pyx.pyx":466 + /* "acados_template/acados_ocp_solver_pyx.pyx":498 * # compute residuals if RTI * if self.nlp_solver_type == 'SQP_RTI' or recompute: * acados_solver_common.ocp_nlp_eval_residuals(self.nlp_solver, self.nlp_in, self.nlp_out) # <<<<<<<<<<<<<< @@ -25617,7 +26469,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ ocp_nlp_eval_residuals(__pyx_v_self->nlp_solver, __pyx_v_self->nlp_in, __pyx_v_self->nlp_out); - /* "acados_template/acados_ocp_solver_pyx.pyx":465 + /* "acados_template/acados_ocp_solver_pyx.pyx":497 * """ * # compute residuals if RTI * if self.nlp_solver_type == 'SQP_RTI' or recompute: # <<<<<<<<<<<<<< @@ -25626,33 +26478,33 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":469 + /* "acados_template/acados_ocp_solver_pyx.pyx":501 * * # create output array * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.ascontiguousarray(np.zeros((4,), dtype=np.float64)) # <<<<<<<<<<<<<< * cdef double double_value * */ - __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_np); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 469, __pyx_L1_error) + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_np); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 501, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); - __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 469, __pyx_L1_error) + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 501, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_5); __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_np); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 469, __pyx_L1_error) + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_np); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 501, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); - __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_zeros); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 469, __pyx_L1_error) + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_zeros); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 501, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_6); __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __pyx_t_4 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 469, __pyx_L1_error) + __pyx_t_4 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 501, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); - __Pyx_GetModuleGlobalName(__pyx_t_7, __pyx_n_s_np); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 469, __pyx_L1_error) + __Pyx_GetModuleGlobalName(__pyx_t_7, __pyx_n_s_np); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 501, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); - __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_t_7, __pyx_n_s_float64); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 469, __pyx_L1_error) + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_t_7, __pyx_n_s_float64); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 501, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_8); __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - if (PyDict_SetItem(__pyx_t_4, __pyx_n_s_dtype, __pyx_t_8) < 0) __PYX_ERR(0, 469, __pyx_L1_error) + if (PyDict_SetItem(__pyx_t_4, __pyx_n_s_dtype, __pyx_t_8) < 0) __PYX_ERR(0, 501, __pyx_L1_error) __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; - __pyx_t_8 = __Pyx_PyObject_Call(__pyx_t_6, __pyx_tuple__25, __pyx_t_4); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 469, __pyx_L1_error) + __pyx_t_8 = __Pyx_PyObject_Call(__pyx_t_6, __pyx_tuple__27, __pyx_t_4); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 501, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_8); __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; @@ -25673,17 +26525,17 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_9, 1+__pyx_t_9); __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; - if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 469, __pyx_L1_error) + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 501, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; } - if (!(likely(((__pyx_t_3) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_3, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 469, __pyx_L1_error) + if (!(likely(((__pyx_t_3) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_3, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 501, __pyx_L1_error) __pyx_t_10 = ((PyArrayObject *)__pyx_t_3); { __Pyx_BufFmt_StackElem __pyx_stack[1]; if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_out.rcbuffer->pybuffer, (PyObject*)__pyx_t_10, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES| PyBUF_WRITABLE, 1, 0, __pyx_stack) == -1)) { __pyx_v_out = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_out.rcbuffer->pybuffer.buf = NULL; - __PYX_ERR(0, 469, __pyx_L1_error) + __PYX_ERR(0, 501, __pyx_L1_error) } else {__pyx_pybuffernd_out.diminfo[0].strides = __pyx_pybuffernd_out.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_out.diminfo[0].shape = __pyx_pybuffernd_out.rcbuffer->pybuffer.shape[0]; } } @@ -25691,7 +26543,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_v_out = ((PyArrayObject *)__pyx_t_3); __pyx_t_3 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":472 + /* "acados_template/acados_ocp_solver_pyx.pyx":504 * cdef double double_value * * field = "res_stat".encode('utf-8') # <<<<<<<<<<<<<< @@ -25701,17 +26553,17 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __Pyx_INCREF(__pyx_n_b_res_stat); __pyx_v_field = __pyx_n_b_res_stat; - /* "acados_template/acados_ocp_solver_pyx.pyx":473 + /* "acados_template/acados_ocp_solver_pyx.pyx":505 * * field = "res_stat".encode('utf-8') * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) # <<<<<<<<<<<<<< * out[0] = double_value * */ - __pyx_t_11 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_11) && PyErr_Occurred())) __PYX_ERR(0, 473, __pyx_L1_error) + __pyx_t_11 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_11) && PyErr_Occurred())) __PYX_ERR(0, 505, __pyx_L1_error) ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_t_11, ((void *)(&__pyx_v_double_value))); - /* "acados_template/acados_ocp_solver_pyx.pyx":474 + /* "acados_template/acados_ocp_solver_pyx.pyx":506 * field = "res_stat".encode('utf-8') * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) * out[0] = double_value # <<<<<<<<<<<<<< @@ -25726,11 +26578,11 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS } else if (unlikely(__pyx_t_12 >= __pyx_pybuffernd_out.diminfo[0].shape)) __pyx_t_9 = 0; if (unlikely(__pyx_t_9 != -1)) { __Pyx_RaiseBufferIndexError(__pyx_t_9); - __PYX_ERR(0, 474, __pyx_L1_error) + __PYX_ERR(0, 506, __pyx_L1_error) } *__Pyx_BufPtrStrided1d(__pyx_t_5numpy_float64_t *, __pyx_pybuffernd_out.rcbuffer->pybuffer.buf, __pyx_t_12, __pyx_pybuffernd_out.diminfo[0].strides) = __pyx_v_double_value; - /* "acados_template/acados_ocp_solver_pyx.pyx":476 + /* "acados_template/acados_ocp_solver_pyx.pyx":508 * out[0] = double_value * * field = "res_eq".encode('utf-8') # <<<<<<<<<<<<<< @@ -25740,17 +26592,17 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __Pyx_INCREF(__pyx_n_b_res_eq); __Pyx_DECREF_SET(__pyx_v_field, __pyx_n_b_res_eq); - /* "acados_template/acados_ocp_solver_pyx.pyx":477 + /* "acados_template/acados_ocp_solver_pyx.pyx":509 * * field = "res_eq".encode('utf-8') * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) # <<<<<<<<<<<<<< * out[1] = double_value * */ - __pyx_t_11 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_11) && PyErr_Occurred())) __PYX_ERR(0, 477, __pyx_L1_error) + __pyx_t_11 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_11) && PyErr_Occurred())) __PYX_ERR(0, 509, __pyx_L1_error) ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_t_11, ((void *)(&__pyx_v_double_value))); - /* "acados_template/acados_ocp_solver_pyx.pyx":478 + /* "acados_template/acados_ocp_solver_pyx.pyx":510 * field = "res_eq".encode('utf-8') * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) * out[1] = double_value # <<<<<<<<<<<<<< @@ -25765,11 +26617,11 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS } else if (unlikely(__pyx_t_12 >= __pyx_pybuffernd_out.diminfo[0].shape)) __pyx_t_9 = 0; if (unlikely(__pyx_t_9 != -1)) { __Pyx_RaiseBufferIndexError(__pyx_t_9); - __PYX_ERR(0, 478, __pyx_L1_error) + __PYX_ERR(0, 510, __pyx_L1_error) } *__Pyx_BufPtrStrided1d(__pyx_t_5numpy_float64_t *, __pyx_pybuffernd_out.rcbuffer->pybuffer.buf, __pyx_t_12, __pyx_pybuffernd_out.diminfo[0].strides) = __pyx_v_double_value; - /* "acados_template/acados_ocp_solver_pyx.pyx":480 + /* "acados_template/acados_ocp_solver_pyx.pyx":512 * out[1] = double_value * * field = "res_ineq".encode('utf-8') # <<<<<<<<<<<<<< @@ -25779,17 +26631,17 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __Pyx_INCREF(__pyx_n_b_res_ineq); __Pyx_DECREF_SET(__pyx_v_field, __pyx_n_b_res_ineq); - /* "acados_template/acados_ocp_solver_pyx.pyx":481 + /* "acados_template/acados_ocp_solver_pyx.pyx":513 * * field = "res_ineq".encode('utf-8') * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) # <<<<<<<<<<<<<< * out[2] = double_value * */ - __pyx_t_11 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_11) && PyErr_Occurred())) __PYX_ERR(0, 481, __pyx_L1_error) + __pyx_t_11 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_11) && PyErr_Occurred())) __PYX_ERR(0, 513, __pyx_L1_error) ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_t_11, ((void *)(&__pyx_v_double_value))); - /* "acados_template/acados_ocp_solver_pyx.pyx":482 + /* "acados_template/acados_ocp_solver_pyx.pyx":514 * field = "res_ineq".encode('utf-8') * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) * out[2] = double_value # <<<<<<<<<<<<<< @@ -25804,11 +26656,11 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS } else if (unlikely(__pyx_t_12 >= __pyx_pybuffernd_out.diminfo[0].shape)) __pyx_t_9 = 0; if (unlikely(__pyx_t_9 != -1)) { __Pyx_RaiseBufferIndexError(__pyx_t_9); - __PYX_ERR(0, 482, __pyx_L1_error) + __PYX_ERR(0, 514, __pyx_L1_error) } *__Pyx_BufPtrStrided1d(__pyx_t_5numpy_float64_t *, __pyx_pybuffernd_out.rcbuffer->pybuffer.buf, __pyx_t_12, __pyx_pybuffernd_out.diminfo[0].strides) = __pyx_v_double_value; - /* "acados_template/acados_ocp_solver_pyx.pyx":484 + /* "acados_template/acados_ocp_solver_pyx.pyx":516 * out[2] = double_value * * field = "res_comp".encode('utf-8') # <<<<<<<<<<<<<< @@ -25818,17 +26670,17 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __Pyx_INCREF(__pyx_n_b_res_comp); __Pyx_DECREF_SET(__pyx_v_field, __pyx_n_b_res_comp); - /* "acados_template/acados_ocp_solver_pyx.pyx":485 + /* "acados_template/acados_ocp_solver_pyx.pyx":517 * * field = "res_comp".encode('utf-8') * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) # <<<<<<<<<<<<<< * out[3] = double_value * */ - __pyx_t_11 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_11) && PyErr_Occurred())) __PYX_ERR(0, 485, __pyx_L1_error) + __pyx_t_11 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_11) && PyErr_Occurred())) __PYX_ERR(0, 517, __pyx_L1_error) ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_t_11, ((void *)(&__pyx_v_double_value))); - /* "acados_template/acados_ocp_solver_pyx.pyx":486 + /* "acados_template/acados_ocp_solver_pyx.pyx":518 * field = "res_comp".encode('utf-8') * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) * out[3] = double_value # <<<<<<<<<<<<<< @@ -25843,11 +26695,11 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS } else if (unlikely(__pyx_t_12 >= __pyx_pybuffernd_out.diminfo[0].shape)) __pyx_t_9 = 0; if (unlikely(__pyx_t_9 != -1)) { __Pyx_RaiseBufferIndexError(__pyx_t_9); - __PYX_ERR(0, 486, __pyx_L1_error) + __PYX_ERR(0, 518, __pyx_L1_error) } *__Pyx_BufPtrStrided1d(__pyx_t_5numpy_float64_t *, __pyx_pybuffernd_out.rcbuffer->pybuffer.buf, __pyx_t_12, __pyx_pybuffernd_out.diminfo[0].strides) = __pyx_v_double_value; - /* "acados_template/acados_ocp_solver_pyx.pyx":488 + /* "acados_template/acados_ocp_solver_pyx.pyx":520 * out[3] = double_value * * return out # <<<<<<<<<<<<<< @@ -25859,7 +26711,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_r = ((PyObject *)__pyx_v_out); goto __pyx_L0; - /* "acados_template/acados_ocp_solver_pyx.pyx":460 + /* "acados_template/acados_ocp_solver_pyx.pyx":492 * * * def get_residuals(self, recompute=False): # <<<<<<<<<<<<<< @@ -25894,7 +26746,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":492 +/* "acados_template/acados_ocp_solver_pyx.pyx":524 * * # Note: this function should not be used anymore, better use cost_set, constraints_set * def set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< @@ -25903,16 +26755,16 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ /* Python wrapper */ -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35set(PyObject *__pyx_v_self, +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39set(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else PyObject *__pyx_args, PyObject *__pyx_kwds #endif ); /*proto*/ -PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34set, "\n Set numerical data inside the solver.\n\n :param stage: integer corresponding to shooting node\n :param field: string in ['x', 'u', 'pi', 'lam', 't', 'p']\n\n .. note:: regarding lam, t: \n\n the inequalities are internally organized in the following order: \n\n [ lbu lbx lg lh lphi ubu ubx ug uh uphi; \n\n lsbu lsbx lsg lsh lsphi usbu usbx usg ush usphi]\n\n .. note:: pi: multipliers for dynamics equality constraints \n\n lam: multipliers for inequalities \n\n t: slack variables corresponding to evaluation of all inequalities (at the solution) \n\n sl: slack variables of soft lower inequality constraints \n\n su: slack variables of soft upper inequality constraints \n\n "); -static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35set = {"set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34set}; -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35set(PyObject *__pyx_v_self, +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38set, "\n Set numerical data inside the solver.\n\n :param stage: integer corresponding to shooting node\n :param field: string in ['x', 'u', 'pi', 'lam', 't', 'p']\n\n .. note:: regarding lam, t: \n\n the inequalities are internally organized in the following order: \n\n [ lbu lbx lg lh lphi ubu ubx ug uh uphi; \n\n lsbu lsbx lsg lsh lsphi usbu usbx usg ush usphi]\n\n .. note:: pi: multipliers for dynamics equality constraints \n\n lam: multipliers for inequalities \n\n t: slack variables corresponding to evaluation of all inequalities (at the solution) \n\n sl: slack variables of soft lower inequality constraints \n\n su: slack variables of soft upper inequality constraints \n\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39set = {"set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38set}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39set(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else @@ -25951,26 +26803,26 @@ PyObject *__pyx_args, PyObject *__pyx_kwds switch (__pyx_nargs) { case 0: if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_stage)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 492, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 524, __pyx_L3_error) else goto __pyx_L5_argtuple_error; CYTHON_FALLTHROUGH; case 1: if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field_2)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 492, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 524, __pyx_L3_error) else { - __Pyx_RaiseArgtupleInvalid("set", 1, 3, 3, 1); __PYX_ERR(0, 492, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("set", 1, 3, 3, 1); __PYX_ERR(0, 524, __pyx_L3_error) } CYTHON_FALLTHROUGH; case 2: if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_value)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 492, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 524, __pyx_L3_error) else { - __Pyx_RaiseArgtupleInvalid("set", 1, 3, 3, 2); __PYX_ERR(0, 492, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("set", 1, 3, 3, 2); __PYX_ERR(0, 524, __pyx_L3_error) } } if (unlikely(kw_args > 0)) { const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "set") < 0)) __PYX_ERR(0, 492, __pyx_L3_error) + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "set") < 0)) __PYX_ERR(0, 524, __pyx_L3_error) } } else if (unlikely(__pyx_nargs != 3)) { goto __pyx_L5_argtuple_error; @@ -25979,20 +26831,20 @@ PyObject *__pyx_args, PyObject *__pyx_kwds values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); } - __pyx_v_stage = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_stage == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 492, __pyx_L3_error) + __pyx_v_stage = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_stage == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 524, __pyx_L3_error) __pyx_v_field_ = ((PyObject*)values[1]); __pyx_v_value_ = values[2]; } goto __pyx_L4_argument_unpacking_done; __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("set", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 492, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("set", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 524, __pyx_L3_error) __pyx_L3_error:; __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.set", __pyx_clineno, __pyx_lineno, __pyx_filename); __Pyx_RefNannyFinishContext(); return NULL; __pyx_L4_argument_unpacking_done:; - if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 492, __pyx_L1_error) - __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34set(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_stage, __pyx_v_field_, __pyx_v_value_); + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 524, __pyx_L1_error) + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38set(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_stage, __pyx_v_field_, __pyx_v_value_); /* function exit code */ goto __pyx_L0; @@ -26003,7 +26855,7 @@ PyObject *__pyx_args, PyObject *__pyx_kwds return __pyx_r; } -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_) { +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_) { PyObject *__pyx_v_cost_fields = NULL; PyObject *__pyx_v_constraints_fields = NULL; PyObject *__pyx_v_out_fields = NULL; @@ -26018,19 +26870,22 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __Pyx_RefNannyDeclarations PyObject *__pyx_t_1 = NULL; PyObject *__pyx_t_2 = NULL; - PyObject *__pyx_t_3 = NULL; - PyObject *__pyx_t_4 = NULL; - PyObject *__pyx_t_5 = NULL; - PyArrayObject *__pyx_t_6 = NULL; - int __pyx_t_7; - char *__pyx_t_8; - npy_intp *__pyx_t_9; - int __pyx_t_10; - char const *__pyx_t_11; - char const *__pyx_t_12; - char const *__pyx_t_13; + int __pyx_t_3; + int __pyx_t_4; + Py_ssize_t __pyx_t_5; + Py_UCS4 __pyx_t_6; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + PyObject *__pyx_t_9 = NULL; + PyArrayObject *__pyx_t_10 = NULL; + char *__pyx_t_11; + npy_intp *__pyx_t_12; + int __pyx_t_13; char const *__pyx_t_14; char const *__pyx_t_15; + char const *__pyx_t_16; + char const *__pyx_t_17; + char const *__pyx_t_18; int __pyx_lineno = 0; const char *__pyx_filename = NULL; int __pyx_clineno = 0; @@ -26040,103 +26895,165 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_pybuffernd_value.data = NULL; __pyx_pybuffernd_value.rcbuffer = &__pyx_pybuffer_value; - /* "acados_template/acados_ocp_solver_pyx.pyx":511 + /* "acados_template/acados_ocp_solver_pyx.pyx":543 * su: slack variables of soft upper inequality constraints \n * """ + * if not isinstance(value_, np.ndarray): # <<<<<<<<<<<<<< + * raise Exception(f"set: value must be numpy array, got {type(value_)}.") + * cost_fields = ['y_ref', 'yref'] + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 543, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_ndarray); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 543, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_3 = PyObject_IsInstance(__pyx_v_value_, __pyx_t_2); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(0, 543, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_4 = (!__pyx_t_3); + if (unlikely(__pyx_t_4)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":544 + * """ + * if not isinstance(value_, np.ndarray): + * raise Exception(f"set: value must be numpy array, got {type(value_)}.") # <<<<<<<<<<<<<< + * cost_fields = ['y_ref', 'yref'] + * constraints_fields = ['lbx', 'ubx', 'lbu', 'ubu'] + */ + __pyx_t_2 = PyTuple_New(3); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 544, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_5 = 0; + __pyx_t_6 = 127; + __Pyx_INCREF(__pyx_kp_u_set_value_must_be_numpy_array_go); + __pyx_t_5 += 36; + __Pyx_GIVEREF(__pyx_kp_u_set_value_must_be_numpy_array_go); + PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_kp_u_set_value_must_be_numpy_array_go); + __pyx_t_1 = __Pyx_PyObject_FormatSimple(((PyObject *)Py_TYPE(__pyx_v_value_)), __pyx_empty_unicode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 544, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_2, 1, __pyx_t_1); + __pyx_t_1 = 0; + __Pyx_INCREF(__pyx_kp_u__2); + __pyx_t_5 += 1; + __Pyx_GIVEREF(__pyx_kp_u__2); + PyTuple_SET_ITEM(__pyx_t_2, 2, __pyx_kp_u__2); + __pyx_t_1 = __Pyx_PyUnicode_Join(__pyx_t_2, 3, __pyx_t_5, __pyx_t_6); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 544, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 544, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 544, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":543 + * su: slack variables of soft upper inequality constraints \n + * """ + * if not isinstance(value_, np.ndarray): # <<<<<<<<<<<<<< + * raise Exception(f"set: value must be numpy array, got {type(value_)}.") + * cost_fields = ['y_ref', 'yref'] + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":545 + * if not isinstance(value_, np.ndarray): + * raise Exception(f"set: value must be numpy array, got {type(value_)}.") * cost_fields = ['y_ref', 'yref'] # <<<<<<<<<<<<<< * constraints_fields = ['lbx', 'ubx', 'lbu', 'ubu'] * out_fields = ['x', 'u', 'pi', 'lam', 't', 'z', 'sl', 'su'] */ - __pyx_t_1 = PyList_New(2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 511, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = PyList_New(2); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 545, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); __Pyx_INCREF(__pyx_n_u_y_ref); __Pyx_GIVEREF(__pyx_n_u_y_ref); - PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_u_y_ref); + PyList_SET_ITEM(__pyx_t_2, 0, __pyx_n_u_y_ref); __Pyx_INCREF(__pyx_n_u_yref); __Pyx_GIVEREF(__pyx_n_u_yref); - PyList_SET_ITEM(__pyx_t_1, 1, __pyx_n_u_yref); - __pyx_v_cost_fields = ((PyObject*)__pyx_t_1); - __pyx_t_1 = 0; + PyList_SET_ITEM(__pyx_t_2, 1, __pyx_n_u_yref); + __pyx_v_cost_fields = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":512 - * """ + /* "acados_template/acados_ocp_solver_pyx.pyx":546 + * raise Exception(f"set: value must be numpy array, got {type(value_)}.") * cost_fields = ['y_ref', 'yref'] * constraints_fields = ['lbx', 'ubx', 'lbu', 'ubu'] # <<<<<<<<<<<<<< * out_fields = ['x', 'u', 'pi', 'lam', 't', 'z', 'sl', 'su'] * mem_fields = ['xdot_guess', 'z_guess'] */ - __pyx_t_1 = PyList_New(4); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 512, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = PyList_New(4); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 546, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); __Pyx_INCREF(__pyx_n_u_lbx); __Pyx_GIVEREF(__pyx_n_u_lbx); - PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_u_lbx); + PyList_SET_ITEM(__pyx_t_2, 0, __pyx_n_u_lbx); __Pyx_INCREF(__pyx_n_u_ubx); __Pyx_GIVEREF(__pyx_n_u_ubx); - PyList_SET_ITEM(__pyx_t_1, 1, __pyx_n_u_ubx); + PyList_SET_ITEM(__pyx_t_2, 1, __pyx_n_u_ubx); __Pyx_INCREF(__pyx_n_u_lbu); __Pyx_GIVEREF(__pyx_n_u_lbu); - PyList_SET_ITEM(__pyx_t_1, 2, __pyx_n_u_lbu); + PyList_SET_ITEM(__pyx_t_2, 2, __pyx_n_u_lbu); __Pyx_INCREF(__pyx_n_u_ubu); __Pyx_GIVEREF(__pyx_n_u_ubu); - PyList_SET_ITEM(__pyx_t_1, 3, __pyx_n_u_ubu); - __pyx_v_constraints_fields = ((PyObject*)__pyx_t_1); - __pyx_t_1 = 0; + PyList_SET_ITEM(__pyx_t_2, 3, __pyx_n_u_ubu); + __pyx_v_constraints_fields = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":513 + /* "acados_template/acados_ocp_solver_pyx.pyx":547 * cost_fields = ['y_ref', 'yref'] * constraints_fields = ['lbx', 'ubx', 'lbu', 'ubu'] * out_fields = ['x', 'u', 'pi', 'lam', 't', 'z', 'sl', 'su'] # <<<<<<<<<<<<<< * mem_fields = ['xdot_guess', 'z_guess'] * */ - __pyx_t_1 = PyList_New(8); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 513, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = PyList_New(8); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 547, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); __Pyx_INCREF(__pyx_n_u_x); __Pyx_GIVEREF(__pyx_n_u_x); - PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_u_x); + PyList_SET_ITEM(__pyx_t_2, 0, __pyx_n_u_x); __Pyx_INCREF(__pyx_n_u_u); __Pyx_GIVEREF(__pyx_n_u_u); - PyList_SET_ITEM(__pyx_t_1, 1, __pyx_n_u_u); + PyList_SET_ITEM(__pyx_t_2, 1, __pyx_n_u_u); __Pyx_INCREF(__pyx_n_u_pi); __Pyx_GIVEREF(__pyx_n_u_pi); - PyList_SET_ITEM(__pyx_t_1, 2, __pyx_n_u_pi); + PyList_SET_ITEM(__pyx_t_2, 2, __pyx_n_u_pi); __Pyx_INCREF(__pyx_n_u_lam); __Pyx_GIVEREF(__pyx_n_u_lam); - PyList_SET_ITEM(__pyx_t_1, 3, __pyx_n_u_lam); + PyList_SET_ITEM(__pyx_t_2, 3, __pyx_n_u_lam); __Pyx_INCREF(__pyx_n_u_t); __Pyx_GIVEREF(__pyx_n_u_t); - PyList_SET_ITEM(__pyx_t_1, 4, __pyx_n_u_t); + PyList_SET_ITEM(__pyx_t_2, 4, __pyx_n_u_t); __Pyx_INCREF(__pyx_n_u_z); __Pyx_GIVEREF(__pyx_n_u_z); - PyList_SET_ITEM(__pyx_t_1, 5, __pyx_n_u_z); + PyList_SET_ITEM(__pyx_t_2, 5, __pyx_n_u_z); __Pyx_INCREF(__pyx_n_u_sl); __Pyx_GIVEREF(__pyx_n_u_sl); - PyList_SET_ITEM(__pyx_t_1, 6, __pyx_n_u_sl); + PyList_SET_ITEM(__pyx_t_2, 6, __pyx_n_u_sl); __Pyx_INCREF(__pyx_n_u_su); __Pyx_GIVEREF(__pyx_n_u_su); - PyList_SET_ITEM(__pyx_t_1, 7, __pyx_n_u_su); - __pyx_v_out_fields = ((PyObject*)__pyx_t_1); - __pyx_t_1 = 0; + PyList_SET_ITEM(__pyx_t_2, 7, __pyx_n_u_su); + __pyx_v_out_fields = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":514 + /* "acados_template/acados_ocp_solver_pyx.pyx":548 * constraints_fields = ['lbx', 'ubx', 'lbu', 'ubu'] * out_fields = ['x', 'u', 'pi', 'lam', 't', 'z', 'sl', 'su'] * mem_fields = ['xdot_guess', 'z_guess'] # <<<<<<<<<<<<<< * * field = field_.encode('utf-8') */ - __pyx_t_1 = PyList_New(2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 514, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = PyList_New(2); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 548, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); __Pyx_INCREF(__pyx_n_u_xdot_guess); __Pyx_GIVEREF(__pyx_n_u_xdot_guess); - PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_u_xdot_guess); + PyList_SET_ITEM(__pyx_t_2, 0, __pyx_n_u_xdot_guess); __Pyx_INCREF(__pyx_n_u_z_guess); __Pyx_GIVEREF(__pyx_n_u_z_guess); - PyList_SET_ITEM(__pyx_t_1, 1, __pyx_n_u_z_guess); - __pyx_v_mem_fields = ((PyObject*)__pyx_t_1); - __pyx_t_1 = 0; + PyList_SET_ITEM(__pyx_t_2, 1, __pyx_n_u_z_guess); + __pyx_v_mem_fields = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":516 + /* "acados_template/acados_ocp_solver_pyx.pyx":550 * mem_fields = ['xdot_guess', 'z_guess'] * * field = field_.encode('utf-8') # <<<<<<<<<<<<<< @@ -26145,69 +27062,69 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ if (unlikely(__pyx_v_field_ == Py_None)) { PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "encode"); - __PYX_ERR(0, 516, __pyx_L1_error) + __PYX_ERR(0, 550, __pyx_L1_error) } - __pyx_t_1 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 516, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_v_field = __pyx_t_1; - __pyx_t_1 = 0; + __pyx_t_2 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 550, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_v_field = __pyx_t_2; + __pyx_t_2 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":518 + /* "acados_template/acados_ocp_solver_pyx.pyx":552 * field = field_.encode('utf-8') * * cdef cnp.ndarray[cnp.float64_t, ndim=1] value = np.ascontiguousarray(value_, dtype=np.float64) # <<<<<<<<<<<<<< * * # treat parameters separately */ - __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 518, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 518, __pyx_L1_error) + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_np); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 552, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_1 = PyTuple_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 518, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 552, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = PyTuple_New(1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 552, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); __Pyx_INCREF(__pyx_v_value_); __Pyx_GIVEREF(__pyx_v_value_); - PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v_value_); - __pyx_t_3 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 518, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_np); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 518, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_float64); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 518, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_dtype, __pyx_t_5) < 0) __PYX_ERR(0, 518, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __pyx_t_5 = __Pyx_PyObject_Call(__pyx_t_2, __pyx_t_1, __pyx_t_3); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 518, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_v_value_); + __pyx_t_7 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 552, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_GetModuleGlobalName(__pyx_t_8, __pyx_n_s_np); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 552, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_9 = __Pyx_PyObject_GetAttrStr(__pyx_t_8, __pyx_n_s_float64); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 552, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + if (PyDict_SetItem(__pyx_t_7, __pyx_n_s_dtype, __pyx_t_9) < 0) __PYX_ERR(0, 552, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + __pyx_t_9 = __Pyx_PyObject_Call(__pyx_t_1, __pyx_t_2, __pyx_t_7); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 552, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - if (!(likely(((__pyx_t_5) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_5, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 518, __pyx_L1_error) - __pyx_t_6 = ((PyArrayObject *)__pyx_t_5); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (!(likely(((__pyx_t_9) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_9, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 552, __pyx_L1_error) + __pyx_t_10 = ((PyArrayObject *)__pyx_t_9); { __Pyx_BufFmt_StackElem __pyx_stack[1]; - if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_value.rcbuffer->pybuffer, (PyObject*)__pyx_t_6, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 1, 0, __pyx_stack) == -1)) { + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_value.rcbuffer->pybuffer, (PyObject*)__pyx_t_10, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 1, 0, __pyx_stack) == -1)) { __pyx_v_value = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_value.rcbuffer->pybuffer.buf = NULL; - __PYX_ERR(0, 518, __pyx_L1_error) + __PYX_ERR(0, 552, __pyx_L1_error) } else {__pyx_pybuffernd_value.diminfo[0].strides = __pyx_pybuffernd_value.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_value.diminfo[0].shape = __pyx_pybuffernd_value.rcbuffer->pybuffer.shape[0]; } } - __pyx_t_6 = 0; - __pyx_v_value = ((PyArrayObject *)__pyx_t_5); - __pyx_t_5 = 0; + __pyx_t_10 = 0; + __pyx_v_value = ((PyArrayObject *)__pyx_t_9); + __pyx_t_9 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":521 + /* "acados_template/acados_ocp_solver_pyx.pyx":555 * * # treat parameters separately * if field_ == 'p': # <<<<<<<<<<<<<< * assert acados_solver.acados_update_params(self.capsule, stage, value.data, value.shape[0]) == 0 * else: */ - __pyx_t_7 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_p, Py_EQ)); if (unlikely((__pyx_t_7 < 0))) __PYX_ERR(0, 521, __pyx_L1_error) - if (__pyx_t_7) { + __pyx_t_4 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_p, Py_EQ)); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 555, __pyx_L1_error) + if (__pyx_t_4) { - /* "acados_template/acados_ocp_solver_pyx.pyx":522 + /* "acados_template/acados_ocp_solver_pyx.pyx":556 * # treat parameters separately * if field_ == 'p': * assert acados_solver.acados_update_params(self.capsule, stage, value.data, value.shape[0]) == 0 # <<<<<<<<<<<<<< @@ -26216,247 +27133,247 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ #ifndef CYTHON_WITHOUT_ASSERTIONS if (unlikely(__pyx_assertions_enabled())) { - __pyx_t_8 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_8 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 522, __pyx_L1_error) - __pyx_t_9 = __pyx_f_5numpy_7ndarray_5shape_shape(((PyArrayObject *)__pyx_v_value)); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 522, __pyx_L1_error) - __pyx_t_7 = (lat_acados_update_params(__pyx_v_self->capsule, __pyx_v_stage, ((double *)__pyx_t_8), (__pyx_t_9[0])) == 0); - if (unlikely(!__pyx_t_7)) { + __pyx_t_11 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_11 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 556, __pyx_L1_error) + __pyx_t_12 = __pyx_f_5numpy_7ndarray_5shape_shape(((PyArrayObject *)__pyx_v_value)); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 556, __pyx_L1_error) + __pyx_t_4 = (lat_acados_update_params(__pyx_v_self->capsule, __pyx_v_stage, ((double *)__pyx_t_11), (__pyx_t_12[0])) == 0); + if (unlikely(!__pyx_t_4)) { __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); - __PYX_ERR(0, 522, __pyx_L1_error) + __PYX_ERR(0, 556, __pyx_L1_error) } } #else - if ((1)); else __PYX_ERR(0, 522, __pyx_L1_error) + if ((1)); else __PYX_ERR(0, 556, __pyx_L1_error) #endif - /* "acados_template/acados_ocp_solver_pyx.pyx":521 + /* "acados_template/acados_ocp_solver_pyx.pyx":555 * * # treat parameters separately * if field_ == 'p': # <<<<<<<<<<<<<< * assert acados_solver.acados_update_params(self.capsule, stage, value.data, value.shape[0]) == 0 * else: */ - goto __pyx_L3; + goto __pyx_L4; } - /* "acados_template/acados_ocp_solver_pyx.pyx":524 + /* "acados_template/acados_ocp_solver_pyx.pyx":558 * assert acados_solver.acados_update_params(self.capsule, stage, value.data, value.shape[0]) == 0 * else: * if field_ not in constraints_fields + cost_fields + out_fields: # <<<<<<<<<<<<<< * raise Exception("AcadosOcpSolverCython.set(): {} is not a valid argument.\ - * \nPossible values are {}. Exiting.".format(field, \ + * \nPossible values are {}.".format(field, \ */ /*else*/ { - __pyx_t_5 = PyNumber_Add(__pyx_v_constraints_fields, __pyx_v_cost_fields); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 524, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __pyx_t_3 = PyNumber_Add(__pyx_t_5, __pyx_v_out_fields); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 524, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __pyx_t_7 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_t_3, Py_NE)); if (unlikely((__pyx_t_7 < 0))) __PYX_ERR(0, 524, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - if (unlikely(__pyx_t_7)) { + __pyx_t_9 = PyNumber_Add(__pyx_v_constraints_fields, __pyx_v_cost_fields); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 558, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __pyx_t_7 = PyNumber_Add(__pyx_t_9, __pyx_v_out_fields); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 558, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + __pyx_t_4 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_t_7, Py_NE)); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 558, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(__pyx_t_4)) { - /* "acados_template/acados_ocp_solver_pyx.pyx":526 + /* "acados_template/acados_ocp_solver_pyx.pyx":560 * if field_ not in constraints_fields + cost_fields + out_fields: * raise Exception("AcadosOcpSolverCython.set(): {} is not a valid argument.\ - * \nPossible values are {}. Exiting.".format(field, \ # <<<<<<<<<<<<<< + * \nPossible values are {}.".format(field, \ # <<<<<<<<<<<<<< * constraints_fields + cost_fields + out_fields + ['p'])) * */ - __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_set_is_not, __pyx_n_s_format); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 526, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); + __pyx_t_9 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_set_is_not, __pyx_n_s_format); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 560, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); - /* "acados_template/acados_ocp_solver_pyx.pyx":527 + /* "acados_template/acados_ocp_solver_pyx.pyx":561 * raise Exception("AcadosOcpSolverCython.set(): {} is not a valid argument.\ - * \nPossible values are {}. Exiting.".format(field, \ + * \nPossible values are {}.".format(field, \ * constraints_fields + cost_fields + out_fields + ['p'])) # <<<<<<<<<<<<<< * * dims = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, */ - __pyx_t_1 = PyNumber_Add(__pyx_v_constraints_fields, __pyx_v_cost_fields); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 527, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_2 = PyNumber_Add(__pyx_t_1, __pyx_v_out_fields); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 527, __pyx_L1_error) + __pyx_t_2 = PyNumber_Add(__pyx_v_constraints_fields, __pyx_v_cost_fields); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 561, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_1 = PyList_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 527, __pyx_L1_error) + __pyx_t_1 = PyNumber_Add(__pyx_t_2, __pyx_v_out_fields); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 561, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = PyList_New(1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 561, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); __Pyx_INCREF(__pyx_n_u_p); __Pyx_GIVEREF(__pyx_n_u_p); - PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_u_p); - __pyx_t_4 = PyNumber_Add(__pyx_t_2, __pyx_t_1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 527, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + PyList_SET_ITEM(__pyx_t_2, 0, __pyx_n_u_p); + __pyx_t_8 = PyNumber_Add(__pyx_t_1, __pyx_t_2); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 561, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_1 = NULL; - __pyx_t_10 = 0; - if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_5))) { - __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_5); - if (likely(__pyx_t_1)) { - PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); - __Pyx_INCREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = NULL; + __pyx_t_13 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_9))) { + __pyx_t_2 = PyMethod_GET_SELF(__pyx_t_9); + if (likely(__pyx_t_2)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_9); + __Pyx_INCREF(__pyx_t_2); __Pyx_INCREF(function); - __Pyx_DECREF_SET(__pyx_t_5, function); - __pyx_t_10 = 1; + __Pyx_DECREF_SET(__pyx_t_9, function); + __pyx_t_13 = 1; } } { - PyObject *__pyx_callargs[3] = {__pyx_t_1, __pyx_v_field, __pyx_t_4}; - __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_10, 2+__pyx_t_10); - __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 526, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + PyObject *__pyx_callargs[3] = {__pyx_t_2, __pyx_v_field, __pyx_t_8}; + __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_9, __pyx_callargs+1-__pyx_t_13, 2+__pyx_t_13); + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 560, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; } - /* "acados_template/acados_ocp_solver_pyx.pyx":525 + /* "acados_template/acados_ocp_solver_pyx.pyx":559 * else: * if field_ not in constraints_fields + cost_fields + out_fields: * raise Exception("AcadosOcpSolverCython.set(): {} is not a valid argument.\ # <<<<<<<<<<<<<< - * \nPossible values are {}. Exiting.".format(field, \ + * \nPossible values are {}.".format(field, \ * constraints_fields + cost_fields + out_fields + ['p'])) */ - __pyx_t_5 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_3); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 525, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - __Pyx_Raise(__pyx_t_5, 0, 0, 0); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __PYX_ERR(0, 525, __pyx_L1_error) + __pyx_t_9 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_7); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 559, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_Raise(__pyx_t_9, 0, 0, 0); + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + __PYX_ERR(0, 559, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":524 + /* "acados_template/acados_ocp_solver_pyx.pyx":558 * assert acados_solver.acados_update_params(self.capsule, stage, value.data, value.shape[0]) == 0 * else: * if field_ not in constraints_fields + cost_fields + out_fields: # <<<<<<<<<<<<<< * raise Exception("AcadosOcpSolverCython.set(): {} is not a valid argument.\ - * \nPossible values are {}. Exiting.".format(field, \ + * \nPossible values are {}.".format(field, \ */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":530 + /* "acados_template/acados_ocp_solver_pyx.pyx":564 * * dims = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, * self.nlp_dims, self.nlp_out, stage, field) # <<<<<<<<<<<<<< * * if value_.shape[0] != dims: */ - __pyx_t_11 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_11) && PyErr_Occurred())) __PYX_ERR(0, 530, __pyx_L1_error) + __pyx_t_14 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_14) && PyErr_Occurred())) __PYX_ERR(0, 564, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":529 + /* "acados_template/acados_ocp_solver_pyx.pyx":563 * constraints_fields + cost_fields + out_fields + ['p'])) * * dims = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, # <<<<<<<<<<<<<< * self.nlp_dims, self.nlp_out, stage, field) * */ - __pyx_t_5 = __Pyx_PyInt_From_int(ocp_nlp_dims_get_from_attr(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_11)); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 529, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __pyx_v_dims = __pyx_t_5; - __pyx_t_5 = 0; + __pyx_t_9 = __Pyx_PyInt_From_int(ocp_nlp_dims_get_from_attr(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_14)); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 563, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __pyx_v_dims = __pyx_t_9; + __pyx_t_9 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":532 + /* "acados_template/acados_ocp_solver_pyx.pyx":566 * self.nlp_dims, self.nlp_out, stage, field) * * if value_.shape[0] != dims: # <<<<<<<<<<<<<< * msg = 'AcadosOcpSolverCython.set(): mismatching dimension for field "{}" '.format(field_) * msg += 'with dimension {} (you have {})'.format(dims, value_.shape[0]) */ - __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_v_value_, __pyx_n_s_shape); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 532, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __pyx_t_3 = __Pyx_GetItemInt(__pyx_t_5, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 532, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __pyx_t_5 = PyObject_RichCompare(__pyx_t_3, __pyx_v_dims, Py_NE); __Pyx_XGOTREF(__pyx_t_5); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 532, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - __pyx_t_7 = __Pyx_PyObject_IsTrue(__pyx_t_5); if (unlikely((__pyx_t_7 < 0))) __PYX_ERR(0, 532, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - if (unlikely(__pyx_t_7)) { + __pyx_t_9 = __Pyx_PyObject_GetAttrStr(__pyx_v_value_, __pyx_n_s_shape); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 566, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __pyx_t_7 = __Pyx_GetItemInt(__pyx_t_9, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 566, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + __pyx_t_9 = PyObject_RichCompare(__pyx_t_7, __pyx_v_dims, Py_NE); __Pyx_XGOTREF(__pyx_t_9); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 566, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_t_9); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 566, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + if (unlikely(__pyx_t_4)) { - /* "acados_template/acados_ocp_solver_pyx.pyx":533 + /* "acados_template/acados_ocp_solver_pyx.pyx":567 * * if value_.shape[0] != dims: * msg = 'AcadosOcpSolverCython.set(): mismatching dimension for field "{}" '.format(field_) # <<<<<<<<<<<<<< * msg += 'with dimension {} (you have {})'.format(dims, value_.shape[0]) * raise Exception(msg) */ - __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_set_mismat, __pyx_n_s_format); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 533, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __pyx_t_4 = NULL; - __pyx_t_10 = 0; - if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_3))) { - __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_3); - if (likely(__pyx_t_4)) { - PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); - __Pyx_INCREF(__pyx_t_4); + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_set_mismat, __pyx_n_s_format); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 567, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_8 = NULL; + __pyx_t_13 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_7))) { + __pyx_t_8 = PyMethod_GET_SELF(__pyx_t_7); + if (likely(__pyx_t_8)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_7); + __Pyx_INCREF(__pyx_t_8); __Pyx_INCREF(function); - __Pyx_DECREF_SET(__pyx_t_3, function); - __pyx_t_10 = 1; + __Pyx_DECREF_SET(__pyx_t_7, function); + __pyx_t_13 = 1; } } { - PyObject *__pyx_callargs[2] = {__pyx_t_4, __pyx_v_field_}; - __pyx_t_5 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_10, 1+__pyx_t_10); - __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; - if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 533, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + PyObject *__pyx_callargs[2] = {__pyx_t_8, __pyx_v_field_}; + __pyx_t_9 = __Pyx_PyObject_FastCall(__pyx_t_7, __pyx_callargs+1-__pyx_t_13, 1+__pyx_t_13); + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 567, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; } - __pyx_v_msg = __pyx_t_5; - __pyx_t_5 = 0; + __pyx_v_msg = __pyx_t_9; + __pyx_t_9 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":534 + /* "acados_template/acados_ocp_solver_pyx.pyx":568 * if value_.shape[0] != dims: * msg = 'AcadosOcpSolverCython.set(): mismatching dimension for field "{}" '.format(field_) * msg += 'with dimension {} (you have {})'.format(dims, value_.shape[0]) # <<<<<<<<<<<<<< * raise Exception(msg) * */ - __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_with_dimension_you_have, __pyx_n_s_format); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 534, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_v_value_, __pyx_n_s_shape); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 534, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __pyx_t_1 = __Pyx_GetItemInt(__pyx_t_4, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 534, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __pyx_t_4 = NULL; - __pyx_t_10 = 0; - if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_3))) { - __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_3); - if (likely(__pyx_t_4)) { - PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); - __Pyx_INCREF(__pyx_t_4); + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_with_dimension_you_have, __pyx_n_s_format); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 568, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_value_, __pyx_n_s_shape); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 568, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_2 = __Pyx_GetItemInt(__pyx_t_8, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 568, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_t_8 = NULL; + __pyx_t_13 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_7))) { + __pyx_t_8 = PyMethod_GET_SELF(__pyx_t_7); + if (likely(__pyx_t_8)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_7); + __Pyx_INCREF(__pyx_t_8); __Pyx_INCREF(function); - __Pyx_DECREF_SET(__pyx_t_3, function); - __pyx_t_10 = 1; + __Pyx_DECREF_SET(__pyx_t_7, function); + __pyx_t_13 = 1; } } { - PyObject *__pyx_callargs[3] = {__pyx_t_4, __pyx_v_dims, __pyx_t_1}; - __pyx_t_5 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_10, 2+__pyx_t_10); - __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 534, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + PyObject *__pyx_callargs[3] = {__pyx_t_8, __pyx_v_dims, __pyx_t_2}; + __pyx_t_9 = __Pyx_PyObject_FastCall(__pyx_t_7, __pyx_callargs+1-__pyx_t_13, 2+__pyx_t_13); + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 568, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; } - __pyx_t_3 = PyNumber_InPlaceAdd(__pyx_v_msg, __pyx_t_5); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 534, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __Pyx_DECREF_SET(__pyx_v_msg, __pyx_t_3); - __pyx_t_3 = 0; + __pyx_t_7 = PyNumber_InPlaceAdd(__pyx_v_msg, __pyx_t_9); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 568, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + __Pyx_DECREF_SET(__pyx_v_msg, __pyx_t_7); + __pyx_t_7 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":535 + /* "acados_template/acados_ocp_solver_pyx.pyx":569 * msg = 'AcadosOcpSolverCython.set(): mismatching dimension for field "{}" '.format(field_) * msg += 'with dimension {} (you have {})'.format(dims, value_.shape[0]) * raise Exception(msg) # <<<<<<<<<<<<<< * * if field_ in constraints_fields: */ - __pyx_t_3 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_v_msg); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 535, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __Pyx_Raise(__pyx_t_3, 0, 0, 0); - __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - __PYX_ERR(0, 535, __pyx_L1_error) + __pyx_t_7 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_v_msg); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 569, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_Raise(__pyx_t_7, 0, 0, 0); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __PYX_ERR(0, 569, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":532 + /* "acados_template/acados_ocp_solver_pyx.pyx":566 * self.nlp_dims, self.nlp_out, stage, field) * * if value_.shape[0] != dims: # <<<<<<<<<<<<<< @@ -26465,153 +27382,153 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":537 + /* "acados_template/acados_ocp_solver_pyx.pyx":571 * raise Exception(msg) * * if field_ in constraints_fields: # <<<<<<<<<<<<<< * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, * self.nlp_dims, self.nlp_in, stage, field, value.data) */ - __pyx_t_7 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_constraints_fields, Py_EQ)); if (unlikely((__pyx_t_7 < 0))) __PYX_ERR(0, 537, __pyx_L1_error) - if (__pyx_t_7) { + __pyx_t_4 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_constraints_fields, Py_EQ)); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 571, __pyx_L1_error) + if (__pyx_t_4) { - /* "acados_template/acados_ocp_solver_pyx.pyx":539 + /* "acados_template/acados_ocp_solver_pyx.pyx":573 * if field_ in constraints_fields: * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, * self.nlp_dims, self.nlp_in, stage, field, value.data) # <<<<<<<<<<<<<< * elif field_ in cost_fields: * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, */ - __pyx_t_12 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_12) && PyErr_Occurred())) __PYX_ERR(0, 539, __pyx_L1_error) - __pyx_t_8 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_8 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 539, __pyx_L1_error) + __pyx_t_15 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_15) && PyErr_Occurred())) __PYX_ERR(0, 573, __pyx_L1_error) + __pyx_t_11 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_11 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 573, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":538 + /* "acados_template/acados_ocp_solver_pyx.pyx":572 * * if field_ in constraints_fields: * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, # <<<<<<<<<<<<<< * self.nlp_dims, self.nlp_in, stage, field, value.data) * elif field_ in cost_fields: */ - (void)(ocp_nlp_constraints_model_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_in, __pyx_v_stage, __pyx_t_12, ((void *)__pyx_t_8))); + (void)(ocp_nlp_constraints_model_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_in, __pyx_v_stage, __pyx_t_15, ((void *)__pyx_t_11))); - /* "acados_template/acados_ocp_solver_pyx.pyx":537 + /* "acados_template/acados_ocp_solver_pyx.pyx":571 * raise Exception(msg) * * if field_ in constraints_fields: # <<<<<<<<<<<<<< * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, * self.nlp_dims, self.nlp_in, stage, field, value.data) */ - goto __pyx_L6; + goto __pyx_L7; } - /* "acados_template/acados_ocp_solver_pyx.pyx":540 + /* "acados_template/acados_ocp_solver_pyx.pyx":574 * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, * self.nlp_dims, self.nlp_in, stage, field, value.data) * elif field_ in cost_fields: # <<<<<<<<<<<<<< * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, * self.nlp_dims, self.nlp_in, stage, field, value.data) */ - __pyx_t_7 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_cost_fields, Py_EQ)); if (unlikely((__pyx_t_7 < 0))) __PYX_ERR(0, 540, __pyx_L1_error) - if (__pyx_t_7) { + __pyx_t_4 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_cost_fields, Py_EQ)); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 574, __pyx_L1_error) + if (__pyx_t_4) { - /* "acados_template/acados_ocp_solver_pyx.pyx":542 + /* "acados_template/acados_ocp_solver_pyx.pyx":576 * elif field_ in cost_fields: * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, * self.nlp_dims, self.nlp_in, stage, field, value.data) # <<<<<<<<<<<<<< * elif field_ in out_fields: * acados_solver_common.ocp_nlp_out_set(self.nlp_config, */ - __pyx_t_13 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_13) && PyErr_Occurred())) __PYX_ERR(0, 542, __pyx_L1_error) - __pyx_t_8 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_8 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 542, __pyx_L1_error) + __pyx_t_16 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_16) && PyErr_Occurred())) __PYX_ERR(0, 576, __pyx_L1_error) + __pyx_t_11 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_11 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 576, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":541 + /* "acados_template/acados_ocp_solver_pyx.pyx":575 * self.nlp_dims, self.nlp_in, stage, field, value.data) * elif field_ in cost_fields: * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, # <<<<<<<<<<<<<< * self.nlp_dims, self.nlp_in, stage, field, value.data) * elif field_ in out_fields: */ - (void)(ocp_nlp_cost_model_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_in, __pyx_v_stage, __pyx_t_13, ((void *)__pyx_t_8))); + (void)(ocp_nlp_cost_model_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_in, __pyx_v_stage, __pyx_t_16, ((void *)__pyx_t_11))); - /* "acados_template/acados_ocp_solver_pyx.pyx":540 + /* "acados_template/acados_ocp_solver_pyx.pyx":574 * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, * self.nlp_dims, self.nlp_in, stage, field, value.data) * elif field_ in cost_fields: # <<<<<<<<<<<<<< * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, * self.nlp_dims, self.nlp_in, stage, field, value.data) */ - goto __pyx_L6; + goto __pyx_L7; } - /* "acados_template/acados_ocp_solver_pyx.pyx":543 + /* "acados_template/acados_ocp_solver_pyx.pyx":577 * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, * self.nlp_dims, self.nlp_in, stage, field, value.data) * elif field_ in out_fields: # <<<<<<<<<<<<<< * acados_solver_common.ocp_nlp_out_set(self.nlp_config, * self.nlp_dims, self.nlp_out, stage, field, value.data) */ - __pyx_t_7 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_out_fields, Py_EQ)); if (unlikely((__pyx_t_7 < 0))) __PYX_ERR(0, 543, __pyx_L1_error) - if (__pyx_t_7) { + __pyx_t_4 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_out_fields, Py_EQ)); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 577, __pyx_L1_error) + if (__pyx_t_4) { - /* "acados_template/acados_ocp_solver_pyx.pyx":545 + /* "acados_template/acados_ocp_solver_pyx.pyx":579 * elif field_ in out_fields: * acados_solver_common.ocp_nlp_out_set(self.nlp_config, * self.nlp_dims, self.nlp_out, stage, field, value.data) # <<<<<<<<<<<<<< * elif field_ in mem_fields: * acados_solver_common.ocp_nlp_set(self.nlp_config, \ */ - __pyx_t_14 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_14) && PyErr_Occurred())) __PYX_ERR(0, 545, __pyx_L1_error) - __pyx_t_8 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_8 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 545, __pyx_L1_error) + __pyx_t_17 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_17) && PyErr_Occurred())) __PYX_ERR(0, 579, __pyx_L1_error) + __pyx_t_11 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_11 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 579, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":544 + /* "acados_template/acados_ocp_solver_pyx.pyx":578 * self.nlp_dims, self.nlp_in, stage, field, value.data) * elif field_ in out_fields: * acados_solver_common.ocp_nlp_out_set(self.nlp_config, # <<<<<<<<<<<<<< * self.nlp_dims, self.nlp_out, stage, field, value.data) * elif field_ in mem_fields: */ - ocp_nlp_out_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_14, ((void *)__pyx_t_8)); + ocp_nlp_out_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_17, ((void *)__pyx_t_11)); - /* "acados_template/acados_ocp_solver_pyx.pyx":543 + /* "acados_template/acados_ocp_solver_pyx.pyx":577 * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, * self.nlp_dims, self.nlp_in, stage, field, value.data) * elif field_ in out_fields: # <<<<<<<<<<<<<< * acados_solver_common.ocp_nlp_out_set(self.nlp_config, * self.nlp_dims, self.nlp_out, stage, field, value.data) */ - goto __pyx_L6; + goto __pyx_L7; } - /* "acados_template/acados_ocp_solver_pyx.pyx":546 + /* "acados_template/acados_ocp_solver_pyx.pyx":580 * acados_solver_common.ocp_nlp_out_set(self.nlp_config, * self.nlp_dims, self.nlp_out, stage, field, value.data) * elif field_ in mem_fields: # <<<<<<<<<<<<<< * acados_solver_common.ocp_nlp_set(self.nlp_config, \ * self.nlp_solver, stage, field, value.data) */ - __pyx_t_7 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_mem_fields, Py_EQ)); if (unlikely((__pyx_t_7 < 0))) __PYX_ERR(0, 546, __pyx_L1_error) - if (__pyx_t_7) { + __pyx_t_4 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_mem_fields, Py_EQ)); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 580, __pyx_L1_error) + if (__pyx_t_4) { - /* "acados_template/acados_ocp_solver_pyx.pyx":548 + /* "acados_template/acados_ocp_solver_pyx.pyx":582 * elif field_ in mem_fields: * acados_solver_common.ocp_nlp_set(self.nlp_config, \ * self.nlp_solver, stage, field, value.data) # <<<<<<<<<<<<<< * - * + * if field_ == 'z': */ - __pyx_t_15 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_15) && PyErr_Occurred())) __PYX_ERR(0, 548, __pyx_L1_error) - __pyx_t_8 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_8 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 548, __pyx_L1_error) + __pyx_t_18 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_18) && PyErr_Occurred())) __PYX_ERR(0, 582, __pyx_L1_error) + __pyx_t_11 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_11 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 582, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":547 + /* "acados_template/acados_ocp_solver_pyx.pyx":581 * self.nlp_dims, self.nlp_out, stage, field, value.data) * elif field_ in mem_fields: * acados_solver_common.ocp_nlp_set(self.nlp_config, \ # <<<<<<<<<<<<<< * self.nlp_solver, stage, field, value.data) * */ - ocp_nlp_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_v_stage, __pyx_t_15, ((void *)__pyx_t_8)); + ocp_nlp_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_v_stage, __pyx_t_18, ((void *)__pyx_t_11)); - /* "acados_template/acados_ocp_solver_pyx.pyx":546 + /* "acados_template/acados_ocp_solver_pyx.pyx":580 * acados_solver_common.ocp_nlp_out_set(self.nlp_config, * self.nlp_dims, self.nlp_out, stage, field, value.data) * elif field_ in mem_fields: # <<<<<<<<<<<<<< @@ -26619,11 +27536,70 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS * self.nlp_solver, stage, field, value.data) */ } - __pyx_L6:; - } - __pyx_L3:; + __pyx_L7:; - /* "acados_template/acados_ocp_solver_pyx.pyx":492 + /* "acados_template/acados_ocp_solver_pyx.pyx":584 + * self.nlp_solver, stage, field, value.data) + * + * if field_ == 'z': # <<<<<<<<<<<<<< + * field = 'z_guess'.encode('utf-8') + * acados_solver_common.ocp_nlp_set(self.nlp_config, \ + */ + __pyx_t_4 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_z, Py_EQ)); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 584, __pyx_L1_error) + if (__pyx_t_4) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":585 + * + * if field_ == 'z': + * field = 'z_guess'.encode('utf-8') # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_set(self.nlp_config, \ + * self.nlp_solver, stage, field, value.data) + */ + __Pyx_INCREF(__pyx_n_b_z_guess); + __Pyx_DECREF_SET(__pyx_v_field, __pyx_n_b_z_guess); + + /* "acados_template/acados_ocp_solver_pyx.pyx":587 + * field = 'z_guess'.encode('utf-8') + * acados_solver_common.ocp_nlp_set(self.nlp_config, \ + * self.nlp_solver, stage, field, value.data) # <<<<<<<<<<<<<< + * return + * + */ + __pyx_t_18 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_18) && PyErr_Occurred())) __PYX_ERR(0, 587, __pyx_L1_error) + __pyx_t_11 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_11 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 587, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":586 + * if field_ == 'z': + * field = 'z_guess'.encode('utf-8') + * acados_solver_common.ocp_nlp_set(self.nlp_config, \ # <<<<<<<<<<<<<< + * self.nlp_solver, stage, field, value.data) + * return + */ + ocp_nlp_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_v_stage, __pyx_t_18, ((void *)__pyx_t_11)); + + /* "acados_template/acados_ocp_solver_pyx.pyx":584 + * self.nlp_solver, stage, field, value.data) + * + * if field_ == 'z': # <<<<<<<<<<<<<< + * field = 'z_guess'.encode('utf-8') + * acados_solver_common.ocp_nlp_set(self.nlp_config, \ + */ + } + } + __pyx_L4:; + + /* "acados_template/acados_ocp_solver_pyx.pyx":588 + * acados_solver_common.ocp_nlp_set(self.nlp_config, \ + * self.nlp_solver, stage, field, value.data) + * return # <<<<<<<<<<<<<< + * + * def cost_set(self, int stage, str field_, value_): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":524 * * # Note: this function should not be used anymore, better use cost_set, constraints_set * def set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< @@ -26632,14 +27608,12 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ /* function exit code */ - __pyx_r = Py_None; __Pyx_INCREF(Py_None); - goto __pyx_L0; __pyx_L1_error:; __Pyx_XDECREF(__pyx_t_1); __Pyx_XDECREF(__pyx_t_2); - __Pyx_XDECREF(__pyx_t_3); - __Pyx_XDECREF(__pyx_t_4); - __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_XDECREF(__pyx_t_9); { PyObject *__pyx_type, *__pyx_value, *__pyx_tb; __Pyx_PyThreadState_declare __Pyx_PyThreadState_assign @@ -26665,8 +27639,8 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":551 - * +/* "acados_template/acados_ocp_solver_pyx.pyx":590 + * return * * def cost_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< * """ @@ -26674,16 +27648,16 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ /* Python wrapper */ -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37cost_set(PyObject *__pyx_v_self, +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41cost_set(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else PyObject *__pyx_args, PyObject *__pyx_kwds #endif ); /*proto*/ -PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36cost_set, "\n Set numerical data in the cost module of the solver.\n\n :param stage: integer corresponding to shooting node\n :param field: string, e.g. 'yref', 'W', 'ext_cost_num_hess'\n :param value: of appropriate size\n "); -static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37cost_set = {"cost_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37cost_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36cost_set}; -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37cost_set(PyObject *__pyx_v_self, +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40cost_set, "\n Set numerical data in the cost module of the solver.\n\n :param stage: integer corresponding to shooting node\n :param field: string, e.g. 'yref', 'W', 'ext_cost_num_hess'\n :param value: of appropriate size\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41cost_set = {"cost_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41cost_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40cost_set}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41cost_set(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else @@ -26722,26 +27696,26 @@ PyObject *__pyx_args, PyObject *__pyx_kwds switch (__pyx_nargs) { case 0: if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_stage)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 551, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 590, __pyx_L3_error) else goto __pyx_L5_argtuple_error; CYTHON_FALLTHROUGH; case 1: if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field_2)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 551, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 590, __pyx_L3_error) else { - __Pyx_RaiseArgtupleInvalid("cost_set", 1, 3, 3, 1); __PYX_ERR(0, 551, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("cost_set", 1, 3, 3, 1); __PYX_ERR(0, 590, __pyx_L3_error) } CYTHON_FALLTHROUGH; case 2: if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_value)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 551, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 590, __pyx_L3_error) else { - __Pyx_RaiseArgtupleInvalid("cost_set", 1, 3, 3, 2); __PYX_ERR(0, 551, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("cost_set", 1, 3, 3, 2); __PYX_ERR(0, 590, __pyx_L3_error) } } if (unlikely(kw_args > 0)) { const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "cost_set") < 0)) __PYX_ERR(0, 551, __pyx_L3_error) + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "cost_set") < 0)) __PYX_ERR(0, 590, __pyx_L3_error) } } else if (unlikely(__pyx_nargs != 3)) { goto __pyx_L5_argtuple_error; @@ -26750,20 +27724,20 @@ PyObject *__pyx_args, PyObject *__pyx_kwds values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); } - __pyx_v_stage = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_stage == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 551, __pyx_L3_error) + __pyx_v_stage = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_stage == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 590, __pyx_L3_error) __pyx_v_field_ = ((PyObject*)values[1]); __pyx_v_value_ = values[2]; } goto __pyx_L4_argument_unpacking_done; __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("cost_set", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 551, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("cost_set", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 590, __pyx_L3_error) __pyx_L3_error:; __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.cost_set", __pyx_clineno, __pyx_lineno, __pyx_filename); __Pyx_RefNannyFinishContext(); return NULL; __pyx_L4_argument_unpacking_done:; - if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 551, __pyx_L1_error) - __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36cost_set(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_stage, __pyx_v_field_, __pyx_v_value_); + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 590, __pyx_L1_error) + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40cost_set(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_stage, __pyx_v_field_, __pyx_v_value_); /* function exit code */ goto __pyx_L0; @@ -26774,7 +27748,7 @@ PyObject *__pyx_args, PyObject *__pyx_kwds return __pyx_r; } -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36cost_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_) { +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40cost_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_) { PyObject *__pyx_v_field = NULL; int __pyx_v_dims[2]; __Pyx_memviewslice __pyx_v_value = { 0, 0, { 0 }, { 0 }, { 0 } }; @@ -26782,16 +27756,16 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_r = NULL; __Pyx_RefNannyDeclarations PyObject *__pyx_t_1 = NULL; - char const *__pyx_t_2; - Py_ssize_t __pyx_t_3; + PyObject *__pyx_t_2 = NULL; + int __pyx_t_3; int __pyx_t_4; - PyObject *__pyx_t_5 = NULL; - PyObject *__pyx_t_6 = NULL; - PyObject *__pyx_t_7 = NULL; - int __pyx_t_8; - __Pyx_memviewslice __pyx_t_9 = { 0, 0, { 0 }, { 0 }, { 0 } }; + Py_ssize_t __pyx_t_5; + Py_UCS4 __pyx_t_6; + char const *__pyx_t_7; + PyObject *__pyx_t_8 = NULL; + PyObject *__pyx_t_9 = NULL; int __pyx_t_10; - Py_UCS4 __pyx_t_11; + __Pyx_memviewslice __pyx_t_11 = { 0, 0, { 0 }, { 0 }, { 0 } }; char const *__pyx_t_12; Py_ssize_t __pyx_t_13; Py_ssize_t __pyx_t_14; @@ -26800,184 +27774,246 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS int __pyx_clineno = 0; __Pyx_RefNannySetupContext("cost_set", 0); - /* "acados_template/acados_ocp_solver_pyx.pyx":559 + /* "acados_template/acados_ocp_solver_pyx.pyx":598 * :param value: of appropriate size * """ + * if not isinstance(value_, np.ndarray): # <<<<<<<<<<<<<< + * raise Exception(f"cost_set: value must be numpy array, got {type(value_)}.") + * field = field_.encode('utf-8') + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 598, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_ndarray); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 598, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_3 = PyObject_IsInstance(__pyx_v_value_, __pyx_t_2); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(0, 598, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_4 = (!__pyx_t_3); + if (unlikely(__pyx_t_4)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":599 + * """ + * if not isinstance(value_, np.ndarray): + * raise Exception(f"cost_set: value must be numpy array, got {type(value_)}.") # <<<<<<<<<<<<<< + * field = field_.encode('utf-8') + * + */ + __pyx_t_2 = PyTuple_New(3); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 599, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_5 = 0; + __pyx_t_6 = 127; + __Pyx_INCREF(__pyx_kp_u_cost_set_value_must_be_numpy_arr); + __pyx_t_5 += 41; + __Pyx_GIVEREF(__pyx_kp_u_cost_set_value_must_be_numpy_arr); + PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_kp_u_cost_set_value_must_be_numpy_arr); + __pyx_t_1 = __Pyx_PyObject_FormatSimple(((PyObject *)Py_TYPE(__pyx_v_value_)), __pyx_empty_unicode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 599, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_2, 1, __pyx_t_1); + __pyx_t_1 = 0; + __Pyx_INCREF(__pyx_kp_u__2); + __pyx_t_5 += 1; + __Pyx_GIVEREF(__pyx_kp_u__2); + PyTuple_SET_ITEM(__pyx_t_2, 2, __pyx_kp_u__2); + __pyx_t_1 = __Pyx_PyUnicode_Join(__pyx_t_2, 3, __pyx_t_5, __pyx_t_6); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 599, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 599, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 599, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":598 + * :param value: of appropriate size + * """ + * if not isinstance(value_, np.ndarray): # <<<<<<<<<<<<<< + * raise Exception(f"cost_set: value must be numpy array, got {type(value_)}.") + * field = field_.encode('utf-8') + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":600 + * if not isinstance(value_, np.ndarray): + * raise Exception(f"cost_set: value must be numpy array, got {type(value_)}.") * field = field_.encode('utf-8') # <<<<<<<<<<<<<< * * cdef int dims[2] */ if (unlikely(__pyx_v_field_ == Py_None)) { PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "encode"); - __PYX_ERR(0, 559, __pyx_L1_error) + __PYX_ERR(0, 600, __pyx_L1_error) } - __pyx_t_1 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 559, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_v_field = __pyx_t_1; - __pyx_t_1 = 0; + __pyx_t_2 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 600, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_v_field = __pyx_t_2; + __pyx_t_2 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":563 + /* "acados_template/acados_ocp_solver_pyx.pyx":604 * cdef int dims[2] * acados_solver_common.ocp_nlp_cost_dims_get_from_attr(self.nlp_config, \ * self.nlp_dims, self.nlp_out, stage, field, &dims[0]) # <<<<<<<<<<<<<< * * cdef double[::1,:] value */ - __pyx_t_2 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_2) && PyErr_Occurred())) __PYX_ERR(0, 563, __pyx_L1_error) + __pyx_t_7 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 604, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":562 + /* "acados_template/acados_ocp_solver_pyx.pyx":603 * * cdef int dims[2] * acados_solver_common.ocp_nlp_cost_dims_get_from_attr(self.nlp_config, \ # <<<<<<<<<<<<<< * self.nlp_dims, self.nlp_out, stage, field, &dims[0]) * */ - ocp_nlp_cost_dims_get_from_attr(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_2, (&(__pyx_v_dims[0]))); + ocp_nlp_cost_dims_get_from_attr(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_7, (&(__pyx_v_dims[0]))); - /* "acados_template/acados_ocp_solver_pyx.pyx":567 + /* "acados_template/acados_ocp_solver_pyx.pyx":608 * cdef double[::1,:] value * * value_shape = value_.shape # <<<<<<<<<<<<<< * if len(value_shape) == 1: * value_shape = (value_shape[0], 0) */ - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_value_, __pyx_n_s_shape); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 567, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_v_value_shape = __pyx_t_1; - __pyx_t_1 = 0; + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_value_, __pyx_n_s_shape); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 608, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_v_value_shape = __pyx_t_2; + __pyx_t_2 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":568 + /* "acados_template/acados_ocp_solver_pyx.pyx":609 * * value_shape = value_.shape * if len(value_shape) == 1: # <<<<<<<<<<<<<< * value_shape = (value_shape[0], 0) * value = np.asfortranarray(value_[None,:]) */ - __pyx_t_3 = PyObject_Length(__pyx_v_value_shape); if (unlikely(__pyx_t_3 == ((Py_ssize_t)-1))) __PYX_ERR(0, 568, __pyx_L1_error) - __pyx_t_4 = (__pyx_t_3 == 1); + __pyx_t_5 = PyObject_Length(__pyx_v_value_shape); if (unlikely(__pyx_t_5 == ((Py_ssize_t)-1))) __PYX_ERR(0, 609, __pyx_L1_error) + __pyx_t_4 = (__pyx_t_5 == 1); if (__pyx_t_4) { - /* "acados_template/acados_ocp_solver_pyx.pyx":569 + /* "acados_template/acados_ocp_solver_pyx.pyx":610 * value_shape = value_.shape * if len(value_shape) == 1: * value_shape = (value_shape[0], 0) # <<<<<<<<<<<<<< * value = np.asfortranarray(value_[None,:]) * */ - __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_value_shape, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 569, __pyx_L1_error) + __pyx_t_2 = __Pyx_GetItemInt(__pyx_v_value_shape, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 610, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_1 = PyTuple_New(2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 610, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); - __pyx_t_5 = PyTuple_New(2); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 569, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_GIVEREF(__pyx_t_1); - PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_t_1); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_t_2); __Pyx_INCREF(__pyx_int_0); __Pyx_GIVEREF(__pyx_int_0); - PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_int_0); + PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_int_0); + __pyx_t_2 = 0; + __Pyx_DECREF_SET(__pyx_v_value_shape, __pyx_t_1); __pyx_t_1 = 0; - __Pyx_DECREF_SET(__pyx_v_value_shape, __pyx_t_5); - __pyx_t_5 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":570 + /* "acados_template/acados_ocp_solver_pyx.pyx":611 * if len(value_shape) == 1: * value_shape = (value_shape[0], 0) * value = np.asfortranarray(value_[None,:]) # <<<<<<<<<<<<<< * * elif len(value_shape) == 2: */ - __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 570, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_asfortranarray); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 570, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_6); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_1 = __Pyx_PyObject_GetItem(__pyx_v_value_, __pyx_tuple__26); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 570, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_7 = NULL; - __pyx_t_8 = 0; - if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_6))) { - __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_6); - if (likely(__pyx_t_7)) { - PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_6); - __Pyx_INCREF(__pyx_t_7); + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_np); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 611, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_asfortranarray); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 611, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_v_value_, __pyx_tuple__28); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 611, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_9 = NULL; + __pyx_t_10 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_8))) { + __pyx_t_9 = PyMethod_GET_SELF(__pyx_t_8); + if (likely(__pyx_t_9)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_8); + __Pyx_INCREF(__pyx_t_9); __Pyx_INCREF(function); - __Pyx_DECREF_SET(__pyx_t_6, function); - __pyx_t_8 = 1; + __Pyx_DECREF_SET(__pyx_t_8, function); + __pyx_t_10 = 1; } } { - PyObject *__pyx_callargs[2] = {__pyx_t_7, __pyx_t_1}; - __pyx_t_5 = __Pyx_PyObject_FastCall(__pyx_t_6, __pyx_callargs+1-__pyx_t_8, 1+__pyx_t_8); - __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 570, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + PyObject *__pyx_callargs[2] = {__pyx_t_9, __pyx_t_2}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_8, __pyx_callargs+1-__pyx_t_10, 1+__pyx_t_10); + __Pyx_XDECREF(__pyx_t_9); __pyx_t_9 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 611, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; } - __pyx_t_9 = __Pyx_PyObject_to_MemoryviewSlice_dcd__double(__pyx_t_5, PyBUF_WRITABLE); if (unlikely(!__pyx_t_9.memview)) __PYX_ERR(0, 570, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __pyx_v_value = __pyx_t_9; - __pyx_t_9.memview = NULL; - __pyx_t_9.data = NULL; + __pyx_t_11 = __Pyx_PyObject_to_MemoryviewSlice_dcd__double(__pyx_t_1, PyBUF_WRITABLE); if (unlikely(!__pyx_t_11.memview)) __PYX_ERR(0, 611, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_value = __pyx_t_11; + __pyx_t_11.memview = NULL; + __pyx_t_11.data = NULL; - /* "acados_template/acados_ocp_solver_pyx.pyx":568 + /* "acados_template/acados_ocp_solver_pyx.pyx":609 * * value_shape = value_.shape * if len(value_shape) == 1: # <<<<<<<<<<<<<< * value_shape = (value_shape[0], 0) * value = np.asfortranarray(value_[None,:]) */ - goto __pyx_L3; + goto __pyx_L4; } - /* "acados_template/acados_ocp_solver_pyx.pyx":572 + /* "acados_template/acados_ocp_solver_pyx.pyx":613 * value = np.asfortranarray(value_[None,:]) * * elif len(value_shape) == 2: # <<<<<<<<<<<<<< * # Get elements in column major order * value = np.asfortranarray(value_) */ - __pyx_t_3 = PyObject_Length(__pyx_v_value_shape); if (unlikely(__pyx_t_3 == ((Py_ssize_t)-1))) __PYX_ERR(0, 572, __pyx_L1_error) - __pyx_t_4 = (__pyx_t_3 == 2); + __pyx_t_5 = PyObject_Length(__pyx_v_value_shape); if (unlikely(__pyx_t_5 == ((Py_ssize_t)-1))) __PYX_ERR(0, 613, __pyx_L1_error) + __pyx_t_4 = (__pyx_t_5 == 2); if (__pyx_t_4) { - /* "acados_template/acados_ocp_solver_pyx.pyx":574 + /* "acados_template/acados_ocp_solver_pyx.pyx":615 * elif len(value_shape) == 2: * # Get elements in column major order * value = np.asfortranarray(value_) # <<<<<<<<<<<<<< * * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: */ - __Pyx_GetModuleGlobalName(__pyx_t_6, __pyx_n_s_np); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 574, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_6); - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_6, __pyx_n_s_asfortranarray); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 574, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; - __pyx_t_6 = NULL; - __pyx_t_8 = 0; - if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_1))) { - __pyx_t_6 = PyMethod_GET_SELF(__pyx_t_1); - if (likely(__pyx_t_6)) { - PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); - __Pyx_INCREF(__pyx_t_6); + __Pyx_GetModuleGlobalName(__pyx_t_8, __pyx_n_s_np); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 615, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_8, __pyx_n_s_asfortranarray); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 615, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_t_8 = NULL; + __pyx_t_10 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_8 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_8)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_8); __Pyx_INCREF(function); - __Pyx_DECREF_SET(__pyx_t_1, function); - __pyx_t_8 = 1; + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_10 = 1; } } { - PyObject *__pyx_callargs[2] = {__pyx_t_6, __pyx_v_value_}; - __pyx_t_5 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_8, 1+__pyx_t_8); - __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; - if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 574, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + PyObject *__pyx_callargs[2] = {__pyx_t_8, __pyx_v_value_}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_10, 1+__pyx_t_10); + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 615, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; } - __pyx_t_9 = __Pyx_PyObject_to_MemoryviewSlice_dcd__double(__pyx_t_5, PyBUF_WRITABLE); if (unlikely(!__pyx_t_9.memview)) __PYX_ERR(0, 574, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __pyx_v_value = __pyx_t_9; - __pyx_t_9.memview = NULL; - __pyx_t_9.data = NULL; + __pyx_t_11 = __Pyx_PyObject_to_MemoryviewSlice_dcd__double(__pyx_t_1, PyBUF_WRITABLE); if (unlikely(!__pyx_t_11.memview)) __PYX_ERR(0, 615, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_value = __pyx_t_11; + __pyx_t_11.memview = NULL; + __pyx_t_11.data = NULL; - /* "acados_template/acados_ocp_solver_pyx.pyx":572 + /* "acados_template/acados_ocp_solver_pyx.pyx":613 * value = np.asfortranarray(value_[None,:]) * * elif len(value_shape) == 2: # <<<<<<<<<<<<<< @@ -26985,128 +28021,128 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS * value = np.asfortranarray(value_) */ } - __pyx_L3:; + __pyx_L4:; - /* "acados_template/acados_ocp_solver_pyx.pyx":576 + /* "acados_template/acados_ocp_solver_pyx.pyx":617 * value = np.asfortranarray(value_) * * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: # <<<<<<<<<<<<<< * raise Exception('AcadosOcpSolverCython.cost_set(): mismatching dimension' + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') */ - __pyx_t_5 = __Pyx_GetItemInt(__pyx_v_value_shape, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 576, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __pyx_t_1 = __Pyx_PyInt_From_int((__pyx_v_dims[0])); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 576, __pyx_L1_error) + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_value_shape, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 617, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); - __pyx_t_6 = PyObject_RichCompare(__pyx_t_5, __pyx_t_1, Py_NE); __Pyx_XGOTREF(__pyx_t_6); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 576, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_2 = __Pyx_PyInt_From_int((__pyx_v_dims[0])); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_8 = PyObject_RichCompare(__pyx_t_1, __pyx_t_2, Py_NE); __Pyx_XGOTREF(__pyx_t_8); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 617, __pyx_L1_error) __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_10 = __Pyx_PyObject_IsTrue(__pyx_t_6); if (unlikely((__pyx_t_10 < 0))) __PYX_ERR(0, 576, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; - if (!__pyx_t_10) { + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_3 = __Pyx_PyObject_IsTrue(__pyx_t_8); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(0, 617, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + if (!__pyx_t_3) { } else { - __pyx_t_4 = __pyx_t_10; - goto __pyx_L5_bool_binop_done; + __pyx_t_4 = __pyx_t_3; + goto __pyx_L6_bool_binop_done; } - __pyx_t_6 = __Pyx_GetItemInt(__pyx_v_value_shape, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 576, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_6); - __pyx_t_1 = __Pyx_PyInt_From_int((__pyx_v_dims[1])); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 576, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_5 = PyObject_RichCompare(__pyx_t_6, __pyx_t_1, Py_NE); __Pyx_XGOTREF(__pyx_t_5); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 576, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __pyx_t_8 = __Pyx_GetItemInt(__pyx_v_value_shape, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_2 = __Pyx_PyInt_From_int((__pyx_v_dims[1])); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_1 = PyObject_RichCompare(__pyx_t_8, __pyx_t_2, Py_NE); __Pyx_XGOTREF(__pyx_t_1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 617, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_3 = __Pyx_PyObject_IsTrue(__pyx_t_1); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(0, 617, __pyx_L1_error) __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_10 = __Pyx_PyObject_IsTrue(__pyx_t_5); if (unlikely((__pyx_t_10 < 0))) __PYX_ERR(0, 576, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __pyx_t_4 = __pyx_t_10; - __pyx_L5_bool_binop_done:; + __pyx_t_4 = __pyx_t_3; + __pyx_L6_bool_binop_done:; if (unlikely(__pyx_t_4)) { - /* "acados_template/acados_ocp_solver_pyx.pyx":578 + /* "acados_template/acados_ocp_solver_pyx.pyx":619 * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: * raise Exception('AcadosOcpSolverCython.cost_set(): mismatching dimension' + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') # <<<<<<<<<<<<<< * * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, \ */ - __pyx_t_5 = PyTuple_New(9); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 578, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __pyx_t_3 = 0; - __pyx_t_11 = 127; + __pyx_t_1 = PyTuple_New(9); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 619, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = 0; + __pyx_t_6 = 127; __Pyx_INCREF(__pyx_kp_u_for_field); - __pyx_t_3 += 12; + __pyx_t_5 += 12; __Pyx_GIVEREF(__pyx_kp_u_for_field); - PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_kp_u_for_field); - __pyx_t_1 = __Pyx_PyUnicode_Unicode(__pyx_v_field_); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 578, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_11 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) > __pyx_t_11) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) : __pyx_t_11; - __pyx_t_3 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); - __Pyx_GIVEREF(__pyx_t_1); - PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_1); - __pyx_t_1 = 0; + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_kp_u_for_field); + __pyx_t_2 = __Pyx_PyUnicode_Unicode(__pyx_v_field_); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 619, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_t_2); + __pyx_t_2 = 0; __Pyx_INCREF(__pyx_kp_u_at_stage); - __pyx_t_3 += 11; + __pyx_t_5 += 11; __Pyx_GIVEREF(__pyx_kp_u_at_stage); - PyTuple_SET_ITEM(__pyx_t_5, 2, __pyx_kp_u_at_stage); - __pyx_t_1 = __Pyx_PyUnicode_From_int(__pyx_v_stage, 0, ' ', 'd'); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 578, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_3 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); - __Pyx_GIVEREF(__pyx_t_1); - PyTuple_SET_ITEM(__pyx_t_5, 3, __pyx_t_1); - __pyx_t_1 = 0; + PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_kp_u_at_stage); + __pyx_t_2 = __Pyx_PyUnicode_From_int(__pyx_v_stage, 0, ' ', 'd'); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 619, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_1, 3, __pyx_t_2); + __pyx_t_2 = 0; __Pyx_INCREF(__pyx_kp_u_with_dimension); - __pyx_t_3 += 16; + __pyx_t_5 += 16; __Pyx_GIVEREF(__pyx_kp_u_with_dimension); - PyTuple_SET_ITEM(__pyx_t_5, 4, __pyx_kp_u_with_dimension); - __pyx_t_1 = __Pyx_carray_to_py_int(__pyx_v_dims, 2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 578, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_6 = __Pyx_PySequence_Tuple(__pyx_t_1); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 578, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_6); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_1 = __Pyx_PyObject_FormatSimple(__pyx_t_6, __pyx_empty_unicode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 578, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; - __pyx_t_11 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) > __pyx_t_11) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) : __pyx_t_11; - __pyx_t_3 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); - __Pyx_GIVEREF(__pyx_t_1); - PyTuple_SET_ITEM(__pyx_t_5, 5, __pyx_t_1); - __pyx_t_1 = 0; + PyTuple_SET_ITEM(__pyx_t_1, 4, __pyx_kp_u_with_dimension); + __pyx_t_2 = __Pyx_carray_to_py_int(__pyx_v_dims, 2); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 619, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_8 = __Pyx_PySequence_Tuple(__pyx_t_2); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 619, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_FormatSimple(__pyx_t_8, __pyx_empty_unicode); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 619, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_1, 5, __pyx_t_2); + __pyx_t_2 = 0; __Pyx_INCREF(__pyx_kp_u_you_have); - __pyx_t_3 += 11; + __pyx_t_5 += 11; __Pyx_GIVEREF(__pyx_kp_u_you_have); - PyTuple_SET_ITEM(__pyx_t_5, 6, __pyx_kp_u_you_have); - __pyx_t_1 = __Pyx_PyObject_FormatSimple(__pyx_v_value_shape, __pyx_empty_unicode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 578, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_11 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) > __pyx_t_11) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) : __pyx_t_11; - __pyx_t_3 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); - __Pyx_GIVEREF(__pyx_t_1); - PyTuple_SET_ITEM(__pyx_t_5, 7, __pyx_t_1); - __pyx_t_1 = 0; + PyTuple_SET_ITEM(__pyx_t_1, 6, __pyx_kp_u_you_have); + __pyx_t_2 = __Pyx_PyObject_FormatSimple(__pyx_v_value_shape, __pyx_empty_unicode); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 619, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_1, 7, __pyx_t_2); + __pyx_t_2 = 0; __Pyx_INCREF(__pyx_kp_u__7); - __pyx_t_3 += 1; + __pyx_t_5 += 1; __Pyx_GIVEREF(__pyx_kp_u__7); - PyTuple_SET_ITEM(__pyx_t_5, 8, __pyx_kp_u__7); - __pyx_t_1 = __Pyx_PyUnicode_Join(__pyx_t_5, 9, __pyx_t_3, __pyx_t_11); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 578, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + PyTuple_SET_ITEM(__pyx_t_1, 8, __pyx_kp_u__7); + __pyx_t_2 = __Pyx_PyUnicode_Join(__pyx_t_1, 9, __pyx_t_5, __pyx_t_6); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 619, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":577 + /* "acados_template/acados_ocp_solver_pyx.pyx":618 * * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: * raise Exception('AcadosOcpSolverCython.cost_set(): mismatching dimension' + # <<<<<<<<<<<<<< * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') * */ - __pyx_t_5 = __Pyx_PyUnicode_Concat(__pyx_kp_u_AcadosOcpSolverCython_cost_set_m, __pyx_t_1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 577, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_1 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_5); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 577, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyUnicode_Concat(__pyx_kp_u_AcadosOcpSolverCython_cost_set_m, __pyx_t_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 618, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 618, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __PYX_ERR(0, 577, __pyx_L1_error) + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 618, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":576 + /* "acados_template/acados_ocp_solver_pyx.pyx":617 * value = np.asfortranarray(value_) * * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: # <<<<<<<<<<<<<< @@ -27115,32 +28151,32 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":581 + /* "acados_template/acados_ocp_solver_pyx.pyx":622 * * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, \ * self.nlp_dims, self.nlp_in, stage, field, &value[0][0]) # <<<<<<<<<<<<<< * * */ - __pyx_t_12 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_12) && PyErr_Occurred())) __PYX_ERR(0, 581, __pyx_L1_error) - if (unlikely(!__pyx_v_value.memview)) { __Pyx_RaiseUnboundLocalError("value"); __PYX_ERR(0, 581, __pyx_L1_error) } + __pyx_t_12 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_12) && PyErr_Occurred())) __PYX_ERR(0, 622, __pyx_L1_error) + if (unlikely(!__pyx_v_value.memview)) { __Pyx_RaiseUnboundLocalError("value"); __PYX_ERR(0, 622, __pyx_L1_error) } __pyx_t_13 = 0; __pyx_t_14 = 0; - __pyx_t_8 = -1; + __pyx_t_10 = -1; if (__pyx_t_13 < 0) { __pyx_t_13 += __pyx_v_value.shape[0]; - if (unlikely(__pyx_t_13 < 0)) __pyx_t_8 = 0; - } else if (unlikely(__pyx_t_13 >= __pyx_v_value.shape[0])) __pyx_t_8 = 0; + if (unlikely(__pyx_t_13 < 0)) __pyx_t_10 = 0; + } else if (unlikely(__pyx_t_13 >= __pyx_v_value.shape[0])) __pyx_t_10 = 0; if (__pyx_t_14 < 0) { __pyx_t_14 += __pyx_v_value.shape[1]; - if (unlikely(__pyx_t_14 < 0)) __pyx_t_8 = 1; - } else if (unlikely(__pyx_t_14 >= __pyx_v_value.shape[1])) __pyx_t_8 = 1; - if (unlikely(__pyx_t_8 != -1)) { - __Pyx_RaiseBufferIndexError(__pyx_t_8); - __PYX_ERR(0, 581, __pyx_L1_error) + if (unlikely(__pyx_t_14 < 0)) __pyx_t_10 = 1; + } else if (unlikely(__pyx_t_14 >= __pyx_v_value.shape[1])) __pyx_t_10 = 1; + if (unlikely(__pyx_t_10 != -1)) { + __Pyx_RaiseBufferIndexError(__pyx_t_10); + __PYX_ERR(0, 622, __pyx_L1_error) } - /* "acados_template/acados_ocp_solver_pyx.pyx":580 + /* "acados_template/acados_ocp_solver_pyx.pyx":621 * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') * * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, \ # <<<<<<<<<<<<<< @@ -27149,8 +28185,8 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ (void)(ocp_nlp_cost_model_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_in, __pyx_v_stage, __pyx_t_12, ((void *)(&(*((double *) ( /* dim=1 */ (( /* dim=0 */ ((char *) (((double *) __pyx_v_value.data) + __pyx_t_13)) ) + __pyx_t_14 * __pyx_v_value.strides[1]) ))))))); - /* "acados_template/acados_ocp_solver_pyx.pyx":551 - * + /* "acados_template/acados_ocp_solver_pyx.pyx":590 + * return * * def cost_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< * """ @@ -27162,10 +28198,10 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS goto __pyx_L0; __pyx_L1_error:; __Pyx_XDECREF(__pyx_t_1); - __Pyx_XDECREF(__pyx_t_5); - __Pyx_XDECREF(__pyx_t_6); - __Pyx_XDECREF(__pyx_t_7); - __PYX_XCLEAR_MEMVIEW(&__pyx_t_9, 1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_XDECREF(__pyx_t_9); + __PYX_XCLEAR_MEMVIEW(&__pyx_t_11, 1); __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.cost_set", __pyx_clineno, __pyx_lineno, __pyx_filename); __pyx_r = NULL; __pyx_L0:; @@ -27177,7 +28213,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":584 +/* "acados_template/acados_ocp_solver_pyx.pyx":625 * * * def constraints_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< @@ -27186,16 +28222,16 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ /* Python wrapper */ -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39constraints_set(PyObject *__pyx_v_self, +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43constraints_set(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else PyObject *__pyx_args, PyObject *__pyx_kwds #endif ); /*proto*/ -PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38constraints_set, "\n Set numerical data in the constraint module of the solver.\n\n :param stage: integer corresponding to shooting node\n :param field: string in ['lbx', 'ubx', 'lbu', 'ubu', 'lg', 'ug', 'lh', 'uh', 'uphi', 'C', 'D']\n :param value: of appropriate size\n "); -static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39constraints_set = {"constraints_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39constraints_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38constraints_set}; -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39constraints_set(PyObject *__pyx_v_self, +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42constraints_set, "\n Set numerical data in the constraint module of the solver.\n\n :param stage: integer corresponding to shooting node\n :param field: string in ['lbx', 'ubx', 'lbu', 'ubu', 'lg', 'ug', 'lh', 'uh', 'uphi', 'C', 'D']\n :param value: of appropriate size\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43constraints_set = {"constraints_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43constraints_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42constraints_set}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43constraints_set(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else @@ -27234,26 +28270,26 @@ PyObject *__pyx_args, PyObject *__pyx_kwds switch (__pyx_nargs) { case 0: if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_stage)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 584, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 625, __pyx_L3_error) else goto __pyx_L5_argtuple_error; CYTHON_FALLTHROUGH; case 1: if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field_2)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 584, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 625, __pyx_L3_error) else { - __Pyx_RaiseArgtupleInvalid("constraints_set", 1, 3, 3, 1); __PYX_ERR(0, 584, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("constraints_set", 1, 3, 3, 1); __PYX_ERR(0, 625, __pyx_L3_error) } CYTHON_FALLTHROUGH; case 2: if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_value)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 584, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 625, __pyx_L3_error) else { - __Pyx_RaiseArgtupleInvalid("constraints_set", 1, 3, 3, 2); __PYX_ERR(0, 584, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("constraints_set", 1, 3, 3, 2); __PYX_ERR(0, 625, __pyx_L3_error) } } if (unlikely(kw_args > 0)) { const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "constraints_set") < 0)) __PYX_ERR(0, 584, __pyx_L3_error) + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "constraints_set") < 0)) __PYX_ERR(0, 625, __pyx_L3_error) } } else if (unlikely(__pyx_nargs != 3)) { goto __pyx_L5_argtuple_error; @@ -27262,20 +28298,20 @@ PyObject *__pyx_args, PyObject *__pyx_kwds values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); } - __pyx_v_stage = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_stage == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 584, __pyx_L3_error) + __pyx_v_stage = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_stage == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 625, __pyx_L3_error) __pyx_v_field_ = ((PyObject*)values[1]); __pyx_v_value_ = values[2]; } goto __pyx_L4_argument_unpacking_done; __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("constraints_set", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 584, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("constraints_set", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 625, __pyx_L3_error) __pyx_L3_error:; __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.constraints_set", __pyx_clineno, __pyx_lineno, __pyx_filename); __Pyx_RefNannyFinishContext(); return NULL; __pyx_L4_argument_unpacking_done:; - if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 584, __pyx_L1_error) - __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38constraints_set(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_stage, __pyx_v_field_, __pyx_v_value_); + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 625, __pyx_L1_error) + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42constraints_set(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_stage, __pyx_v_field_, __pyx_v_value_); /* function exit code */ goto __pyx_L0; @@ -27286,7 +28322,7 @@ PyObject *__pyx_args, PyObject *__pyx_kwds return __pyx_r; } -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38constraints_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_) { +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42constraints_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_) { PyObject *__pyx_v_field = NULL; int __pyx_v_dims[2]; __Pyx_memviewslice __pyx_v_value = { 0, 0, { 0 }, { 0 }, { 0 } }; @@ -27294,16 +28330,16 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_r = NULL; __Pyx_RefNannyDeclarations PyObject *__pyx_t_1 = NULL; - char const *__pyx_t_2; - Py_ssize_t __pyx_t_3; + PyObject *__pyx_t_2 = NULL; + int __pyx_t_3; int __pyx_t_4; - PyObject *__pyx_t_5 = NULL; - PyObject *__pyx_t_6 = NULL; - PyObject *__pyx_t_7 = NULL; - int __pyx_t_8; - __Pyx_memviewslice __pyx_t_9 = { 0, 0, { 0 }, { 0 }, { 0 } }; + Py_ssize_t __pyx_t_5; + Py_UCS4 __pyx_t_6; + char const *__pyx_t_7; + PyObject *__pyx_t_8 = NULL; + PyObject *__pyx_t_9 = NULL; int __pyx_t_10; - Py_UCS4 __pyx_t_11; + __Pyx_memviewslice __pyx_t_11 = { 0, 0, { 0 }, { 0 }, { 0 } }; char const *__pyx_t_12; Py_ssize_t __pyx_t_13; Py_ssize_t __pyx_t_14; @@ -27312,184 +28348,246 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS int __pyx_clineno = 0; __Pyx_RefNannySetupContext("constraints_set", 0); - /* "acados_template/acados_ocp_solver_pyx.pyx":592 + /* "acados_template/acados_ocp_solver_pyx.pyx":633 * :param value: of appropriate size * """ + * if not isinstance(value_, np.ndarray): # <<<<<<<<<<<<<< + * raise Exception(f"constraints_set: value must be numpy array, got {type(value_)}.") + * + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 633, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_ndarray); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 633, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_3 = PyObject_IsInstance(__pyx_v_value_, __pyx_t_2); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(0, 633, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_4 = (!__pyx_t_3); + if (unlikely(__pyx_t_4)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":634 + * """ + * if not isinstance(value_, np.ndarray): + * raise Exception(f"constraints_set: value must be numpy array, got {type(value_)}.") # <<<<<<<<<<<<<< + * + * field = field_.encode('utf-8') + */ + __pyx_t_2 = PyTuple_New(3); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 634, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_5 = 0; + __pyx_t_6 = 127; + __Pyx_INCREF(__pyx_kp_u_constraints_set_value_must_be_nu); + __pyx_t_5 += 48; + __Pyx_GIVEREF(__pyx_kp_u_constraints_set_value_must_be_nu); + PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_kp_u_constraints_set_value_must_be_nu); + __pyx_t_1 = __Pyx_PyObject_FormatSimple(((PyObject *)Py_TYPE(__pyx_v_value_)), __pyx_empty_unicode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 634, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_2, 1, __pyx_t_1); + __pyx_t_1 = 0; + __Pyx_INCREF(__pyx_kp_u__2); + __pyx_t_5 += 1; + __Pyx_GIVEREF(__pyx_kp_u__2); + PyTuple_SET_ITEM(__pyx_t_2, 2, __pyx_kp_u__2); + __pyx_t_1 = __Pyx_PyUnicode_Join(__pyx_t_2, 3, __pyx_t_5, __pyx_t_6); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 634, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 634, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 634, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":633 + * :param value: of appropriate size + * """ + * if not isinstance(value_, np.ndarray): # <<<<<<<<<<<<<< + * raise Exception(f"constraints_set: value must be numpy array, got {type(value_)}.") + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":636 + * raise Exception(f"constraints_set: value must be numpy array, got {type(value_)}.") + * * field = field_.encode('utf-8') # <<<<<<<<<<<<<< * * cdef int dims[2] */ if (unlikely(__pyx_v_field_ == Py_None)) { PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "encode"); - __PYX_ERR(0, 592, __pyx_L1_error) + __PYX_ERR(0, 636, __pyx_L1_error) } - __pyx_t_1 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 592, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_v_field = __pyx_t_1; - __pyx_t_1 = 0; + __pyx_t_2 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 636, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_v_field = __pyx_t_2; + __pyx_t_2 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":596 + /* "acados_template/acados_ocp_solver_pyx.pyx":640 * cdef int dims[2] * acados_solver_common.ocp_nlp_constraint_dims_get_from_attr(self.nlp_config, \ * self.nlp_dims, self.nlp_out, stage, field, &dims[0]) # <<<<<<<<<<<<<< * * cdef double[::1,:] value */ - __pyx_t_2 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_2) && PyErr_Occurred())) __PYX_ERR(0, 596, __pyx_L1_error) + __pyx_t_7 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 640, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":595 + /* "acados_template/acados_ocp_solver_pyx.pyx":639 * * cdef int dims[2] * acados_solver_common.ocp_nlp_constraint_dims_get_from_attr(self.nlp_config, \ # <<<<<<<<<<<<<< * self.nlp_dims, self.nlp_out, stage, field, &dims[0]) * */ - ocp_nlp_constraint_dims_get_from_attr(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_2, (&(__pyx_v_dims[0]))); + ocp_nlp_constraint_dims_get_from_attr(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_7, (&(__pyx_v_dims[0]))); - /* "acados_template/acados_ocp_solver_pyx.pyx":600 + /* "acados_template/acados_ocp_solver_pyx.pyx":644 * cdef double[::1,:] value * * value_shape = value_.shape # <<<<<<<<<<<<<< * if len(value_shape) == 1: * value_shape = (value_shape[0], 0) */ - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_value_, __pyx_n_s_shape); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 600, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_v_value_shape = __pyx_t_1; - __pyx_t_1 = 0; + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_value_, __pyx_n_s_shape); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 644, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_v_value_shape = __pyx_t_2; + __pyx_t_2 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":601 + /* "acados_template/acados_ocp_solver_pyx.pyx":645 * * value_shape = value_.shape * if len(value_shape) == 1: # <<<<<<<<<<<<<< * value_shape = (value_shape[0], 0) * value = np.asfortranarray(value_[None,:]) */ - __pyx_t_3 = PyObject_Length(__pyx_v_value_shape); if (unlikely(__pyx_t_3 == ((Py_ssize_t)-1))) __PYX_ERR(0, 601, __pyx_L1_error) - __pyx_t_4 = (__pyx_t_3 == 1); + __pyx_t_5 = PyObject_Length(__pyx_v_value_shape); if (unlikely(__pyx_t_5 == ((Py_ssize_t)-1))) __PYX_ERR(0, 645, __pyx_L1_error) + __pyx_t_4 = (__pyx_t_5 == 1); if (__pyx_t_4) { - /* "acados_template/acados_ocp_solver_pyx.pyx":602 + /* "acados_template/acados_ocp_solver_pyx.pyx":646 * value_shape = value_.shape * if len(value_shape) == 1: * value_shape = (value_shape[0], 0) # <<<<<<<<<<<<<< * value = np.asfortranarray(value_[None,:]) * */ - __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_value_shape, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 602, __pyx_L1_error) + __pyx_t_2 = __Pyx_GetItemInt(__pyx_v_value_shape, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 646, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_1 = PyTuple_New(2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 646, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); - __pyx_t_5 = PyTuple_New(2); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 602, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_GIVEREF(__pyx_t_1); - PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_t_1); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_t_2); __Pyx_INCREF(__pyx_int_0); __Pyx_GIVEREF(__pyx_int_0); - PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_int_0); + PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_int_0); + __pyx_t_2 = 0; + __Pyx_DECREF_SET(__pyx_v_value_shape, __pyx_t_1); __pyx_t_1 = 0; - __Pyx_DECREF_SET(__pyx_v_value_shape, __pyx_t_5); - __pyx_t_5 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":603 + /* "acados_template/acados_ocp_solver_pyx.pyx":647 * if len(value_shape) == 1: * value_shape = (value_shape[0], 0) * value = np.asfortranarray(value_[None,:]) # <<<<<<<<<<<<<< * * elif len(value_shape) == 2: */ - __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 603, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_asfortranarray); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 603, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_6); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_1 = __Pyx_PyObject_GetItem(__pyx_v_value_, __pyx_tuple__26); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 603, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_7 = NULL; - __pyx_t_8 = 0; - if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_6))) { - __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_6); - if (likely(__pyx_t_7)) { - PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_6); - __Pyx_INCREF(__pyx_t_7); + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_np); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 647, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_asfortranarray); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 647, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_v_value_, __pyx_tuple__28); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 647, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_9 = NULL; + __pyx_t_10 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_8))) { + __pyx_t_9 = PyMethod_GET_SELF(__pyx_t_8); + if (likely(__pyx_t_9)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_8); + __Pyx_INCREF(__pyx_t_9); __Pyx_INCREF(function); - __Pyx_DECREF_SET(__pyx_t_6, function); - __pyx_t_8 = 1; + __Pyx_DECREF_SET(__pyx_t_8, function); + __pyx_t_10 = 1; } } { - PyObject *__pyx_callargs[2] = {__pyx_t_7, __pyx_t_1}; - __pyx_t_5 = __Pyx_PyObject_FastCall(__pyx_t_6, __pyx_callargs+1-__pyx_t_8, 1+__pyx_t_8); - __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 603, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + PyObject *__pyx_callargs[2] = {__pyx_t_9, __pyx_t_2}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_8, __pyx_callargs+1-__pyx_t_10, 1+__pyx_t_10); + __Pyx_XDECREF(__pyx_t_9); __pyx_t_9 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 647, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; } - __pyx_t_9 = __Pyx_PyObject_to_MemoryviewSlice_dcd__double(__pyx_t_5, PyBUF_WRITABLE); if (unlikely(!__pyx_t_9.memview)) __PYX_ERR(0, 603, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __pyx_v_value = __pyx_t_9; - __pyx_t_9.memview = NULL; - __pyx_t_9.data = NULL; + __pyx_t_11 = __Pyx_PyObject_to_MemoryviewSlice_dcd__double(__pyx_t_1, PyBUF_WRITABLE); if (unlikely(!__pyx_t_11.memview)) __PYX_ERR(0, 647, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_value = __pyx_t_11; + __pyx_t_11.memview = NULL; + __pyx_t_11.data = NULL; - /* "acados_template/acados_ocp_solver_pyx.pyx":601 + /* "acados_template/acados_ocp_solver_pyx.pyx":645 * * value_shape = value_.shape * if len(value_shape) == 1: # <<<<<<<<<<<<<< * value_shape = (value_shape[0], 0) * value = np.asfortranarray(value_[None,:]) */ - goto __pyx_L3; + goto __pyx_L4; } - /* "acados_template/acados_ocp_solver_pyx.pyx":605 + /* "acados_template/acados_ocp_solver_pyx.pyx":649 * value = np.asfortranarray(value_[None,:]) * * elif len(value_shape) == 2: # <<<<<<<<<<<<<< * # Get elements in column major order * value = np.asfortranarray(value_) */ - __pyx_t_3 = PyObject_Length(__pyx_v_value_shape); if (unlikely(__pyx_t_3 == ((Py_ssize_t)-1))) __PYX_ERR(0, 605, __pyx_L1_error) - __pyx_t_4 = (__pyx_t_3 == 2); + __pyx_t_5 = PyObject_Length(__pyx_v_value_shape); if (unlikely(__pyx_t_5 == ((Py_ssize_t)-1))) __PYX_ERR(0, 649, __pyx_L1_error) + __pyx_t_4 = (__pyx_t_5 == 2); if (__pyx_t_4) { - /* "acados_template/acados_ocp_solver_pyx.pyx":607 + /* "acados_template/acados_ocp_solver_pyx.pyx":651 * elif len(value_shape) == 2: * # Get elements in column major order * value = np.asfortranarray(value_) # <<<<<<<<<<<<<< * - * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: + * if value_shape != tuple(dims): */ - __Pyx_GetModuleGlobalName(__pyx_t_6, __pyx_n_s_np); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 607, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_6); - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_6, __pyx_n_s_asfortranarray); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 607, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; - __pyx_t_6 = NULL; - __pyx_t_8 = 0; - if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_1))) { - __pyx_t_6 = PyMethod_GET_SELF(__pyx_t_1); - if (likely(__pyx_t_6)) { - PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); - __Pyx_INCREF(__pyx_t_6); + __Pyx_GetModuleGlobalName(__pyx_t_8, __pyx_n_s_np); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 651, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_8, __pyx_n_s_asfortranarray); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 651, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_t_8 = NULL; + __pyx_t_10 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_8 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_8)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_8); __Pyx_INCREF(function); - __Pyx_DECREF_SET(__pyx_t_1, function); - __pyx_t_8 = 1; + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_10 = 1; } } { - PyObject *__pyx_callargs[2] = {__pyx_t_6, __pyx_v_value_}; - __pyx_t_5 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_8, 1+__pyx_t_8); - __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; - if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 607, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + PyObject *__pyx_callargs[2] = {__pyx_t_8, __pyx_v_value_}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_10, 1+__pyx_t_10); + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 651, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; } - __pyx_t_9 = __Pyx_PyObject_to_MemoryviewSlice_dcd__double(__pyx_t_5, PyBUF_WRITABLE); if (unlikely(!__pyx_t_9.memview)) __PYX_ERR(0, 607, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __pyx_v_value = __pyx_t_9; - __pyx_t_9.memview = NULL; - __pyx_t_9.data = NULL; + __pyx_t_11 = __Pyx_PyObject_to_MemoryviewSlice_dcd__double(__pyx_t_1, PyBUF_WRITABLE); if (unlikely(!__pyx_t_11.memview)) __PYX_ERR(0, 651, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_value = __pyx_t_11; + __pyx_t_11.memview = NULL; + __pyx_t_11.data = NULL; - /* "acados_template/acados_ocp_solver_pyx.pyx":605 + /* "acados_template/acados_ocp_solver_pyx.pyx":649 * value = np.asfortranarray(value_[None,:]) * * elif len(value_shape) == 2: # <<<<<<<<<<<<<< @@ -27497,162 +28595,146 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS * value = np.asfortranarray(value_) */ } - __pyx_L3:; + __pyx_L4:; - /* "acados_template/acados_ocp_solver_pyx.pyx":609 + /* "acados_template/acados_ocp_solver_pyx.pyx":653 * value = np.asfortranarray(value_) * - * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: # <<<<<<<<<<<<<< + * if value_shape != tuple(dims): # <<<<<<<<<<<<<< * raise Exception(f'AcadosOcpSolverCython.constraints_set(): mismatching dimension' + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') */ - __pyx_t_5 = __Pyx_GetItemInt(__pyx_v_value_shape, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 609, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __pyx_t_1 = __Pyx_PyInt_From_int((__pyx_v_dims[0])); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 609, __pyx_L1_error) + __pyx_t_1 = __Pyx_carray_to_py_int(__pyx_v_dims, 2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 653, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); - __pyx_t_6 = PyObject_RichCompare(__pyx_t_5, __pyx_t_1, Py_NE); __Pyx_XGOTREF(__pyx_t_6); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 609, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_2 = __Pyx_PySequence_Tuple(__pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 653, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_10 = __Pyx_PyObject_IsTrue(__pyx_t_6); if (unlikely((__pyx_t_10 < 0))) __PYX_ERR(0, 609, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; - if (!__pyx_t_10) { - } else { - __pyx_t_4 = __pyx_t_10; - goto __pyx_L5_bool_binop_done; - } - __pyx_t_6 = __Pyx_GetItemInt(__pyx_v_value_shape, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 609, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_6); - __pyx_t_1 = __Pyx_PyInt_From_int((__pyx_v_dims[1])); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 609, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_5 = PyObject_RichCompare(__pyx_t_6, __pyx_t_1, Py_NE); __Pyx_XGOTREF(__pyx_t_5); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 609, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __pyx_t_1 = PyObject_RichCompare(__pyx_v_value_shape, __pyx_t_2, Py_NE); __Pyx_XGOTREF(__pyx_t_1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 653, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_t_1); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 653, __pyx_L1_error) __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_10 = __Pyx_PyObject_IsTrue(__pyx_t_5); if (unlikely((__pyx_t_10 < 0))) __PYX_ERR(0, 609, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __pyx_t_4 = __pyx_t_10; - __pyx_L5_bool_binop_done:; if (unlikely(__pyx_t_4)) { - /* "acados_template/acados_ocp_solver_pyx.pyx":611 - * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: + /* "acados_template/acados_ocp_solver_pyx.pyx":655 + * if value_shape != tuple(dims): * raise Exception(f'AcadosOcpSolverCython.constraints_set(): mismatching dimension' + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') # <<<<<<<<<<<<<< * * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, \ */ - __pyx_t_5 = PyTuple_New(9); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 611, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __pyx_t_3 = 0; - __pyx_t_11 = 127; + __pyx_t_1 = PyTuple_New(9); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 655, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = 0; + __pyx_t_6 = 127; __Pyx_INCREF(__pyx_kp_u_for_field); - __pyx_t_3 += 12; + __pyx_t_5 += 12; __Pyx_GIVEREF(__pyx_kp_u_for_field); - PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_kp_u_for_field); - __pyx_t_1 = __Pyx_PyUnicode_Unicode(__pyx_v_field_); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 611, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_11 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) > __pyx_t_11) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) : __pyx_t_11; - __pyx_t_3 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); - __Pyx_GIVEREF(__pyx_t_1); - PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_1); - __pyx_t_1 = 0; + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_kp_u_for_field); + __pyx_t_2 = __Pyx_PyUnicode_Unicode(__pyx_v_field_); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 655, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_t_2); + __pyx_t_2 = 0; __Pyx_INCREF(__pyx_kp_u_at_stage); - __pyx_t_3 += 11; + __pyx_t_5 += 11; __Pyx_GIVEREF(__pyx_kp_u_at_stage); - PyTuple_SET_ITEM(__pyx_t_5, 2, __pyx_kp_u_at_stage); - __pyx_t_1 = __Pyx_PyUnicode_From_int(__pyx_v_stage, 0, ' ', 'd'); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 611, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_3 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); - __Pyx_GIVEREF(__pyx_t_1); - PyTuple_SET_ITEM(__pyx_t_5, 3, __pyx_t_1); - __pyx_t_1 = 0; + PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_kp_u_at_stage); + __pyx_t_2 = __Pyx_PyUnicode_From_int(__pyx_v_stage, 0, ' ', 'd'); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 655, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_1, 3, __pyx_t_2); + __pyx_t_2 = 0; __Pyx_INCREF(__pyx_kp_u_with_dimension); - __pyx_t_3 += 16; + __pyx_t_5 += 16; __Pyx_GIVEREF(__pyx_kp_u_with_dimension); - PyTuple_SET_ITEM(__pyx_t_5, 4, __pyx_kp_u_with_dimension); - __pyx_t_1 = __Pyx_carray_to_py_int(__pyx_v_dims, 2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 611, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_6 = __Pyx_PySequence_Tuple(__pyx_t_1); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 611, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_6); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_1 = __Pyx_PyObject_FormatSimple(__pyx_t_6, __pyx_empty_unicode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 611, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; - __pyx_t_11 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) > __pyx_t_11) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) : __pyx_t_11; - __pyx_t_3 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); - __Pyx_GIVEREF(__pyx_t_1); - PyTuple_SET_ITEM(__pyx_t_5, 5, __pyx_t_1); - __pyx_t_1 = 0; + PyTuple_SET_ITEM(__pyx_t_1, 4, __pyx_kp_u_with_dimension); + __pyx_t_2 = __Pyx_carray_to_py_int(__pyx_v_dims, 2); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 655, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_8 = __Pyx_PySequence_Tuple(__pyx_t_2); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 655, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_FormatSimple(__pyx_t_8, __pyx_empty_unicode); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 655, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_1, 5, __pyx_t_2); + __pyx_t_2 = 0; __Pyx_INCREF(__pyx_kp_u_you_have); - __pyx_t_3 += 11; + __pyx_t_5 += 11; __Pyx_GIVEREF(__pyx_kp_u_you_have); - PyTuple_SET_ITEM(__pyx_t_5, 6, __pyx_kp_u_you_have); - __pyx_t_1 = __Pyx_PyObject_FormatSimple(__pyx_v_value_shape, __pyx_empty_unicode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 611, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_11 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) > __pyx_t_11) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) : __pyx_t_11; - __pyx_t_3 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); - __Pyx_GIVEREF(__pyx_t_1); - PyTuple_SET_ITEM(__pyx_t_5, 7, __pyx_t_1); - __pyx_t_1 = 0; + PyTuple_SET_ITEM(__pyx_t_1, 6, __pyx_kp_u_you_have); + __pyx_t_2 = __Pyx_PyObject_FormatSimple(__pyx_v_value_shape, __pyx_empty_unicode); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 655, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_1, 7, __pyx_t_2); + __pyx_t_2 = 0; __Pyx_INCREF(__pyx_kp_u__7); - __pyx_t_3 += 1; + __pyx_t_5 += 1; __Pyx_GIVEREF(__pyx_kp_u__7); - PyTuple_SET_ITEM(__pyx_t_5, 8, __pyx_kp_u__7); - __pyx_t_1 = __Pyx_PyUnicode_Join(__pyx_t_5, 9, __pyx_t_3, __pyx_t_11); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 611, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + PyTuple_SET_ITEM(__pyx_t_1, 8, __pyx_kp_u__7); + __pyx_t_2 = __Pyx_PyUnicode_Join(__pyx_t_1, 9, __pyx_t_5, __pyx_t_6); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 655, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":610 + /* "acados_template/acados_ocp_solver_pyx.pyx":654 * - * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: + * if value_shape != tuple(dims): * raise Exception(f'AcadosOcpSolverCython.constraints_set(): mismatching dimension' + # <<<<<<<<<<<<<< * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') * */ - __pyx_t_5 = __Pyx_PyUnicode_Concat(__pyx_kp_u_AcadosOcpSolverCython_constraint, __pyx_t_1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 610, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_1 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_5); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 610, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyUnicode_Concat(__pyx_kp_u_AcadosOcpSolverCython_constraint, __pyx_t_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 654, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 654, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __PYX_ERR(0, 610, __pyx_L1_error) + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 654, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":609 + /* "acados_template/acados_ocp_solver_pyx.pyx":653 * value = np.asfortranarray(value_) * - * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: # <<<<<<<<<<<<<< + * if value_shape != tuple(dims): # <<<<<<<<<<<<<< * raise Exception(f'AcadosOcpSolverCython.constraints_set(): mismatching dimension' + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":614 + /* "acados_template/acados_ocp_solver_pyx.pyx":658 * * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, \ * self.nlp_dims, self.nlp_in, stage, field, &value[0][0]) # <<<<<<<<<<<<<< * * return */ - __pyx_t_12 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_12) && PyErr_Occurred())) __PYX_ERR(0, 614, __pyx_L1_error) - if (unlikely(!__pyx_v_value.memview)) { __Pyx_RaiseUnboundLocalError("value"); __PYX_ERR(0, 614, __pyx_L1_error) } + __pyx_t_12 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_12) && PyErr_Occurred())) __PYX_ERR(0, 658, __pyx_L1_error) + if (unlikely(!__pyx_v_value.memview)) { __Pyx_RaiseUnboundLocalError("value"); __PYX_ERR(0, 658, __pyx_L1_error) } __pyx_t_13 = 0; __pyx_t_14 = 0; - __pyx_t_8 = -1; + __pyx_t_10 = -1; if (__pyx_t_13 < 0) { __pyx_t_13 += __pyx_v_value.shape[0]; - if (unlikely(__pyx_t_13 < 0)) __pyx_t_8 = 0; - } else if (unlikely(__pyx_t_13 >= __pyx_v_value.shape[0])) __pyx_t_8 = 0; + if (unlikely(__pyx_t_13 < 0)) __pyx_t_10 = 0; + } else if (unlikely(__pyx_t_13 >= __pyx_v_value.shape[0])) __pyx_t_10 = 0; if (__pyx_t_14 < 0) { __pyx_t_14 += __pyx_v_value.shape[1]; - if (unlikely(__pyx_t_14 < 0)) __pyx_t_8 = 1; - } else if (unlikely(__pyx_t_14 >= __pyx_v_value.shape[1])) __pyx_t_8 = 1; - if (unlikely(__pyx_t_8 != -1)) { - __Pyx_RaiseBufferIndexError(__pyx_t_8); - __PYX_ERR(0, 614, __pyx_L1_error) + if (unlikely(__pyx_t_14 < 0)) __pyx_t_10 = 1; + } else if (unlikely(__pyx_t_14 >= __pyx_v_value.shape[1])) __pyx_t_10 = 1; + if (unlikely(__pyx_t_10 != -1)) { + __Pyx_RaiseBufferIndexError(__pyx_t_10); + __PYX_ERR(0, 658, __pyx_L1_error) } - /* "acados_template/acados_ocp_solver_pyx.pyx":613 + /* "acados_template/acados_ocp_solver_pyx.pyx":657 * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') * * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, \ # <<<<<<<<<<<<<< @@ -27661,7 +28743,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ (void)(ocp_nlp_constraints_model_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_in, __pyx_v_stage, __pyx_t_12, ((void *)(&(*((double *) ( /* dim=1 */ (( /* dim=0 */ ((char *) (((double *) __pyx_v_value.data) + __pyx_t_13)) ) + __pyx_t_14 * __pyx_v_value.strides[1]) ))))))); - /* "acados_template/acados_ocp_solver_pyx.pyx":616 + /* "acados_template/acados_ocp_solver_pyx.pyx":660 * self.nlp_dims, self.nlp_in, stage, field, &value[0][0]) * * return # <<<<<<<<<<<<<< @@ -27672,7 +28754,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_r = Py_None; __Pyx_INCREF(Py_None); goto __pyx_L0; - /* "acados_template/acados_ocp_solver_pyx.pyx":584 + /* "acados_template/acados_ocp_solver_pyx.pyx":625 * * * def constraints_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< @@ -27683,10 +28765,10 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS /* function exit code */ __pyx_L1_error:; __Pyx_XDECREF(__pyx_t_1); - __Pyx_XDECREF(__pyx_t_5); - __Pyx_XDECREF(__pyx_t_6); - __Pyx_XDECREF(__pyx_t_7); - __PYX_XCLEAR_MEMVIEW(&__pyx_t_9, 1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_XDECREF(__pyx_t_9); + __PYX_XCLEAR_MEMVIEW(&__pyx_t_11, 1); __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.constraints_set", __pyx_clineno, __pyx_lineno, __pyx_filename); __pyx_r = NULL; __pyx_L0:; @@ -27698,25 +28780,25 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":619 +/* "acados_template/acados_ocp_solver_pyx.pyx":663 * * - * def dynamics_get(self, int stage, str field_): # <<<<<<<<<<<<<< + * def get_from_qp_in(self, int stage, str field_): # <<<<<<<<<<<<<< * """ * Get numerical data from the dynamics module of the solver: */ /* Python wrapper */ -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41dynamics_get(PyObject *__pyx_v_self, +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_45get_from_qp_in(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else PyObject *__pyx_args, PyObject *__pyx_kwds #endif ); /*proto*/ -PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40dynamics_get, "\n Get numerical data from the dynamics module of the solver:\n\n :param stage: integer corresponding to shooting node\n :param field: string, e.g. 'A'\n "); -static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41dynamics_get = {"dynamics_get", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41dynamics_get, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40dynamics_get}; -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41dynamics_get(PyObject *__pyx_v_self, +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_44get_from_qp_in, "\n Get numerical data from the dynamics module of the solver:\n\n :param stage: integer corresponding to shooting node\n :param field: string, e.g. 'A'\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_45get_from_qp_in = {"get_from_qp_in", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_45get_from_qp_in, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_44get_from_qp_in}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_45get_from_qp_in(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else @@ -27734,7 +28816,7 @@ PyObject *__pyx_args, PyObject *__pyx_kwds int __pyx_clineno = 0; PyObject *__pyx_r = 0; __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("dynamics_get (wrapper)", 0); + __Pyx_RefNannySetupContext("get_from_qp_in (wrapper)", 0); { PyObject **__pyx_pyargnames[] = {&__pyx_n_s_stage,&__pyx_n_s_field_2,0}; PyObject* values[2] = {0,0}; @@ -27752,19 +28834,19 @@ PyObject *__pyx_args, PyObject *__pyx_kwds switch (__pyx_nargs) { case 0: if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_stage)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 619, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 663, __pyx_L3_error) else goto __pyx_L5_argtuple_error; CYTHON_FALLTHROUGH; case 1: if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field_2)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 619, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 663, __pyx_L3_error) else { - __Pyx_RaiseArgtupleInvalid("dynamics_get", 1, 2, 2, 1); __PYX_ERR(0, 619, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("get_from_qp_in", 1, 2, 2, 1); __PYX_ERR(0, 663, __pyx_L3_error) } } if (unlikely(kw_args > 0)) { const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "dynamics_get") < 0)) __PYX_ERR(0, 619, __pyx_L3_error) + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "get_from_qp_in") < 0)) __PYX_ERR(0, 663, __pyx_L3_error) } } else if (unlikely(__pyx_nargs != 2)) { goto __pyx_L5_argtuple_error; @@ -27772,19 +28854,19 @@ PyObject *__pyx_args, PyObject *__pyx_kwds values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); } - __pyx_v_stage = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_stage == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 619, __pyx_L3_error) + __pyx_v_stage = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_stage == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 663, __pyx_L3_error) __pyx_v_field_ = ((PyObject*)values[1]); } goto __pyx_L4_argument_unpacking_done; __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("dynamics_get", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 619, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("get_from_qp_in", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 663, __pyx_L3_error) __pyx_L3_error:; - __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.dynamics_get", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.get_from_qp_in", __pyx_clineno, __pyx_lineno, __pyx_filename); __Pyx_RefNannyFinishContext(); return NULL; __pyx_L4_argument_unpacking_done:; - if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 619, __pyx_L1_error) - __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40dynamics_get(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_stage, __pyx_v_field_); + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 663, __pyx_L1_error) + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_44get_from_qp_in(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_stage, __pyx_v_field_); /* function exit code */ goto __pyx_L0; @@ -27795,7 +28877,7 @@ PyObject *__pyx_args, PyObject *__pyx_kwds return __pyx_r; } -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40dynamics_get(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_) { +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_44get_from_qp_in(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_) { PyObject *__pyx_v_field = NULL; int __pyx_v_dims[2]; PyArrayObject *__pyx_v_out = 0; @@ -27814,13 +28896,13 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS int __pyx_lineno = 0; const char *__pyx_filename = NULL; int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("dynamics_get", 0); + __Pyx_RefNannySetupContext("get_from_qp_in", 0); __pyx_pybuffer_out.pybuffer.buf = NULL; __pyx_pybuffer_out.refcount = 0; __pyx_pybuffernd_out.data = NULL; __pyx_pybuffernd_out.rcbuffer = &__pyx_pybuffer_out; - /* "acados_template/acados_ocp_solver_pyx.pyx":626 + /* "acados_template/acados_ocp_solver_pyx.pyx":670 * :param field: string, e.g. 'A' * """ * field = field_.encode('utf-8') # <<<<<<<<<<<<<< @@ -27829,40 +28911,40 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ if (unlikely(__pyx_v_field_ == Py_None)) { PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "encode"); - __PYX_ERR(0, 626, __pyx_L1_error) + __PYX_ERR(0, 670, __pyx_L1_error) } - __pyx_t_1 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 626, __pyx_L1_error) + __pyx_t_1 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 670, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __pyx_v_field = __pyx_t_1; __pyx_t_1 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":630 + /* "acados_template/acados_ocp_solver_pyx.pyx":674 * # get dims * cdef int[2] dims - * acados_solver_common.ocp_nlp_dynamics_dims_get_from_attr(self.nlp_config, self.nlp_dims, self.nlp_out, stage, field, &dims[0]) # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_qp_dims_get_from_attr(self.nlp_config, self.nlp_dims, self.nlp_out, stage, field, &dims[0]) # <<<<<<<<<<<<<< * * # create output data */ - __pyx_t_2 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_2) && PyErr_Occurred())) __PYX_ERR(0, 630, __pyx_L1_error) - ocp_nlp_dynamics_dims_get_from_attr(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_2, (&(__pyx_v_dims[0]))); + __pyx_t_2 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_2) && PyErr_Occurred())) __PYX_ERR(0, 674, __pyx_L1_error) + ocp_nlp_qp_dims_get_from_attr(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_2, (&(__pyx_v_dims[0]))); - /* "acados_template/acados_ocp_solver_pyx.pyx":633 + /* "acados_template/acados_ocp_solver_pyx.pyx":677 * * # create output data * cdef cnp.ndarray[cnp.float64_t, ndim=2] out = np.zeros((dims[0], dims[1]), order='F') # <<<<<<<<<<<<<< * * # call getter */ - __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 633, __pyx_L1_error) + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 677, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); - __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_zeros); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 633, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_zeros); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 677, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_1 = __Pyx_PyInt_From_int((__pyx_v_dims[0])); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 633, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyInt_From_int((__pyx_v_dims[0])); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 677, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); - __pyx_t_4 = __Pyx_PyInt_From_int((__pyx_v_dims[1])); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 633, __pyx_L1_error) + __pyx_t_4 = __Pyx_PyInt_From_int((__pyx_v_dims[1])); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 677, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); - __pyx_t_5 = PyTuple_New(2); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 633, __pyx_L1_error) + __pyx_t_5 = PyTuple_New(2); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 677, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_5); __Pyx_GIVEREF(__pyx_t_1); PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_t_1); @@ -27870,26 +28952,26 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_4); __pyx_t_1 = 0; __pyx_t_4 = 0; - __pyx_t_4 = PyTuple_New(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 633, __pyx_L1_error) + __pyx_t_4 = PyTuple_New(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 677, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); __Pyx_GIVEREF(__pyx_t_5); PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_5); __pyx_t_5 = 0; - __pyx_t_5 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 633, __pyx_L1_error) + __pyx_t_5 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 677, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_5); - if (PyDict_SetItem(__pyx_t_5, __pyx_n_s_order, __pyx_n_u_F) < 0) __PYX_ERR(0, 633, __pyx_L1_error) - __pyx_t_1 = __Pyx_PyObject_Call(__pyx_t_3, __pyx_t_4, __pyx_t_5); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 633, __pyx_L1_error) + if (PyDict_SetItem(__pyx_t_5, __pyx_n_s_order, __pyx_n_u_F) < 0) __PYX_ERR(0, 677, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_Call(__pyx_t_3, __pyx_t_4, __pyx_t_5); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 677, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - if (!(likely(((__pyx_t_1) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_1, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 633, __pyx_L1_error) + if (!(likely(((__pyx_t_1) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_1, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 677, __pyx_L1_error) __pyx_t_6 = ((PyArrayObject *)__pyx_t_1); { __Pyx_BufFmt_StackElem __pyx_stack[1]; if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_out.rcbuffer->pybuffer, (PyObject*)__pyx_t_6, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 2, 0, __pyx_stack) == -1)) { __pyx_v_out = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_out.rcbuffer->pybuffer.buf = NULL; - __PYX_ERR(0, 633, __pyx_L1_error) + __PYX_ERR(0, 677, __pyx_L1_error) } else {__pyx_pybuffernd_out.diminfo[0].strides = __pyx_pybuffernd_out.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_out.diminfo[0].shape = __pyx_pybuffernd_out.rcbuffer->pybuffer.shape[0]; __pyx_pybuffernd_out.diminfo[1].strides = __pyx_pybuffernd_out.rcbuffer->pybuffer.strides[1]; __pyx_pybuffernd_out.diminfo[1].shape = __pyx_pybuffernd_out.rcbuffer->pybuffer.shape[1]; } } @@ -27897,18 +28979,18 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_v_out = ((PyArrayObject *)__pyx_t_1); __pyx_t_1 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":636 + /* "acados_template/acados_ocp_solver_pyx.pyx":680 * * # call getter * acados_solver_common.ocp_nlp_get_at_stage(self.nlp_config, self.nlp_dims, self.nlp_solver, stage, field, out.data) # <<<<<<<<<<<<<< * * return out */ - __pyx_t_7 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 636, __pyx_L1_error) - __pyx_t_8 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_out)); if (unlikely(__pyx_t_8 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 636, __pyx_L1_error) + __pyx_t_7 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 680, __pyx_L1_error) + __pyx_t_8 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_out)); if (unlikely(__pyx_t_8 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 680, __pyx_L1_error) ocp_nlp_get_at_stage(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_solver, __pyx_v_stage, __pyx_t_7, ((void *)__pyx_t_8)); - /* "acados_template/acados_ocp_solver_pyx.pyx":638 + /* "acados_template/acados_ocp_solver_pyx.pyx":682 * acados_solver_common.ocp_nlp_get_at_stage(self.nlp_config, self.nlp_dims, self.nlp_solver, stage, field, out.data) * * return out # <<<<<<<<<<<<<< @@ -27920,10 +29002,10 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_r = ((PyObject *)__pyx_v_out); goto __pyx_L0; - /* "acados_template/acados_ocp_solver_pyx.pyx":619 + /* "acados_template/acados_ocp_solver_pyx.pyx":663 * * - * def dynamics_get(self, int stage, str field_): # <<<<<<<<<<<<<< + * def get_from_qp_in(self, int stage, str field_): # <<<<<<<<<<<<<< * """ * Get numerical data from the dynamics module of the solver: */ @@ -27940,7 +29022,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __Pyx_ErrFetch(&__pyx_type, &__pyx_value, &__pyx_tb); __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_out.rcbuffer->pybuffer); __Pyx_ErrRestore(__pyx_type, __pyx_value, __pyx_tb);} - __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.dynamics_get", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.get_from_qp_in", __pyx_clineno, __pyx_lineno, __pyx_filename); __pyx_r = NULL; goto __pyx_L2; __pyx_L0:; @@ -27953,7 +29035,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":641 +/* "acados_template/acados_ocp_solver_pyx.pyx":685 * * * def options_set(self, str field_, value_): # <<<<<<<<<<<<<< @@ -27962,16 +29044,16 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ /* Python wrapper */ -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43options_set(PyObject *__pyx_v_self, +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47options_set(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else PyObject *__pyx_args, PyObject *__pyx_kwds #endif ); /*proto*/ -PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42options_set, "\n Set options of the solver.\n\n :param field: string, e.g. 'print_level', 'rti_phase', 'initialize_t_slacks', 'step_length', 'alpha_min', 'alpha_reduction', 'qp_warm_start', 'line_search_use_sufficient_descent', 'full_step_dual', 'globalization_use_SOC', 'qp_tol_stat', 'qp_tol_eq', 'qp_tol_ineq', 'qp_tol_comp', 'qp_tau_min', 'qp_mu0'\n\n :param value: of type int, float, string\n\n - qp_tol_stat: QP solver tolerance stationarity\n - qp_tol_eq: QP solver tolerance equalities\n - qp_tol_ineq: QP solver tolerance inequalities\n - qp_tol_comp: QP solver tolerance complementarity\n - qp_tau_min: for HPIPM QP solvers: minimum value of barrier parameter in HPIPM\n - qp_mu0: for HPIPM QP solvers: initial value for complementarity slackness\n - warm_start_first_qp: indicates if first QP in SQP is warm_started\n "); -static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43options_set = {"options_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43options_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42options_set}; -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43options_set(PyObject *__pyx_v_self, +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_46options_set, "\n Set options of the solver.\n\n :param field: string, e.g. 'print_level', 'rti_phase', 'initialize_t_slacks', 'step_length', 'alpha_min', 'alpha_reduction', 'qp_warm_start', 'line_search_use_sufficient_descent', 'full_step_dual', 'globalization_use_SOC', 'qp_tol_stat', 'qp_tol_eq', 'qp_tol_ineq', 'qp_tol_comp', 'qp_tau_min', 'qp_mu0'\n\n :param value: of type int, float, string\n\n - qp_tol_stat: QP solver tolerance stationarity\n - qp_tol_eq: QP solver tolerance equalities\n - qp_tol_ineq: QP solver tolerance inequalities\n - qp_tol_comp: QP solver tolerance complementarity\n - qp_tau_min: for HPIPM QP solvers: minimum value of barrier parameter in HPIPM\n - qp_mu0: for HPIPM QP solvers: initial value for complementarity slackness\n - warm_start_first_qp: indicates if first QP in SQP is warm_started\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47options_set = {"options_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47options_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_46options_set}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47options_set(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else @@ -28007,19 +29089,19 @@ PyObject *__pyx_args, PyObject *__pyx_kwds switch (__pyx_nargs) { case 0: if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field_2)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 641, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 685, __pyx_L3_error) else goto __pyx_L5_argtuple_error; CYTHON_FALLTHROUGH; case 1: if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_value)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 641, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 685, __pyx_L3_error) else { - __Pyx_RaiseArgtupleInvalid("options_set", 1, 2, 2, 1); __PYX_ERR(0, 641, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("options_set", 1, 2, 2, 1); __PYX_ERR(0, 685, __pyx_L3_error) } } if (unlikely(kw_args > 0)) { const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "options_set") < 0)) __PYX_ERR(0, 641, __pyx_L3_error) + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "options_set") < 0)) __PYX_ERR(0, 685, __pyx_L3_error) } } else if (unlikely(__pyx_nargs != 2)) { goto __pyx_L5_argtuple_error; @@ -28032,14 +29114,14 @@ PyObject *__pyx_args, PyObject *__pyx_kwds } goto __pyx_L4_argument_unpacking_done; __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("options_set", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 641, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("options_set", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 685, __pyx_L3_error) __pyx_L3_error:; __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.options_set", __pyx_clineno, __pyx_lineno, __pyx_filename); __Pyx_RefNannyFinishContext(); return NULL; __pyx_L4_argument_unpacking_done:; - if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 641, __pyx_L1_error) - __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42options_set(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_field_, __pyx_v_value_); + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 685, __pyx_L1_error) + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_46options_set(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_field_, __pyx_v_value_); /* function exit code */ goto __pyx_L0; @@ -28050,7 +29132,7 @@ PyObject *__pyx_args, PyObject *__pyx_kwds return __pyx_r; } -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42options_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_) { +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_46options_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_) { PyObject *__pyx_v_int_fields = NULL; PyObject *__pyx_v_double_fields = NULL; PyObject *__pyx_v_string_fields = NULL; @@ -28076,14 +29158,14 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS int __pyx_clineno = 0; __Pyx_RefNannySetupContext("options_set", 0); - /* "acados_template/acados_ocp_solver_pyx.pyx":657 + /* "acados_template/acados_ocp_solver_pyx.pyx":701 * - warm_start_first_qp: indicates if first QP in SQP is warm_started * """ * int_fields = ['print_level', 'rti_phase', 'initialize_t_slacks', 'qp_warm_start', 'line_search_use_sufficient_descent', 'full_step_dual', 'globalization_use_SOC', 'warm_start_first_qp'] # <<<<<<<<<<<<<< * double_fields = ['step_length', 'tol_eq', 'tol_stat', 'tol_ineq', 'tol_comp', 'alpha_min', 'alpha_reduction', 'eps_sufficient_descent', * 'qp_tol_stat', 'qp_tol_eq', 'qp_tol_ineq', 'qp_tol_comp', 'qp_tau_min', 'qp_mu0'] */ - __pyx_t_1 = PyList_New(8); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 657, __pyx_L1_error) + __pyx_t_1 = PyList_New(8); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 701, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_INCREF(__pyx_n_u_print_level); __Pyx_GIVEREF(__pyx_n_u_print_level); @@ -28112,14 +29194,14 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_v_int_fields = ((PyObject*)__pyx_t_1); __pyx_t_1 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":658 + /* "acados_template/acados_ocp_solver_pyx.pyx":702 * """ * int_fields = ['print_level', 'rti_phase', 'initialize_t_slacks', 'qp_warm_start', 'line_search_use_sufficient_descent', 'full_step_dual', 'globalization_use_SOC', 'warm_start_first_qp'] * double_fields = ['step_length', 'tol_eq', 'tol_stat', 'tol_ineq', 'tol_comp', 'alpha_min', 'alpha_reduction', 'eps_sufficient_descent', # <<<<<<<<<<<<<< * 'qp_tol_stat', 'qp_tol_eq', 'qp_tol_ineq', 'qp_tol_comp', 'qp_tau_min', 'qp_mu0'] * string_fields = ['globalization'] */ - __pyx_t_1 = PyList_New(14); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 658, __pyx_L1_error) + __pyx_t_1 = PyList_New(14); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 702, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_INCREF(__pyx_n_u_step_length); __Pyx_GIVEREF(__pyx_n_u_step_length); @@ -28166,14 +29248,14 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_v_double_fields = ((PyObject*)__pyx_t_1); __pyx_t_1 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":660 + /* "acados_template/acados_ocp_solver_pyx.pyx":704 * double_fields = ['step_length', 'tol_eq', 'tol_stat', 'tol_ineq', 'tol_comp', 'alpha_min', 'alpha_reduction', 'eps_sufficient_descent', * 'qp_tol_stat', 'qp_tol_eq', 'qp_tol_ineq', 'qp_tol_comp', 'qp_tau_min', 'qp_mu0'] * string_fields = ['globalization'] # <<<<<<<<<<<<<< * * # encode */ - __pyx_t_1 = PyList_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 660, __pyx_L1_error) + __pyx_t_1 = PyList_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 704, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_INCREF(__pyx_n_u_globalization); __Pyx_GIVEREF(__pyx_n_u_globalization); @@ -28181,7 +29263,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_v_string_fields = ((PyObject*)__pyx_t_1); __pyx_t_1 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":663 + /* "acados_template/acados_ocp_solver_pyx.pyx":707 * * # encode * field = field_.encode('utf-8') # <<<<<<<<<<<<<< @@ -28190,24 +29272,24 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ if (unlikely(__pyx_v_field_ == Py_None)) { PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "encode"); - __PYX_ERR(0, 663, __pyx_L1_error) + __PYX_ERR(0, 707, __pyx_L1_error) } - __pyx_t_1 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 663, __pyx_L1_error) + __pyx_t_1 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 707, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __pyx_v_field = __pyx_t_1; __pyx_t_1 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":670 + /* "acados_template/acados_ocp_solver_pyx.pyx":714 * * # check field availability and type * if field_ in int_fields: # <<<<<<<<<<<<<< * if not isinstance(value_, int): * raise Exception('solver option {} must be of type int. You have {}.'.format(field_, type(value_))) */ - __pyx_t_2 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_int_fields, Py_EQ)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 670, __pyx_L1_error) + __pyx_t_2 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_int_fields, Py_EQ)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 714, __pyx_L1_error) if (__pyx_t_2) { - /* "acados_template/acados_ocp_solver_pyx.pyx":671 + /* "acados_template/acados_ocp_solver_pyx.pyx":715 * # check field availability and type * if field_ in int_fields: * if not isinstance(value_, int): # <<<<<<<<<<<<<< @@ -28218,14 +29300,14 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_t_3 = (!__pyx_t_2); if (unlikely(__pyx_t_3)) { - /* "acados_template/acados_ocp_solver_pyx.pyx":672 + /* "acados_template/acados_ocp_solver_pyx.pyx":716 * if field_ in int_fields: * if not isinstance(value_, int): * raise Exception('solver option {} must be of type int. You have {}.'.format(field_, type(value_))) # <<<<<<<<<<<<<< * * if field_ == 'rti_phase': */ - __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_solver_option_must_be_of_type_in, __pyx_n_s_format); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 672, __pyx_L1_error) + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_solver_option_must_be_of_type_in, __pyx_n_s_format); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 716, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); __pyx_t_5 = NULL; __pyx_t_6 = 0; @@ -28243,18 +29325,18 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_v_field_, ((PyObject *)Py_TYPE(__pyx_v_value_))}; __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; - if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 672, __pyx_L1_error) + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 716, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; } - __pyx_t_4 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 672, __pyx_L1_error) + __pyx_t_4 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 716, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; __Pyx_Raise(__pyx_t_4, 0, 0, 0); __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __PYX_ERR(0, 672, __pyx_L1_error) + __PYX_ERR(0, 716, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":671 + /* "acados_template/acados_ocp_solver_pyx.pyx":715 * # check field availability and type * if field_ in int_fields: * if not isinstance(value_, int): # <<<<<<<<<<<<<< @@ -28263,52 +29345,52 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":674 + /* "acados_template/acados_ocp_solver_pyx.pyx":718 * raise Exception('solver option {} must be of type int. You have {}.'.format(field_, type(value_))) * * if field_ == 'rti_phase': # <<<<<<<<<<<<<< * if value_ < 0 or value_ > 2: * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' */ - __pyx_t_3 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_rti_phase, Py_EQ)); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(0, 674, __pyx_L1_error) + __pyx_t_3 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_rti_phase, Py_EQ)); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(0, 718, __pyx_L1_error) if (__pyx_t_3) { - /* "acados_template/acados_ocp_solver_pyx.pyx":675 + /* "acados_template/acados_ocp_solver_pyx.pyx":719 * * if field_ == 'rti_phase': * if value_ < 0 or value_ > 2: # <<<<<<<<<<<<<< * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' * 'take only values 0, 1, 2 for SQP-RTI-type solvers') */ - __pyx_t_4 = PyObject_RichCompare(__pyx_v_value_, __pyx_int_0, Py_LT); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 675, __pyx_L1_error) - __pyx_t_2 = __Pyx_PyObject_IsTrue(__pyx_t_4); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 675, __pyx_L1_error) + __pyx_t_4 = PyObject_RichCompare(__pyx_v_value_, __pyx_int_0, Py_LT); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 719, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_IsTrue(__pyx_t_4); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 719, __pyx_L1_error) __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; if (!__pyx_t_2) { } else { __pyx_t_3 = __pyx_t_2; goto __pyx_L7_bool_binop_done; } - __pyx_t_4 = PyObject_RichCompare(__pyx_v_value_, __pyx_int_2, Py_GT); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 675, __pyx_L1_error) - __pyx_t_2 = __Pyx_PyObject_IsTrue(__pyx_t_4); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 675, __pyx_L1_error) + __pyx_t_4 = PyObject_RichCompare(__pyx_v_value_, __pyx_int_2, Py_GT); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 719, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_IsTrue(__pyx_t_4); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 719, __pyx_L1_error) __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; __pyx_t_3 = __pyx_t_2; __pyx_L7_bool_binop_done:; if (unlikely(__pyx_t_3)) { - /* "acados_template/acados_ocp_solver_pyx.pyx":676 + /* "acados_template/acados_ocp_solver_pyx.pyx":720 * if field_ == 'rti_phase': * if value_ < 0 or value_ > 2: * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' # <<<<<<<<<<<<<< * 'take only values 0, 1, 2 for SQP-RTI-type solvers') * if self.nlp_solver_type != 'SQP_RTI' and value_ > 0: */ - __pyx_t_4 = __Pyx_PyObject_Call(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_tuple__27, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 676, __pyx_L1_error) + __pyx_t_4 = __Pyx_PyObject_Call(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_tuple__29, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 720, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); __Pyx_Raise(__pyx_t_4, 0, 0, 0); __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __PYX_ERR(0, 676, __pyx_L1_error) + __PYX_ERR(0, 720, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":675 + /* "acados_template/acados_ocp_solver_pyx.pyx":719 * * if field_ == 'rti_phase': * if value_ < 0 or value_ > 2: # <<<<<<<<<<<<<< @@ -28317,40 +29399,40 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":678 + /* "acados_template/acados_ocp_solver_pyx.pyx":722 * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' * 'take only values 0, 1, 2 for SQP-RTI-type solvers') * if self.nlp_solver_type != 'SQP_RTI' and value_ > 0: # <<<<<<<<<<<<<< * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' * 'take only value 0 for SQP-type solvers') */ - __pyx_t_2 = (__Pyx_PyUnicode_Equals(__pyx_v_self->nlp_solver_type, __pyx_n_u_SQP_RTI, Py_NE)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 678, __pyx_L1_error) + __pyx_t_2 = (__Pyx_PyUnicode_Equals(__pyx_v_self->nlp_solver_type, __pyx_n_u_SQP_RTI, Py_NE)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 722, __pyx_L1_error) if (__pyx_t_2) { } else { __pyx_t_3 = __pyx_t_2; goto __pyx_L10_bool_binop_done; } - __pyx_t_4 = PyObject_RichCompare(__pyx_v_value_, __pyx_int_0, Py_GT); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 678, __pyx_L1_error) - __pyx_t_2 = __Pyx_PyObject_IsTrue(__pyx_t_4); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 678, __pyx_L1_error) + __pyx_t_4 = PyObject_RichCompare(__pyx_v_value_, __pyx_int_0, Py_GT); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 722, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_IsTrue(__pyx_t_4); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 722, __pyx_L1_error) __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; __pyx_t_3 = __pyx_t_2; __pyx_L10_bool_binop_done:; if (unlikely(__pyx_t_3)) { - /* "acados_template/acados_ocp_solver_pyx.pyx":679 + /* "acados_template/acados_ocp_solver_pyx.pyx":723 * 'take only values 0, 1, 2 for SQP-RTI-type solvers') * if self.nlp_solver_type != 'SQP_RTI' and value_ > 0: * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' # <<<<<<<<<<<<<< * 'take only value 0 for SQP-type solvers') * */ - __pyx_t_4 = __Pyx_PyObject_Call(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_tuple__28, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 679, __pyx_L1_error) + __pyx_t_4 = __Pyx_PyObject_Call(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_tuple__30, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 723, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); __Pyx_Raise(__pyx_t_4, 0, 0, 0); __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __PYX_ERR(0, 679, __pyx_L1_error) + __PYX_ERR(0, 723, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":678 + /* "acados_template/acados_ocp_solver_pyx.pyx":722 * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' * 'take only values 0, 1, 2 for SQP-RTI-type solvers') * if self.nlp_solver_type != 'SQP_RTI' and value_ > 0: # <<<<<<<<<<<<<< @@ -28359,7 +29441,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":674 + /* "acados_template/acados_ocp_solver_pyx.pyx":718 * raise Exception('solver option {} must be of type int. You have {}.'.format(field_, type(value_))) * * if field_ == 'rti_phase': # <<<<<<<<<<<<<< @@ -28368,27 +29450,27 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":682 + /* "acados_template/acados_ocp_solver_pyx.pyx":726 * 'take only value 0 for SQP-type solvers') * * int_value = value_ # <<<<<<<<<<<<<< * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &int_value) * */ - __pyx_t_6 = __Pyx_PyInt_As_int(__pyx_v_value_); if (unlikely((__pyx_t_6 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 682, __pyx_L1_error) + __pyx_t_6 = __Pyx_PyInt_As_int(__pyx_v_value_); if (unlikely((__pyx_t_6 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 726, __pyx_L1_error) __pyx_v_int_value = __pyx_t_6; - /* "acados_template/acados_ocp_solver_pyx.pyx":683 + /* "acados_template/acados_ocp_solver_pyx.pyx":727 * * int_value = value_ * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &int_value) # <<<<<<<<<<<<<< * * elif field_ in double_fields: */ - __pyx_t_7 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 683, __pyx_L1_error) + __pyx_t_7 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 727, __pyx_L1_error) ocp_nlp_solver_opts_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_opts, __pyx_t_7, ((void *)(&__pyx_v_int_value))); - /* "acados_template/acados_ocp_solver_pyx.pyx":670 + /* "acados_template/acados_ocp_solver_pyx.pyx":714 * * # check field availability and type * if field_ in int_fields: # <<<<<<<<<<<<<< @@ -28398,17 +29480,17 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS goto __pyx_L3; } - /* "acados_template/acados_ocp_solver_pyx.pyx":685 + /* "acados_template/acados_ocp_solver_pyx.pyx":729 * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &int_value) * * elif field_ in double_fields: # <<<<<<<<<<<<<< * if not isinstance(value_, float): * raise Exception('solver option {} must be of type float. You have {}.'.format(field_, type(value_))) */ - __pyx_t_3 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_double_fields, Py_EQ)); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(0, 685, __pyx_L1_error) + __pyx_t_3 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_double_fields, Py_EQ)); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(0, 729, __pyx_L1_error) if (__pyx_t_3) { - /* "acados_template/acados_ocp_solver_pyx.pyx":686 + /* "acados_template/acados_ocp_solver_pyx.pyx":730 * * elif field_ in double_fields: * if not isinstance(value_, float): # <<<<<<<<<<<<<< @@ -28419,14 +29501,14 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_t_2 = (!__pyx_t_3); if (unlikely(__pyx_t_2)) { - /* "acados_template/acados_ocp_solver_pyx.pyx":687 + /* "acados_template/acados_ocp_solver_pyx.pyx":731 * elif field_ in double_fields: * if not isinstance(value_, float): * raise Exception('solver option {} must be of type float. You have {}.'.format(field_, type(value_))) # <<<<<<<<<<<<<< * * double_value = value_ */ - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_solver_option_must_be_of_type_fl, __pyx_n_s_format); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 687, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_solver_option_must_be_of_type_fl, __pyx_n_s_format); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 731, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __pyx_t_5 = NULL; __pyx_t_6 = 0; @@ -28444,18 +29526,18 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_v_field_, ((PyObject *)Py_TYPE(__pyx_v_value_))}; __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; - if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 687, __pyx_L1_error) + if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 731, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; } - __pyx_t_1 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_4); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 687, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_4); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 731, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; __Pyx_Raise(__pyx_t_1, 0, 0, 0); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __PYX_ERR(0, 687, __pyx_L1_error) + __PYX_ERR(0, 731, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":686 + /* "acados_template/acados_ocp_solver_pyx.pyx":730 * * elif field_ in double_fields: * if not isinstance(value_, float): # <<<<<<<<<<<<<< @@ -28464,27 +29546,27 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":689 + /* "acados_template/acados_ocp_solver_pyx.pyx":733 * raise Exception('solver option {} must be of type float. You have {}.'.format(field_, type(value_))) * * double_value = value_ # <<<<<<<<<<<<<< * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &double_value) * */ - __pyx_t_8 = __pyx_PyFloat_AsDouble(__pyx_v_value_); if (unlikely((__pyx_t_8 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 689, __pyx_L1_error) + __pyx_t_8 = __pyx_PyFloat_AsDouble(__pyx_v_value_); if (unlikely((__pyx_t_8 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 733, __pyx_L1_error) __pyx_v_double_value = __pyx_t_8; - /* "acados_template/acados_ocp_solver_pyx.pyx":690 + /* "acados_template/acados_ocp_solver_pyx.pyx":734 * * double_value = value_ * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &double_value) # <<<<<<<<<<<<<< * * elif field_ in string_fields: */ - __pyx_t_7 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 690, __pyx_L1_error) + __pyx_t_7 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 734, __pyx_L1_error) ocp_nlp_solver_opts_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_opts, __pyx_t_7, ((void *)(&__pyx_v_double_value))); - /* "acados_template/acados_ocp_solver_pyx.pyx":685 + /* "acados_template/acados_ocp_solver_pyx.pyx":729 * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &int_value) * * elif field_ in double_fields: # <<<<<<<<<<<<<< @@ -28494,17 +29576,17 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS goto __pyx_L3; } - /* "acados_template/acados_ocp_solver_pyx.pyx":692 + /* "acados_template/acados_ocp_solver_pyx.pyx":736 * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &double_value) * * elif field_ in string_fields: # <<<<<<<<<<<<<< * if not isinstance(value_, bytes): * raise Exception('solver option {} must be of type str. You have {}.'.format(field_, type(value_))) */ - __pyx_t_2 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_string_fields, Py_EQ)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 692, __pyx_L1_error) + __pyx_t_2 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_string_fields, Py_EQ)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 736, __pyx_L1_error) if (likely(__pyx_t_2)) { - /* "acados_template/acados_ocp_solver_pyx.pyx":693 + /* "acados_template/acados_ocp_solver_pyx.pyx":737 * * elif field_ in string_fields: * if not isinstance(value_, bytes): # <<<<<<<<<<<<<< @@ -28515,14 +29597,14 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_t_3 = (!__pyx_t_2); if (unlikely(__pyx_t_3)) { - /* "acados_template/acados_ocp_solver_pyx.pyx":694 + /* "acados_template/acados_ocp_solver_pyx.pyx":738 * elif field_ in string_fields: * if not isinstance(value_, bytes): * raise Exception('solver option {} must be of type str. You have {}.'.format(field_, type(value_))) # <<<<<<<<<<<<<< * * string_value = value_.encode('utf-8') */ - __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_solver_option_must_be_of_type_st, __pyx_n_s_format); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 694, __pyx_L1_error) + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_solver_option_must_be_of_type_st, __pyx_n_s_format); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 738, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); __pyx_t_5 = NULL; __pyx_t_6 = 0; @@ -28540,18 +29622,18 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_v_field_, ((PyObject *)Py_TYPE(__pyx_v_value_))}; __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; - if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 694, __pyx_L1_error) + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 738, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; } - __pyx_t_4 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 694, __pyx_L1_error) + __pyx_t_4 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 738, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; __Pyx_Raise(__pyx_t_4, 0, 0, 0); __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __PYX_ERR(0, 694, __pyx_L1_error) + __PYX_ERR(0, 738, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":693 + /* "acados_template/acados_ocp_solver_pyx.pyx":737 * * elif field_ in string_fields: * if not isinstance(value_, bytes): # <<<<<<<<<<<<<< @@ -28560,14 +29642,14 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":696 + /* "acados_template/acados_ocp_solver_pyx.pyx":740 * raise Exception('solver option {} must be of type str. You have {}.'.format(field_, type(value_))) * * string_value = value_.encode('utf-8') # <<<<<<<<<<<<<< * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &string_value[0]) * */ - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_value_, __pyx_n_s_encode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 696, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_value_, __pyx_n_s_encode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 740, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __pyx_t_5 = NULL; __pyx_t_6 = 0; @@ -28585,24 +29667,24 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_callargs[2] = {__pyx_t_5, __pyx_kp_u_utf_8}; __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 1+__pyx_t_6); __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; - if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 696, __pyx_L1_error) + if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 740, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; } - __pyx_t_9 = __Pyx_PyObject_to_MemoryviewSlice_dc_unsigned_char(__pyx_t_4, PyBUF_WRITABLE); if (unlikely(!__pyx_t_9.memview)) __PYX_ERR(0, 696, __pyx_L1_error) + __pyx_t_9 = __Pyx_PyObject_to_MemoryviewSlice_dc_unsigned_char(__pyx_t_4, PyBUF_WRITABLE); if (unlikely(!__pyx_t_9.memview)) __PYX_ERR(0, 740, __pyx_L1_error) __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; __pyx_v_string_value = __pyx_t_9; __pyx_t_9.memview = NULL; __pyx_t_9.data = NULL; - /* "acados_template/acados_ocp_solver_pyx.pyx":697 + /* "acados_template/acados_ocp_solver_pyx.pyx":741 * * string_value = value_.encode('utf-8') * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &string_value[0]) # <<<<<<<<<<<<<< * * else: */ - __pyx_t_7 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 697, __pyx_L1_error) + __pyx_t_7 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 741, __pyx_L1_error) __pyx_t_10 = 0; __pyx_t_6 = -1; if (__pyx_t_10 < 0) { @@ -28611,11 +29693,11 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS } else if (unlikely(__pyx_t_10 >= __pyx_v_string_value.shape[0])) __pyx_t_6 = 0; if (unlikely(__pyx_t_6 != -1)) { __Pyx_RaiseBufferIndexError(__pyx_t_6); - __PYX_ERR(0, 697, __pyx_L1_error) + __PYX_ERR(0, 741, __pyx_L1_error) } ocp_nlp_solver_opts_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_opts, __pyx_t_7, ((void *)(&(*((unsigned char *) ( /* dim=0 */ ((char *) (((unsigned char *) __pyx_v_string_value.data) + __pyx_t_10)) )))))); - /* "acados_template/acados_ocp_solver_pyx.pyx":692 + /* "acados_template/acados_ocp_solver_pyx.pyx":736 * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &double_value) * * elif field_ in string_fields: # <<<<<<<<<<<<<< @@ -28625,7 +29707,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS goto __pyx_L3; } - /* "acados_template/acados_ocp_solver_pyx.pyx":700 + /* "acados_template/acados_ocp_solver_pyx.pyx":744 * * else: * raise Exception('AcadosOcpSolverCython.options_set() does not support field {}.'\ # <<<<<<<<<<<<<< @@ -28634,21 +29716,21 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ /*else*/ { - /* "acados_template/acados_ocp_solver_pyx.pyx":701 + /* "acados_template/acados_ocp_solver_pyx.pyx":745 * else: * raise Exception('AcadosOcpSolverCython.options_set() does not support field {}.'\ * '\n Possible values are {}.'.format(field_, ', '.join(int_fields + double_fields + string_fields))) # <<<<<<<<<<<<<< * * */ - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_options_se, __pyx_n_s_format); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 701, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_options_se, __pyx_n_s_format); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 745, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); - __pyx_t_5 = PyNumber_Add(__pyx_v_int_fields, __pyx_v_double_fields); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 701, __pyx_L1_error) + __pyx_t_5 = PyNumber_Add(__pyx_v_int_fields, __pyx_v_double_fields); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 745, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_5); - __pyx_t_11 = PyNumber_Add(__pyx_t_5, __pyx_v_string_fields); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 701, __pyx_L1_error) + __pyx_t_11 = PyNumber_Add(__pyx_t_5, __pyx_v_string_fields); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 745, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_11); __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __pyx_t_5 = PyUnicode_Join(__pyx_kp_u__29, __pyx_t_11); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 701, __pyx_L1_error) + __pyx_t_5 = PyUnicode_Join(__pyx_kp_u__31, __pyx_t_11); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 745, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_5); __Pyx_DECREF(__pyx_t_11); __pyx_t_11 = 0; __pyx_t_11 = NULL; @@ -28668,28 +29750,28 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); __Pyx_XDECREF(__pyx_t_11); __pyx_t_11 = 0; __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 701, __pyx_L1_error) + if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 745, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; } - /* "acados_template/acados_ocp_solver_pyx.pyx":700 + /* "acados_template/acados_ocp_solver_pyx.pyx":744 * * else: * raise Exception('AcadosOcpSolverCython.options_set() does not support field {}.'\ # <<<<<<<<<<<<<< * '\n Possible values are {}.'.format(field_, ', '.join(int_fields + double_fields + string_fields))) * */ - __pyx_t_1 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_4); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 700, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_4); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 744, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; __Pyx_Raise(__pyx_t_1, 0, 0, 0); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __PYX_ERR(0, 700, __pyx_L1_error) + __PYX_ERR(0, 744, __pyx_L1_error) } __pyx_L3:; - /* "acados_template/acados_ocp_solver_pyx.pyx":641 + /* "acados_template/acados_ocp_solver_pyx.pyx":685 * * * def options_set(self, str field_, value_): # <<<<<<<<<<<<<< @@ -28719,7 +29801,451 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":704 +/* "acados_template/acados_ocp_solver_pyx.pyx":748 + * + * + * def set_params_sparse(self, int stage, idx_values_, param_values_): # <<<<<<<<<<<<<< + * """ + * set parameters of the solvers external function partially: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49set_params_sparse(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_48set_params_sparse, "\n set parameters of the solvers external function partially:\n Pseudo: solver.param[idx_values_] = param_values_;\n Parameters:\n :param stage_: integer corresponding to shooting node\n :param idx_values_: 0 based integer array corresponding to parameter indices to be set\n :param param_values_: new parameter values as numpy array\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49set_params_sparse = {"set_params_sparse", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49set_params_sparse, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_48set_params_sparse}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49set_params_sparse(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + int __pyx_v_stage; + PyObject *__pyx_v_idx_values_ = 0; + PyObject *__pyx_v_param_values_ = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("set_params_sparse (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_stage,&__pyx_n_s_idx_values,&__pyx_n_s_param_values,0}; + PyObject* values[3] = {0,0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_stage)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 748, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_idx_values)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 748, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("set_params_sparse", 1, 3, 3, 1); __PYX_ERR(0, 748, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_param_values)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 748, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("set_params_sparse", 1, 3, 3, 2); __PYX_ERR(0, 748, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "set_params_sparse") < 0)) __PYX_ERR(0, 748, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + } + __pyx_v_stage = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_stage == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 748, __pyx_L3_error) + __pyx_v_idx_values_ = values[1]; + __pyx_v_param_values_ = values[2]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("set_params_sparse", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 748, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.set_params_sparse", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_48set_params_sparse(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_stage, __pyx_v_idx_values_, __pyx_v_param_values_); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_48set_params_sparse(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_idx_values_, PyObject *__pyx_v_param_values_) { + PyArrayObject *__pyx_v_value = 0; + PyArrayObject *__pyx_v_idx = 0; + int __pyx_v_n_update; + __Pyx_LocalBuf_ND __pyx_pybuffernd_idx; + __Pyx_Buffer __pyx_pybuffer_idx; + __Pyx_LocalBuf_ND __pyx_pybuffernd_value; + __Pyx_Buffer __pyx_pybuffer_value; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_t_3; + int __pyx_t_4; + Py_ssize_t __pyx_t_5; + PyObject *__pyx_t_6 = NULL; + Py_UCS4 __pyx_t_7; + Py_ssize_t __pyx_t_8; + PyObject *__pyx_t_9 = NULL; + PyObject *__pyx_t_10 = NULL; + PyArrayObject *__pyx_t_11 = NULL; + PyArrayObject *__pyx_t_12 = NULL; + npy_intp *__pyx_t_13; + char *__pyx_t_14; + char *__pyx_t_15; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("set_params_sparse", 0); + __pyx_pybuffer_value.pybuffer.buf = NULL; + __pyx_pybuffer_value.refcount = 0; + __pyx_pybuffernd_value.data = NULL; + __pyx_pybuffernd_value.rcbuffer = &__pyx_pybuffer_value; + __pyx_pybuffer_idx.pybuffer.buf = NULL; + __pyx_pybuffer_idx.refcount = 0; + __pyx_pybuffernd_idx.data = NULL; + __pyx_pybuffernd_idx.rcbuffer = &__pyx_pybuffer_idx; + + /* "acados_template/acados_ocp_solver_pyx.pyx":758 + * """ + * + * if not isinstance(param_values_, np.ndarray): # <<<<<<<<<<<<<< + * raise Exception('param_values_ must be np.array.') + * + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 758, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_ndarray); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 758, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_3 = PyObject_IsInstance(__pyx_v_param_values_, __pyx_t_2); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(0, 758, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_4 = (!__pyx_t_3); + if (unlikely(__pyx_t_4)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":759 + * + * if not isinstance(param_values_, np.ndarray): + * raise Exception('param_values_ must be np.array.') # <<<<<<<<<<<<<< + * + * if param_values_.shape[0] != len(idx_values_): + */ + __pyx_t_2 = __Pyx_PyObject_Call(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_tuple__32, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 759, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 759, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":758 + * """ + * + * if not isinstance(param_values_, np.ndarray): # <<<<<<<<<<<<<< + * raise Exception('param_values_ must be np.array.') + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":761 + * raise Exception('param_values_ must be np.array.') + * + * if param_values_.shape[0] != len(idx_values_): # <<<<<<<<<<<<<< + * raise Exception(f'param_values_ and idx_values_ must be of the same size.' + + * f' Got sizes idx {param_values_.shape[0]}, param_values {len(idx_values_)}.') + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_param_values_, __pyx_n_s_shape); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 761, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_1 = __Pyx_GetItemInt(__pyx_t_2, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 761, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_5 = PyObject_Length(__pyx_v_idx_values_); if (unlikely(__pyx_t_5 == ((Py_ssize_t)-1))) __PYX_ERR(0, 761, __pyx_L1_error) + __pyx_t_2 = PyInt_FromSsize_t(__pyx_t_5); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 761, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_6 = PyObject_RichCompare(__pyx_t_1, __pyx_t_2, Py_NE); __Pyx_XGOTREF(__pyx_t_6); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 761, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_t_6); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 761, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(__pyx_t_4)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":763 + * if param_values_.shape[0] != len(idx_values_): + * raise Exception(f'param_values_ and idx_values_ must be of the same size.' + + * f' Got sizes idx {param_values_.shape[0]}, param_values {len(idx_values_)}.') # <<<<<<<<<<<<<< + * + * # n_update = c_int(len(param_values_)) + */ + __pyx_t_6 = PyTuple_New(5); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 763, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_5 = 0; + __pyx_t_7 = 127; + __Pyx_INCREF(__pyx_kp_u_Got_sizes_idx); + __pyx_t_5 += 15; + __Pyx_GIVEREF(__pyx_kp_u_Got_sizes_idx); + PyTuple_SET_ITEM(__pyx_t_6, 0, __pyx_kp_u_Got_sizes_idx); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_param_values_, __pyx_n_s_shape); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 763, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_1 = __Pyx_GetItemInt(__pyx_t_2, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 763, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_FormatSimple(__pyx_t_1, __pyx_empty_unicode); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 763, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_7 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) > __pyx_t_7) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) : __pyx_t_7; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_6, 1, __pyx_t_2); + __pyx_t_2 = 0; + __Pyx_INCREF(__pyx_kp_u_param_values_2); + __pyx_t_5 += 15; + __Pyx_GIVEREF(__pyx_kp_u_param_values_2); + PyTuple_SET_ITEM(__pyx_t_6, 2, __pyx_kp_u_param_values_2); + __pyx_t_8 = PyObject_Length(__pyx_v_idx_values_); if (unlikely(__pyx_t_8 == ((Py_ssize_t)-1))) __PYX_ERR(0, 763, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_t_8, 0, ' ', 'd'); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 763, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_6, 3, __pyx_t_2); + __pyx_t_2 = 0; + __Pyx_INCREF(__pyx_kp_u__2); + __pyx_t_5 += 1; + __Pyx_GIVEREF(__pyx_kp_u__2); + PyTuple_SET_ITEM(__pyx_t_6, 4, __pyx_kp_u__2); + __pyx_t_2 = __Pyx_PyUnicode_Join(__pyx_t_6, 5, __pyx_t_5, __pyx_t_7); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 763, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":762 + * + * if param_values_.shape[0] != len(idx_values_): + * raise Exception(f'param_values_ and idx_values_ must be of the same size.' + # <<<<<<<<<<<<<< + * f' Got sizes idx {param_values_.shape[0]}, param_values {len(idx_values_)}.') + * + */ + __pyx_t_6 = __Pyx_PyUnicode_Concat(__pyx_kp_u_param_values__and_idx_values__mu, __pyx_t_2); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 762, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_6); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 762, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 762, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":761 + * raise Exception('param_values_ must be np.array.') + * + * if param_values_.shape[0] != len(idx_values_): # <<<<<<<<<<<<<< + * raise Exception(f'param_values_ and idx_values_ must be of the same size.' + + * f' Got sizes idx {param_values_.shape[0]}, param_values {len(idx_values_)}.') + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":777 + * # (self.capsule, stage, idx_data, param_data, n_update) + * + * cdef cnp.ndarray[cnp.float64_t, ndim=1] value = np.ascontiguousarray(param_values_, dtype=np.float64) # <<<<<<<<<<<<<< + * # cdef cnp.ndarray[cnp.intc, ndim=1] idx = np.ascontiguousarray(idx_values_, dtype=np.intc) + * + */ + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_np); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 777, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 777, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = PyTuple_New(1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 777, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_INCREF(__pyx_v_param_values_); + __Pyx_GIVEREF(__pyx_v_param_values_); + PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_v_param_values_); + __pyx_t_1 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 777, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_GetModuleGlobalName(__pyx_t_9, __pyx_n_s_np); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 777, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __pyx_t_10 = __Pyx_PyObject_GetAttrStr(__pyx_t_9, __pyx_n_s_float64); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 777, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + if (PyDict_SetItem(__pyx_t_1, __pyx_n_s_dtype, __pyx_t_10) < 0) __PYX_ERR(0, 777, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + __pyx_t_10 = __Pyx_PyObject_Call(__pyx_t_6, __pyx_t_2, __pyx_t_1); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 777, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (!(likely(((__pyx_t_10) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_10, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 777, __pyx_L1_error) + __pyx_t_11 = ((PyArrayObject *)__pyx_t_10); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_value.rcbuffer->pybuffer, (PyObject*)__pyx_t_11, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 1, 0, __pyx_stack) == -1)) { + __pyx_v_value = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_value.rcbuffer->pybuffer.buf = NULL; + __PYX_ERR(0, 777, __pyx_L1_error) + } else {__pyx_pybuffernd_value.diminfo[0].strides = __pyx_pybuffernd_value.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_value.diminfo[0].shape = __pyx_pybuffernd_value.rcbuffer->pybuffer.shape[0]; + } + } + __pyx_t_11 = 0; + __pyx_v_value = ((PyArrayObject *)__pyx_t_10); + __pyx_t_10 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":784 + * # cdef cnp.ndarray[cnp.int, ndim=1] idx = np.ascontiguousarray(idx_values_, dtype=np.intc) + * + * cdef cnp.ndarray[cnp.int32_t, ndim=1] idx = np.ascontiguousarray(idx_values_, dtype=np.int32) # <<<<<<<<<<<<<< + * cdef int n_update = value.shape[0] + * # print(f"in set_params_sparse Cython n_update {n_update}") + */ + __Pyx_GetModuleGlobalName(__pyx_t_10, __pyx_n_s_np); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 784, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_10, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 784, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + __pyx_t_10 = PyTuple_New(1); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 784, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __Pyx_INCREF(__pyx_v_idx_values_); + __Pyx_GIVEREF(__pyx_v_idx_values_); + PyTuple_SET_ITEM(__pyx_t_10, 0, __pyx_v_idx_values_); + __pyx_t_2 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 784, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_GetModuleGlobalName(__pyx_t_6, __pyx_n_s_np); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 784, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_9 = __Pyx_PyObject_GetAttrStr(__pyx_t_6, __pyx_n_s_int32); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 784, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + if (PyDict_SetItem(__pyx_t_2, __pyx_n_s_dtype, __pyx_t_9) < 0) __PYX_ERR(0, 784, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + __pyx_t_9 = __Pyx_PyObject_Call(__pyx_t_1, __pyx_t_10, __pyx_t_2); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 784, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + if (!(likely(((__pyx_t_9) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_9, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 784, __pyx_L1_error) + __pyx_t_12 = ((PyArrayObject *)__pyx_t_9); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_idx.rcbuffer->pybuffer, (PyObject*)__pyx_t_12, &__Pyx_TypeInfo_nn___pyx_t_5numpy_int32_t, PyBUF_FORMAT| PyBUF_STRIDES, 1, 0, __pyx_stack) == -1)) { + __pyx_v_idx = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_idx.rcbuffer->pybuffer.buf = NULL; + __PYX_ERR(0, 784, __pyx_L1_error) + } else {__pyx_pybuffernd_idx.diminfo[0].strides = __pyx_pybuffernd_idx.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_idx.diminfo[0].shape = __pyx_pybuffernd_idx.rcbuffer->pybuffer.shape[0]; + } + } + __pyx_t_12 = 0; + __pyx_v_idx = ((PyArrayObject *)__pyx_t_9); + __pyx_t_9 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":785 + * + * cdef cnp.ndarray[cnp.int32_t, ndim=1] idx = np.ascontiguousarray(idx_values_, dtype=np.int32) + * cdef int n_update = value.shape[0] # <<<<<<<<<<<<<< + * # print(f"in set_params_sparse Cython n_update {n_update}") + * + */ + __pyx_t_13 = __pyx_f_5numpy_7ndarray_5shape_shape(((PyArrayObject *)__pyx_v_value)); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 785, __pyx_L1_error) + __pyx_v_n_update = (__pyx_t_13[0]); + + /* "acados_template/acados_ocp_solver_pyx.pyx":788 + * # print(f"in set_params_sparse Cython n_update {n_update}") + * + * assert acados_solver.acados_update_params_sparse(self.capsule, stage, idx.data, value.data, n_update) == 0 # <<<<<<<<<<<<<< + * return + * + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_14 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_idx)); if (unlikely(__pyx_t_14 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 788, __pyx_L1_error) + __pyx_t_15 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_15 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 788, __pyx_L1_error) + __pyx_t_4 = (lat_acados_update_params_sparse(__pyx_v_self->capsule, __pyx_v_stage, ((int *)__pyx_t_14), ((double *)__pyx_t_15), __pyx_v_n_update) == 0); + if (unlikely(!__pyx_t_4)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(0, 788, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(0, 788, __pyx_L1_error) + #endif + + /* "acados_template/acados_ocp_solver_pyx.pyx":789 + * + * assert acados_solver.acados_update_params_sparse(self.capsule, stage, idx.data, value.data, n_update) == 0 + * return # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":748 + * + * + * def set_params_sparse(self, int stage, idx_values_, param_values_): # <<<<<<<<<<<<<< + * """ + * set parameters of the solvers external function partially: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_9); + __Pyx_XDECREF(__pyx_t_10); + { PyObject *__pyx_type, *__pyx_value, *__pyx_tb; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&__pyx_type, &__pyx_value, &__pyx_tb); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_idx.rcbuffer->pybuffer); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_value.rcbuffer->pybuffer); + __Pyx_ErrRestore(__pyx_type, __pyx_value, __pyx_tb);} + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.set_params_sparse", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + goto __pyx_L2; + __pyx_L0:; + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_idx.rcbuffer->pybuffer); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_value.rcbuffer->pybuffer); + __pyx_L2:; + __Pyx_XDECREF((PyObject *)__pyx_v_value); + __Pyx_XDECREF((PyObject *)__pyx_v_idx); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":792 * * * def __del__(self): # <<<<<<<<<<<<<< @@ -28728,22 +30254,22 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ /* Python wrapper */ -static void __pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_45__del__(PyObject *__pyx_v_self); /*proto*/ -static void __pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_45__del__(PyObject *__pyx_v_self) { +static void __pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_51__del__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_51__del__(PyObject *__pyx_v_self) { CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); __Pyx_RefNannyDeclarations __Pyx_RefNannySetupContext("__del__ (wrapper)", 0); - __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_44__del__(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); + __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_50__del__(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); /* function exit code */ __Pyx_RefNannyFinishContext(); } -static void __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_44__del__(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { +static void __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_50__del__(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { __Pyx_RefNannyDeclarations __Pyx_RefNannySetupContext("__del__", 0); - /* "acados_template/acados_ocp_solver_pyx.pyx":705 + /* "acados_template/acados_ocp_solver_pyx.pyx":793 * * def __del__(self): * if self.solver_created: # <<<<<<<<<<<<<< @@ -28752,7 +30278,7 @@ static void __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolver */ if (__pyx_v_self->solver_created) { - /* "acados_template/acados_ocp_solver_pyx.pyx":706 + /* "acados_template/acados_ocp_solver_pyx.pyx":794 * def __del__(self): * if self.solver_created: * acados_solver.acados_free(self.capsule) # <<<<<<<<<<<<<< @@ -28760,14 +30286,14 @@ static void __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolver */ (void)(lat_acados_free(__pyx_v_self->capsule)); - /* "acados_template/acados_ocp_solver_pyx.pyx":707 + /* "acados_template/acados_ocp_solver_pyx.pyx":795 * if self.solver_created: * acados_solver.acados_free(self.capsule) * acados_solver.acados_free_capsule(self.capsule) # <<<<<<<<<<<<<< */ (void)(lat_acados_free_capsule(__pyx_v_self->capsule)); - /* "acados_template/acados_ocp_solver_pyx.pyx":705 + /* "acados_template/acados_ocp_solver_pyx.pyx":793 * * def __del__(self): * if self.solver_created: # <<<<<<<<<<<<<< @@ -28776,7 +30302,7 @@ static void __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolver */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":704 + /* "acados_template/acados_ocp_solver_pyx.pyx":792 * * * def __del__(self): # <<<<<<<<<<<<<< @@ -28795,15 +30321,15 @@ static void __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolver */ /* Python wrapper */ -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47__reduce_cython__(PyObject *__pyx_v_self, +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_53__reduce_cython__(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else PyObject *__pyx_args, PyObject *__pyx_kwds #endif ); /*proto*/ -static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47__reduce_cython__(PyObject *__pyx_v_self, +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_53__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_53__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_53__reduce_cython__(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else @@ -28820,14 +30346,14 @@ PyObject *__pyx_args, PyObject *__pyx_kwds if (unlikely(__pyx_nargs > 0)) { __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; - __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_46__reduce_cython__(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_52__reduce_cython__(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); /* function exit code */ __Pyx_RefNannyFinishContext(); return __pyx_r; } -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_46__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_52__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { PyObject *__pyx_r = NULL; __Pyx_RefNannyDeclarations int __pyx_lineno = 0; @@ -28867,15 +30393,15 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ /* Python wrapper */ -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49__setstate_cython__(PyObject *__pyx_v_self, +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_55__setstate_cython__(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else PyObject *__pyx_args, PyObject *__pyx_kwds #endif ); /*proto*/ -static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49__setstate_cython__(PyObject *__pyx_v_self, +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_55__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_55__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_55__setstate_cython__(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else @@ -28930,14 +30456,14 @@ PyObject *__pyx_args, PyObject *__pyx_kwds __Pyx_RefNannyFinishContext(); return NULL; __pyx_L4_argument_unpacking_done:; - __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_48__setstate_cython__(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v___pyx_state); + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_54__setstate_cython__(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v___pyx_state); /* function exit code */ __Pyx_RefNannyFinishContext(); return __pyx_r; } -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_48__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_54__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { PyObject *__pyx_r = NULL; __Pyx_RefNannyDeclarations int __pyx_lineno = 0; @@ -28997,7 +30523,7 @@ static PyObject *__pyx_tp_new_15acados_template_21acados_ocp_solver_pyx_AcadosOc static void __pyx_tp_finalize_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython(PyObject *o) { PyObject *etype, *eval, *etb; PyErr_Fetch(&etype, &eval, &etb); - __pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_45__del__(o); + __pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_51__del__(o); PyErr_Restore(etype, eval, etb); } #endif @@ -29018,28 +30544,31 @@ static void __pyx_tp_dealloc_15acados_template_21acados_ocp_solver_pyx_AcadosOcp static PyMethodDef __pyx_methods_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython[] = { {"_AcadosOcpSolverCython__get_pointers_solver", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_3_AcadosOcpSolverCython__get_pointers_solver, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_2__get_pointers_solver}, - {"solve", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve}, - {"reset", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7reset, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6reset}, - {"set_new_time_steps", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9set_new_time_steps, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8set_new_time_steps}, - {"update_qp_solver_cond_N", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11update_qp_solver_cond_N, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10update_qp_solver_cond_N}, - {"eval_param_sens", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13eval_param_sens, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12eval_param_sens}, - {"get", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15get, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14get}, - {"print_statistics", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17print_statistics, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16print_statistics}, - {"store_iterate", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19store_iterate, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18store_iterate}, - {"load_iterate", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21load_iterate, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20load_iterate}, - {"get_stats", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23get_stats, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22get_stats}, - {"_AcadosOcpSolverCython__get_stat_int", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25_AcadosOcpSolverCython__get_stat_int, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, - {"_AcadosOcpSolverCython__get_stat_double", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27_AcadosOcpSolverCython__get_stat_double, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, - {"_AcadosOcpSolverCython__get_stat_matrix", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_matrix, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, - {"get_cost", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31get_cost, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_30get_cost}, - {"get_residuals", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33get_residuals, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_32get_residuals}, - {"set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34set}, - {"cost_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37cost_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36cost_set}, - {"constraints_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39constraints_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38constraints_set}, - {"dynamics_get", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41dynamics_get, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40dynamics_get}, - {"options_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43options_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42options_set}, - {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, - {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"solve_for_x0", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve_for_x0, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve_for_x0}, + {"solve", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7solve, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6solve}, + {"reset", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9reset, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8reset}, + {"custom_update", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11custom_update, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10custom_update}, + {"set_new_time_steps", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13set_new_time_steps, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12set_new_time_steps}, + {"update_qp_solver_cond_N", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15update_qp_solver_cond_N, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14update_qp_solver_cond_N}, + {"eval_param_sens", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17eval_param_sens, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16eval_param_sens}, + {"get", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19get, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18get}, + {"print_statistics", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21print_statistics, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20print_statistics}, + {"store_iterate", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23store_iterate, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22store_iterate}, + {"load_iterate", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25load_iterate, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_24load_iterate}, + {"get_stats", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27get_stats, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_26get_stats}, + {"_AcadosOcpSolverCython__get_stat_int", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_int, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"_AcadosOcpSolverCython__get_stat_double", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31_AcadosOcpSolverCython__get_stat_double, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"_AcadosOcpSolverCython__get_stat_matrix", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33_AcadosOcpSolverCython__get_stat_matrix, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"get_cost", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35get_cost, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34get_cost}, + {"get_residuals", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37get_residuals, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36get_residuals}, + {"set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38set}, + {"cost_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41cost_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40cost_set}, + {"constraints_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43constraints_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42constraints_set}, + {"get_from_qp_in", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_45get_from_qp_in, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_44get_from_qp_in}, + {"options_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47options_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_46options_set}, + {"set_params_sparse", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49set_params_sparse, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_48set_params_sparse}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_53__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_55__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, {0, 0, 0, 0} }; #if CYTHON_USE_TYPE_SPECS @@ -30086,6 +31615,7 @@ static PyMethodDef __pyx_methods[] = { static int __Pyx_CreateStringTabAndInitStrings(void) { __Pyx_StringTabEntry __pyx_string_tab[] = { {&__pyx_kp_u_, __pyx_k_, sizeof(__pyx_k_), 0, 1, 0, 0}, + {&__pyx_kp_u_0, __pyx_k_0, sizeof(__pyx_k_0), 0, 1, 0, 0}, {&__pyx_n_s_ASCII, __pyx_k_ASCII, sizeof(__pyx_k_ASCII), 0, 0, 1, 1}, {&__pyx_n_s_AcadosOcpSolverCython, __pyx_k_AcadosOcpSolverCython, sizeof(__pyx_k_AcadosOcpSolverCython), 0, 0, 1, 1}, {&__pyx_n_s_AcadosOcpSolverCython___get_poin, __pyx_k_AcadosOcpSolverCython___get_poin, sizeof(__pyx_k_AcadosOcpSolverCython___get_poin), 0, 0, 1, 1}, @@ -30102,15 +31632,16 @@ static int __Pyx_CreateStringTabAndInitStrings(void) { {&__pyx_n_s_AcadosOcpSolverCython_constraint_2, __pyx_k_AcadosOcpSolverCython_constraint_2, sizeof(__pyx_k_AcadosOcpSolverCython_constraint_2), 0, 0, 1, 1}, {&__pyx_n_s_AcadosOcpSolverCython_cost_set, __pyx_k_AcadosOcpSolverCython_cost_set, sizeof(__pyx_k_AcadosOcpSolverCython_cost_set), 0, 0, 1, 1}, {&__pyx_kp_u_AcadosOcpSolverCython_cost_set_m, __pyx_k_AcadosOcpSolverCython_cost_set_m, sizeof(__pyx_k_AcadosOcpSolverCython_cost_set_m), 0, 1, 0, 0}, + {&__pyx_n_s_AcadosOcpSolverCython_custom_upd, __pyx_k_AcadosOcpSolverCython_custom_upd, sizeof(__pyx_k_AcadosOcpSolverCython_custom_upd), 0, 0, 1, 1}, {&__pyx_kp_u_AcadosOcpSolverCython_does_not_s, __pyx_k_AcadosOcpSolverCython_does_not_s, sizeof(__pyx_k_AcadosOcpSolverCython_does_not_s), 0, 1, 0, 0}, {&__pyx_kp_u_AcadosOcpSolverCython_does_not_s_2, __pyx_k_AcadosOcpSolverCython_does_not_s_2, sizeof(__pyx_k_AcadosOcpSolverCython_does_not_s_2), 0, 1, 0, 0}, - {&__pyx_n_s_AcadosOcpSolverCython_dynamics_g, __pyx_k_AcadosOcpSolverCython_dynamics_g, sizeof(__pyx_k_AcadosOcpSolverCython_dynamics_g), 0, 0, 1, 1}, {&__pyx_kp_u_AcadosOcpSolverCython_eval_param, __pyx_k_AcadosOcpSolverCython_eval_param, sizeof(__pyx_k_AcadosOcpSolverCython_eval_param), 0, 1, 0, 0}, {&__pyx_kp_u_AcadosOcpSolverCython_eval_param_2, __pyx_k_AcadosOcpSolverCython_eval_param_2, sizeof(__pyx_k_AcadosOcpSolverCython_eval_param_2), 0, 1, 0, 0}, {&__pyx_n_s_AcadosOcpSolverCython_eval_param_3, __pyx_k_AcadosOcpSolverCython_eval_param_3, sizeof(__pyx_k_AcadosOcpSolverCython_eval_param_3), 0, 0, 1, 1}, {&__pyx_n_s_AcadosOcpSolverCython_get, __pyx_k_AcadosOcpSolverCython_get, sizeof(__pyx_k_AcadosOcpSolverCython_get), 0, 0, 1, 1}, {&__pyx_n_s_AcadosOcpSolverCython_get_cost, __pyx_k_AcadosOcpSolverCython_get_cost, sizeof(__pyx_k_AcadosOcpSolverCython_get_cost), 0, 0, 1, 1}, {&__pyx_kp_u_AcadosOcpSolverCython_get_field, __pyx_k_AcadosOcpSolverCython_get_field, sizeof(__pyx_k_AcadosOcpSolverCython_get_field), 0, 1, 0, 0}, + {&__pyx_n_s_AcadosOcpSolverCython_get_from_q, __pyx_k_AcadosOcpSolverCython_get_from_q, sizeof(__pyx_k_AcadosOcpSolverCython_get_from_q), 0, 0, 1, 1}, {&__pyx_kp_u_AcadosOcpSolverCython_get_is_an, __pyx_k_AcadosOcpSolverCython_get_is_an, sizeof(__pyx_k_AcadosOcpSolverCython_get_is_an), 0, 1, 0, 0}, {&__pyx_n_s_AcadosOcpSolverCython_get_residu, __pyx_k_AcadosOcpSolverCython_get_residu, sizeof(__pyx_k_AcadosOcpSolverCython_get_residu), 0, 0, 1, 1}, {&__pyx_kp_u_AcadosOcpSolverCython_get_stage, __pyx_k_AcadosOcpSolverCython_get_stage, sizeof(__pyx_k_AcadosOcpSolverCython_get_stage), 0, 1, 0, 0}, @@ -30124,9 +31655,11 @@ static int __Pyx_CreateStringTabAndInitStrings(void) { {&__pyx_kp_u_AcadosOcpSolverCython_set_is_not, __pyx_k_AcadosOcpSolverCython_set_is_not, sizeof(__pyx_k_AcadosOcpSolverCython_set_is_not), 0, 1, 0, 0}, {&__pyx_kp_u_AcadosOcpSolverCython_set_mismat, __pyx_k_AcadosOcpSolverCython_set_mismat, sizeof(__pyx_k_AcadosOcpSolverCython_set_mismat), 0, 1, 0, 0}, {&__pyx_n_s_AcadosOcpSolverCython_set_new_ti, __pyx_k_AcadosOcpSolverCython_set_new_ti, sizeof(__pyx_k_AcadosOcpSolverCython_set_new_ti), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython_set_params, __pyx_k_AcadosOcpSolverCython_set_params, sizeof(__pyx_k_AcadosOcpSolverCython_set_params), 0, 0, 1, 1}, {&__pyx_n_s_AcadosOcpSolverCython_solve, __pyx_k_AcadosOcpSolverCython_solve, sizeof(__pyx_k_AcadosOcpSolverCython_solve), 0, 0, 1, 1}, {&__pyx_kp_u_AcadosOcpSolverCython_solve_argu, __pyx_k_AcadosOcpSolverCython_solve_argu, sizeof(__pyx_k_AcadosOcpSolverCython_solve_argu), 0, 1, 0, 0}, {&__pyx_kp_u_AcadosOcpSolverCython_solve_argu_2, __pyx_k_AcadosOcpSolverCython_solve_argu_2, sizeof(__pyx_k_AcadosOcpSolverCython_solve_argu_2), 0, 1, 0, 0}, + {&__pyx_n_s_AcadosOcpSolverCython_solve_for, __pyx_k_AcadosOcpSolverCython_solve_for, sizeof(__pyx_k_AcadosOcpSolverCython_solve_for), 0, 0, 1, 1}, {&__pyx_n_s_AcadosOcpSolverCython_store_iter, __pyx_k_AcadosOcpSolverCython_store_iter, sizeof(__pyx_k_AcadosOcpSolverCython_store_iter), 0, 0, 1, 1}, {&__pyx_n_s_AcadosOcpSolverCython_update_qp, __pyx_k_AcadosOcpSolverCython_update_qp, sizeof(__pyx_k_AcadosOcpSolverCython_update_qp), 0, 0, 1, 1}, {&__pyx_kp_s_All_dimensions_preceding_dimensi, __pyx_k_All_dimensions_preceding_dimensi, sizeof(__pyx_k_All_dimensions_preceding_dimensi), 0, 0, 1, 0}, @@ -30141,6 +31674,7 @@ static int __Pyx_CreateStringTabAndInitStrings(void) { {&__pyx_n_s_Ellipsis, __pyx_k_Ellipsis, sizeof(__pyx_k_Ellipsis), 0, 0, 1, 1}, {&__pyx_kp_s_Empty_shape_tuple_for_cython_arr, __pyx_k_Empty_shape_tuple_for_cython_arr, sizeof(__pyx_k_Empty_shape_tuple_for_cython_arr), 0, 0, 1, 0}, {&__pyx_n_u_F, __pyx_k_F, sizeof(__pyx_k_F), 0, 1, 0, 1}, + {&__pyx_kp_u_Got_sizes_idx, __pyx_k_Got_sizes_idx, sizeof(__pyx_k_Got_sizes_idx), 0, 1, 0, 0}, {&__pyx_n_s_ImportError, __pyx_k_ImportError, sizeof(__pyx_k_ImportError), 0, 0, 1, 1}, {&__pyx_kp_s_Incompatible_checksums_0x_x_vs_0, __pyx_k_Incompatible_checksums_0x_x_vs_0, sizeof(__pyx_k_Incompatible_checksums_0x_x_vs_0), 0, 0, 1, 0}, {&__pyx_n_s_IndexError, __pyx_k_IndexError, sizeof(__pyx_k_IndexError), 0, 0, 1, 1}, @@ -30166,16 +31700,18 @@ static int __Pyx_CreateStringTabAndInitStrings(void) { {&__pyx_kp_s_Unable_to_convert_item_to_object, __pyx_k_Unable_to_convert_item_to_object, sizeof(__pyx_k_Unable_to_convert_item_to_object), 0, 0, 1, 0}, {&__pyx_n_s_ValueError, __pyx_k_ValueError, sizeof(__pyx_k_ValueError), 0, 0, 1, 1}, {&__pyx_n_s_View_MemoryView, __pyx_k_View_MemoryView, sizeof(__pyx_k_View_MemoryView), 0, 0, 1, 1}, + {&__pyx_kp_u_Warning_acados_ocp_solver_reache, __pyx_k_Warning_acados_ocp_solver_reache, sizeof(__pyx_k_Warning_acados_ocp_solver_reache), 0, 1, 0, 0}, {&__pyx_kp_u_Y_m_d_H_M_S_f, __pyx_k_Y_m_d_H_M_S_f, sizeof(__pyx_k_Y_m_d_H_M_S_f), 0, 1, 0, 0}, - {&__pyx_kp_u__14, __pyx_k__14, sizeof(__pyx_k__14), 0, 1, 0, 0}, - {&__pyx_n_u__15, __pyx_k__15, sizeof(__pyx_k__15), 0, 1, 0, 1}, + {&__pyx_kp_u__16, __pyx_k__16, sizeof(__pyx_k__16), 0, 1, 0, 0}, + {&__pyx_n_u__17, __pyx_k__17, sizeof(__pyx_k__17), 0, 1, 0, 1}, {&__pyx_kp_u__2, __pyx_k__2, sizeof(__pyx_k__2), 0, 1, 0, 0}, - {&__pyx_kp_u__29, __pyx_k__29, sizeof(__pyx_k__29), 0, 1, 0, 0}, {&__pyx_n_s__3, __pyx_k__3, sizeof(__pyx_k__3), 0, 0, 1, 1}, + {&__pyx_kp_u__31, __pyx_k__31, sizeof(__pyx_k__31), 0, 1, 0, 0}, {&__pyx_kp_u__6, __pyx_k__6, sizeof(__pyx_k__6), 0, 1, 0, 0}, {&__pyx_kp_u__7, __pyx_k__7, sizeof(__pyx_k__7), 0, 1, 0, 0}, - {&__pyx_n_s__84, __pyx_k__84, sizeof(__pyx_k__84), 0, 0, 1, 1}, + {&__pyx_n_s__94, __pyx_k__94, sizeof(__pyx_k__94), 0, 0, 1, 1}, {&__pyx_n_s_abc, __pyx_k_abc, sizeof(__pyx_k_abc), 0, 0, 1, 1}, + {&__pyx_kp_u_acados_acados_ocp_solver_returne, __pyx_k_acados_acados_ocp_solver_returne, sizeof(__pyx_k_acados_acados_ocp_solver_returne), 0, 1, 0, 0}, {&__pyx_n_s_acados_template_acados_ocp_solve, __pyx_k_acados_template_acados_ocp_solve, sizeof(__pyx_k_acados_template_acados_ocp_solve), 0, 0, 1, 1}, {&__pyx_n_s_allocate_buffer, __pyx_k_allocate_buffer, sizeof(__pyx_k_allocate_buffer), 0, 0, 1, 1}, {&__pyx_n_u_alpha, __pyx_k_alpha, sizeof(__pyx_k_alpha), 0, 1, 0, 1}, @@ -30198,11 +31734,18 @@ static int __Pyx_CreateStringTabAndInitStrings(void) { {&__pyx_kp_s_collections_abc, __pyx_k_collections_abc, sizeof(__pyx_k_collections_abc), 0, 0, 1, 0}, {&__pyx_n_s_constraints_fields, __pyx_k_constraints_fields, sizeof(__pyx_k_constraints_fields), 0, 0, 1, 1}, {&__pyx_n_s_constraints_set, __pyx_k_constraints_set, sizeof(__pyx_k_constraints_set), 0, 0, 1, 1}, + {&__pyx_kp_u_constraints_set_value_must_be_nu, __pyx_k_constraints_set_value_must_be_nu, sizeof(__pyx_k_constraints_set_value_must_be_nu), 0, 1, 0, 0}, {&__pyx_kp_s_contiguous_and_direct, __pyx_k_contiguous_and_direct, sizeof(__pyx_k_contiguous_and_direct), 0, 0, 1, 0}, {&__pyx_kp_s_contiguous_and_indirect, __pyx_k_contiguous_and_indirect, sizeof(__pyx_k_contiguous_and_indirect), 0, 0, 1, 0}, {&__pyx_n_s_cost_fields, __pyx_k_cost_fields, sizeof(__pyx_k_cost_fields), 0, 0, 1, 1}, {&__pyx_n_s_cost_set, __pyx_k_cost_set, sizeof(__pyx_k_cost_set), 0, 0, 1, 1}, + {&__pyx_kp_u_cost_set_value_must_be_numpy_arr, __pyx_k_cost_set_value_must_be_numpy_arr, sizeof(__pyx_k_cost_set_value_must_be_numpy_arr), 0, 1, 0, 0}, {&__pyx_n_s_count, __pyx_k_count, sizeof(__pyx_k_count), 0, 0, 1, 1}, + {&__pyx_n_s_custom_update, __pyx_k_custom_update, sizeof(__pyx_k_custom_update), 0, 0, 1, 1}, + {&__pyx_n_u_d, __pyx_k_d, sizeof(__pyx_k_d), 0, 1, 0, 1}, + {&__pyx_n_s_data, __pyx_k_data, sizeof(__pyx_k_data), 0, 0, 1, 1}, + {&__pyx_n_s_data_2, __pyx_k_data_2, sizeof(__pyx_k_data_2), 0, 0, 1, 1}, + {&__pyx_n_s_data_len, __pyx_k_data_len, sizeof(__pyx_k_data_len), 0, 0, 1, 1}, {&__pyx_n_s_datetime, __pyx_k_datetime, sizeof(__pyx_k_datetime), 0, 0, 1, 1}, {&__pyx_n_s_default, __pyx_k_default, sizeof(__pyx_k_default), 0, 0, 1, 1}, {&__pyx_n_s_dict, __pyx_k_dict, sizeof(__pyx_k_dict), 0, 0, 1, 1}, @@ -30213,7 +31756,6 @@ static int __Pyx_CreateStringTabAndInitStrings(void) { {&__pyx_n_s_dtype, __pyx_k_dtype, sizeof(__pyx_k_dtype), 0, 0, 1, 1}, {&__pyx_n_s_dtype_is_object, __pyx_k_dtype_is_object, sizeof(__pyx_k_dtype_is_object), 0, 0, 1, 1}, {&__pyx_n_s_dump, __pyx_k_dump, sizeof(__pyx_k_dump), 0, 0, 1, 1}, - {&__pyx_n_s_dynamics_get, __pyx_k_dynamics_get, sizeof(__pyx_k_dynamics_get), 0, 0, 1, 1}, {&__pyx_kp_u_enable, __pyx_k_enable, sizeof(__pyx_k_enable), 0, 1, 0, 0}, {&__pyx_n_s_encode, __pyx_k_encode, sizeof(__pyx_k_encode), 0, 0, 1, 1}, {&__pyx_n_s_enter, __pyx_k_enter, sizeof(__pyx_k_enter), 0, 0, 1, 1}, @@ -30239,6 +31781,7 @@ static int __Pyx_CreateStringTabAndInitStrings(void) { {&__pyx_kp_u_gc, __pyx_k_gc, sizeof(__pyx_k_gc), 0, 1, 0, 0}, {&__pyx_n_s_get, __pyx_k_get, sizeof(__pyx_k_get), 0, 0, 1, 1}, {&__pyx_n_s_get_cost, __pyx_k_get_cost, sizeof(__pyx_k_get_cost), 0, 0, 1, 1}, + {&__pyx_n_s_get_from_qp_in, __pyx_k_get_from_qp_in, sizeof(__pyx_k_get_from_qp_in), 0, 0, 1, 1}, {&__pyx_n_s_get_pointers_solver, __pyx_k_get_pointers_solver, sizeof(__pyx_k_get_pointers_solver), 0, 0, 1, 1}, {&__pyx_n_s_get_residuals, __pyx_k_get_residuals, sizeof(__pyx_k_get_residuals), 0, 0, 1, 1}, {&__pyx_n_s_get_stat_double, __pyx_k_get_stat_double, sizeof(__pyx_k_get_stat_double), 0, 0, 1, 1}, @@ -30252,13 +31795,17 @@ static int __Pyx_CreateStringTabAndInitStrings(void) { {&__pyx_kp_u_got, __pyx_k_got, sizeof(__pyx_k_got), 0, 1, 0, 0}, {&__pyx_kp_u_got_differing_extents_in_dimensi, __pyx_k_got_differing_extents_in_dimensi, sizeof(__pyx_k_got_differing_extents_in_dimensi), 0, 1, 0, 0}, {&__pyx_n_s_i, __pyx_k_i, sizeof(__pyx_k_i), 0, 0, 1, 1}, + {&__pyx_n_s_i_string, __pyx_k_i_string, sizeof(__pyx_k_i_string), 0, 0, 1, 1}, {&__pyx_n_s_id, __pyx_k_id, sizeof(__pyx_k_id), 0, 0, 1, 1}, + {&__pyx_n_s_idx, __pyx_k_idx, sizeof(__pyx_k_idx), 0, 0, 1, 1}, + {&__pyx_n_s_idx_values, __pyx_k_idx_values, sizeof(__pyx_k_idx_values), 0, 0, 1, 1}, {&__pyx_n_s_import, __pyx_k_import, sizeof(__pyx_k_import), 0, 0, 1, 1}, {&__pyx_n_s_indent, __pyx_k_indent, sizeof(__pyx_k_indent), 0, 0, 1, 1}, {&__pyx_n_s_index, __pyx_k_index, sizeof(__pyx_k_index), 0, 0, 1, 1}, {&__pyx_n_u_initialize_t_slacks, __pyx_k_initialize_t_slacks, sizeof(__pyx_k_initialize_t_slacks), 0, 1, 0, 1}, {&__pyx_n_s_initializing, __pyx_k_initializing, sizeof(__pyx_k_initializing), 0, 0, 1, 1}, {&__pyx_n_s_int, __pyx_k_int, sizeof(__pyx_k_int), 0, 0, 1, 1}, + {&__pyx_n_s_int32, __pyx_k_int32, sizeof(__pyx_k_int32), 0, 0, 1, 1}, {&__pyx_n_s_int_fields, __pyx_k_int_fields, sizeof(__pyx_k_int_fields), 0, 0, 1, 1}, {&__pyx_n_s_int_value, __pyx_k_int_value, sizeof(__pyx_k_int_value), 0, 0, 1, 1}, {&__pyx_n_s_is_coroutine, __pyx_k_is_coroutine, sizeof(__pyx_k_is_coroutine), 0, 0, 1, 1}, @@ -30270,8 +31817,10 @@ static int __Pyx_CreateStringTabAndInitStrings(void) { {&__pyx_n_s_join, __pyx_k_join, sizeof(__pyx_k_join), 0, 0, 1, 1}, {&__pyx_n_s_json, __pyx_k_json, sizeof(__pyx_k_json), 0, 0, 1, 1}, {&__pyx_kp_u_json_2, __pyx_k_json_2, sizeof(__pyx_k_json_2), 0, 1, 0, 0}, + {&__pyx_n_s_k, __pyx_k_k, sizeof(__pyx_k_k), 0, 0, 1, 1}, {&__pyx_n_s_key, __pyx_k_key, sizeof(__pyx_k_key), 0, 0, 1, 1}, {&__pyx_n_s_keys, __pyx_k_keys, sizeof(__pyx_k_keys), 0, 0, 1, 1}, + {&__pyx_n_s_lN, __pyx_k_lN, sizeof(__pyx_k_lN), 0, 0, 1, 1}, {&__pyx_n_u_lam, __pyx_k_lam, sizeof(__pyx_k_lam), 0, 1, 0, 1}, {&__pyx_n_u_lam_2, __pyx_k_lam_2, sizeof(__pyx_k_lam_2), 0, 1, 0, 1}, {&__pyx_n_u_lbu, __pyx_k_lbu, sizeof(__pyx_k_lbu), 0, 1, 0, 1}, @@ -30289,8 +31838,10 @@ static int __Pyx_CreateStringTabAndInitStrings(void) { {&__pyx_n_s_model_name, __pyx_k_model_name, sizeof(__pyx_k_model_name), 0, 0, 1, 1}, {&__pyx_n_s_msg, __pyx_k_msg, sizeof(__pyx_k_msg), 0, 0, 1, 1}, {&__pyx_n_s_n, __pyx_k_n, sizeof(__pyx_k_n), 0, 0, 1, 1}, + {&__pyx_n_s_n_update, __pyx_k_n_update, sizeof(__pyx_k_n_update), 0, 0, 1, 1}, {&__pyx_n_s_name, __pyx_k_name, sizeof(__pyx_k_name), 0, 0, 1, 1}, {&__pyx_n_s_name_2, __pyx_k_name_2, sizeof(__pyx_k_name_2), 0, 0, 1, 1}, + {&__pyx_n_s_ndarray, __pyx_k_ndarray, sizeof(__pyx_k_ndarray), 0, 0, 1, 1}, {&__pyx_n_s_ndim, __pyx_k_ndim, sizeof(__pyx_k_ndim), 0, 0, 1, 1}, {&__pyx_n_s_new, __pyx_k_new, sizeof(__pyx_k_new), 0, 0, 1, 1}, {&__pyx_n_s_new_time_steps, __pyx_k_new_time_steps, sizeof(__pyx_k_new_time_steps), 0, 0, 1, 1}, @@ -30312,6 +31863,10 @@ static int __Pyx_CreateStringTabAndInitStrings(void) { {&__pyx_n_s_overwrite, __pyx_k_overwrite, sizeof(__pyx_k_overwrite), 0, 0, 1, 1}, {&__pyx_n_u_p, __pyx_k_p, sizeof(__pyx_k_p), 0, 1, 0, 1}, {&__pyx_n_s_pack, __pyx_k_pack, sizeof(__pyx_k_pack), 0, 0, 1, 1}, + {&__pyx_n_s_param_values, __pyx_k_param_values, sizeof(__pyx_k_param_values), 0, 0, 1, 1}, + {&__pyx_kp_u_param_values_2, __pyx_k_param_values_2, sizeof(__pyx_k_param_values_2), 0, 1, 0, 0}, + {&__pyx_kp_u_param_values__and_idx_values__mu, __pyx_k_param_values__and_idx_values__mu, sizeof(__pyx_k_param_values__and_idx_values__mu), 0, 1, 0, 0}, + {&__pyx_kp_u_param_values__must_be_np_array, __pyx_k_param_values__must_be_np_array, sizeof(__pyx_k_param_values__must_be_np_array), 0, 1, 0, 0}, {&__pyx_n_s_path, __pyx_k_path, sizeof(__pyx_k_path), 0, 0, 1, 1}, {&__pyx_n_u_pi, __pyx_k_pi, sizeof(__pyx_k_pi), 0, 1, 0, 1}, {&__pyx_n_u_pi_2, __pyx_k_pi_2, sizeof(__pyx_k_pi_2), 0, 1, 0, 1}, @@ -30347,11 +31902,14 @@ static int __Pyx_CreateStringTabAndInitStrings(void) { {&__pyx_n_b_res_ineq, __pyx_k_res_ineq, sizeof(__pyx_k_res_ineq), 0, 0, 0, 1}, {&__pyx_n_b_res_stat, __pyx_k_res_stat, sizeof(__pyx_k_res_stat), 0, 0, 0, 1}, {&__pyx_n_s_reset, __pyx_k_reset, sizeof(__pyx_k_reset), 0, 0, 1, 1}, + {&__pyx_n_s_reset_qp_solver_mem, __pyx_k_reset_qp_solver_mem, sizeof(__pyx_k_reset_qp_solver_mem), 0, 0, 1, 1}, {&__pyx_n_u_residuals, __pyx_k_residuals, sizeof(__pyx_k_residuals), 0, 1, 0, 1}, {&__pyx_n_u_rti_phase, __pyx_k_rti_phase, sizeof(__pyx_k_rti_phase), 0, 1, 0, 1}, {&__pyx_n_s_self, __pyx_k_self, sizeof(__pyx_k_self), 0, 0, 1, 1}, {&__pyx_n_s_set, __pyx_k_set, sizeof(__pyx_k_set), 0, 0, 1, 1}, {&__pyx_n_s_set_new_time_steps, __pyx_k_set_new_time_steps, sizeof(__pyx_k_set_new_time_steps), 0, 0, 1, 1}, + {&__pyx_n_s_set_params_sparse, __pyx_k_set_params_sparse, sizeof(__pyx_k_set_params_sparse), 0, 0, 1, 1}, + {&__pyx_kp_u_set_value_must_be_numpy_array_go, __pyx_k_set_value_must_be_numpy_array_go, sizeof(__pyx_k_set_value_must_be_numpy_array_go), 0, 1, 0, 0}, {&__pyx_n_s_setstate, __pyx_k_setstate, sizeof(__pyx_k_setstate), 0, 0, 1, 1}, {&__pyx_n_s_setstate_cython, __pyx_k_setstate_cython, sizeof(__pyx_k_setstate_cython), 0, 0, 1, 1}, {&__pyx_n_s_shape, __pyx_k_shape, sizeof(__pyx_k_shape), 0, 0, 1, 1}, @@ -30360,6 +31918,7 @@ static int __Pyx_CreateStringTabAndInitStrings(void) { {&__pyx_n_u_sl_2, __pyx_k_sl_2, sizeof(__pyx_k_sl_2), 0, 1, 0, 1}, {&__pyx_n_s_solution, __pyx_k_solution, sizeof(__pyx_k_solution), 0, 0, 1, 1}, {&__pyx_n_s_solve, __pyx_k_solve, sizeof(__pyx_k_solve), 0, 0, 1, 1}, + {&__pyx_n_s_solve_for_x0, __pyx_k_solve_for_x0, sizeof(__pyx_k_solve_for_x0), 0, 0, 1, 1}, {&__pyx_kp_u_solver_option_must_be_of_type_fl, __pyx_k_solver_option_must_be_of_type_fl, sizeof(__pyx_k_solver_option_must_be_of_type_fl), 0, 1, 0, 0}, {&__pyx_kp_u_solver_option_must_be_of_type_in, __pyx_k_solver_option_must_be_of_type_in, sizeof(__pyx_k_solver_option_must_be_of_type_in), 0, 1, 0, 0}, {&__pyx_kp_u_solver_option_must_be_of_type_st, __pyx_k_solver_option_must_be_of_type_st, sizeof(__pyx_k_solver_option_must_be_of_type_st), 0, 1, 0, 0}, @@ -30375,6 +31934,7 @@ static int __Pyx_CreateStringTabAndInitStrings(void) { {&__pyx_n_s_stat_n, __pyx_k_stat_n, sizeof(__pyx_k_stat_n), 0, 0, 1, 1}, {&__pyx_n_u_stat_n, __pyx_k_stat_n, sizeof(__pyx_k_stat_n), 0, 1, 0, 1}, {&__pyx_n_u_statistics, __pyx_k_statistics, sizeof(__pyx_k_statistics), 0, 1, 0, 1}, + {&__pyx_n_s_status, __pyx_k_status, sizeof(__pyx_k_status), 0, 0, 1, 1}, {&__pyx_n_s_step, __pyx_k_step, sizeof(__pyx_k_step), 0, 0, 1, 1}, {&__pyx_n_u_step_length, __pyx_k_step_length, sizeof(__pyx_k_step_length), 0, 1, 0, 1}, {&__pyx_n_s_stop, __pyx_k_stop, sizeof(__pyx_k_stop), 0, 0, 1, 1}, @@ -30413,6 +31973,7 @@ static int __Pyx_CreateStringTabAndInitStrings(void) { {&__pyx_n_u_tol_stat, __pyx_k_tol_stat, sizeof(__pyx_k_tol_stat), 0, 1, 0, 1}, {&__pyx_n_s_tolist, __pyx_k_tolist, sizeof(__pyx_k_tolist), 0, 0, 1, 1}, {&__pyx_n_u_u, __pyx_k_u, sizeof(__pyx_k_u), 0, 1, 0, 1}, + {&__pyx_n_s_u0, __pyx_k_u0, sizeof(__pyx_k_u0), 0, 0, 1, 1}, {&__pyx_n_u_u_2, __pyx_k_u_2, sizeof(__pyx_k_u_2), 0, 1, 0, 1}, {&__pyx_n_u_ubu, __pyx_k_ubu, sizeof(__pyx_k_ubu), 0, 1, 0, 1}, {&__pyx_n_u_ubx, __pyx_k_ubx, sizeof(__pyx_k_ubx), 0, 1, 0, 1}, @@ -30434,6 +31995,7 @@ static int __Pyx_CreateStringTabAndInitStrings(void) { {&__pyx_n_b_x, __pyx_k_x, sizeof(__pyx_k_x), 0, 0, 0, 1}, {&__pyx_n_s_x, __pyx_k_x, sizeof(__pyx_k_x), 0, 0, 1, 1}, {&__pyx_n_u_x, __pyx_k_x, sizeof(__pyx_k_x), 0, 1, 0, 1}, + {&__pyx_n_s_x0_bar, __pyx_k_x0_bar, sizeof(__pyx_k_x0_bar), 0, 0, 1, 1}, {&__pyx_n_u_x_2, __pyx_k_x_2, sizeof(__pyx_k_x_2), 0, 1, 0, 1}, {&__pyx_n_u_xdot_guess, __pyx_k_xdot_guess, sizeof(__pyx_k_xdot_guess), 0, 1, 0, 1}, {&__pyx_n_u_y_ref, __pyx_k_y_ref, sizeof(__pyx_k_y_ref), 0, 1, 0, 1}, @@ -30441,6 +32003,7 @@ static int __Pyx_CreateStringTabAndInitStrings(void) { {&__pyx_n_u_yref, __pyx_k_yref, sizeof(__pyx_k_yref), 0, 1, 0, 1}, {&__pyx_n_u_z, __pyx_k_z, sizeof(__pyx_k_z), 0, 1, 0, 1}, {&__pyx_n_u_z_2, __pyx_k_z_2, sizeof(__pyx_k_z_2), 0, 1, 0, 1}, + {&__pyx_n_b_z_guess, __pyx_k_z_guess, sizeof(__pyx_k_z_guess), 0, 0, 0, 1}, {&__pyx_n_u_z_guess, __pyx_k_z_guess, sizeof(__pyx_k_z_guess), 0, 1, 0, 1}, {&__pyx_n_s_zeros, __pyx_k_zeros, sizeof(__pyx_k_zeros), 0, 0, 1, 1}, {0, 0, 0, 0, 0, 0, 0} @@ -30449,11 +32012,11 @@ static int __Pyx_CreateStringTabAndInitStrings(void) { } /* #### Code section: cached_builtins ### */ static CYTHON_SMALL_CODE int __Pyx_InitCachedBuiltins(void) { - __pyx_builtin_AssertionError = __Pyx_GetBuiltinName(__pyx_n_s_AssertionError); if (!__pyx_builtin_AssertionError) __PYX_ERR(0, 86, __pyx_L1_error) - __pyx_builtin_NotImplementedError = __Pyx_GetBuiltinName(__pyx_n_s_NotImplementedError); if (!__pyx_builtin_NotImplementedError) __PYX_ERR(0, 134, __pyx_L1_error) - __pyx_builtin_range = __Pyx_GetBuiltinName(__pyx_n_s_range); if (!__pyx_builtin_range) __PYX_ERR(0, 313, __pyx_L1_error) - __pyx_builtin_open = __Pyx_GetBuiltinName(__pyx_n_s_open); if (!__pyx_builtin_open) __PYX_ERR(0, 325, __pyx_L1_error) - __pyx_builtin_print = __Pyx_GetBuiltinName(__pyx_n_s_print); if (!__pyx_builtin_print) __PYX_ERR(0, 327, __pyx_L1_error) + __pyx_builtin_AssertionError = __Pyx_GetBuiltinName(__pyx_n_s_AssertionError); if (!__pyx_builtin_AssertionError) __PYX_ERR(0, 82, __pyx_L1_error) + __pyx_builtin_print = __Pyx_GetBuiltinName(__pyx_n_s_print); if (!__pyx_builtin_print) __PYX_ERR(0, 113, __pyx_L1_error) + __pyx_builtin_NotImplementedError = __Pyx_GetBuiltinName(__pyx_n_s_NotImplementedError); if (!__pyx_builtin_NotImplementedError) __PYX_ERR(0, 160, __pyx_L1_error) + __pyx_builtin_range = __Pyx_GetBuiltinName(__pyx_n_s_range); if (!__pyx_builtin_range) __PYX_ERR(0, 340, __pyx_L1_error) + __pyx_builtin_open = __Pyx_GetBuiltinName(__pyx_n_s_open); if (!__pyx_builtin_open) __PYX_ERR(0, 357, __pyx_L1_error) __pyx_builtin_TypeError = __Pyx_GetBuiltinName(__pyx_n_s_TypeError); if (!__pyx_builtin_TypeError) __PYX_ERR(1, 2, __pyx_L1_error) __pyx_builtin___import__ = __Pyx_GetBuiltinName(__pyx_n_s_import); if (!__pyx_builtin___import__) __PYX_ERR(1, 100, __pyx_L1_error) __pyx_builtin_ValueError = __Pyx_GetBuiltinName(__pyx_n_s_ValueError); if (!__pyx_builtin_ValueError) __PYX_ERR(1, 141, __pyx_L1_error) @@ -30531,173 +32094,206 @@ static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { __Pyx_GOTREF(__pyx_tuple__10); __Pyx_GIVEREF(__pyx_tuple__10); - /* "acados_template/acados_ocp_solver_pyx.pyx":134 + /* "acados_template/acados_ocp_solver_pyx.pyx":113 + * + * if status == 2: + * print("Warning: acados_ocp_solver reached maximum iterations.") # <<<<<<<<<<<<<< + * elif status != 0: + * raise Exception(f'acados acados_ocp_solver returned status {status}') + */ + __pyx_tuple__11 = PyTuple_Pack(1, __pyx_kp_u_Warning_acados_ocp_solver_reache); if (unlikely(!__pyx_tuple__11)) __PYX_ERR(0, 113, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__11); + __Pyx_GIVEREF(__pyx_tuple__11); + + /* "acados_template/acados_ocp_solver_pyx.pyx":117 + * raise Exception(f'acados acados_ocp_solver returned status {status}') + * + * u0 = self.get(0, "u") # <<<<<<<<<<<<<< + * return u0 + * + */ + __pyx_tuple__12 = PyTuple_Pack(2, __pyx_int_0, __pyx_n_u_u); if (unlikely(!__pyx_tuple__12)) __PYX_ERR(0, 117, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__12); + __Pyx_GIVEREF(__pyx_tuple__12); + + /* "acados_template/acados_ocp_solver_pyx.pyx":160 * """ * * raise NotImplementedError("AcadosOcpSolverCython: does not support set_new_time_steps() since it is only a prototyping feature") # <<<<<<<<<<<<<< * # # unlikely but still possible * # if not self.solver_created: */ - __pyx_tuple__11 = PyTuple_Pack(1, __pyx_kp_u_AcadosOcpSolverCython_does_not_s); if (unlikely(!__pyx_tuple__11)) __PYX_ERR(0, 134, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__11); - __Pyx_GIVEREF(__pyx_tuple__11); + __pyx_tuple__13 = PyTuple_Pack(1, __pyx_kp_u_AcadosOcpSolverCython_does_not_s); if (unlikely(!__pyx_tuple__13)) __PYX_ERR(0, 160, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__13); + __Pyx_GIVEREF(__pyx_tuple__13); - /* "acados_template/acados_ocp_solver_pyx.pyx":186 + /* "acados_template/acados_ocp_solver_pyx.pyx":212 * `qp_solver_cond_N < N`. * """ * raise NotImplementedError("AcadosOcpSolverCython: does not support update_qp_solver_cond_N() since it is only a prototyping feature") # <<<<<<<<<<<<<< * * # # unlikely but still possible */ - __pyx_tuple__12 = PyTuple_Pack(1, __pyx_kp_u_AcadosOcpSolverCython_does_not_s_2); if (unlikely(!__pyx_tuple__12)) __PYX_ERR(0, 186, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__12); - __Pyx_GIVEREF(__pyx_tuple__12); + __pyx_tuple__14 = PyTuple_Pack(1, __pyx_kp_u_AcadosOcpSolverCython_does_not_s_2); if (unlikely(!__pyx_tuple__14)) __PYX_ERR(0, 212, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__14); + __Pyx_GIVEREF(__pyx_tuple__14); - /* "acados_template/acados_ocp_solver_pyx.pyx":219 + /* "acados_template/acados_ocp_solver_pyx.pyx":245 * # checks * if not isinstance(index, int): * raise Exception('AcadosOcpSolverCython.eval_param_sens(): index must be Integer.') # <<<<<<<<<<<<<< * * cdef int nx = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, self.nlp_dims, self.nlp_out, 0, "x".encode('utf-8')) */ - __pyx_tuple__13 = PyTuple_Pack(1, __pyx_kp_u_AcadosOcpSolverCython_eval_param); if (unlikely(!__pyx_tuple__13)) __PYX_ERR(0, 219, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__13); - __Pyx_GIVEREF(__pyx_tuple__13); + __pyx_tuple__15 = PyTuple_Pack(1, __pyx_kp_u_AcadosOcpSolverCython_eval_param); if (unlikely(!__pyx_tuple__15)) __PYX_ERR(0, 245, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__15); + __Pyx_GIVEREF(__pyx_tuple__15); - /* "acados_template/acados_ocp_solver_pyx.pyx":307 + /* "acados_template/acados_ocp_solver_pyx.pyx":333 * # append timestamp * if os.path.isfile(filename): * filename = filename[:-5] # <<<<<<<<<<<<<< * filename += datetime.utcnow().strftime('%Y-%m-%d-%H:%M:%S.%f') + '.json' * */ - __pyx_slice__16 = PySlice_New(Py_None, __pyx_int_neg_5, Py_None); if (unlikely(!__pyx_slice__16)) __PYX_ERR(0, 307, __pyx_L1_error) - __Pyx_GOTREF(__pyx_slice__16); - __Pyx_GIVEREF(__pyx_slice__16); + __pyx_slice__18 = PySlice_New(Py_None, __pyx_int_neg_5, Py_None); if (unlikely(!__pyx_slice__18)) __PYX_ERR(0, 333, __pyx_L1_error) + __Pyx_GOTREF(__pyx_slice__18); + __Pyx_GIVEREF(__pyx_slice__18); - /* "acados_template/acados_ocp_solver_pyx.pyx":325 + /* "acados_template/acados_ocp_solver_pyx.pyx":357 * * # save * with open(filename, 'w') as f: # <<<<<<<<<<<<<< * json.dump(solution, f, default=lambda x: x.tolist(), indent=4, sort_keys=True) * print("stored current iterate in ", os.path.join(os.getcwd(), filename)) */ - __pyx_tuple__17 = PyTuple_Pack(3, Py_None, Py_None, Py_None); if (unlikely(!__pyx_tuple__17)) __PYX_ERR(0, 325, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__17); - __Pyx_GIVEREF(__pyx_tuple__17); + __pyx_tuple__19 = PyTuple_Pack(3, Py_None, Py_None, Py_None); if (unlikely(!__pyx_tuple__19)) __PYX_ERR(0, 357, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__19); + __Pyx_GIVEREF(__pyx_tuple__19); - /* "acados_template/acados_ocp_solver_pyx.pyx":410 + /* "acados_template/acados_ocp_solver_pyx.pyx":442 * full_stats = self.get_stats('statistics') * if self.nlp_solver_type == 'SQP': * return full_stats[6, :] # <<<<<<<<<<<<<< * elif self.nlp_solver_type == 'SQP_RTI': * return full_stats[2, :] */ - __pyx_tuple__18 = PyTuple_Pack(2, __pyx_int_6, __pyx_slice__5); if (unlikely(!__pyx_tuple__18)) __PYX_ERR(0, 410, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__18); - __Pyx_GIVEREF(__pyx_tuple__18); + __pyx_tuple__20 = PyTuple_Pack(2, __pyx_int_6, __pyx_slice__5); if (unlikely(!__pyx_tuple__20)) __PYX_ERR(0, 442, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__20); + __Pyx_GIVEREF(__pyx_tuple__20); - /* "acados_template/acados_ocp_solver_pyx.pyx":412 + /* "acados_template/acados_ocp_solver_pyx.pyx":444 * return full_stats[6, :] * elif self.nlp_solver_type == 'SQP_RTI': * return full_stats[2, :] # <<<<<<<<<<<<<< * * elif field_ == 'alpha': */ - __pyx_tuple__19 = PyTuple_Pack(2, __pyx_int_2, __pyx_slice__5); if (unlikely(!__pyx_tuple__19)) __PYX_ERR(0, 412, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__19); - __Pyx_GIVEREF(__pyx_tuple__19); + __pyx_tuple__21 = PyTuple_Pack(2, __pyx_int_2, __pyx_slice__5); if (unlikely(!__pyx_tuple__21)) __PYX_ERR(0, 444, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__21); + __Pyx_GIVEREF(__pyx_tuple__21); - /* "acados_template/acados_ocp_solver_pyx.pyx":417 + /* "acados_template/acados_ocp_solver_pyx.pyx":449 * full_stats = self.get_stats('statistics') * if self.nlp_solver_type == 'SQP': * return full_stats[7, :] # <<<<<<<<<<<<<< * else: # self.nlp_solver_type == 'SQP_RTI': * raise Exception("alpha values are not available for SQP_RTI") */ - __pyx_tuple__20 = PyTuple_Pack(2, __pyx_int_7, __pyx_slice__5); if (unlikely(!__pyx_tuple__20)) __PYX_ERR(0, 417, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__20); - __Pyx_GIVEREF(__pyx_tuple__20); + __pyx_tuple__22 = PyTuple_Pack(2, __pyx_int_7, __pyx_slice__5); if (unlikely(!__pyx_tuple__22)) __PYX_ERR(0, 449, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__22); + __Pyx_GIVEREF(__pyx_tuple__22); - /* "acados_template/acados_ocp_solver_pyx.pyx":419 + /* "acados_template/acados_ocp_solver_pyx.pyx":451 * return full_stats[7, :] * else: # self.nlp_solver_type == 'SQP_RTI': * raise Exception("alpha values are not available for SQP_RTI") # <<<<<<<<<<<<<< * * elif field_ == 'residuals': */ - __pyx_tuple__21 = PyTuple_Pack(1, __pyx_kp_u_alpha_values_are_not_available_f); if (unlikely(!__pyx_tuple__21)) __PYX_ERR(0, 419, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__21); - __Pyx_GIVEREF(__pyx_tuple__21); + __pyx_tuple__23 = PyTuple_Pack(1, __pyx_kp_u_alpha_values_are_not_available_f); if (unlikely(!__pyx_tuple__23)) __PYX_ERR(0, 451, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__23); + __Pyx_GIVEREF(__pyx_tuple__23); - /* "acados_template/acados_ocp_solver_pyx.pyx":425 + /* "acados_template/acados_ocp_solver_pyx.pyx":457 * * else: * raise NotImplementedError("TODO!") # <<<<<<<<<<<<<< * * */ - __pyx_tuple__22 = PyTuple_Pack(1, __pyx_kp_u_TODO); if (unlikely(!__pyx_tuple__22)) __PYX_ERR(0, 425, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__22); - __Pyx_GIVEREF(__pyx_tuple__22); + __pyx_tuple__24 = PyTuple_Pack(1, __pyx_kp_u_TODO); if (unlikely(!__pyx_tuple__24)) __PYX_ERR(0, 457, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__24); + __Pyx_GIVEREF(__pyx_tuple__24); - /* "acados_template/acados_ocp_solver_pyx.pyx":434 + /* "acados_template/acados_ocp_solver_pyx.pyx":466 * * def __get_stat_double(self, field): * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) # <<<<<<<<<<<<<< * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) * return out */ - __pyx_tuple__23 = PyTuple_Pack(1, __pyx_int_1); if (unlikely(!__pyx_tuple__23)) __PYX_ERR(0, 434, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__23); - __Pyx_GIVEREF(__pyx_tuple__23); + __pyx_tuple__25 = PyTuple_Pack(1, __pyx_int_1); if (unlikely(!__pyx_tuple__25)) __PYX_ERR(0, 466, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__25); + __Pyx_GIVEREF(__pyx_tuple__25); - /* "acados_template/acados_ocp_solver_pyx.pyx":469 + /* "acados_template/acados_ocp_solver_pyx.pyx":501 * * # create output array * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.ascontiguousarray(np.zeros((4,), dtype=np.float64)) # <<<<<<<<<<<<<< * cdef double double_value * */ - __pyx_tuple__24 = PyTuple_Pack(1, __pyx_int_4); if (unlikely(!__pyx_tuple__24)) __PYX_ERR(0, 469, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__24); - __Pyx_GIVEREF(__pyx_tuple__24); - __pyx_tuple__25 = PyTuple_Pack(1, __pyx_tuple__24); if (unlikely(!__pyx_tuple__25)) __PYX_ERR(0, 469, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__25); - __Pyx_GIVEREF(__pyx_tuple__25); + __pyx_tuple__26 = PyTuple_Pack(1, __pyx_int_4); if (unlikely(!__pyx_tuple__26)) __PYX_ERR(0, 501, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__26); + __Pyx_GIVEREF(__pyx_tuple__26); + __pyx_tuple__27 = PyTuple_Pack(1, __pyx_tuple__26); if (unlikely(!__pyx_tuple__27)) __PYX_ERR(0, 501, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__27); + __Pyx_GIVEREF(__pyx_tuple__27); - /* "acados_template/acados_ocp_solver_pyx.pyx":570 + /* "acados_template/acados_ocp_solver_pyx.pyx":611 * if len(value_shape) == 1: * value_shape = (value_shape[0], 0) * value = np.asfortranarray(value_[None,:]) # <<<<<<<<<<<<<< * * elif len(value_shape) == 2: */ - __pyx_tuple__26 = PyTuple_Pack(2, Py_None, __pyx_slice__5); if (unlikely(!__pyx_tuple__26)) __PYX_ERR(0, 570, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__26); - __Pyx_GIVEREF(__pyx_tuple__26); + __pyx_tuple__28 = PyTuple_Pack(2, Py_None, __pyx_slice__5); if (unlikely(!__pyx_tuple__28)) __PYX_ERR(0, 611, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__28); + __Pyx_GIVEREF(__pyx_tuple__28); - /* "acados_template/acados_ocp_solver_pyx.pyx":676 + /* "acados_template/acados_ocp_solver_pyx.pyx":720 * if field_ == 'rti_phase': * if value_ < 0 or value_ > 2: * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' # <<<<<<<<<<<<<< * 'take only values 0, 1, 2 for SQP-RTI-type solvers') * if self.nlp_solver_type != 'SQP_RTI' and value_ > 0: */ - __pyx_tuple__27 = PyTuple_Pack(1, __pyx_kp_u_AcadosOcpSolverCython_solve_argu); if (unlikely(!__pyx_tuple__27)) __PYX_ERR(0, 676, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__27); - __Pyx_GIVEREF(__pyx_tuple__27); + __pyx_tuple__29 = PyTuple_Pack(1, __pyx_kp_u_AcadosOcpSolverCython_solve_argu); if (unlikely(!__pyx_tuple__29)) __PYX_ERR(0, 720, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__29); + __Pyx_GIVEREF(__pyx_tuple__29); - /* "acados_template/acados_ocp_solver_pyx.pyx":679 + /* "acados_template/acados_ocp_solver_pyx.pyx":723 * 'take only values 0, 1, 2 for SQP-RTI-type solvers') * if self.nlp_solver_type != 'SQP_RTI' and value_ > 0: * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' # <<<<<<<<<<<<<< * 'take only value 0 for SQP-type solvers') * */ - __pyx_tuple__28 = PyTuple_Pack(1, __pyx_kp_u_AcadosOcpSolverCython_solve_argu_2); if (unlikely(!__pyx_tuple__28)) __PYX_ERR(0, 679, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__28); - __Pyx_GIVEREF(__pyx_tuple__28); + __pyx_tuple__30 = PyTuple_Pack(1, __pyx_kp_u_AcadosOcpSolverCython_solve_argu_2); if (unlikely(!__pyx_tuple__30)) __PYX_ERR(0, 723, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__30); + __Pyx_GIVEREF(__pyx_tuple__30); + + /* "acados_template/acados_ocp_solver_pyx.pyx":759 + * + * if not isinstance(param_values_, np.ndarray): + * raise Exception('param_values_ must be np.array.') # <<<<<<<<<<<<<< + * + * if param_values_.shape[0] != len(idx_values_): + */ + __pyx_tuple__32 = PyTuple_Pack(1, __pyx_kp_u_param_values__must_be_np_array); if (unlikely(!__pyx_tuple__32)) __PYX_ERR(0, 759, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__32); + __Pyx_GIVEREF(__pyx_tuple__32); /* "View.MemoryView":100 * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" @@ -30706,12 +32302,12 @@ static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence * else: */ - __pyx_tuple__30 = PyTuple_Pack(1, __pyx_n_s_sys); if (unlikely(!__pyx_tuple__30)) __PYX_ERR(1, 100, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__30); - __Pyx_GIVEREF(__pyx_tuple__30); - __pyx_tuple__31 = PyTuple_Pack(2, __pyx_int_3, __pyx_int_3); if (unlikely(!__pyx_tuple__31)) __PYX_ERR(1, 100, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__31); - __Pyx_GIVEREF(__pyx_tuple__31); + __pyx_tuple__33 = PyTuple_Pack(1, __pyx_n_s_sys); if (unlikely(!__pyx_tuple__33)) __PYX_ERR(1, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__33); + __Pyx_GIVEREF(__pyx_tuple__33); + __pyx_tuple__34 = PyTuple_Pack(2, __pyx_int_3, __pyx_int_3); if (unlikely(!__pyx_tuple__34)) __PYX_ERR(1, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__34); + __Pyx_GIVEREF(__pyx_tuple__34); /* "View.MemoryView":101 * try: @@ -30720,9 +32316,9 @@ static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { * else: * __pyx_collections_abc_Sequence = __import__("collections").Sequence */ - __pyx_tuple__32 = PyTuple_Pack(1, __pyx_kp_s_collections_abc); if (unlikely(!__pyx_tuple__32)) __PYX_ERR(1, 101, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__32); - __Pyx_GIVEREF(__pyx_tuple__32); + __pyx_tuple__35 = PyTuple_Pack(1, __pyx_kp_s_collections_abc); if (unlikely(!__pyx_tuple__35)) __PYX_ERR(1, 101, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__35); + __Pyx_GIVEREF(__pyx_tuple__35); /* "View.MemoryView":103 * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence @@ -30731,9 +32327,9 @@ static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { * except: * */ - __pyx_tuple__33 = PyTuple_Pack(1, __pyx_n_s_collections); if (unlikely(!__pyx_tuple__33)) __PYX_ERR(1, 103, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__33); - __Pyx_GIVEREF(__pyx_tuple__33); + __pyx_tuple__36 = PyTuple_Pack(1, __pyx_n_s_collections); if (unlikely(!__pyx_tuple__36)) __PYX_ERR(1, 103, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__36); + __Pyx_GIVEREF(__pyx_tuple__36); /* "View.MemoryView":309 * return self.name @@ -30742,9 +32338,9 @@ static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { * cdef strided = Enum("") # default * cdef indirect = Enum("") */ - __pyx_tuple__34 = PyTuple_Pack(1, __pyx_kp_s_strided_and_direct_or_indirect); if (unlikely(!__pyx_tuple__34)) __PYX_ERR(1, 309, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__34); - __Pyx_GIVEREF(__pyx_tuple__34); + __pyx_tuple__37 = PyTuple_Pack(1, __pyx_kp_s_strided_and_direct_or_indirect); if (unlikely(!__pyx_tuple__37)) __PYX_ERR(1, 309, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__37); + __Pyx_GIVEREF(__pyx_tuple__37); /* "View.MemoryView":310 * @@ -30753,9 +32349,9 @@ static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { * cdef indirect = Enum("") * */ - __pyx_tuple__35 = PyTuple_Pack(1, __pyx_kp_s_strided_and_direct); if (unlikely(!__pyx_tuple__35)) __PYX_ERR(1, 310, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__35); - __Pyx_GIVEREF(__pyx_tuple__35); + __pyx_tuple__38 = PyTuple_Pack(1, __pyx_kp_s_strided_and_direct); if (unlikely(!__pyx_tuple__38)) __PYX_ERR(1, 310, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__38); + __Pyx_GIVEREF(__pyx_tuple__38); /* "View.MemoryView":311 * cdef generic = Enum("") @@ -30764,9 +32360,9 @@ static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { * * */ - __pyx_tuple__36 = PyTuple_Pack(1, __pyx_kp_s_strided_and_indirect); if (unlikely(!__pyx_tuple__36)) __PYX_ERR(1, 311, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__36); - __Pyx_GIVEREF(__pyx_tuple__36); + __pyx_tuple__39 = PyTuple_Pack(1, __pyx_kp_s_strided_and_indirect); if (unlikely(!__pyx_tuple__39)) __PYX_ERR(1, 311, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__39); + __Pyx_GIVEREF(__pyx_tuple__39); /* "View.MemoryView":314 * @@ -30775,9 +32371,9 @@ static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { * cdef indirect_contiguous = Enum("") * */ - __pyx_tuple__37 = PyTuple_Pack(1, __pyx_kp_s_contiguous_and_direct); if (unlikely(!__pyx_tuple__37)) __PYX_ERR(1, 314, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__37); - __Pyx_GIVEREF(__pyx_tuple__37); + __pyx_tuple__40 = PyTuple_Pack(1, __pyx_kp_s_contiguous_and_direct); if (unlikely(!__pyx_tuple__40)) __PYX_ERR(1, 314, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__40); + __Pyx_GIVEREF(__pyx_tuple__40); /* "View.MemoryView":315 * @@ -30786,272 +32382,311 @@ static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { * * */ - __pyx_tuple__38 = PyTuple_Pack(1, __pyx_kp_s_contiguous_and_indirect); if (unlikely(!__pyx_tuple__38)) __PYX_ERR(1, 315, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__38); - __Pyx_GIVEREF(__pyx_tuple__38); + __pyx_tuple__41 = PyTuple_Pack(1, __pyx_kp_s_contiguous_and_indirect); if (unlikely(!__pyx_tuple__41)) __PYX_ERR(1, 315, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__41); + __Pyx_GIVEREF(__pyx_tuple__41); /* "(tree fragment)":1 * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< * cdef object __pyx_PickleError * cdef object __pyx_result */ - __pyx_tuple__39 = PyTuple_Pack(5, __pyx_n_s_pyx_type, __pyx_n_s_pyx_checksum, __pyx_n_s_pyx_state, __pyx_n_s_pyx_PickleError, __pyx_n_s_pyx_result); if (unlikely(!__pyx_tuple__39)) __PYX_ERR(1, 1, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__39); - __Pyx_GIVEREF(__pyx_tuple__39); - __pyx_codeobj__40 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__39, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_pyx_unpickle_Enum, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__40)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_tuple__42 = PyTuple_Pack(5, __pyx_n_s_pyx_type, __pyx_n_s_pyx_checksum, __pyx_n_s_pyx_state, __pyx_n_s_pyx_PickleError, __pyx_n_s_pyx_result); if (unlikely(!__pyx_tuple__42)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__42); + __Pyx_GIVEREF(__pyx_tuple__42); + __pyx_codeobj__43 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__42, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_pyx_unpickle_Enum, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__43)) __PYX_ERR(1, 1, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":94 + /* "acados_template/acados_ocp_solver_pyx.pyx":89 * * * def __get_pointers_solver(self): # <<<<<<<<<<<<<< * """ * Private function to get the pointers for solver */ - __pyx_tuple__41 = PyTuple_Pack(1, __pyx_n_s_self); if (unlikely(!__pyx_tuple__41)) __PYX_ERR(0, 94, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__41); - __Pyx_GIVEREF(__pyx_tuple__41); - __pyx_codeobj__42 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__41, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_pointers_solver, 94, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__42)) __PYX_ERR(0, 94, __pyx_L1_error) + __pyx_tuple__44 = PyTuple_Pack(1, __pyx_n_s_self); if (unlikely(!__pyx_tuple__44)) __PYX_ERR(0, 89, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__44); + __Pyx_GIVEREF(__pyx_tuple__44); + __pyx_codeobj__45 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__44, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_pointers_solver, 89, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__45)) __PYX_ERR(0, 89, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":108 + /* "acados_template/acados_ocp_solver_pyx.pyx":103 + * + * + * def solve_for_x0(self, x0_bar): # <<<<<<<<<<<<<< + * """ + * Wrapper around `solve()` which sets initial state constraint, solves the OCP, and returns u0. + */ + __pyx_tuple__46 = PyTuple_Pack(4, __pyx_n_s_self, __pyx_n_s_x0_bar, __pyx_n_s_status, __pyx_n_s_u0); if (unlikely(!__pyx_tuple__46)) __PYX_ERR(0, 103, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__46); + __Pyx_GIVEREF(__pyx_tuple__46); + __pyx_codeobj__47 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 4, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__46, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_solve_for_x0, 103, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__47)) __PYX_ERR(0, 103, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":121 * * * def solve(self): # <<<<<<<<<<<<<< * """ * Solve the ocp with current input. */ - __pyx_codeobj__43 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__41, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_solve, 108, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__43)) __PYX_ERR(0, 108, __pyx_L1_error) + __pyx_codeobj__48 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__44, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_solve, 121, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__48)) __PYX_ERR(0, 121, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":115 + /* "acados_template/acados_ocp_solver_pyx.pyx":128 * * - * def reset(self): # <<<<<<<<<<<<<< + * def reset(self, reset_qp_solver_mem=1): # <<<<<<<<<<<<<< * """ * Sets current iterate to all zeros. */ - __pyx_codeobj__44 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__41, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_reset, 115, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__44)) __PYX_ERR(0, 115, __pyx_L1_error) + __pyx_tuple__49 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_reset_qp_solver_mem); if (unlikely(!__pyx_tuple__49)) __PYX_ERR(0, 128, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__49); + __Pyx_GIVEREF(__pyx_tuple__49); + __pyx_codeobj__50 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__49, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_reset, 128, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__50)) __PYX_ERR(0, 128, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":122 + /* "acados_template/acados_ocp_solver_pyx.pyx":135 + * + * + * def custom_update(self, data_): # <<<<<<<<<<<<<< + * """ + * A custom function that can be implemented by a user to be called between solver calls. + */ + __pyx_tuple__51 = PyTuple_Pack(4, __pyx_n_s_self, __pyx_n_s_data, __pyx_n_s_data_len, __pyx_n_s_data_2); if (unlikely(!__pyx_tuple__51)) __PYX_ERR(0, 135, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__51); + __Pyx_GIVEREF(__pyx_tuple__51); + __pyx_codeobj__52 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 4, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__51, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_custom_update, 135, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__52)) __PYX_ERR(0, 135, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":148 * * * def set_new_time_steps(self, new_time_steps): # <<<<<<<<<<<<<< * """ * Set new time steps. */ - __pyx_tuple__45 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_new_time_steps); if (unlikely(!__pyx_tuple__45)) __PYX_ERR(0, 122, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__45); - __Pyx_GIVEREF(__pyx_tuple__45); - __pyx_codeobj__46 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__45, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_set_new_time_steps, 122, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__46)) __PYX_ERR(0, 122, __pyx_L1_error) + __pyx_tuple__53 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_new_time_steps); if (unlikely(!__pyx_tuple__53)) __PYX_ERR(0, 148, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__53); + __Pyx_GIVEREF(__pyx_tuple__53); + __pyx_codeobj__54 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__53, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_set_new_time_steps, 148, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__54)) __PYX_ERR(0, 148, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":173 + /* "acados_template/acados_ocp_solver_pyx.pyx":199 * * * def update_qp_solver_cond_N(self, qp_solver_cond_N: int): # <<<<<<<<<<<<<< * """ * Recreate solver with new value `qp_solver_cond_N` with a partial condensing QP solver. */ - __pyx_tuple__47 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_qp_solver_cond_N); if (unlikely(!__pyx_tuple__47)) __PYX_ERR(0, 173, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__47); - __Pyx_GIVEREF(__pyx_tuple__47); - __pyx_codeobj__48 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__47, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_update_qp_solver_cond_N, 173, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__48)) __PYX_ERR(0, 173, __pyx_L1_error) + __pyx_tuple__55 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_qp_solver_cond_N); if (unlikely(!__pyx_tuple__55)) __PYX_ERR(0, 199, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__55); + __Pyx_GIVEREF(__pyx_tuple__55); + __pyx_codeobj__56 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__55, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_update_qp_solver_cond_N, 199, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__56)) __PYX_ERR(0, 199, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":207 + /* "acados_template/acados_ocp_solver_pyx.pyx":233 * * * def eval_param_sens(self, index, stage=0, field="ex"): # <<<<<<<<<<<<<< * """ * Calculate the sensitivity of the curent solution with respect to the initial state component of index */ - __pyx_tuple__49 = PyTuple_Pack(6, __pyx_n_s_self, __pyx_n_s_index, __pyx_n_s_stage, __pyx_n_s_field, __pyx_n_s_field_2, __pyx_n_s_nx); if (unlikely(!__pyx_tuple__49)) __PYX_ERR(0, 207, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__49); - __Pyx_GIVEREF(__pyx_tuple__49); - __pyx_codeobj__50 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 6, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__49, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_eval_param_sens, 207, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__50)) __PYX_ERR(0, 207, __pyx_L1_error) - __pyx_tuple__51 = PyTuple_Pack(2, __pyx_int_0, __pyx_n_u_ex); if (unlikely(!__pyx_tuple__51)) __PYX_ERR(0, 207, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__51); - __Pyx_GIVEREF(__pyx_tuple__51); + __pyx_tuple__57 = PyTuple_Pack(6, __pyx_n_s_self, __pyx_n_s_index, __pyx_n_s_stage, __pyx_n_s_field, __pyx_n_s_field_2, __pyx_n_s_nx); if (unlikely(!__pyx_tuple__57)) __PYX_ERR(0, 233, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__57); + __Pyx_GIVEREF(__pyx_tuple__57); + __pyx_codeobj__58 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 6, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__57, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_eval_param_sens, 233, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__58)) __PYX_ERR(0, 233, __pyx_L1_error) + __pyx_tuple__59 = PyTuple_Pack(2, __pyx_int_0, __pyx_n_u_ex); if (unlikely(!__pyx_tuple__59)) __PYX_ERR(0, 233, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__59); + __Pyx_GIVEREF(__pyx_tuple__59); - /* "acados_template/acados_ocp_solver_pyx.pyx":232 + /* "acados_template/acados_ocp_solver_pyx.pyx":258 * * * def get(self, int stage, str field_): # <<<<<<<<<<<<<< * """ * Get the last solution of the solver: */ - __pyx_tuple__52 = PyTuple_Pack(7, __pyx_n_s_self, __pyx_n_s_stage, __pyx_n_s_field_2, __pyx_n_s_out_fields, __pyx_n_s_field, __pyx_n_s_dims, __pyx_n_s_out); if (unlikely(!__pyx_tuple__52)) __PYX_ERR(0, 232, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__52); - __Pyx_GIVEREF(__pyx_tuple__52); - __pyx_codeobj__53 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 7, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__52, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get, 232, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__53)) __PYX_ERR(0, 232, __pyx_L1_error) + __pyx_tuple__60 = PyTuple_Pack(7, __pyx_n_s_self, __pyx_n_s_stage, __pyx_n_s_field_2, __pyx_n_s_out_fields, __pyx_n_s_field, __pyx_n_s_dims, __pyx_n_s_out); if (unlikely(!__pyx_tuple__60)) __PYX_ERR(0, 258, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__60); + __Pyx_GIVEREF(__pyx_tuple__60); + __pyx_codeobj__61 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 7, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__60, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get, 258, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__61)) __PYX_ERR(0, 258, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":275 + /* "acados_template/acados_ocp_solver_pyx.pyx":301 * * * def print_statistics(self): # <<<<<<<<<<<<<< * """ * prints statistics of previous solver run as a table: */ - __pyx_codeobj__54 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__41, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_print_statistics, 275, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__54)) __PYX_ERR(0, 275, __pyx_L1_error) + __pyx_codeobj__62 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__44, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_print_statistics, 301, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__62)) __PYX_ERR(0, 301, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":293 + /* "acados_template/acados_ocp_solver_pyx.pyx":319 * * * def store_iterate(self, filename='', overwrite=False): # <<<<<<<<<<<<<< * """ * Stores the current iterate of the ocp solver in a json file. */ - __pyx_tuple__55 = PyTuple_Pack(7, __pyx_n_s_self, __pyx_n_s_filename, __pyx_n_s_overwrite, __pyx_n_s_json, __pyx_n_s_solution, __pyx_n_s_i, __pyx_n_s_f); if (unlikely(!__pyx_tuple__55)) __PYX_ERR(0, 293, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__55); - __Pyx_GIVEREF(__pyx_tuple__55); - __pyx_codeobj__56 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 7, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__55, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_store_iterate, 293, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__56)) __PYX_ERR(0, 293, __pyx_L1_error) - __pyx_tuple__57 = PyTuple_Pack(2, __pyx_kp_u__14, Py_False); if (unlikely(!__pyx_tuple__57)) __PYX_ERR(0, 293, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__57); - __Pyx_GIVEREF(__pyx_tuple__57); + __pyx_tuple__63 = PyTuple_Pack(10, __pyx_n_s_self, __pyx_n_s_filename, __pyx_n_s_overwrite, __pyx_n_s_json, __pyx_n_s_solution, __pyx_n_s_lN, __pyx_n_s_i, __pyx_n_s_i_string, __pyx_n_s_k, __pyx_n_s_f); if (unlikely(!__pyx_tuple__63)) __PYX_ERR(0, 319, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__63); + __Pyx_GIVEREF(__pyx_tuple__63); + __pyx_codeobj__64 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 10, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__63, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_store_iterate, 319, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__64)) __PYX_ERR(0, 319, __pyx_L1_error) + __pyx_tuple__65 = PyTuple_Pack(2, __pyx_kp_u__16, Py_False); if (unlikely(!__pyx_tuple__65)) __PYX_ERR(0, 319, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__65); + __Pyx_GIVEREF(__pyx_tuple__65); - /* "acados_template/acados_ocp_solver_pyx.pyx":330 + /* "acados_template/acados_ocp_solver_pyx.pyx":362 * * * def load_iterate(self, filename): # <<<<<<<<<<<<<< * """ * Loads the iterate stored in json file with filename into the ocp solver. */ - __pyx_tuple__58 = PyTuple_Pack(8, __pyx_n_s_self, __pyx_n_s_filename, __pyx_n_s_json, __pyx_n_s_f, __pyx_n_s_solution, __pyx_n_s_key, __pyx_n_s_field, __pyx_n_s_stage); if (unlikely(!__pyx_tuple__58)) __PYX_ERR(0, 330, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__58); - __Pyx_GIVEREF(__pyx_tuple__58); - __pyx_codeobj__59 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 8, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__58, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_load_iterate, 330, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__59)) __PYX_ERR(0, 330, __pyx_L1_error) + __pyx_tuple__66 = PyTuple_Pack(8, __pyx_n_s_self, __pyx_n_s_filename, __pyx_n_s_json, __pyx_n_s_f, __pyx_n_s_solution, __pyx_n_s_key, __pyx_n_s_field, __pyx_n_s_stage); if (unlikely(!__pyx_tuple__66)) __PYX_ERR(0, 362, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__66); + __Pyx_GIVEREF(__pyx_tuple__66); + __pyx_codeobj__67 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 8, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__66, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_load_iterate, 362, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__67)) __PYX_ERR(0, 362, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":346 + /* "acados_template/acados_ocp_solver_pyx.pyx":378 * * * def get_stats(self, field_): # <<<<<<<<<<<<<< * """ * Get the information of the last solver call. */ - __pyx_tuple__60 = PyTuple_Pack(10, __pyx_n_s_self, __pyx_n_s_field_2, __pyx_n_s_double_fields, __pyx_n_s_fields, __pyx_n_s_field, __pyx_n_s_sqp_iter, __pyx_n_s_stat_m, __pyx_n_s_stat_n, __pyx_n_s_min_size, __pyx_n_s_full_stats); if (unlikely(!__pyx_tuple__60)) __PYX_ERR(0, 346, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__60); - __Pyx_GIVEREF(__pyx_tuple__60); - __pyx_codeobj__61 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 10, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__60, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_stats, 346, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__61)) __PYX_ERR(0, 346, __pyx_L1_error) + __pyx_tuple__68 = PyTuple_Pack(10, __pyx_n_s_self, __pyx_n_s_field_2, __pyx_n_s_double_fields, __pyx_n_s_fields, __pyx_n_s_field, __pyx_n_s_sqp_iter, __pyx_n_s_stat_m, __pyx_n_s_stat_n, __pyx_n_s_min_size, __pyx_n_s_full_stats); if (unlikely(!__pyx_tuple__68)) __PYX_ERR(0, 378, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__68); + __Pyx_GIVEREF(__pyx_tuple__68); + __pyx_codeobj__69 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 10, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__68, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_stats, 378, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__69)) __PYX_ERR(0, 378, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":428 + /* "acados_template/acados_ocp_solver_pyx.pyx":460 * * * def __get_stat_int(self, field): # <<<<<<<<<<<<<< * cdef int out * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &out) */ - __pyx_tuple__62 = PyTuple_Pack(3, __pyx_n_s_self, __pyx_n_s_field, __pyx_n_s_out); if (unlikely(!__pyx_tuple__62)) __PYX_ERR(0, 428, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__62); - __Pyx_GIVEREF(__pyx_tuple__62); - __pyx_codeobj__63 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__62, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_stat_int, 428, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__63)) __PYX_ERR(0, 428, __pyx_L1_error) + __pyx_tuple__70 = PyTuple_Pack(3, __pyx_n_s_self, __pyx_n_s_field, __pyx_n_s_out); if (unlikely(!__pyx_tuple__70)) __PYX_ERR(0, 460, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__70); + __Pyx_GIVEREF(__pyx_tuple__70); + __pyx_codeobj__71 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__70, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_stat_int, 460, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__71)) __PYX_ERR(0, 460, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":433 + /* "acados_template/acados_ocp_solver_pyx.pyx":465 * return out * * def __get_stat_double(self, field): # <<<<<<<<<<<<<< * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) */ - __pyx_codeobj__64 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__62, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_stat_double, 433, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__64)) __PYX_ERR(0, 433, __pyx_L1_error) + __pyx_codeobj__72 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__70, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_stat_double, 465, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__72)) __PYX_ERR(0, 465, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":438 + /* "acados_template/acados_ocp_solver_pyx.pyx":470 * return out * * def __get_stat_matrix(self, field, n, m): # <<<<<<<<<<<<<< * cdef cnp.ndarray[cnp.float64_t, ndim=2] out_mat = np.ascontiguousarray(np.zeros((n, m)), dtype=np.float64) * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_mat.data) */ - __pyx_tuple__65 = PyTuple_Pack(5, __pyx_n_s_self, __pyx_n_s_field, __pyx_n_s_n, __pyx_n_s_m, __pyx_n_s_out_mat); if (unlikely(!__pyx_tuple__65)) __PYX_ERR(0, 438, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__65); - __Pyx_GIVEREF(__pyx_tuple__65); - __pyx_codeobj__66 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__65, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_stat_matrix, 438, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__66)) __PYX_ERR(0, 438, __pyx_L1_error) + __pyx_tuple__73 = PyTuple_Pack(5, __pyx_n_s_self, __pyx_n_s_field, __pyx_n_s_n, __pyx_n_s_m, __pyx_n_s_out_mat); if (unlikely(!__pyx_tuple__73)) __PYX_ERR(0, 470, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__73); + __Pyx_GIVEREF(__pyx_tuple__73); + __pyx_codeobj__74 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__73, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_stat_matrix, 470, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__74)) __PYX_ERR(0, 470, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":444 + /* "acados_template/acados_ocp_solver_pyx.pyx":476 * * * def get_cost(self): # <<<<<<<<<<<<<< * """ * Returns the cost value of the current solution. */ - __pyx_tuple__67 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_out); if (unlikely(!__pyx_tuple__67)) __PYX_ERR(0, 444, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__67); - __Pyx_GIVEREF(__pyx_tuple__67); - __pyx_codeobj__68 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__67, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_cost, 444, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__68)) __PYX_ERR(0, 444, __pyx_L1_error) + __pyx_tuple__75 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_out); if (unlikely(!__pyx_tuple__75)) __PYX_ERR(0, 476, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__75); + __Pyx_GIVEREF(__pyx_tuple__75); + __pyx_codeobj__76 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__75, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_cost, 476, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__76)) __PYX_ERR(0, 476, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":460 + /* "acados_template/acados_ocp_solver_pyx.pyx":492 * * * def get_residuals(self, recompute=False): # <<<<<<<<<<<<<< * """ * Returns an array of the form [res_stat, res_eq, res_ineq, res_comp]. */ - __pyx_tuple__69 = PyTuple_Pack(5, __pyx_n_s_self, __pyx_n_s_recompute, __pyx_n_s_out, __pyx_n_s_double_value, __pyx_n_s_field); if (unlikely(!__pyx_tuple__69)) __PYX_ERR(0, 460, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__69); - __Pyx_GIVEREF(__pyx_tuple__69); - __pyx_codeobj__70 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__69, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_residuals, 460, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__70)) __PYX_ERR(0, 460, __pyx_L1_error) - __pyx_tuple__71 = PyTuple_Pack(1, Py_False); if (unlikely(!__pyx_tuple__71)) __PYX_ERR(0, 460, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__71); - __Pyx_GIVEREF(__pyx_tuple__71); + __pyx_tuple__77 = PyTuple_Pack(5, __pyx_n_s_self, __pyx_n_s_recompute, __pyx_n_s_out, __pyx_n_s_double_value, __pyx_n_s_field); if (unlikely(!__pyx_tuple__77)) __PYX_ERR(0, 492, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__77); + __Pyx_GIVEREF(__pyx_tuple__77); + __pyx_codeobj__78 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__77, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_residuals, 492, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__78)) __PYX_ERR(0, 492, __pyx_L1_error) + __pyx_tuple__79 = PyTuple_Pack(1, Py_False); if (unlikely(!__pyx_tuple__79)) __PYX_ERR(0, 492, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__79); + __Pyx_GIVEREF(__pyx_tuple__79); - /* "acados_template/acados_ocp_solver_pyx.pyx":492 + /* "acados_template/acados_ocp_solver_pyx.pyx":524 * * # Note: this function should not be used anymore, better use cost_set, constraints_set * def set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< * * """ */ - __pyx_tuple__72 = PyTuple_Pack(12, __pyx_n_s_self, __pyx_n_s_stage, __pyx_n_s_field_2, __pyx_n_s_value, __pyx_n_s_cost_fields, __pyx_n_s_constraints_fields, __pyx_n_s_out_fields, __pyx_n_s_mem_fields, __pyx_n_s_field, __pyx_n_s_value_2, __pyx_n_s_dims, __pyx_n_s_msg); if (unlikely(!__pyx_tuple__72)) __PYX_ERR(0, 492, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__72); - __Pyx_GIVEREF(__pyx_tuple__72); - __pyx_codeobj__73 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 12, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__72, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_set, 492, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__73)) __PYX_ERR(0, 492, __pyx_L1_error) + __pyx_tuple__80 = PyTuple_Pack(12, __pyx_n_s_self, __pyx_n_s_stage, __pyx_n_s_field_2, __pyx_n_s_value, __pyx_n_s_cost_fields, __pyx_n_s_constraints_fields, __pyx_n_s_out_fields, __pyx_n_s_mem_fields, __pyx_n_s_field, __pyx_n_s_value_2, __pyx_n_s_dims, __pyx_n_s_msg); if (unlikely(!__pyx_tuple__80)) __PYX_ERR(0, 524, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__80); + __Pyx_GIVEREF(__pyx_tuple__80); + __pyx_codeobj__81 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 12, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__80, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_set, 524, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__81)) __PYX_ERR(0, 524, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":551 - * + /* "acados_template/acados_ocp_solver_pyx.pyx":590 + * return * * def cost_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< * """ * Set numerical data in the cost module of the solver. */ - __pyx_tuple__74 = PyTuple_Pack(8, __pyx_n_s_self, __pyx_n_s_stage, __pyx_n_s_field_2, __pyx_n_s_value, __pyx_n_s_field, __pyx_n_s_dims, __pyx_n_s_value_2, __pyx_n_s_value_shape); if (unlikely(!__pyx_tuple__74)) __PYX_ERR(0, 551, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__74); - __Pyx_GIVEREF(__pyx_tuple__74); - __pyx_codeobj__75 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 8, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__74, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_cost_set, 551, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__75)) __PYX_ERR(0, 551, __pyx_L1_error) + __pyx_tuple__82 = PyTuple_Pack(8, __pyx_n_s_self, __pyx_n_s_stage, __pyx_n_s_field_2, __pyx_n_s_value, __pyx_n_s_field, __pyx_n_s_dims, __pyx_n_s_value_2, __pyx_n_s_value_shape); if (unlikely(!__pyx_tuple__82)) __PYX_ERR(0, 590, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__82); + __Pyx_GIVEREF(__pyx_tuple__82); + __pyx_codeobj__83 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 8, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__82, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_cost_set, 590, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__83)) __PYX_ERR(0, 590, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":584 + /* "acados_template/acados_ocp_solver_pyx.pyx":625 * * * def constraints_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< * """ * Set numerical data in the constraint module of the solver. */ - __pyx_codeobj__76 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 8, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__74, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_constraints_set, 584, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__76)) __PYX_ERR(0, 584, __pyx_L1_error) + __pyx_codeobj__84 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 8, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__82, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_constraints_set, 625, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__84)) __PYX_ERR(0, 625, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":619 + /* "acados_template/acados_ocp_solver_pyx.pyx":663 * * - * def dynamics_get(self, int stage, str field_): # <<<<<<<<<<<<<< + * def get_from_qp_in(self, int stage, str field_): # <<<<<<<<<<<<<< * """ * Get numerical data from the dynamics module of the solver: */ - __pyx_tuple__77 = PyTuple_Pack(6, __pyx_n_s_self, __pyx_n_s_stage, __pyx_n_s_field_2, __pyx_n_s_field, __pyx_n_s_dims, __pyx_n_s_out); if (unlikely(!__pyx_tuple__77)) __PYX_ERR(0, 619, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__77); - __Pyx_GIVEREF(__pyx_tuple__77); - __pyx_codeobj__78 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 6, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__77, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_dynamics_get, 619, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__78)) __PYX_ERR(0, 619, __pyx_L1_error) + __pyx_tuple__85 = PyTuple_Pack(6, __pyx_n_s_self, __pyx_n_s_stage, __pyx_n_s_field_2, __pyx_n_s_field, __pyx_n_s_dims, __pyx_n_s_out); if (unlikely(!__pyx_tuple__85)) __PYX_ERR(0, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__85); + __Pyx_GIVEREF(__pyx_tuple__85); + __pyx_codeobj__86 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 6, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__85, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_from_qp_in, 663, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__86)) __PYX_ERR(0, 663, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":641 + /* "acados_template/acados_ocp_solver_pyx.pyx":685 * * * def options_set(self, str field_, value_): # <<<<<<<<<<<<<< * """ * Set options of the solver. */ - __pyx_tuple__79 = PyTuple_Pack(10, __pyx_n_s_self, __pyx_n_s_field_2, __pyx_n_s_value, __pyx_n_s_int_fields, __pyx_n_s_double_fields, __pyx_n_s_string_fields, __pyx_n_s_field, __pyx_n_s_int_value, __pyx_n_s_double_value, __pyx_n_s_string_value); if (unlikely(!__pyx_tuple__79)) __PYX_ERR(0, 641, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__79); - __Pyx_GIVEREF(__pyx_tuple__79); - __pyx_codeobj__80 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 10, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__79, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_options_set, 641, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__80)) __PYX_ERR(0, 641, __pyx_L1_error) + __pyx_tuple__87 = PyTuple_Pack(10, __pyx_n_s_self, __pyx_n_s_field_2, __pyx_n_s_value, __pyx_n_s_int_fields, __pyx_n_s_double_fields, __pyx_n_s_string_fields, __pyx_n_s_field, __pyx_n_s_int_value, __pyx_n_s_double_value, __pyx_n_s_string_value); if (unlikely(!__pyx_tuple__87)) __PYX_ERR(0, 685, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__87); + __Pyx_GIVEREF(__pyx_tuple__87); + __pyx_codeobj__88 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 10, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__87, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_options_set, 685, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__88)) __PYX_ERR(0, 685, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":748 + * + * + * def set_params_sparse(self, int stage, idx_values_, param_values_): # <<<<<<<<<<<<<< + * """ + * set parameters of the solvers external function partially: + */ + __pyx_tuple__89 = PyTuple_Pack(7, __pyx_n_s_self, __pyx_n_s_stage, __pyx_n_s_idx_values, __pyx_n_s_param_values, __pyx_n_s_value_2, __pyx_n_s_idx, __pyx_n_s_n_update); if (unlikely(!__pyx_tuple__89)) __PYX_ERR(0, 748, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__89); + __Pyx_GIVEREF(__pyx_tuple__89); + __pyx_codeobj__90 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 7, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__89, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_set_params_sparse, 748, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__90)) __PYX_ERR(0, 748, __pyx_L1_error) /* "(tree fragment)":1 * def __reduce_cython__(self): # <<<<<<<<<<<<<< * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" * def __setstate_cython__(self, __pyx_state): */ - __pyx_codeobj__81 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__41, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__81)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_codeobj__91 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__44, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__91)) __PYX_ERR(1, 1, __pyx_L1_error) /* "(tree fragment)":3 * def __reduce_cython__(self): @@ -31059,10 +32694,10 @@ static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" */ - __pyx_tuple__82 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_pyx_state); if (unlikely(!__pyx_tuple__82)) __PYX_ERR(1, 3, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__82); - __Pyx_GIVEREF(__pyx_tuple__82); - __pyx_codeobj__83 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__82, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__83)) __PYX_ERR(1, 3, __pyx_L1_error) + __pyx_tuple__92 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_pyx_state); if (unlikely(!__pyx_tuple__92)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__92); + __Pyx_GIVEREF(__pyx_tuple__92); + __pyx_codeobj__93 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__92, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__93)) __PYX_ERR(1, 3, __pyx_L1_error) __Pyx_RefNannyFinishContext(); return 0; __pyx_L1_error:; @@ -31072,6 +32707,8 @@ static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { /* #### Code section: init_constants ### */ static CYTHON_SMALL_CODE int __Pyx_InitConstants(void) { + __pyx_umethod_PyDict_Type_keys.type = (PyObject*)&PyDict_Type; + __pyx_umethod_PyDict_Type_keys.method_name = &__pyx_n_s_keys; if (__Pyx_CreateStringTabAndInitStrings() < 0) __PYX_ERR(0, 1, __pyx_L1_error); __pyx_int_0 = PyInt_FromLong(0); if (unlikely(!__pyx_int_0)) __PYX_ERR(0, 1, __pyx_L1_error) __pyx_int_1 = PyInt_FromLong(1); if (unlikely(!__pyx_int_1)) __PYX_ERR(0, 1, __pyx_L1_error) @@ -31169,15 +32806,15 @@ static int __Pyx_modinit_type_init_code(void) { __Pyx_RefNannySetupContext("__Pyx_modinit_type_init_code", 0); /*--- Type init code ---*/ #if CYTHON_USE_TYPE_SPECS - __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython_spec, NULL); if (unlikely(!__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython)) __PYX_ERR(0, 52, __pyx_L1_error) - if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython_spec, __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython) < 0) __PYX_ERR(0, 52, __pyx_L1_error) + __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython_spec, NULL); if (unlikely(!__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython)) __PYX_ERR(0, 49, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython_spec, __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython) < 0) __PYX_ERR(0, 49, __pyx_L1_error) #else __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython = &__pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython; #endif #if !CYTHON_COMPILING_IN_LIMITED_API #endif #if !CYTHON_USE_TYPE_SPECS - if (__Pyx_PyType_Ready(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython) < 0) __PYX_ERR(0, 52, __pyx_L1_error) + if (__Pyx_PyType_Ready(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython) < 0) __PYX_ERR(0, 49, __pyx_L1_error) #endif #if PY_MAJOR_VERSION < 3 __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_print = 0; @@ -31187,9 +32824,9 @@ static int __Pyx_modinit_type_init_code(void) { __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_getattro = __Pyx_PyObject_GenericGetAttr; } #endif - if (PyObject_SetAttr(__pyx_m, __pyx_n_s_AcadosOcpSolverCython, (PyObject *) __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython) < 0) __PYX_ERR(0, 52, __pyx_L1_error) + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_AcadosOcpSolverCython, (PyObject *) __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython) < 0) __PYX_ERR(0, 49, __pyx_L1_error) #if !CYTHON_COMPILING_IN_LIMITED_API - if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython) < 0) __PYX_ERR(0, 52, __pyx_L1_error) + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython) < 0) __PYX_ERR(0, 49, __pyx_L1_error) #endif __pyx_vtabptr_array = &__pyx_vtable_array; __pyx_vtable_array.get_memview = (PyObject *(*)(struct __pyx_array_obj *))__pyx_array_get_memview; @@ -31710,12 +33347,12 @@ if (!__Pyx_RefNanny) { * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence * else: */ - __pyx_t_4 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__30, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 100, __pyx_L2_error) + __pyx_t_4 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__33, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 100, __pyx_L2_error) __Pyx_GOTREF(__pyx_t_4); __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_version_info); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 100, __pyx_L2_error) __Pyx_GOTREF(__pyx_t_5); __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __pyx_t_4 = PyObject_RichCompare(__pyx_t_5, __pyx_tuple__31, Py_GE); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 100, __pyx_L2_error) + __pyx_t_4 = PyObject_RichCompare(__pyx_t_5, __pyx_tuple__34, Py_GE); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 100, __pyx_L2_error) __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; __pyx_t_6 = __Pyx_PyObject_IsTrue(__pyx_t_4); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(1, 100, __pyx_L2_error) __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; @@ -31728,7 +33365,7 @@ if (!__Pyx_RefNanny) { * else: * __pyx_collections_abc_Sequence = __import__("collections").Sequence */ - __pyx_t_4 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__32, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 101, __pyx_L2_error) + __pyx_t_4 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__35, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 101, __pyx_L2_error) __Pyx_GOTREF(__pyx_t_4); __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_abc); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 101, __pyx_L2_error) __Pyx_GOTREF(__pyx_t_5); @@ -31759,7 +33396,7 @@ if (!__Pyx_RefNanny) { * */ /*else*/ { - __pyx_t_4 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__33, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 103, __pyx_L2_error) + __pyx_t_4 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__36, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 103, __pyx_L2_error) __Pyx_GOTREF(__pyx_t_4); __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_Sequence); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 103, __pyx_L2_error) __Pyx_GOTREF(__pyx_t_5); @@ -31924,7 +33561,7 @@ if (!__Pyx_RefNanny) { * cdef strided = Enum("") # default * cdef indirect = Enum("") */ - __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__34, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 309, __pyx_L1_error) + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__37, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 309, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); __Pyx_XGOTREF(generic); __Pyx_DECREF_SET(generic, __pyx_t_7); @@ -31938,7 +33575,7 @@ if (!__Pyx_RefNanny) { * cdef indirect = Enum("") * */ - __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__35, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 310, __pyx_L1_error) + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__38, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 310, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); __Pyx_XGOTREF(strided); __Pyx_DECREF_SET(strided, __pyx_t_7); @@ -31952,7 +33589,7 @@ if (!__Pyx_RefNanny) { * * */ - __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__36, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 311, __pyx_L1_error) + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__39, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 311, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); __Pyx_XGOTREF(indirect); __Pyx_DECREF_SET(indirect, __pyx_t_7); @@ -31966,7 +33603,7 @@ if (!__Pyx_RefNanny) { * cdef indirect_contiguous = Enum("") * */ - __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__37, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 314, __pyx_L1_error) + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__40, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 314, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); __Pyx_XGOTREF(contiguous); __Pyx_DECREF_SET(contiguous, __pyx_t_7); @@ -31980,7 +33617,7 @@ if (!__Pyx_RefNanny) { * * */ - __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__38, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 315, __pyx_L1_error) + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__41, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 315, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); __Pyx_XGOTREF(indirect_contiguous); __Pyx_DECREF_SET(indirect_contiguous, __pyx_t_7); @@ -32200,329 +33837,369 @@ if (!__Pyx_RefNanny) { if (PyDict_SetItem(__pyx_d, __pyx_n_s_pyx_unpickle_Enum, __pyx_t_7) < 0) __PYX_ERR(1, 1, __pyx_L1_error) __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":47 + /* "acados_template/acados_ocp_solver_pyx.pyx":44 * cimport numpy as cnp * * import os # <<<<<<<<<<<<<< * from datetime import datetime * import numpy as np */ - __pyx_t_7 = __Pyx_ImportDottedModule(__pyx_n_s_os, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 47, __pyx_L1_error) + __pyx_t_7 = __Pyx_ImportDottedModule(__pyx_n_s_os, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 44, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); - if (PyDict_SetItem(__pyx_d, __pyx_n_s_os, __pyx_t_7) < 0) __PYX_ERR(0, 47, __pyx_L1_error) + if (PyDict_SetItem(__pyx_d, __pyx_n_s_os, __pyx_t_7) < 0) __PYX_ERR(0, 44, __pyx_L1_error) __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":48 + /* "acados_template/acados_ocp_solver_pyx.pyx":45 * * import os * from datetime import datetime # <<<<<<<<<<<<<< * import numpy as np * */ - __pyx_t_7 = PyList_New(1); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 48, __pyx_L1_error) + __pyx_t_7 = PyList_New(1); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 45, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); __Pyx_INCREF(__pyx_n_s_datetime); __Pyx_GIVEREF(__pyx_n_s_datetime); PyList_SET_ITEM(__pyx_t_7, 0, __pyx_n_s_datetime); - __pyx_t_4 = __Pyx_Import(__pyx_n_s_datetime, __pyx_t_7, 0); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 48, __pyx_L1_error) + __pyx_t_4 = __Pyx_Import(__pyx_n_s_datetime, __pyx_t_7, 0); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 45, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - __pyx_t_7 = __Pyx_ImportFrom(__pyx_t_4, __pyx_n_s_datetime); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 48, __pyx_L1_error) + __pyx_t_7 = __Pyx_ImportFrom(__pyx_t_4, __pyx_n_s_datetime); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 45, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); - if (PyDict_SetItem(__pyx_d, __pyx_n_s_datetime, __pyx_t_7) < 0) __PYX_ERR(0, 48, __pyx_L1_error) + if (PyDict_SetItem(__pyx_d, __pyx_n_s_datetime, __pyx_t_7) < 0) __PYX_ERR(0, 45, __pyx_L1_error) __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":49 + /* "acados_template/acados_ocp_solver_pyx.pyx":46 * import os * from datetime import datetime * import numpy as np # <<<<<<<<<<<<<< * * */ - __pyx_t_4 = __Pyx_ImportDottedModule(__pyx_n_s_numpy, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 49, __pyx_L1_error) + __pyx_t_4 = __Pyx_ImportDottedModule(__pyx_n_s_numpy, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 46, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); - if (PyDict_SetItem(__pyx_d, __pyx_n_s_np, __pyx_t_4) < 0) __PYX_ERR(0, 49, __pyx_L1_error) + if (PyDict_SetItem(__pyx_d, __pyx_n_s_np, __pyx_t_4) < 0) __PYX_ERR(0, 46, __pyx_L1_error) __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":94 + /* "acados_template/acados_ocp_solver_pyx.pyx":89 * * * def __get_pointers_solver(self): # <<<<<<<<<<<<<< * """ * Private function to get the pointers for solver */ - __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_3_AcadosOcpSolverCython__get_pointers_solver, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___get_poin, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__42)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 94, __pyx_L1_error) + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_3_AcadosOcpSolverCython__get_pointers_solver, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___get_poin, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__45)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 89, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); - if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_AcadosOcpSolverCython__get_poin, __pyx_t_4) < 0) __PYX_ERR(0, 94, __pyx_L1_error) + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_AcadosOcpSolverCython__get_poin, __pyx_t_4) < 0) __PYX_ERR(0, 89, __pyx_L1_error) __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); - /* "acados_template/acados_ocp_solver_pyx.pyx":108 + /* "acados_template/acados_ocp_solver_pyx.pyx":103 + * + * + * def solve_for_x0(self, x0_bar): # <<<<<<<<<<<<<< + * """ + * Wrapper around `solve()` which sets initial state constraint, solves the OCP, and returns u0. + */ + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve_for_x0, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_solve_for, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__47)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 103, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_solve_for_x0, __pyx_t_4) < 0) __PYX_ERR(0, 103, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":121 * * * def solve(self): # <<<<<<<<<<<<<< * """ * Solve the ocp with current input. */ - __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_solve, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__43)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 108, __pyx_L1_error) + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7solve, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_solve, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__48)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 121, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); - if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_solve, __pyx_t_4) < 0) __PYX_ERR(0, 108, __pyx_L1_error) + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_solve, __pyx_t_4) < 0) __PYX_ERR(0, 121, __pyx_L1_error) __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); - /* "acados_template/acados_ocp_solver_pyx.pyx":115 + /* "acados_template/acados_ocp_solver_pyx.pyx":128 * * - * def reset(self): # <<<<<<<<<<<<<< + * def reset(self, reset_qp_solver_mem=1): # <<<<<<<<<<<<<< * """ * Sets current iterate to all zeros. */ - __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7reset, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_reset, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__44)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 115, __pyx_L1_error) + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9reset, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_reset, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__50)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 128, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); - if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_reset, __pyx_t_4) < 0) __PYX_ERR(0, 115, __pyx_L1_error) + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_4, __pyx_tuple__25); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_reset, __pyx_t_4) < 0) __PYX_ERR(0, 128, __pyx_L1_error) __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); - /* "acados_template/acados_ocp_solver_pyx.pyx":122 + /* "acados_template/acados_ocp_solver_pyx.pyx":135 + * + * + * def custom_update(self, data_): # <<<<<<<<<<<<<< + * """ + * A custom function that can be implemented by a user to be called between solver calls. + */ + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11custom_update, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_custom_upd, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__52)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 135, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_custom_update, __pyx_t_4) < 0) __PYX_ERR(0, 135, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":148 * * * def set_new_time_steps(self, new_time_steps): # <<<<<<<<<<<<<< * """ * Set new time steps. */ - __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9set_new_time_steps, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_set_new_ti, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__46)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 122, __pyx_L1_error) + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13set_new_time_steps, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_set_new_ti, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__54)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 148, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); - if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_set_new_time_steps, __pyx_t_4) < 0) __PYX_ERR(0, 122, __pyx_L1_error) + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_set_new_time_steps, __pyx_t_4) < 0) __PYX_ERR(0, 148, __pyx_L1_error) __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); - /* "acados_template/acados_ocp_solver_pyx.pyx":173 + /* "acados_template/acados_ocp_solver_pyx.pyx":199 * * * def update_qp_solver_cond_N(self, qp_solver_cond_N: int): # <<<<<<<<<<<<<< * """ * Recreate solver with new value `qp_solver_cond_N` with a partial condensing QP solver. */ - __pyx_t_4 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 173, __pyx_L1_error) + __pyx_t_4 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 199, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); - if (PyDict_SetItem(__pyx_t_4, __pyx_n_s_qp_solver_cond_N, __pyx_n_s_int) < 0) __PYX_ERR(0, 173, __pyx_L1_error) - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11update_qp_solver_cond_N, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_update_qp, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__48)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 173, __pyx_L1_error) + if (PyDict_SetItem(__pyx_t_4, __pyx_n_s_qp_solver_cond_N, __pyx_n_s_int) < 0) __PYX_ERR(0, 199, __pyx_L1_error) + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15update_qp_solver_cond_N, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_update_qp, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__56)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 199, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); __Pyx_CyFunction_SetAnnotationsDict(__pyx_t_7, __pyx_t_4); __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_update_qp_solver_cond_N, __pyx_t_7) < 0) __PYX_ERR(0, 173, __pyx_L1_error) + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_update_qp_solver_cond_N, __pyx_t_7) < 0) __PYX_ERR(0, 199, __pyx_L1_error) __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); - /* "acados_template/acados_ocp_solver_pyx.pyx":207 + /* "acados_template/acados_ocp_solver_pyx.pyx":233 * * * def eval_param_sens(self, index, stage=0, field="ex"): # <<<<<<<<<<<<<< * """ * Calculate the sensitivity of the curent solution with respect to the initial state component of index */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13eval_param_sens, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_eval_param_3, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__50)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 207, __pyx_L1_error) + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17eval_param_sens, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_eval_param_3, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__58)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 233, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); - __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_7, __pyx_tuple__51); - if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_eval_param_sens, __pyx_t_7) < 0) __PYX_ERR(0, 207, __pyx_L1_error) + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_7, __pyx_tuple__59); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_eval_param_sens, __pyx_t_7) < 0) __PYX_ERR(0, 233, __pyx_L1_error) __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); - /* "acados_template/acados_ocp_solver_pyx.pyx":232 + /* "acados_template/acados_ocp_solver_pyx.pyx":258 * * * def get(self, int stage, str field_): # <<<<<<<<<<<<<< * """ * Get the last solution of the solver: */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15get, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_get, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__53)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 232, __pyx_L1_error) + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19get, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_get, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__61)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 258, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); - if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_get, __pyx_t_7) < 0) __PYX_ERR(0, 232, __pyx_L1_error) + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_get, __pyx_t_7) < 0) __PYX_ERR(0, 258, __pyx_L1_error) __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); - /* "acados_template/acados_ocp_solver_pyx.pyx":275 + /* "acados_template/acados_ocp_solver_pyx.pyx":301 * * * def print_statistics(self): # <<<<<<<<<<<<<< * """ * prints statistics of previous solver run as a table: */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17print_statistics, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_print_stat, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__54)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 275, __pyx_L1_error) + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21print_statistics, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_print_stat, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__62)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 301, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); - if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_print_statistics, __pyx_t_7) < 0) __PYX_ERR(0, 275, __pyx_L1_error) + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_print_statistics, __pyx_t_7) < 0) __PYX_ERR(0, 301, __pyx_L1_error) __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); - /* "acados_template/acados_ocp_solver_pyx.pyx":293 + /* "acados_template/acados_ocp_solver_pyx.pyx":319 * * * def store_iterate(self, filename='', overwrite=False): # <<<<<<<<<<<<<< * """ * Stores the current iterate of the ocp solver in a json file. */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19store_iterate, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_store_iter, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__56)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 293, __pyx_L1_error) + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23store_iterate, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_store_iter, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__64)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 319, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); - __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_7, __pyx_tuple__57); - if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_store_iterate, __pyx_t_7) < 0) __PYX_ERR(0, 293, __pyx_L1_error) + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_7, __pyx_tuple__65); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_store_iterate, __pyx_t_7) < 0) __PYX_ERR(0, 319, __pyx_L1_error) __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); - /* "acados_template/acados_ocp_solver_pyx.pyx":330 + /* "acados_template/acados_ocp_solver_pyx.pyx":362 * * * def load_iterate(self, filename): # <<<<<<<<<<<<<< * """ * Loads the iterate stored in json file with filename into the ocp solver. */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21load_iterate, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_load_itera, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__59)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 330, __pyx_L1_error) + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25load_iterate, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_load_itera, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__67)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 362, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); - if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_load_iterate, __pyx_t_7) < 0) __PYX_ERR(0, 330, __pyx_L1_error) + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_load_iterate, __pyx_t_7) < 0) __PYX_ERR(0, 362, __pyx_L1_error) __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); - /* "acados_template/acados_ocp_solver_pyx.pyx":346 + /* "acados_template/acados_ocp_solver_pyx.pyx":378 * * * def get_stats(self, field_): # <<<<<<<<<<<<<< * """ * Get the information of the last solver call. */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23get_stats, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_get_stats, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__61)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 346, __pyx_L1_error) + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27get_stats, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_get_stats, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__69)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 378, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); - if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_get_stats, __pyx_t_7) < 0) __PYX_ERR(0, 346, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); - - /* "acados_template/acados_ocp_solver_pyx.pyx":428 - * - * - * def __get_stat_int(self, field): # <<<<<<<<<<<<<< - * cdef int out - * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &out) - */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25_AcadosOcpSolverCython__get_stat_int, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___get_stat, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__63)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 428, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_AcadosOcpSolverCython__get_stat, __pyx_t_7) < 0) __PYX_ERR(0, 428, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); - - /* "acados_template/acados_ocp_solver_pyx.pyx":433 - * return out - * - * def __get_stat_double(self, field): # <<<<<<<<<<<<<< - * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) - * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) - */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27_AcadosOcpSolverCython__get_stat_double, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___get_stat_2, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__64)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 433, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_AcadosOcpSolverCython__get_stat_2, __pyx_t_7) < 0) __PYX_ERR(0, 433, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); - - /* "acados_template/acados_ocp_solver_pyx.pyx":438 - * return out - * - * def __get_stat_matrix(self, field, n, m): # <<<<<<<<<<<<<< - * cdef cnp.ndarray[cnp.float64_t, ndim=2] out_mat = np.ascontiguousarray(np.zeros((n, m)), dtype=np.float64) - * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_mat.data) - */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_matrix, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___get_stat_3, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__66)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 438, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_AcadosOcpSolverCython__get_stat_3, __pyx_t_7) < 0) __PYX_ERR(0, 438, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); - - /* "acados_template/acados_ocp_solver_pyx.pyx":444 - * - * - * def get_cost(self): # <<<<<<<<<<<<<< - * """ - * Returns the cost value of the current solution. - */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31get_cost, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_get_cost, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__68)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 444, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_get_cost, __pyx_t_7) < 0) __PYX_ERR(0, 444, __pyx_L1_error) + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_get_stats, __pyx_t_7) < 0) __PYX_ERR(0, 378, __pyx_L1_error) __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); /* "acados_template/acados_ocp_solver_pyx.pyx":460 * * - * def get_residuals(self, recompute=False): # <<<<<<<<<<<<<< - * """ - * Returns an array of the form [res_stat, res_eq, res_ineq, res_comp]. + * def __get_stat_int(self, field): # <<<<<<<<<<<<<< + * cdef int out + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &out) */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33get_residuals, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_get_residu, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__70)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 460, __pyx_L1_error) + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_int, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___get_stat, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__71)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 460, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); - __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_7, __pyx_tuple__71); - if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_get_residuals, __pyx_t_7) < 0) __PYX_ERR(0, 460, __pyx_L1_error) + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_AcadosOcpSolverCython__get_stat, __pyx_t_7) < 0) __PYX_ERR(0, 460, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":465 + * return out + * + * def __get_stat_double(self, field): # <<<<<<<<<<<<<< + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31_AcadosOcpSolverCython__get_stat_double, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___get_stat_2, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__72)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 465, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_AcadosOcpSolverCython__get_stat_2, __pyx_t_7) < 0) __PYX_ERR(0, 465, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":470 + * return out + * + * def __get_stat_matrix(self, field, n, m): # <<<<<<<<<<<<<< + * cdef cnp.ndarray[cnp.float64_t, ndim=2] out_mat = np.ascontiguousarray(np.zeros((n, m)), dtype=np.float64) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_mat.data) + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33_AcadosOcpSolverCython__get_stat_matrix, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___get_stat_3, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__74)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 470, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_AcadosOcpSolverCython__get_stat_3, __pyx_t_7) < 0) __PYX_ERR(0, 470, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":476 + * + * + * def get_cost(self): # <<<<<<<<<<<<<< + * """ + * Returns the cost value of the current solution. + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35get_cost, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_get_cost, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__76)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 476, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_get_cost, __pyx_t_7) < 0) __PYX_ERR(0, 476, __pyx_L1_error) __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); /* "acados_template/acados_ocp_solver_pyx.pyx":492 * + * + * def get_residuals(self, recompute=False): # <<<<<<<<<<<<<< + * """ + * Returns an array of the form [res_stat, res_eq, res_ineq, res_comp]. + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37get_residuals, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_get_residu, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__78)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 492, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_7, __pyx_tuple__79); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_get_residuals, __pyx_t_7) < 0) __PYX_ERR(0, 492, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":524 + * * # Note: this function should not be used anymore, better use cost_set, constraints_set * def set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< * * """ */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35set, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_set, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__73)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 492, __pyx_L1_error) + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39set, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_set, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__81)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 524, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); - if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_set, __pyx_t_7) < 0) __PYX_ERR(0, 492, __pyx_L1_error) + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_set, __pyx_t_7) < 0) __PYX_ERR(0, 524, __pyx_L1_error) __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); - /* "acados_template/acados_ocp_solver_pyx.pyx":551 - * + /* "acados_template/acados_ocp_solver_pyx.pyx":590 + * return * * def cost_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< * """ * Set numerical data in the cost module of the solver. */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37cost_set, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_cost_set, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__75)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 551, __pyx_L1_error) + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41cost_set, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_cost_set, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__83)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 590, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); - if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_cost_set, __pyx_t_7) < 0) __PYX_ERR(0, 551, __pyx_L1_error) + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_cost_set, __pyx_t_7) < 0) __PYX_ERR(0, 590, __pyx_L1_error) __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); - /* "acados_template/acados_ocp_solver_pyx.pyx":584 + /* "acados_template/acados_ocp_solver_pyx.pyx":625 * * * def constraints_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< * """ * Set numerical data in the constraint module of the solver. */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39constraints_set, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_constraint_2, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__76)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 584, __pyx_L1_error) + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43constraints_set, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_constraint_2, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__84)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 625, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); - if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_constraints_set, __pyx_t_7) < 0) __PYX_ERR(0, 584, __pyx_L1_error) + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_constraints_set, __pyx_t_7) < 0) __PYX_ERR(0, 625, __pyx_L1_error) __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); - /* "acados_template/acados_ocp_solver_pyx.pyx":619 + /* "acados_template/acados_ocp_solver_pyx.pyx":663 * * - * def dynamics_get(self, int stage, str field_): # <<<<<<<<<<<<<< + * def get_from_qp_in(self, int stage, str field_): # <<<<<<<<<<<<<< * """ * Get numerical data from the dynamics module of the solver: */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41dynamics_get, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_dynamics_g, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__78)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 619, __pyx_L1_error) + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_45get_from_qp_in, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_get_from_q, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__86)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 663, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); - if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_dynamics_get, __pyx_t_7) < 0) __PYX_ERR(0, 619, __pyx_L1_error) + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_get_from_qp_in, __pyx_t_7) < 0) __PYX_ERR(0, 663, __pyx_L1_error) __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); - /* "acados_template/acados_ocp_solver_pyx.pyx":641 + /* "acados_template/acados_ocp_solver_pyx.pyx":685 * * * def options_set(self, str field_, value_): # <<<<<<<<<<<<<< * """ * Set options of the solver. */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43options_set, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_options_se_2, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__80)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 641, __pyx_L1_error) + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47options_set, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_options_se_2, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__88)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 685, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); - if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_options_set, __pyx_t_7) < 0) __PYX_ERR(0, 641, __pyx_L1_error) + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_options_set, __pyx_t_7) < 0) __PYX_ERR(0, 685, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":748 + * + * + * def set_params_sparse(self, int stage, idx_values_, param_values_): # <<<<<<<<<<<<<< + * """ + * set parameters of the solvers external function partially: + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49set_params_sparse, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_set_params, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__90)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 748, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_set_params_sparse, __pyx_t_7) < 0) __PYX_ERR(0, 748, __pyx_L1_error) __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); @@ -32531,7 +34208,7 @@ if (!__Pyx_RefNanny) { * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" * def __setstate_cython__(self, __pyx_state): */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___reduce_c, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__81)); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_53__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___reduce_c, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__91)); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 1, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); if (PyDict_SetItem(__pyx_d, __pyx_n_s_reduce_cython, __pyx_t_7) < 0) __PYX_ERR(1, 1, __pyx_L1_error) __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; @@ -32542,7 +34219,7 @@ if (!__Pyx_RefNanny) { * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___setstate, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__83)); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 3, __pyx_L1_error) + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_55__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___setstate, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__93)); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 3, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); if (PyDict_SetItem(__pyx_d, __pyx_n_s_setstate_cython, __pyx_t_7) < 0) __PYX_ERR(1, 3, __pyx_L1_error) __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; @@ -32550,7 +34227,7 @@ if (!__Pyx_RefNanny) { /* "acados_template/acados_ocp_solver_pyx.pyx":1 * # -*- coding: future_fstrings -*- # <<<<<<<<<<<<<< * # - * # Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, + * # Copyright (c) The acados authors. */ __pyx_t_7 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 1, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); @@ -34953,6 +36630,150 @@ static CYTHON_INLINE int __Pyx_HasAttr(PyObject *o, PyObject *n) { } } +/* PyIntCompare */ +static CYTHON_INLINE int __Pyx_PyInt_BoolEqObjC(PyObject *op1, PyObject *op2, long intval, long inplace) { + CYTHON_MAYBE_UNUSED_VAR(intval); + CYTHON_UNUSED_VAR(inplace); + if (op1 == op2) { + return 1; + } + #if PY_MAJOR_VERSION < 3 + if (likely(PyInt_CheckExact(op1))) { + const long b = intval; + long a = PyInt_AS_LONG(op1); + return (a == b); + } + #endif + #if CYTHON_USE_PYLONG_INTERNALS + if (likely(PyLong_CheckExact(op1))) { + int unequal; + unsigned long uintval; + Py_ssize_t size = __Pyx_PyLong_DigitCount(op1); + const digit* digits = __Pyx_PyLong_Digits(op1); + if (intval == 0) { + return (__Pyx_PyLong_IsZero(op1) == 1); + } else if (intval < 0) { + if (__Pyx_PyLong_IsNonNeg(op1)) + return 0; + intval = -intval; + } else { + if (__Pyx_PyLong_IsNeg(op1)) + return 0; + } + uintval = (unsigned long) intval; +#if PyLong_SHIFT * 4 < SIZEOF_LONG*8 + if (uintval >> (PyLong_SHIFT * 4)) { + unequal = (size != 5) || (digits[0] != (uintval & (unsigned long) PyLong_MASK)) + | (digits[1] != ((uintval >> (1 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[2] != ((uintval >> (2 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[3] != ((uintval >> (3 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[4] != ((uintval >> (4 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)); + } else +#endif +#if PyLong_SHIFT * 3 < SIZEOF_LONG*8 + if (uintval >> (PyLong_SHIFT * 3)) { + unequal = (size != 4) || (digits[0] != (uintval & (unsigned long) PyLong_MASK)) + | (digits[1] != ((uintval >> (1 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[2] != ((uintval >> (2 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[3] != ((uintval >> (3 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)); + } else +#endif +#if PyLong_SHIFT * 2 < SIZEOF_LONG*8 + if (uintval >> (PyLong_SHIFT * 2)) { + unequal = (size != 3) || (digits[0] != (uintval & (unsigned long) PyLong_MASK)) + | (digits[1] != ((uintval >> (1 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[2] != ((uintval >> (2 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)); + } else +#endif +#if PyLong_SHIFT * 1 < SIZEOF_LONG*8 + if (uintval >> (PyLong_SHIFT * 1)) { + unequal = (size != 2) || (digits[0] != (uintval & (unsigned long) PyLong_MASK)) + | (digits[1] != ((uintval >> (1 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)); + } else +#endif + unequal = (size != 1) || (((unsigned long) digits[0]) != (uintval & (unsigned long) PyLong_MASK)); + return (unequal == 0); + } + #endif + if (PyFloat_CheckExact(op1)) { + const long b = intval; +#if CYTHON_COMPILING_IN_LIMITED_API + double a = __pyx_PyFloat_AsDouble(op1); +#else + double a = PyFloat_AS_DOUBLE(op1); +#endif + return ((double)a == (double)b); + } + return __Pyx_PyObject_IsTrueAndDecref( + PyObject_RichCompare(op1, op2, Py_EQ)); +} + +/* PyIntCompare */ +static CYTHON_INLINE int __Pyx_PyInt_BoolNeObjC(PyObject *op1, PyObject *op2, long intval, long inplace) { + CYTHON_MAYBE_UNUSED_VAR(intval); + CYTHON_UNUSED_VAR(inplace); + if (op1 == op2) { + return 0; + } + #if PY_MAJOR_VERSION < 3 + if (likely(PyInt_CheckExact(op1))) { + const long b = intval; + long a = PyInt_AS_LONG(op1); + return (a != b); + } + #endif + #if CYTHON_USE_PYLONG_INTERNALS + if (likely(PyLong_CheckExact(op1))) { + int unequal; + unsigned long uintval; + Py_ssize_t size = __Pyx_PyLong_DigitCount(op1); + const digit* digits = __Pyx_PyLong_Digits(op1); + if (intval == 0) { + return (__Pyx_PyLong_IsZero(op1) != 1); + } else if (intval < 0) { + if (__Pyx_PyLong_IsNonNeg(op1)) + return 1; + intval = -intval; + } else { + if (__Pyx_PyLong_IsNeg(op1)) + return 1; + } + uintval = (unsigned long) intval; +#if PyLong_SHIFT * 4 < SIZEOF_LONG*8 + if (uintval >> (PyLong_SHIFT * 4)) { + unequal = (size != 5) || (digits[0] != (uintval & (unsigned long) PyLong_MASK)) + | (digits[1] != ((uintval >> (1 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[2] != ((uintval >> (2 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[3] != ((uintval >> (3 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[4] != ((uintval >> (4 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)); + } else +#endif +#if PyLong_SHIFT * 3 < SIZEOF_LONG*8 + if (uintval >> (PyLong_SHIFT * 3)) { + unequal = (size != 4) || (digits[0] != (uintval & (unsigned long) PyLong_MASK)) + | (digits[1] != ((uintval >> (1 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[2] != ((uintval >> (2 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[3] != ((uintval >> (3 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)); + } else +#endif +#if PyLong_SHIFT * 2 < SIZEOF_LONG*8 + if (uintval >> (PyLong_SHIFT * 2)) { + unequal = (size != 3) || (digits[0] != (uintval & (unsigned long) PyLong_MASK)) + | (digits[1] != ((uintval >> (1 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[2] != ((uintval >> (2 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)); + } else +#endif +#if PyLong_SHIFT * 1 < SIZEOF_LONG*8 + if (uintval >> (PyLong_SHIFT * 1)) { + unequal = (size != 2) || (digits[0] != (uintval & (unsigned long) PyLong_MASK)) + | (digits[1] != ((uintval >> (1 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)); + } else +#endif + unequal = (size != 1) || (((unsigned long) digits[0]) != (uintval & (unsigned long) PyLong_MASK)); + return (unequal != 0); + } + #endif + if (PyFloat_CheckExact(op1)) { + const long b = intval; +#if CYTHON_COMPILING_IN_LIMITED_API + double a = __pyx_PyFloat_AsDouble(op1); +#else + double a = PyFloat_AS_DOUBLE(op1); +#endif + return ((double)a != (double)b); + } + return __Pyx_PyObject_IsTrueAndDecref( + PyObject_RichCompare(op1, op2, Py_NE)); +} + /* IsLittleEndian */ static CYTHON_INLINE int __Pyx_Is_Little_Endian(void) { @@ -35677,6 +37498,156 @@ bad: return NULL; } +/* PyObjectFormat */ + #if CYTHON_USE_UNICODE_WRITER +static PyObject* __Pyx_PyObject_Format(PyObject* obj, PyObject* format_spec) { + int ret; + _PyUnicodeWriter writer; + if (likely(PyFloat_CheckExact(obj))) { +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x03040000 + _PyUnicodeWriter_Init(&writer, 0); +#else + _PyUnicodeWriter_Init(&writer); +#endif + ret = _PyFloat_FormatAdvancedWriter( + &writer, + obj, + format_spec, 0, PyUnicode_GET_LENGTH(format_spec)); + } else if (likely(PyLong_CheckExact(obj))) { +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x03040000 + _PyUnicodeWriter_Init(&writer, 0); +#else + _PyUnicodeWriter_Init(&writer); +#endif + ret = _PyLong_FormatAdvancedWriter( + &writer, + obj, + format_spec, 0, PyUnicode_GET_LENGTH(format_spec)); + } else { + return PyObject_Format(obj, format_spec); + } + if (unlikely(ret == -1)) { + _PyUnicodeWriter_Dealloc(&writer); + return NULL; + } + return _PyUnicodeWriter_Finish(&writer); +} +#endif + +/* UnpackUnboundCMethod */ + static PyObject *__Pyx_SelflessCall(PyObject *method, PyObject *args, PyObject *kwargs) { + PyObject *selfless_args = PyTuple_GetSlice(args, 1, PyTuple_Size(args)); + if (unlikely(!selfless_args)) return NULL; + PyObject *result = PyObject_Call(method, selfless_args, kwargs); + Py_DECREF(selfless_args); + return result; +} +static PyMethodDef __Pyx_UnboundCMethod_Def = { + "CythonUnboundCMethod", + __PYX_REINTERPRET_FUNCION(PyCFunction, __Pyx_SelflessCall), + METH_VARARGS | METH_KEYWORDS, + NULL +}; +static int __Pyx_TryUnpackUnboundCMethod(__Pyx_CachedCFunction* target) { + PyObject *method; + method = __Pyx_PyObject_GetAttrStr(target->type, *target->method_name); + if (unlikely(!method)) + return -1; + target->method = method; +#if CYTHON_COMPILING_IN_CPYTHON + #if PY_MAJOR_VERSION >= 3 + if (likely(__Pyx_TypeCheck(method, &PyMethodDescr_Type))) + #else + if (likely(!PyCFunction_Check(method))) + #endif + { + PyMethodDescrObject *descr = (PyMethodDescrObject*) method; + target->func = descr->d_method->ml_meth; + target->flag = descr->d_method->ml_flags & ~(METH_CLASS | METH_STATIC | METH_COEXIST | METH_STACKLESS); + } else +#endif +#if defined(CYTHON_COMPILING_IN_PYPY) +#elif PY_VERSION_HEX >= 0x03090000 + if (PyCFunction_CheckExact(method)) +#else + if (PyCFunction_Check(method)) +#endif + { + PyObject *self; + int self_found; +#if CYTHON_COMPILING_IN_LIMITED_API || CYTHON_COMPILING_IN_PYPY + self = PyObject_GetAttrString(method, "__self__"); + if (!self) { + PyErr_Clear(); + } +#else + self = PyCFunction_GET_SELF(method); +#endif + self_found = (self && self != Py_None); +#if CYTHON_COMPILING_IN_LIMITED_API || CYTHON_COMPILING_IN_PYPY + Py_XDECREF(self); +#endif + if (self_found) { + PyObject *unbound_method = PyCFunction_New(&__Pyx_UnboundCMethod_Def, method); + if (unlikely(!unbound_method)) return -1; + Py_DECREF(method); + target->method = unbound_method; + } + } + return 0; +} + +/* CallUnboundCMethod0 */ + static PyObject* __Pyx__CallUnboundCMethod0(__Pyx_CachedCFunction* cfunc, PyObject* self) { + PyObject *args, *result = NULL; + if (unlikely(!cfunc->method) && unlikely(__Pyx_TryUnpackUnboundCMethod(cfunc) < 0)) return NULL; +#if CYTHON_ASSUME_SAFE_MACROS + args = PyTuple_New(1); + if (unlikely(!args)) goto bad; + Py_INCREF(self); + PyTuple_SET_ITEM(args, 0, self); +#else + args = PyTuple_Pack(1, self); + if (unlikely(!args)) goto bad; +#endif + result = __Pyx_PyObject_Call(cfunc->method, args, NULL); + Py_DECREF(args); +bad: + return result; +} + +/* py_dict_keys */ + static CYTHON_INLINE PyObject* __Pyx_PyDict_Keys(PyObject* d) { + if (PY_MAJOR_VERSION >= 3) + return __Pyx_CallUnboundCMethod0(&__pyx_umethod_PyDict_Type_keys, d); + else + return PyDict_Keys(d); +} + +/* DictGetItem */ + #if PY_MAJOR_VERSION >= 3 && !CYTHON_COMPILING_IN_PYPY +static PyObject *__Pyx_PyDict_GetItem(PyObject *d, PyObject* key) { + PyObject *value; + value = PyDict_GetItemWithError(d, key); + if (unlikely(!value)) { + if (!PyErr_Occurred()) { + if (unlikely(PyTuple_Check(key))) { + PyObject* args = PyTuple_Pack(1, key); + if (likely(args)) { + PyErr_SetObject(PyExc_KeyError, args); + Py_DECREF(args); + } + } else { + PyErr_SetObject(PyExc_KeyError, key); + } + } + return NULL; + } + Py_INCREF(value); + return value; +} +#endif + /* PyObjectLookupSpecial */ #if CYTHON_USE_PYTYPE_LOOKUP && CYTHON_USE_TYPE_SLOTS static CYTHON_INLINE PyObject* __Pyx__PyObject_LookupSpecial(PyObject* obj, PyObject* attr_name, int with_error) { @@ -39191,6 +41162,279 @@ raise_neg_overflow: } } +/* CIntFromPy */ + static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(long) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(long, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (long) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 2 * PyLong_SHIFT)) { + return (long) (((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 3 * PyLong_SHIFT)) { + return (long) (((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 4 * PyLong_SHIFT)) { + return (long) (((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(long) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(long) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) ((((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) ((((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) ((((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(long) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + long val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (long) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (long) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (long) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (long) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(long) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(long) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((long) 1) << (sizeof(long) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (long) -1; + } + } else { + long val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (long) -1; + val = __Pyx_PyInt_As_long(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to long"); + return (long) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to long"); + return (long) -1; +} + /* CIntToPy */ static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value) { #ifdef __Pyx_HAS_GCC_DIAGNOSTIC @@ -39502,279 +41746,6 @@ raise_neg_overflow: return (size_t) -1; } -/* CIntFromPy */ - static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *x) { -#ifdef __Pyx_HAS_GCC_DIAGNOSTIC -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wconversion" -#endif - const long neg_one = (long) -1, const_zero = (long) 0; -#ifdef __Pyx_HAS_GCC_DIAGNOSTIC -#pragma GCC diagnostic pop -#endif - const int is_unsigned = neg_one > const_zero; -#if PY_MAJOR_VERSION < 3 - if (likely(PyInt_Check(x))) { - if ((sizeof(long) < sizeof(long))) { - __PYX_VERIFY_RETURN_INT(long, long, PyInt_AS_LONG(x)) - } else { - long val = PyInt_AS_LONG(x); - if (is_unsigned && unlikely(val < 0)) { - goto raise_neg_overflow; - } - return (long) val; - } - } else -#endif - if (likely(PyLong_Check(x))) { - if (is_unsigned) { -#if CYTHON_USE_PYLONG_INTERNALS - if (unlikely(__Pyx_PyLong_IsNeg(x))) { - goto raise_neg_overflow; - } else if (__Pyx_PyLong_IsCompact(x)) { - __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) - } else { - const digit* digits = __Pyx_PyLong_Digits(x); - assert(__Pyx_PyLong_DigitCount(x) > 1); - switch (__Pyx_PyLong_DigitCount(x)) { - case 2: - if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { - if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { - __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) - } else if ((8 * sizeof(long) >= 2 * PyLong_SHIFT)) { - return (long) (((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); - } - } - break; - case 3: - if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { - if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { - __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) - } else if ((8 * sizeof(long) >= 3 * PyLong_SHIFT)) { - return (long) (((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); - } - } - break; - case 4: - if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { - if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { - __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) - } else if ((8 * sizeof(long) >= 4 * PyLong_SHIFT)) { - return (long) (((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); - } - } - break; - } - } -#endif -#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 - if (unlikely(Py_SIZE(x) < 0)) { - goto raise_neg_overflow; - } -#else - { - int result = PyObject_RichCompareBool(x, Py_False, Py_LT); - if (unlikely(result < 0)) - return (long) -1; - if (unlikely(result == 1)) - goto raise_neg_overflow; - } -#endif - if ((sizeof(long) <= sizeof(unsigned long))) { - __PYX_VERIFY_RETURN_INT_EXC(long, unsigned long, PyLong_AsUnsignedLong(x)) -#ifdef HAVE_LONG_LONG - } else if ((sizeof(long) <= sizeof(unsigned PY_LONG_LONG))) { - __PYX_VERIFY_RETURN_INT_EXC(long, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) -#endif - } - } else { -#if CYTHON_USE_PYLONG_INTERNALS - if (__Pyx_PyLong_IsCompact(x)) { - __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) - } else { - const digit* digits = __Pyx_PyLong_Digits(x); - assert(__Pyx_PyLong_DigitCount(x) > 1); - switch (__Pyx_PyLong_SignedDigitCount(x)) { - case -2: - if ((8 * sizeof(long) - 1 > 1 * PyLong_SHIFT)) { - if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { - __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) - } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { - return (long) (((long)-1)*(((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); - } - } - break; - case 2: - if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { - if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { - __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) - } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { - return (long) ((((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); - } - } - break; - case -3: - if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { - if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { - __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) - } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { - return (long) (((long)-1)*(((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); - } - } - break; - case 3: - if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { - if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { - __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) - } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { - return (long) ((((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); - } - } - break; - case -4: - if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { - if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { - __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) - } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { - return (long) (((long)-1)*(((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); - } - } - break; - case 4: - if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { - if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { - __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) - } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { - return (long) ((((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); - } - } - break; - } - } -#endif - if ((sizeof(long) <= sizeof(long))) { - __PYX_VERIFY_RETURN_INT_EXC(long, long, PyLong_AsLong(x)) -#ifdef HAVE_LONG_LONG - } else if ((sizeof(long) <= sizeof(PY_LONG_LONG))) { - __PYX_VERIFY_RETURN_INT_EXC(long, PY_LONG_LONG, PyLong_AsLongLong(x)) -#endif - } - } - { - long val; - PyObject *v = __Pyx_PyNumber_IntOrLong(x); -#if PY_MAJOR_VERSION < 3 - if (likely(v) && !PyLong_Check(v)) { - PyObject *tmp = v; - v = PyNumber_Long(tmp); - Py_DECREF(tmp); - } -#endif - if (likely(v)) { - int ret = -1; -#if !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) - int one = 1; int is_little = (int)*(unsigned char *)&one; - unsigned char *bytes = (unsigned char *)&val; - ret = _PyLong_AsByteArray((PyLongObject *)v, - bytes, sizeof(val), - is_little, !is_unsigned); -#else - PyObject *stepval = NULL, *mask = NULL, *shift = NULL; - int bits, remaining_bits, is_negative = 0; - long idigit; - int chunk_size = (sizeof(long) < 8) ? 30 : 62; - if (unlikely(!PyLong_CheckExact(v))) { - PyObject *tmp = v; - v = PyNumber_Long(v); - assert(PyLong_CheckExact(v)); - Py_DECREF(tmp); - if (unlikely(!v)) return (long) -1; - } -#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 - if (Py_SIZE(x) == 0) - return (long) 0; - is_negative = Py_SIZE(x) < 0; -#else - { - int result = PyObject_RichCompareBool(x, Py_False, Py_LT); - if (unlikely(result < 0)) - return (long) -1; - is_negative = result == 1; - } -#endif - if (is_unsigned && unlikely(is_negative)) { - goto raise_neg_overflow; - } else if (is_negative) { - stepval = PyNumber_Invert(v); - if (unlikely(!stepval)) - return (long) -1; - } else { - stepval = __Pyx_NewRef(v); - } - val = (long) 0; - mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; - shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; - for (bits = 0; bits < (int) sizeof(long) * 8 - chunk_size; bits += chunk_size) { - PyObject *tmp, *digit; - digit = PyNumber_And(stepval, mask); - if (unlikely(!digit)) goto done; - idigit = PyLong_AsLong(digit); - Py_DECREF(digit); - if (unlikely(idigit < 0)) goto done; - tmp = PyNumber_Rshift(stepval, shift); - if (unlikely(!tmp)) goto done; - Py_DECREF(stepval); stepval = tmp; - val |= ((long) idigit) << bits; - #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 - if (Py_SIZE(stepval) == 0) - goto unpacking_done; - #endif - } - idigit = PyLong_AsLong(stepval); - if (unlikely(idigit < 0)) goto done; - remaining_bits = ((int) sizeof(long) * 8) - bits - (is_unsigned ? 0 : 1); - if (unlikely(idigit >= (1L << remaining_bits))) - goto raise_overflow; - val |= ((long) idigit) << bits; - #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 - unpacking_done: - #endif - if (!is_unsigned) { - if (unlikely(val & (((long) 1) << (sizeof(long) * 8 - 1)))) - goto raise_overflow; - if (is_negative) - val = ~val; - } - ret = 0; - done: - Py_XDECREF(shift); - Py_XDECREF(mask); - Py_XDECREF(stepval); -#endif - Py_DECREF(v); - if (likely(!ret)) - return val; - } - return (long) -1; - } - } else { - long val; - PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); - if (!tmp) return (long) -1; - val = __Pyx_PyInt_As_long(tmp); - Py_DECREF(tmp); - return val; - } -raise_overflow: - PyErr_SetString(PyExc_OverflowError, - "value too large to convert to long"); - return (long) -1; -raise_neg_overflow: - PyErr_SetString(PyExc_OverflowError, - "can't convert negative value to long"); - return (long) -1; -} - /* CIntFromPy */ static CYTHON_INLINE char __Pyx_PyInt_As_char(PyObject *x) { #ifdef __Pyx_HAS_GCC_DIAGNOSTIC @@ -40057,7 +42028,7 @@ __Pyx_PyType_GetName(PyTypeObject* tp) __pyx_n_s_name_2); if (unlikely(name == NULL) || unlikely(!PyUnicode_Check(name))) { PyErr_Clear(); - Py_XSETREF(name, __Pyx_NewRef(__pyx_n_s__84)); + Py_XSETREF(name, __Pyx_NewRef(__pyx_n_s__94)); } return name; } diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_ocp_solver_pyx.so b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_ocp_solver_pyx.so index b706c9d01..0ca87a9a8 100755 Binary files a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_ocp_solver_pyx.so and b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_ocp_solver_pyx.so differ diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_sim_solver_lat.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_sim_solver_lat.c index d0c541d3b..0594aa27b 100644 --- a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_sim_solver_lat.c +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_sim_solver_lat.c @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * @@ -82,6 +79,7 @@ int lat_acados_sim_create(sim_solver_capsule * capsule) // explicit ode capsule->sim_forw_vde_casadi = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)); + capsule->sim_vde_adj_casadi = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)); capsule->sim_expl_ode_fun_casadi = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)); capsule->sim_forw_vde_casadi->casadi_fun = &lat_expl_vde_forw; @@ -92,6 +90,14 @@ int lat_acados_sim_create(sim_solver_capsule * capsule) capsule->sim_forw_vde_casadi->casadi_work = &lat_expl_vde_forw_work; external_function_param_casadi_create(capsule->sim_forw_vde_casadi, np); + capsule->sim_vde_adj_casadi->casadi_fun = &lat_expl_vde_adj; + capsule->sim_vde_adj_casadi->casadi_n_in = &lat_expl_vde_adj_n_in; + capsule->sim_vde_adj_casadi->casadi_n_out = &lat_expl_vde_adj_n_out; + capsule->sim_vde_adj_casadi->casadi_sparsity_in = &lat_expl_vde_adj_sparsity_in; + capsule->sim_vde_adj_casadi->casadi_sparsity_out = &lat_expl_vde_adj_sparsity_out; + capsule->sim_vde_adj_casadi->casadi_work = &lat_expl_vde_adj_work; + external_function_param_casadi_create(capsule->sim_vde_adj_casadi, np); + capsule->sim_expl_ode_fun_casadi->casadi_fun = &lat_expl_ode_fun; capsule->sim_expl_ode_fun_casadi->casadi_n_in = &lat_expl_ode_fun_n_in; capsule->sim_expl_ode_fun_casadi->casadi_n_out = &lat_expl_ode_fun_n_out; @@ -123,6 +129,8 @@ int lat_acados_sim_create(sim_solver_capsule * capsule) capsule->acados_sim_opts = lat_sim_opts; int tmp_int = 3; sim_opts_set(lat_sim_config, lat_sim_opts, "newton_iter", &tmp_int); + double tmp_double = 0.0; + sim_opts_set(lat_sim_config, lat_sim_opts, "newton_tol", &tmp_double); sim_collocation_type collocation_type = GAUSS_LEGENDRE; sim_opts_set(lat_sim_config, lat_sim_opts, "collocation_type", &collocation_type); @@ -146,7 +154,9 @@ int lat_acados_sim_create(sim_solver_capsule * capsule) // model functions lat_sim_config->model_set(lat_sim_in->model, - "expl_vde_for", capsule->sim_forw_vde_casadi); + "expl_vde_forw", capsule->sim_forw_vde_casadi); + lat_sim_config->model_set(lat_sim_in->model, + "expl_vde_adj", capsule->sim_vde_adj_casadi); lat_sim_config->model_set(lat_sim_in->model, "expl_ode_fun", capsule->sim_expl_ode_fun_casadi); @@ -223,6 +233,7 @@ int lat_acados_sim_free(sim_solver_capsule *capsule) // free external function external_function_param_casadi_free(capsule->sim_forw_vde_casadi); + external_function_param_casadi_free(capsule->sim_vde_adj_casadi); external_function_param_casadi_free(capsule->sim_expl_ode_fun_casadi); return 0; @@ -240,6 +251,7 @@ int lat_acados_sim_update_params(sim_solver_capsule *capsule, double *p, int np) exit(1); } capsule->sim_forw_vde_casadi[0].set_param(capsule->sim_forw_vde_casadi, p); + capsule->sim_vde_adj_casadi[0].set_param(capsule->sim_vde_adj_casadi, p); capsule->sim_expl_ode_fun_casadi[0].set_param(capsule->sim_expl_ode_fun_casadi, p); return status; diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_sim_solver_lat.h b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_sim_solver_lat.h index 86b9c84c9..e7e8a9d39 100644 --- a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_sim_solver_lat.h +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_sim_solver_lat.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * @@ -61,6 +58,7 @@ typedef struct sim_solver_capsule /* external functions */ // ERK external_function_param_casadi * sim_forw_vde_casadi; + external_function_param_casadi * sim_vde_adj_casadi; external_function_param_casadi * sim_expl_ode_fun_casadi; external_function_param_casadi * sim_expl_ode_hess; diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_solver.pxd b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_solver.pxd index 8397f8e9d..208a515cc 100644 --- a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_solver.pxd +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_solver.pxd @@ -1,8 +1,5 @@ # -# Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, -# Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, -# Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, -# Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl +# Copyright (c) The acados authors. # # This file is part of acados. # @@ -47,11 +44,14 @@ cdef extern from "acados_solver_lat.h": int acados_update_qp_solver_cond_N "lat_acados_update_qp_solver_cond_N"(nlp_solver_capsule * capsule, int qp_solver_cond_N) int acados_update_params "lat_acados_update_params"(nlp_solver_capsule * capsule, int stage, double *value, int np_) + int acados_update_params_sparse "lat_acados_update_params_sparse"(nlp_solver_capsule * capsule, int stage, int *idx, double *p, int n_update) int acados_solve "lat_acados_solve"(nlp_solver_capsule * capsule) - int acados_reset "lat_acados_reset"(nlp_solver_capsule * capsule) + int acados_reset "lat_acados_reset"(nlp_solver_capsule * capsule, int reset_qp_solver_mem) int acados_free "lat_acados_free"(nlp_solver_capsule * capsule) void acados_print_stats "lat_acados_print_stats"(nlp_solver_capsule * capsule) + int acados_custom_update "lat_acados_custom_update"(nlp_solver_capsule* capsule, double * data, int data_len) + acados_solver_common.ocp_nlp_in *acados_get_nlp_in "lat_acados_get_nlp_in"(nlp_solver_capsule * capsule) acados_solver_common.ocp_nlp_out *acados_get_nlp_out "lat_acados_get_nlp_out"(nlp_solver_capsule * capsule) acados_solver_common.ocp_nlp_out *acados_get_sens_out "lat_acados_get_sens_out"(nlp_solver_capsule * capsule) diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_solver_lat.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_solver_lat.c index f95047dae..3ecc293b7 100644 --- a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_solver_lat.c +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_solver_lat.c @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * @@ -42,14 +39,12 @@ // example specific #include "lat_model/lat_model.h" +#include "lat_constraints/lat_constraints.h" +#include "lat_cost/lat_cost.h" -#include "lat_cost/lat_cost_y_fun.h" -#include "lat_cost/lat_cost_y_0_fun.h" -#include "lat_cost/lat_cost_y_e_fun.h" - #include "acados_solver_lat.h" #define NX LAT_NX @@ -289,7 +284,6 @@ return nlp_dims; void lat_acados_create_3_create_and_set_functions(lat_solver_capsule* capsule) { const int N = capsule->nlp_solver_plan->N; - ocp_nlp_config* nlp_config = capsule->nlp_config; /************************************************ * external functions @@ -434,28 +428,38 @@ void lat_acados_create_5_set_nlp_in(lat_solver_capsule* capsule, const int N, do } /**** Cost ****/ - double* W_0 = calloc(NY0*NY0, sizeof(double)); - // change only the non-zero elements: - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "W", W_0); - free(W_0); - double* yref_0 = calloc(NY0, sizeof(double)); // change only the non-zero elements: ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "yref", yref_0); free(yref_0); - double* W = calloc(NY*NY, sizeof(double)); - // change only the non-zero elements: - double* yref = calloc(NY, sizeof(double)); // change only the non-zero elements: for (int i = 1; i < N; i++) { - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "W", W); ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "yref", yref); } - free(W); free(yref); + double* yref_e = calloc(NYN, sizeof(double)); + // change only the non-zero elements: + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "yref", yref_e); + free(yref_e); + double* W_0 = calloc(NY0*NY0, sizeof(double)); + // change only the non-zero elements: + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "W", W_0); + free(W_0); + double* W = calloc(NY*NY, sizeof(double)); + // change only the non-zero elements: + + for (int i = 1; i < N; i++) + { + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "W", W); + } + free(W); + double* W_e = calloc(NYN*NYN, sizeof(double)); + // change only the non-zero elements: + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "W", W_e); + free(W_e); ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "nls_y_fun", &capsule->cost_y_0_fun); ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "nls_y_fun_jac", &capsule->cost_y_0_fun_jac_ut_xt); ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "nls_y_hess", &capsule->cost_y_0_hess); @@ -465,17 +469,6 @@ void lat_acados_create_5_set_nlp_in(lat_solver_capsule* capsule, const int N, do ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "nls_y_fun_jac", &capsule->cost_y_fun_jac_ut_xt[i-1]); ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "nls_y_hess", &capsule->cost_y_hess[i-1]); } - - // terminal cost - double* yref_e = calloc(NYN, sizeof(double)); - // change only the non-zero elements: - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "yref", yref_e); - free(yref_e); - - double* W_e = calloc(NYN*NYN, sizeof(double)); - // change only the non-zero elements: - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "W", W_e); - free(W_e); ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "nls_y_fun", &capsule->cost_y_e_fun); ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "nls_y_fun_jac", &capsule->cost_y_e_fun_jac_ut_xt); ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "nls_y_hess", &capsule->cost_y_e_hess); @@ -576,7 +569,6 @@ void lat_acados_create_6_set_opts(lat_solver_capsule* capsule) { const int N = capsule->nlp_solver_plan->N; ocp_nlp_config* nlp_config = capsule->nlp_config; - ocp_nlp_dims* nlp_dims = capsule->nlp_dims; void *nlp_opts = capsule->nlp_opts; /************************************************ @@ -614,10 +606,10 @@ void lat_acados_create_6_set_opts(lat_solver_capsule* capsule) for (int i = 0; i < N; i++) ocp_nlp_solver_opts_set_at_stage(nlp_config, nlp_opts, i, "dynamics_jac_reuse", &tmp_bool); - double nlp_solver_step_length = 1; + double nlp_solver_step_length = 1.0; ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "step_length", &nlp_solver_step_length); - double levenberg_marquardt = 0; + double levenberg_marquardt = 0.0; ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "levenberg_marquardt", &levenberg_marquardt); /* options QP solver */ @@ -626,6 +618,9 @@ void lat_acados_create_6_set_opts(lat_solver_capsule* capsule) const int qp_solver_cond_N_ori = 1; qp_solver_cond_N = N < qp_solver_cond_N_ori ? N : qp_solver_cond_N_ori; // use the minimum value here ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "qp_cond_N", &qp_solver_cond_N); + + int nlp_solver_ext_qp_res = 0; + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "ext_qp_res", &nlp_solver_ext_qp_res); // set HPIPM mode: should be done before setting other QP solver options ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "qp_hpipm_mode", "BALANCE"); @@ -636,6 +631,11 @@ void lat_acados_create_6_set_opts(lat_solver_capsule* capsule) int print_level = 0; ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "print_level", &print_level); + int qp_solver_cond_ric_alg = 1; + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "qp_cond_ric_alg", &qp_solver_cond_ric_alg); + + int qp_solver_ric_alg = 1; + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "qp_ric_alg", &qp_solver_ric_alg); int ext_cost_num_hess = 0; @@ -744,6 +744,7 @@ int lat_acados_create_with_discretization(lat_solver_capsule* capsule, int N, do // 9) do precomputations int status = lat_acados_create_9_precompute(capsule); + return status; } @@ -771,7 +772,7 @@ int lat_acados_update_qp_solver_cond_N(lat_solver_capsule* capsule, int qp_solve } -int lat_acados_reset(lat_solver_capsule* capsule) +int lat_acados_reset(lat_solver_capsule* capsule, int reset_qp_solver_mem) { // set initialization to all zeros @@ -783,8 +784,6 @@ int lat_acados_reset(lat_solver_capsule* capsule) ocp_nlp_in* nlp_in = capsule->nlp_in; ocp_nlp_solver* nlp_solver = capsule->nlp_solver; - int nx, nu, nv, ns, nz, ni, dim; - double* buffer = calloc(NX+NU+NZ+2*NS+2*NSN+NBX+NBU+NG+NH+NPHI+NBX0+NBXN+NHN+NPHIN+NGN, sizeof(double)); for(int i=0; i reset memory int qp_status; ocp_nlp_get(capsule->nlp_config, capsule->nlp_solver, "qp_status", &qp_status); - if (qp_status == 3) + if (reset_qp_solver_mem || (qp_status == 3)) { // printf("\nin reset qp_status %d -> resetting QP memory\n", qp_status); ocp_nlp_solver_reset_qp_memory(nlp_solver, nlp_in, nlp_out); @@ -827,6 +826,7 @@ int lat_acados_update_params(lat_solver_capsule* capsule, int stage, double *p, " External function has %i parameters. Exiting.\n", np, casadi_np); exit(1); } + const int N = capsule->nlp_solver_plan->N; if (stage < N && stage >= 0) { @@ -863,15 +863,72 @@ int lat_acados_update_params(lat_solver_capsule* capsule, int stage, double *p, } - return solver_status; } +int lat_acados_update_params_sparse(lat_solver_capsule * capsule, int stage, int *idx, double *p, int n_update) +{ + int solver_status = 0; + + int casadi_np = 2; + if (casadi_np < n_update) { + printf("lat_acados_update_params_sparse: trying to set %d parameters for external functions." + " External function has %d parameters. Exiting.\n", n_update, casadi_np); + exit(1); + } + // for (int i = 0; i < n_update; i++) + // { + // if (idx[i] > casadi_np) { + // printf("lat_acados_update_params_sparse: attempt to set parameters with index %d, while" + // " external functions only has %d parameters. Exiting.\n", idx[i], casadi_np); + // exit(1); + // } + // printf("param %d value %e\n", idx[i], p[i]); + // } + const int N = capsule->nlp_solver_plan->N; + if (stage < N && stage >= 0) + { + capsule->forw_vde_casadi[stage].set_param_sparse(capsule->forw_vde_casadi+stage, n_update, idx, p); + capsule->expl_ode_fun[stage].set_param_sparse(capsule->expl_ode_fun+stage, n_update, idx, p); + + + // constraints + + + // cost + if (stage == 0) + { + capsule->cost_y_0_fun.set_param_sparse(&capsule->cost_y_0_fun, n_update, idx, p); + capsule->cost_y_0_fun_jac_ut_xt.set_param_sparse(&capsule->cost_y_0_fun_jac_ut_xt, n_update, idx, p); + capsule->cost_y_0_hess.set_param_sparse(&capsule->cost_y_0_hess, n_update, idx, p); + } + else // 0 < stage < N + { + capsule->cost_y_fun[stage-1].set_param_sparse(capsule->cost_y_fun+stage-1, n_update, idx, p); + capsule->cost_y_fun_jac_ut_xt[stage-1].set_param_sparse(capsule->cost_y_fun_jac_ut_xt+stage-1, n_update, idx, p); + capsule->cost_y_hess[stage-1].set_param_sparse(capsule->cost_y_hess+stage-1, n_update, idx, p); + } + } + + else // stage == N + { + // terminal shooting node has no dynamics + // cost + capsule->cost_y_e_fun.set_param_sparse(&capsule->cost_y_e_fun, n_update, idx, p); + capsule->cost_y_e_fun_jac_ut_xt.set_param_sparse(&capsule->cost_y_e_fun_jac_ut_xt, n_update, idx, p); + capsule->cost_y_e_hess.set_param_sparse(&capsule->cost_y_e_hess, n_update, idx, p); + // constraints + + } + + + return solver_status; +} int lat_acados_solve(lat_solver_capsule* capsule) { - // solve NLP + // solve NLP int solver_status = ocp_nlp_solve(capsule->nlp_solver, capsule->nlp_in, capsule->nlp_out); return solver_status; @@ -924,15 +981,6 @@ int lat_acados_free(lat_solver_capsule* capsule) return 0; } -ocp_nlp_in *lat_acados_get_nlp_in(lat_solver_capsule* capsule) { return capsule->nlp_in; } -ocp_nlp_out *lat_acados_get_nlp_out(lat_solver_capsule* capsule) { return capsule->nlp_out; } -ocp_nlp_out *lat_acados_get_sens_out(lat_solver_capsule* capsule) { return capsule->sens_out; } -ocp_nlp_solver *lat_acados_get_nlp_solver(lat_solver_capsule* capsule) { return capsule->nlp_solver; } -ocp_nlp_config *lat_acados_get_nlp_config(lat_solver_capsule* capsule) { return capsule->nlp_config; } -void *lat_acados_get_nlp_opts(lat_solver_capsule* capsule) { return capsule->nlp_opts; } -ocp_nlp_dims *lat_acados_get_nlp_dims(lat_solver_capsule* capsule) { return capsule->nlp_dims; } -ocp_nlp_plan_t *lat_acados_get_nlp_plan(lat_solver_capsule* capsule) { return capsule->nlp_solver_plan; } - void lat_acados_print_stats(lat_solver_capsule* capsule) { @@ -946,6 +994,11 @@ void lat_acados_print_stats(lat_solver_capsule* capsule) ocp_nlp_get(capsule->nlp_config, capsule->nlp_solver, "statistics", stat); int nrow = sqp_iter+1 < stat_m ? sqp_iter+1 : stat_m; + + printf("iter\tres_stat\tres_eq\t\tres_ineq\tres_comp\tqp_stat\tqp_iter\talpha"); + if (stat_n > 8) + printf("\t\tqp_res_stat\tqp_res_eq\tqp_res_ineq\tqp_res_comp"); + printf("\n"); printf("iter\tqp_stat\tqp_iter\n"); for (int i = 0; i < nrow; i++) { @@ -958,3 +1011,24 @@ void lat_acados_print_stats(lat_solver_capsule* capsule) } } +int lat_acados_custom_update(lat_solver_capsule* capsule, double* data, int data_len) +{ + (void)capsule; + (void)data; + (void)data_len; + printf("\ndummy function that can be called in between solver calls to update parameters or numerical data efficiently in C.\n"); + printf("nothing set yet..\n"); + return 1; + +} + + + +ocp_nlp_in *lat_acados_get_nlp_in(lat_solver_capsule* capsule) { return capsule->nlp_in; } +ocp_nlp_out *lat_acados_get_nlp_out(lat_solver_capsule* capsule) { return capsule->nlp_out; } +ocp_nlp_out *lat_acados_get_sens_out(lat_solver_capsule* capsule) { return capsule->sens_out; } +ocp_nlp_solver *lat_acados_get_nlp_solver(lat_solver_capsule* capsule) { return capsule->nlp_solver; } +ocp_nlp_config *lat_acados_get_nlp_config(lat_solver_capsule* capsule) { return capsule->nlp_config; } +void *lat_acados_get_nlp_opts(lat_solver_capsule* capsule) { return capsule->nlp_opts; } +ocp_nlp_dims *lat_acados_get_nlp_dims(lat_solver_capsule* capsule) { return capsule->nlp_dims; } +ocp_nlp_plan_t *lat_acados_get_nlp_plan(lat_solver_capsule* capsule) { return capsule->nlp_solver_plan; } diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_solver_lat.h b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_solver_lat.h index 0ef4698c2..90e5d202d 100644 --- a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_solver_lat.h +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_solver_lat.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * @@ -74,6 +71,7 @@ extern "C" { #endif + // ** capsule for solver data ** typedef struct lat_solver_capsule { @@ -106,6 +104,7 @@ typedef struct lat_solver_capsule external_function_param_casadi *cost_y_hess; + external_function_param_casadi cost_y_0_fun; external_function_param_casadi cost_y_0_fun_jac_ut_xt; external_function_param_casadi cost_y_0_hess; @@ -129,7 +128,7 @@ ACADOS_SYMBOL_EXPORT int lat_acados_free_capsule(lat_solver_capsule *capsule); ACADOS_SYMBOL_EXPORT int lat_acados_create(lat_solver_capsule * capsule); -ACADOS_SYMBOL_EXPORT int lat_acados_reset(lat_solver_capsule* capsule); +ACADOS_SYMBOL_EXPORT int lat_acados_reset(lat_solver_capsule* capsule, int reset_qp_solver_mem); /** * Generic version of lat_acados_create which allows to use a different number of shooting intervals than @@ -147,10 +146,14 @@ ACADOS_SYMBOL_EXPORT int lat_acados_update_time_steps(lat_solver_capsule * capsu */ ACADOS_SYMBOL_EXPORT int lat_acados_update_qp_solver_cond_N(lat_solver_capsule * capsule, int qp_solver_cond_N); ACADOS_SYMBOL_EXPORT int lat_acados_update_params(lat_solver_capsule * capsule, int stage, double *value, int np); +ACADOS_SYMBOL_EXPORT int lat_acados_update_params_sparse(lat_solver_capsule * capsule, int stage, int *idx, double *p, int n_update); + ACADOS_SYMBOL_EXPORT int lat_acados_solve(lat_solver_capsule * capsule); ACADOS_SYMBOL_EXPORT int lat_acados_free(lat_solver_capsule * capsule); ACADOS_SYMBOL_EXPORT void lat_acados_print_stats(lat_solver_capsule * capsule); - +ACADOS_SYMBOL_EXPORT int lat_acados_custom_update(lat_solver_capsule* capsule, double* data, int data_len); + + ACADOS_SYMBOL_EXPORT ocp_nlp_in *lat_acados_get_nlp_in(lat_solver_capsule * capsule); ACADOS_SYMBOL_EXPORT ocp_nlp_out *lat_acados_get_nlp_out(lat_solver_capsule * capsule); ACADOS_SYMBOL_EXPORT ocp_nlp_out *lat_acados_get_sens_out(lat_solver_capsule * capsule); diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_solver_sfunction_lat.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_solver_sfunction_lat.c deleted file mode 100644 index e0586aadf..000000000 --- a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_solver_sfunction_lat.c +++ /dev/null @@ -1,264 +0,0 @@ -/* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl - * - * This file is part of acados. - * - * 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 HOLDER 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.; - */ - -#define S_FUNCTION_NAME acados_solver_sfunction_lat -#define S_FUNCTION_LEVEL 2 - -#define MDL_START - -// acados -// #include "acados/utils/print.h" -#include "acados_c/sim_interface.h" -#include "acados_c/external_function_interface.h" - -// example specific -#include "lat_model/lat_model.h" -#include "acados_solver_lat.h" - -#include "simstruc.h" - -#define SAMPLINGTIME 0.009765625 - -static void mdlInitializeSizes (SimStruct *S) -{ - // specify the number of continuous and discrete states - ssSetNumContStates(S, 0); - ssSetNumDiscStates(S, 0);// specify the number of input ports - if ( !ssSetNumInputPorts(S, 8) ) - return; - - // specify the number of output ports - if ( !ssSetNumOutputPorts(S, 6) ) - return; - - // specify dimension information for the input ports - // lbx_0 - ssSetInputPortVectorDimension(S, 0, 4); - // ubx_0 - ssSetInputPortVectorDimension(S, 1, 4); - // parameters - ssSetInputPortVectorDimension(S, 2, (32+1) * 2); - // y_ref_0 - ssSetInputPortVectorDimension(S, 3, 5); - // y_ref - ssSetInputPortVectorDimension(S, 4, 155); - // y_ref_e - ssSetInputPortVectorDimension(S, 5, 3); - // lbx - ssSetInputPortVectorDimension(S, 6, 62); - // ubx - ssSetInputPortVectorDimension(S, 7, 62);/* specify dimension information for the OUTPUT ports */ - ssSetOutputPortVectorDimension(S, 0, 1 ); - ssSetOutputPortVectorDimension(S, 1, 1 ); - ssSetOutputPortVectorDimension(S, 2, 1 ); - ssSetOutputPortVectorDimension(S, 3, 4 ); // state at shooting node 1 - ssSetOutputPortVectorDimension(S, 4, 1); - ssSetOutputPortVectorDimension(S, 5, 1 ); - - // specify the direct feedthrough status - // should be set to 1 for all inputs used in mdlOutputs - ssSetInputPortDirectFeedThrough(S, 0, 1); - ssSetInputPortDirectFeedThrough(S, 1, 1); - ssSetInputPortDirectFeedThrough(S, 2, 1); - ssSetInputPortDirectFeedThrough(S, 3, 1); - ssSetInputPortDirectFeedThrough(S, 4, 1); - ssSetInputPortDirectFeedThrough(S, 5, 1); - ssSetInputPortDirectFeedThrough(S, 6, 1); - ssSetInputPortDirectFeedThrough(S, 7, 1); - - // one sample time - ssSetNumSampleTimes(S, 1); -} - - -#if defined(MATLAB_MEX_FILE) - -#define MDL_SET_INPUT_PORT_DIMENSION_INFO -#define MDL_SET_OUTPUT_PORT_DIMENSION_INFO - -static void mdlSetInputPortDimensionInfo(SimStruct *S, int_T port, const DimsInfo_T *dimsInfo) -{ - if ( !ssSetInputPortDimensionInfo(S, port, dimsInfo) ) - return; -} - -static void mdlSetOutputPortDimensionInfo(SimStruct *S, int_T port, const DimsInfo_T *dimsInfo) -{ - if ( !ssSetOutputPortDimensionInfo(S, port, dimsInfo) ) - return; -} - -#endif /* MATLAB_MEX_FILE */ - - -static void mdlInitializeSampleTimes(SimStruct *S) -{ - ssSetSampleTime(S, 0, SAMPLINGTIME); - ssSetOffsetTime(S, 0, 0.0); -} - - -static void mdlStart(SimStruct *S) -{ - lat_solver_capsule *capsule = lat_acados_create_capsule(); - lat_acados_create(capsule); - - ssSetUserData(S, (void*)capsule); -} - - -static void mdlOutputs(SimStruct *S, int_T tid) -{ - lat_solver_capsule *capsule = ssGetUserData(S); - ocp_nlp_config *nlp_config = lat_acados_get_nlp_config(capsule); - ocp_nlp_dims *nlp_dims = lat_acados_get_nlp_dims(capsule); - ocp_nlp_in *nlp_in = lat_acados_get_nlp_in(capsule); - ocp_nlp_out *nlp_out = lat_acados_get_nlp_out(capsule); - - InputRealPtrsType in_sign; - - // local buffer - real_t buffer[5]; - - /* go through inputs */ - // lbx_0 - in_sign = ssGetInputPortRealSignalPtrs(S, 0); - for (int i = 0; i < 4; i++) - buffer[i] = (double)(*in_sign[i]); - - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "lbx", buffer); - // ubx_0 - in_sign = ssGetInputPortRealSignalPtrs(S, 1); - for (int i = 0; i < 4; i++) - buffer[i] = (double)(*in_sign[i]); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "ubx", buffer); - // parameters - stage-variant !!! - in_sign = ssGetInputPortRealSignalPtrs(S, 2); - - // update value of parameters - for (int ii = 0; ii <= 32; ii++) - { - for (int jj = 0; jj < 2; jj++) - buffer[jj] = (double)(*in_sign[ii*2+jj]); - lat_acados_update_params(capsule, ii, buffer, 2); - } - - - // y_ref_0 - in_sign = ssGetInputPortRealSignalPtrs(S, 3); - - for (int i = 0; i < 5; i++) - buffer[i] = (double)(*in_sign[i]); - - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "yref", (void *) buffer); - - - // y_ref - for stages 1 to N-1 - in_sign = ssGetInputPortRealSignalPtrs(S, 4); - - for (int ii = 1; ii < 32; ii++) - { - for (int jj = 0; jj < 5; jj++) - buffer[jj] = (double)(*in_sign[(ii-1)*5+jj]); - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, ii, "yref", (void *) buffer); - } - - - // y_ref_e - in_sign = ssGetInputPortRealSignalPtrs(S, 5); - - for (int i = 0; i < 3; i++) - buffer[i] = (double)(*in_sign[i]); - - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 32, "yref", (void *) buffer); - // lbx - in_sign = ssGetInputPortRealSignalPtrs(S, 6); - for (int ii = 1; ii < 32; ii++) - { - for (int jj = 0; jj < 2; jj++) - buffer[jj] = (double)(*in_sign[(ii-1)*2+jj]); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, ii, "lbx", (void *) buffer); - } - // ubx - in_sign = ssGetInputPortRealSignalPtrs(S, 7); - for (int ii = 1; ii < 32; ii++) - { - for (int jj = 0; jj < 2; jj++) - buffer[jj] = (double)(*in_sign[(ii-1)*2+jj]); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, ii, "ubx", (void *) buffer); - } - - /* call solver */ - int rti_phase = 0; - ocp_nlp_solver_opts_set(nlp_config, capsule->nlp_opts, "rti_phase", &rti_phase); - int acados_status = lat_acados_solve(capsule); - - - /* set outputs */ - // assign pointers to output signals - real_t *out_u0, *out_utraj, *out_xtraj, *out_status, *out_sqp_iter, *out_KKT_res, *out_x1, *out_cpu_time, *out_cpu_time_sim, *out_cpu_time_qp, *out_cpu_time_lin; - int tmp_int; - out_u0 = ssGetOutputPortRealSignal(S, 0); - ocp_nlp_out_get(nlp_config, nlp_dims, nlp_out, 0, "u", (void *) out_u0); - - - out_status = ssGetOutputPortRealSignal(S, 1); - *out_status = (real_t) acados_status; - out_KKT_res = ssGetOutputPortRealSignal(S, 2); - *out_KKT_res = (real_t) nlp_out->inf_norm_res; - out_x1 = ssGetOutputPortRealSignal(S, 3); - ocp_nlp_out_get(nlp_config, nlp_dims, nlp_out, 1, "x", (void *) out_x1); - out_cpu_time = ssGetOutputPortRealSignal(S, 4); - // get solution time - ocp_nlp_get(nlp_config, capsule->nlp_solver, "time_tot", (void *) out_cpu_time); - out_sqp_iter = ssGetOutputPortRealSignal(S, 5); - // get sqp iter - ocp_nlp_get(nlp_config, capsule->nlp_solver, "sqp_iter", (void *) &tmp_int); - *out_sqp_iter = (real_t) tmp_int; - -} - -static void mdlTerminate(SimStruct *S) -{ - lat_solver_capsule *capsule = ssGetUserData(S); - - lat_acados_free(capsule); - lat_acados_free_capsule(capsule); -} - - -#ifdef MATLAB_MEX_FILE -#include "simulink.c" -#else -#include "cg_sfun.h" -#endif diff --git a/third_party/acados/acados_template/c_templates_tera/phi_constraint.in.h b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_constraints/lat_constraints.h similarity index 62% rename from third_party/acados/acados_template/c_templates_tera/phi_constraint.in.h rename to selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_constraints/lat_constraints.h index 283ed7f88..4e0f6e854 100644 --- a/third_party/acados/acados_template/c_templates_tera/phi_constraint.in.h +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_constraints/lat_constraints.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * @@ -31,25 +28,23 @@ * POSSIBILITY OF SUCH DAMAGE.; */ -#ifndef {{ model.name }}_PHI_CONSTRAINT -#define {{ model.name }}_PHI_CONSTRAINT +#ifndef lat_CONSTRAINTS +#define lat_CONSTRAINTS #ifdef __cplusplus extern "C" { #endif -{% if dims.nphi > 0 %} -// implicit ODE -int {{ model.name }}_phi_constraint(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_phi_constraint_work(int *, int *, int *, int *); -const int *{{ model.name }}_phi_constraint_sparsity_in(int); -const int *{{ model.name }}_phi_constraint_sparsity_out(int); -int {{ model.name }}_phi_constraint_n_in(void); -int {{ model.name }}_phi_constraint_n_out(void); -{% endif %} + + + + + + + #ifdef __cplusplus } /* extern "C" */ #endif -#endif // {{ model.name }}_PHI_CONSTRAINT +#endif // lat_CONSTRAINTS diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_e_fun.h b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost.h similarity index 53% rename from selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_e_fun.h rename to selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost.h index 9e444b984..b033ebda1 100644 --- a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_e_fun.h +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * @@ -32,14 +29,66 @@ */ -#ifndef lat_Y_E_COST -#define lat_Y_E_COST +#ifndef lat_COST +#define lat_COST #ifdef __cplusplus extern "C" { #endif +// Cost at initial shooting node + +int lat_cost_y_0_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); +int lat_cost_y_0_fun_work(int *, int *, int *, int *); +const int *lat_cost_y_0_fun_sparsity_in(int); +const int *lat_cost_y_0_fun_sparsity_out(int); +int lat_cost_y_0_fun_n_in(void); +int lat_cost_y_0_fun_n_out(void); + +int lat_cost_y_0_fun_jac_ut_xt(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); +int lat_cost_y_0_fun_jac_ut_xt_work(int *, int *, int *, int *); +const int *lat_cost_y_0_fun_jac_ut_xt_sparsity_in(int); +const int *lat_cost_y_0_fun_jac_ut_xt_sparsity_out(int); +int lat_cost_y_0_fun_jac_ut_xt_n_in(void); +int lat_cost_y_0_fun_jac_ut_xt_n_out(void); + +int lat_cost_y_0_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); +int lat_cost_y_0_hess_work(int *, int *, int *, int *); +const int *lat_cost_y_0_hess_sparsity_in(int); +const int *lat_cost_y_0_hess_sparsity_out(int); +int lat_cost_y_0_hess_n_in(void); +int lat_cost_y_0_hess_n_out(void); + + + +// Cost at path shooting node + +int lat_cost_y_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); +int lat_cost_y_fun_work(int *, int *, int *, int *); +const int *lat_cost_y_fun_sparsity_in(int); +const int *lat_cost_y_fun_sparsity_out(int); +int lat_cost_y_fun_n_in(void); +int lat_cost_y_fun_n_out(void); + +int lat_cost_y_fun_jac_ut_xt(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); +int lat_cost_y_fun_jac_ut_xt_work(int *, int *, int *, int *); +const int *lat_cost_y_fun_jac_ut_xt_sparsity_in(int); +const int *lat_cost_y_fun_jac_ut_xt_sparsity_out(int); +int lat_cost_y_fun_jac_ut_xt_n_in(void); +int lat_cost_y_fun_jac_ut_xt_n_out(void); + +int lat_cost_y_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); +int lat_cost_y_hess_work(int *, int *, int *, int *); +const int *lat_cost_y_hess_sparsity_in(int); +const int *lat_cost_y_hess_sparsity_out(int); +int lat_cost_y_hess_n_in(void); +int lat_cost_y_hess_n_out(void); + + + +// Cost at terminal shooting node + int lat_cost_y_e_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); int lat_cost_y_e_fun_work(int *, int *, int *, int *); const int *lat_cost_y_e_fun_sparsity_in(int); @@ -62,8 +111,9 @@ int lat_cost_y_e_hess_n_in(void); int lat_cost_y_e_hess_n_out(void); + #ifdef __cplusplus } /* extern "C" */ #endif -#endif // lat_Y_E_COST +#endif // lat_COST diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_0_fun.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_0_fun.c index 153bf3c0d..9bc4e4cd4 100644 --- a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_0_fun.c +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_0_fun.c @@ -34,6 +34,7 @@ extern "C" { #define casadi_s1 CASADI_PREFIX(s1) #define casadi_s2 CASADI_PREFIX(s2) #define casadi_s3 CASADI_PREFIX(s3) +#define casadi_s4 CASADI_PREFIX(s4) /* Symbol visibility in DLLs */ #ifndef CASADI_SYMBOL_EXPORT @@ -52,15 +53,16 @@ extern "C" { static const casadi_int casadi_s0[8] = {4, 1, 0, 4, 0, 1, 2, 3}; static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; -static const casadi_int casadi_s2[6] = {2, 1, 0, 2, 0, 1}; -static const casadi_int casadi_s3[9] = {5, 1, 0, 5, 0, 1, 2, 3, 4}; +static const casadi_int casadi_s2[3] = {0, 0, 0}; +static const casadi_int casadi_s3[6] = {2, 1, 0, 2, 0, 1}; +static const casadi_int casadi_s4[9] = {5, 1, 0, 5, 0, 1, 2, 3, 4}; -/* lat_cost_y_0_fun:(i0[4],i1,i2[2])->(o0[5]) */ +/* lat_cost_y_0_fun:(i0[4],i1,i2[],i3[2])->(o0[5]) */ static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { casadi_real a0, a1, a2; a0=arg[0]? arg[0][1] : 0; if (res[0]!=0) res[0][0]=a0; - a0=arg[2]? arg[2][0] : 0; + a0=arg[3]? arg[3][0] : 0; a1=10.; a1=(a0+a1); a2=arg[0]? arg[0][2] : 0; @@ -107,7 +109,7 @@ CASADI_SYMBOL_EXPORT void lat_cost_y_0_fun_incref(void) { CASADI_SYMBOL_EXPORT void lat_cost_y_0_fun_decref(void) { } -CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_0_fun_n_in(void) { return 3;} +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_0_fun_n_in(void) { return 4;} CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_0_fun_n_out(void) { return 1;} @@ -122,6 +124,7 @@ CASADI_SYMBOL_EXPORT const char* lat_cost_y_0_fun_name_in(casadi_int i) { case 0: return "i0"; case 1: return "i1"; case 2: return "i2"; + case 3: return "i3"; default: return 0; } } @@ -138,19 +141,20 @@ CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_0_fun_sparsity_in(casadi_int i case 0: return casadi_s0; case 1: return casadi_s1; case 2: return casadi_s2; + case 3: return casadi_s3; default: return 0; } } CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_0_fun_sparsity_out(casadi_int i) { switch (i) { - case 0: return casadi_s3; + case 0: return casadi_s4; default: return 0; } } CASADI_SYMBOL_EXPORT int lat_cost_y_0_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { - if (sz_arg) *sz_arg = 3; + if (sz_arg) *sz_arg = 4; if (sz_res) *sz_res = 1; if (sz_iw) *sz_iw = 0; if (sz_w) *sz_w = 0; diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_0_fun.h b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_0_fun.h deleted file mode 100644 index 842fc03df..000000000 --- a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_0_fun.h +++ /dev/null @@ -1,69 +0,0 @@ -/* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl - * - * This file is part of acados. - * - * 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 HOLDER 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.; - */ - - -#ifndef lat_Y_0_COST -#define lat_Y_0_COST - -#ifdef __cplusplus -extern "C" { -#endif - - -int lat_cost_y_0_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int lat_cost_y_0_fun_work(int *, int *, int *, int *); -const int *lat_cost_y_0_fun_sparsity_in(int); -const int *lat_cost_y_0_fun_sparsity_out(int); -int lat_cost_y_0_fun_n_in(void); -int lat_cost_y_0_fun_n_out(void); - -int lat_cost_y_0_fun_jac_ut_xt(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int lat_cost_y_0_fun_jac_ut_xt_work(int *, int *, int *, int *); -const int *lat_cost_y_0_fun_jac_ut_xt_sparsity_in(int); -const int *lat_cost_y_0_fun_jac_ut_xt_sparsity_out(int); -int lat_cost_y_0_fun_jac_ut_xt_n_in(void); -int lat_cost_y_0_fun_jac_ut_xt_n_out(void); - -int lat_cost_y_0_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int lat_cost_y_0_hess_work(int *, int *, int *, int *); -const int *lat_cost_y_0_hess_sparsity_in(int); -const int *lat_cost_y_0_hess_sparsity_out(int); -int lat_cost_y_0_hess_n_in(void); -int lat_cost_y_0_hess_n_out(void); - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // lat_Y_0_COST diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_0_fun_jac_ut_xt.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_0_fun_jac_ut_xt.c index fd26beb0a..241353991 100644 --- a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_0_fun_jac_ut_xt.c +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_0_fun_jac_ut_xt.c @@ -35,6 +35,8 @@ extern "C" { #define casadi_s2 CASADI_PREFIX(s2) #define casadi_s3 CASADI_PREFIX(s3) #define casadi_s4 CASADI_PREFIX(s4) +#define casadi_s5 CASADI_PREFIX(s5) +#define casadi_s6 CASADI_PREFIX(s6) /* Symbol visibility in DLLs */ #ifndef CASADI_SYMBOL_EXPORT @@ -53,16 +55,18 @@ extern "C" { static const casadi_int casadi_s0[8] = {4, 1, 0, 4, 0, 1, 2, 3}; static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; -static const casadi_int casadi_s2[6] = {2, 1, 0, 2, 0, 1}; -static const casadi_int casadi_s3[9] = {5, 1, 0, 5, 0, 1, 2, 3, 4}; -static const casadi_int casadi_s4[13] = {5, 5, 0, 1, 2, 3, 4, 5, 2, 3, 4, 0, 0}; +static const casadi_int casadi_s2[3] = {0, 0, 0}; +static const casadi_int casadi_s3[6] = {2, 1, 0, 2, 0, 1}; +static const casadi_int casadi_s4[9] = {5, 1, 0, 5, 0, 1, 2, 3, 4}; +static const casadi_int casadi_s5[13] = {5, 5, 0, 1, 2, 3, 4, 5, 2, 3, 4, 0, 0}; +static const casadi_int casadi_s6[3] = {5, 0, 0}; -/* lat_cost_y_0_fun_jac_ut_xt:(i0[4],i1,i2[2])->(o0[5],o1[5x5,5nz]) */ +/* lat_cost_y_0_fun_jac_ut_xt:(i0[4],i1,i2[],i3[2])->(o0[5],o1[5x5,5nz],o2[5x0]) */ static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { casadi_real a0, a1, a2, a3; a0=arg[0]? arg[0][1] : 0; if (res[0]!=0) res[0][0]=a0; - a0=arg[2]? arg[2][0] : 0; + a0=arg[3]? arg[3][0] : 0; a1=10.; a1=(a0+a1); a2=arg[0]? arg[0][2] : 0; @@ -116,9 +120,9 @@ CASADI_SYMBOL_EXPORT void lat_cost_y_0_fun_jac_ut_xt_incref(void) { CASADI_SYMBOL_EXPORT void lat_cost_y_0_fun_jac_ut_xt_decref(void) { } -CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_0_fun_jac_ut_xt_n_in(void) { return 3;} +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_0_fun_jac_ut_xt_n_in(void) { return 4;} -CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_0_fun_jac_ut_xt_n_out(void) { return 2;} +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_0_fun_jac_ut_xt_n_out(void) { return 3;} CASADI_SYMBOL_EXPORT casadi_real lat_cost_y_0_fun_jac_ut_xt_default_in(casadi_int i) { switch (i) { @@ -131,6 +135,7 @@ CASADI_SYMBOL_EXPORT const char* lat_cost_y_0_fun_jac_ut_xt_name_in(casadi_int i case 0: return "i0"; case 1: return "i1"; case 2: return "i2"; + case 3: return "i3"; default: return 0; } } @@ -139,6 +144,7 @@ CASADI_SYMBOL_EXPORT const char* lat_cost_y_0_fun_jac_ut_xt_name_out(casadi_int switch (i) { case 0: return "o0"; case 1: return "o1"; + case 2: return "o2"; default: return 0; } } @@ -148,21 +154,23 @@ CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_0_fun_jac_ut_xt_sparsity_in(ca case 0: return casadi_s0; case 1: return casadi_s1; case 2: return casadi_s2; + case 3: return casadi_s3; default: return 0; } } CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_0_fun_jac_ut_xt_sparsity_out(casadi_int i) { switch (i) { - case 0: return casadi_s3; - case 1: return casadi_s4; + case 0: return casadi_s4; + case 1: return casadi_s5; + case 2: return casadi_s6; default: return 0; } } CASADI_SYMBOL_EXPORT int lat_cost_y_0_fun_jac_ut_xt_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { - if (sz_arg) *sz_arg = 3; - if (sz_res) *sz_res = 2; + if (sz_arg) *sz_arg = 4; + if (sz_res) *sz_res = 3; if (sz_iw) *sz_iw = 0; if (sz_w) *sz_w = 0; return 0; diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_0_hess.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_0_hess.c index edc3b0561..1e22eaf74 100644 --- a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_0_hess.c +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_0_hess.c @@ -35,6 +35,7 @@ extern "C" { #define casadi_s2 CASADI_PREFIX(s2) #define casadi_s3 CASADI_PREFIX(s3) #define casadi_s4 CASADI_PREFIX(s4) +#define casadi_s5 CASADI_PREFIX(s5) /* Symbol visibility in DLLs */ #ifndef CASADI_SYMBOL_EXPORT @@ -53,11 +54,12 @@ extern "C" { static const casadi_int casadi_s0[8] = {4, 1, 0, 4, 0, 1, 2, 3}; static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; -static const casadi_int casadi_s2[9] = {5, 1, 0, 5, 0, 1, 2, 3, 4}; -static const casadi_int casadi_s3[6] = {2, 1, 0, 2, 0, 1}; -static const casadi_int casadi_s4[8] = {5, 5, 0, 0, 0, 0, 0, 0}; +static const casadi_int casadi_s2[3] = {0, 0, 0}; +static const casadi_int casadi_s3[9] = {5, 1, 0, 5, 0, 1, 2, 3, 4}; +static const casadi_int casadi_s4[6] = {2, 1, 0, 2, 0, 1}; +static const casadi_int casadi_s5[8] = {5, 5, 0, 0, 0, 0, 0, 0}; -/* lat_cost_y_0_hess:(i0[4],i1,i2[5],i3[2])->(o0[5x5,0nz]) */ +/* lat_cost_y_0_hess:(i0[4],i1,i2[],i3[5],i4[2])->(o0[5x5,0nz]) */ static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { return 0; } @@ -90,7 +92,7 @@ CASADI_SYMBOL_EXPORT void lat_cost_y_0_hess_incref(void) { CASADI_SYMBOL_EXPORT void lat_cost_y_0_hess_decref(void) { } -CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_0_hess_n_in(void) { return 4;} +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_0_hess_n_in(void) { return 5;} CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_0_hess_n_out(void) { return 1;} @@ -106,6 +108,7 @@ CASADI_SYMBOL_EXPORT const char* lat_cost_y_0_hess_name_in(casadi_int i) { case 1: return "i1"; case 2: return "i2"; case 3: return "i3"; + case 4: return "i4"; default: return 0; } } @@ -123,19 +126,20 @@ CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_0_hess_sparsity_in(casadi_int case 1: return casadi_s1; case 2: return casadi_s2; case 3: return casadi_s3; + case 4: return casadi_s4; default: return 0; } } CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_0_hess_sparsity_out(casadi_int i) { switch (i) { - case 0: return casadi_s4; + case 0: return casadi_s5; default: return 0; } } CASADI_SYMBOL_EXPORT int lat_cost_y_0_hess_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { - if (sz_arg) *sz_arg = 4; + if (sz_arg) *sz_arg = 5; if (sz_res) *sz_res = 1; if (sz_iw) *sz_iw = 0; if (sz_w) *sz_w = 0; diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_e_fun.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_e_fun.c index 4e3869c68..b04350cdc 100644 --- a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_e_fun.c +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_e_fun.c @@ -55,12 +55,12 @@ static const casadi_int casadi_s1[3] = {0, 0, 0}; static const casadi_int casadi_s2[6] = {2, 1, 0, 2, 0, 1}; static const casadi_int casadi_s3[7] = {3, 1, 0, 3, 0, 1, 2}; -/* lat_cost_y_e_fun:(i0[4],i1[],i2[2])->(o0[3]) */ +/* lat_cost_y_e_fun:(i0[4],i1[],i2[],i3[2])->(o0[3]) */ static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { casadi_real a0, a1; a0=arg[0]? arg[0][1] : 0; if (res[0]!=0) res[0][0]=a0; - a0=arg[2]? arg[2][0] : 0; + a0=arg[3]? arg[3][0] : 0; a1=10.; a0=(a0+a1); a1=arg[0]? arg[0][2] : 0; @@ -100,7 +100,7 @@ CASADI_SYMBOL_EXPORT void lat_cost_y_e_fun_incref(void) { CASADI_SYMBOL_EXPORT void lat_cost_y_e_fun_decref(void) { } -CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_e_fun_n_in(void) { return 3;} +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_e_fun_n_in(void) { return 4;} CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_e_fun_n_out(void) { return 1;} @@ -115,6 +115,7 @@ CASADI_SYMBOL_EXPORT const char* lat_cost_y_e_fun_name_in(casadi_int i) { case 0: return "i0"; case 1: return "i1"; case 2: return "i2"; + case 3: return "i3"; default: return 0; } } @@ -130,7 +131,8 @@ CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_e_fun_sparsity_in(casadi_int i switch (i) { case 0: return casadi_s0; case 1: return casadi_s1; - case 2: return casadi_s2; + case 2: return casadi_s1; + case 3: return casadi_s2; default: return 0; } } @@ -143,7 +145,7 @@ CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_e_fun_sparsity_out(casadi_int } CASADI_SYMBOL_EXPORT int lat_cost_y_e_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { - if (sz_arg) *sz_arg = 3; + if (sz_arg) *sz_arg = 4; if (sz_res) *sz_res = 1; if (sz_iw) *sz_iw = 0; if (sz_w) *sz_w = 0; diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_e_fun_jac_ut_xt.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_e_fun_jac_ut_xt.c index a5db15012..0f777d17a 100644 --- a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_e_fun_jac_ut_xt.c +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_e_fun_jac_ut_xt.c @@ -35,6 +35,7 @@ extern "C" { #define casadi_s2 CASADI_PREFIX(s2) #define casadi_s3 CASADI_PREFIX(s3) #define casadi_s4 CASADI_PREFIX(s4) +#define casadi_s5 CASADI_PREFIX(s5) /* Symbol visibility in DLLs */ #ifndef CASADI_SYMBOL_EXPORT @@ -56,13 +57,14 @@ static const casadi_int casadi_s1[3] = {0, 0, 0}; static const casadi_int casadi_s2[6] = {2, 1, 0, 2, 0, 1}; static const casadi_int casadi_s3[7] = {3, 1, 0, 3, 0, 1, 2}; static const casadi_int casadi_s4[9] = {4, 3, 0, 1, 2, 3, 1, 2, 3}; +static const casadi_int casadi_s5[3] = {3, 0, 0}; -/* lat_cost_y_e_fun_jac_ut_xt:(i0[4],i1[],i2[2])->(o0[3],o1[4x3,3nz]) */ +/* lat_cost_y_e_fun_jac_ut_xt:(i0[4],i1[],i2[],i3[2])->(o0[3],o1[4x3,3nz],o2[3x0]) */ static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { casadi_real a0, a1; a0=arg[0]? arg[0][1] : 0; if (res[0]!=0) res[0][0]=a0; - a0=arg[2]? arg[2][0] : 0; + a0=arg[3]? arg[3][0] : 0; a1=10.; a0=(a0+a1); a1=arg[0]? arg[0][2] : 0; @@ -106,9 +108,9 @@ CASADI_SYMBOL_EXPORT void lat_cost_y_e_fun_jac_ut_xt_incref(void) { CASADI_SYMBOL_EXPORT void lat_cost_y_e_fun_jac_ut_xt_decref(void) { } -CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_e_fun_jac_ut_xt_n_in(void) { return 3;} +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_e_fun_jac_ut_xt_n_in(void) { return 4;} -CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_e_fun_jac_ut_xt_n_out(void) { return 2;} +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_e_fun_jac_ut_xt_n_out(void) { return 3;} CASADI_SYMBOL_EXPORT casadi_real lat_cost_y_e_fun_jac_ut_xt_default_in(casadi_int i) { switch (i) { @@ -121,6 +123,7 @@ CASADI_SYMBOL_EXPORT const char* lat_cost_y_e_fun_jac_ut_xt_name_in(casadi_int i case 0: return "i0"; case 1: return "i1"; case 2: return "i2"; + case 3: return "i3"; default: return 0; } } @@ -129,6 +132,7 @@ CASADI_SYMBOL_EXPORT const char* lat_cost_y_e_fun_jac_ut_xt_name_out(casadi_int switch (i) { case 0: return "o0"; case 1: return "o1"; + case 2: return "o2"; default: return 0; } } @@ -137,7 +141,8 @@ CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_e_fun_jac_ut_xt_sparsity_in(ca switch (i) { case 0: return casadi_s0; case 1: return casadi_s1; - case 2: return casadi_s2; + case 2: return casadi_s1; + case 3: return casadi_s2; default: return 0; } } @@ -146,13 +151,14 @@ CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_e_fun_jac_ut_xt_sparsity_out(c switch (i) { case 0: return casadi_s3; case 1: return casadi_s4; + case 2: return casadi_s5; default: return 0; } } CASADI_SYMBOL_EXPORT int lat_cost_y_e_fun_jac_ut_xt_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { - if (sz_arg) *sz_arg = 3; - if (sz_res) *sz_res = 2; + if (sz_arg) *sz_arg = 4; + if (sz_res) *sz_res = 3; if (sz_iw) *sz_iw = 0; if (sz_w) *sz_w = 0; return 0; diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_e_hess.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_e_hess.c index 54bf12910..1f94488fa 100644 --- a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_e_hess.c +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_e_hess.c @@ -57,7 +57,7 @@ static const casadi_int casadi_s2[7] = {3, 1, 0, 3, 0, 1, 2}; static const casadi_int casadi_s3[6] = {2, 1, 0, 2, 0, 1}; static const casadi_int casadi_s4[7] = {4, 4, 0, 0, 0, 0, 0}; -/* lat_cost_y_e_hess:(i0[4],i1[],i2[3],i3[2])->(o0[4x4,0nz]) */ +/* lat_cost_y_e_hess:(i0[4],i1[],i2[],i3[3],i4[2])->(o0[4x4,0nz]) */ static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { return 0; } @@ -90,7 +90,7 @@ CASADI_SYMBOL_EXPORT void lat_cost_y_e_hess_incref(void) { CASADI_SYMBOL_EXPORT void lat_cost_y_e_hess_decref(void) { } -CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_e_hess_n_in(void) { return 4;} +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_e_hess_n_in(void) { return 5;} CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_e_hess_n_out(void) { return 1;} @@ -106,6 +106,7 @@ CASADI_SYMBOL_EXPORT const char* lat_cost_y_e_hess_name_in(casadi_int i) { case 1: return "i1"; case 2: return "i2"; case 3: return "i3"; + case 4: return "i4"; default: return 0; } } @@ -121,8 +122,9 @@ CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_e_hess_sparsity_in(casadi_int switch (i) { case 0: return casadi_s0; case 1: return casadi_s1; - case 2: return casadi_s2; - case 3: return casadi_s3; + case 2: return casadi_s1; + case 3: return casadi_s2; + case 4: return casadi_s3; default: return 0; } } @@ -135,7 +137,7 @@ CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_e_hess_sparsity_out(casadi_int } CASADI_SYMBOL_EXPORT int lat_cost_y_e_hess_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { - if (sz_arg) *sz_arg = 4; + if (sz_arg) *sz_arg = 5; if (sz_res) *sz_res = 1; if (sz_iw) *sz_iw = 0; if (sz_w) *sz_w = 0; diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_fun.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_fun.c index d6f3db3c2..34f0c8394 100644 --- a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_fun.c +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_fun.c @@ -34,6 +34,7 @@ extern "C" { #define casadi_s1 CASADI_PREFIX(s1) #define casadi_s2 CASADI_PREFIX(s2) #define casadi_s3 CASADI_PREFIX(s3) +#define casadi_s4 CASADI_PREFIX(s4) /* Symbol visibility in DLLs */ #ifndef CASADI_SYMBOL_EXPORT @@ -52,15 +53,16 @@ extern "C" { static const casadi_int casadi_s0[8] = {4, 1, 0, 4, 0, 1, 2, 3}; static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; -static const casadi_int casadi_s2[6] = {2, 1, 0, 2, 0, 1}; -static const casadi_int casadi_s3[9] = {5, 1, 0, 5, 0, 1, 2, 3, 4}; +static const casadi_int casadi_s2[3] = {0, 0, 0}; +static const casadi_int casadi_s3[6] = {2, 1, 0, 2, 0, 1}; +static const casadi_int casadi_s4[9] = {5, 1, 0, 5, 0, 1, 2, 3, 4}; -/* lat_cost_y_fun:(i0[4],i1,i2[2])->(o0[5]) */ +/* lat_cost_y_fun:(i0[4],i1,i2[],i3[2])->(o0[5]) */ static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { casadi_real a0, a1, a2; a0=arg[0]? arg[0][1] : 0; if (res[0]!=0) res[0][0]=a0; - a0=arg[2]? arg[2][0] : 0; + a0=arg[3]? arg[3][0] : 0; a1=10.; a1=(a0+a1); a2=arg[0]? arg[0][2] : 0; @@ -107,7 +109,7 @@ CASADI_SYMBOL_EXPORT void lat_cost_y_fun_incref(void) { CASADI_SYMBOL_EXPORT void lat_cost_y_fun_decref(void) { } -CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_fun_n_in(void) { return 3;} +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_fun_n_in(void) { return 4;} CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_fun_n_out(void) { return 1;} @@ -122,6 +124,7 @@ CASADI_SYMBOL_EXPORT const char* lat_cost_y_fun_name_in(casadi_int i) { case 0: return "i0"; case 1: return "i1"; case 2: return "i2"; + case 3: return "i3"; default: return 0; } } @@ -138,19 +141,20 @@ CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_fun_sparsity_in(casadi_int i) case 0: return casadi_s0; case 1: return casadi_s1; case 2: return casadi_s2; + case 3: return casadi_s3; default: return 0; } } CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_fun_sparsity_out(casadi_int i) { switch (i) { - case 0: return casadi_s3; + case 0: return casadi_s4; default: return 0; } } CASADI_SYMBOL_EXPORT int lat_cost_y_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { - if (sz_arg) *sz_arg = 3; + if (sz_arg) *sz_arg = 4; if (sz_res) *sz_res = 1; if (sz_iw) *sz_iw = 0; if (sz_w) *sz_w = 0; diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_fun_jac_ut_xt.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_fun_jac_ut_xt.c index db1e3598d..28c9899b5 100644 --- a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_fun_jac_ut_xt.c +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_fun_jac_ut_xt.c @@ -35,6 +35,8 @@ extern "C" { #define casadi_s2 CASADI_PREFIX(s2) #define casadi_s3 CASADI_PREFIX(s3) #define casadi_s4 CASADI_PREFIX(s4) +#define casadi_s5 CASADI_PREFIX(s5) +#define casadi_s6 CASADI_PREFIX(s6) /* Symbol visibility in DLLs */ #ifndef CASADI_SYMBOL_EXPORT @@ -53,16 +55,18 @@ extern "C" { static const casadi_int casadi_s0[8] = {4, 1, 0, 4, 0, 1, 2, 3}; static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; -static const casadi_int casadi_s2[6] = {2, 1, 0, 2, 0, 1}; -static const casadi_int casadi_s3[9] = {5, 1, 0, 5, 0, 1, 2, 3, 4}; -static const casadi_int casadi_s4[13] = {5, 5, 0, 1, 2, 3, 4, 5, 2, 3, 4, 0, 0}; +static const casadi_int casadi_s2[3] = {0, 0, 0}; +static const casadi_int casadi_s3[6] = {2, 1, 0, 2, 0, 1}; +static const casadi_int casadi_s4[9] = {5, 1, 0, 5, 0, 1, 2, 3, 4}; +static const casadi_int casadi_s5[13] = {5, 5, 0, 1, 2, 3, 4, 5, 2, 3, 4, 0, 0}; +static const casadi_int casadi_s6[3] = {5, 0, 0}; -/* lat_cost_y_fun_jac_ut_xt:(i0[4],i1,i2[2])->(o0[5],o1[5x5,5nz]) */ +/* lat_cost_y_fun_jac_ut_xt:(i0[4],i1,i2[],i3[2])->(o0[5],o1[5x5,5nz],o2[5x0]) */ static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { casadi_real a0, a1, a2, a3; a0=arg[0]? arg[0][1] : 0; if (res[0]!=0) res[0][0]=a0; - a0=arg[2]? arg[2][0] : 0; + a0=arg[3]? arg[3][0] : 0; a1=10.; a1=(a0+a1); a2=arg[0]? arg[0][2] : 0; @@ -116,9 +120,9 @@ CASADI_SYMBOL_EXPORT void lat_cost_y_fun_jac_ut_xt_incref(void) { CASADI_SYMBOL_EXPORT void lat_cost_y_fun_jac_ut_xt_decref(void) { } -CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_fun_jac_ut_xt_n_in(void) { return 3;} +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_fun_jac_ut_xt_n_in(void) { return 4;} -CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_fun_jac_ut_xt_n_out(void) { return 2;} +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_fun_jac_ut_xt_n_out(void) { return 3;} CASADI_SYMBOL_EXPORT casadi_real lat_cost_y_fun_jac_ut_xt_default_in(casadi_int i) { switch (i) { @@ -131,6 +135,7 @@ CASADI_SYMBOL_EXPORT const char* lat_cost_y_fun_jac_ut_xt_name_in(casadi_int i) case 0: return "i0"; case 1: return "i1"; case 2: return "i2"; + case 3: return "i3"; default: return 0; } } @@ -139,6 +144,7 @@ CASADI_SYMBOL_EXPORT const char* lat_cost_y_fun_jac_ut_xt_name_out(casadi_int i) switch (i) { case 0: return "o0"; case 1: return "o1"; + case 2: return "o2"; default: return 0; } } @@ -148,21 +154,23 @@ CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_fun_jac_ut_xt_sparsity_in(casa case 0: return casadi_s0; case 1: return casadi_s1; case 2: return casadi_s2; + case 3: return casadi_s3; default: return 0; } } CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_fun_jac_ut_xt_sparsity_out(casadi_int i) { switch (i) { - case 0: return casadi_s3; - case 1: return casadi_s4; + case 0: return casadi_s4; + case 1: return casadi_s5; + case 2: return casadi_s6; default: return 0; } } CASADI_SYMBOL_EXPORT int lat_cost_y_fun_jac_ut_xt_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { - if (sz_arg) *sz_arg = 3; - if (sz_res) *sz_res = 2; + if (sz_arg) *sz_arg = 4; + if (sz_res) *sz_res = 3; if (sz_iw) *sz_iw = 0; if (sz_w) *sz_w = 0; return 0; diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_hess.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_hess.c index a437b9748..85b17e70d 100644 --- a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_hess.c +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_hess.c @@ -35,6 +35,7 @@ extern "C" { #define casadi_s2 CASADI_PREFIX(s2) #define casadi_s3 CASADI_PREFIX(s3) #define casadi_s4 CASADI_PREFIX(s4) +#define casadi_s5 CASADI_PREFIX(s5) /* Symbol visibility in DLLs */ #ifndef CASADI_SYMBOL_EXPORT @@ -53,11 +54,12 @@ extern "C" { static const casadi_int casadi_s0[8] = {4, 1, 0, 4, 0, 1, 2, 3}; static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; -static const casadi_int casadi_s2[9] = {5, 1, 0, 5, 0, 1, 2, 3, 4}; -static const casadi_int casadi_s3[6] = {2, 1, 0, 2, 0, 1}; -static const casadi_int casadi_s4[8] = {5, 5, 0, 0, 0, 0, 0, 0}; +static const casadi_int casadi_s2[3] = {0, 0, 0}; +static const casadi_int casadi_s3[9] = {5, 1, 0, 5, 0, 1, 2, 3, 4}; +static const casadi_int casadi_s4[6] = {2, 1, 0, 2, 0, 1}; +static const casadi_int casadi_s5[8] = {5, 5, 0, 0, 0, 0, 0, 0}; -/* lat_cost_y_hess:(i0[4],i1,i2[5],i3[2])->(o0[5x5,0nz]) */ +/* lat_cost_y_hess:(i0[4],i1,i2[],i3[5],i4[2])->(o0[5x5,0nz]) */ static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { return 0; } @@ -90,7 +92,7 @@ CASADI_SYMBOL_EXPORT void lat_cost_y_hess_incref(void) { CASADI_SYMBOL_EXPORT void lat_cost_y_hess_decref(void) { } -CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_hess_n_in(void) { return 4;} +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_hess_n_in(void) { return 5;} CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_hess_n_out(void) { return 1;} @@ -106,6 +108,7 @@ CASADI_SYMBOL_EXPORT const char* lat_cost_y_hess_name_in(casadi_int i) { case 1: return "i1"; case 2: return "i2"; case 3: return "i3"; + case 4: return "i4"; default: return 0; } } @@ -123,19 +126,20 @@ CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_hess_sparsity_in(casadi_int i) case 1: return casadi_s1; case 2: return casadi_s2; case 3: return casadi_s3; + case 4: return casadi_s4; default: return 0; } } CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_hess_sparsity_out(casadi_int i) { switch (i) { - case 0: return casadi_s4; + case 0: return casadi_s5; default: return 0; } } CASADI_SYMBOL_EXPORT int lat_cost_y_hess_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { - if (sz_arg) *sz_arg = 4; + if (sz_arg) *sz_arg = 5; if (sz_res) *sz_res = 1; if (sz_iw) *sz_iw = 0; if (sz_w) *sz_w = 0; diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_model/lat_model.h b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_model/lat_model.h index 98ed49214..9d28e962d 100644 --- a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_model/lat_model.h +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_model/lat_model.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/libacados_ocp_solver_lat.so b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/libacados_ocp_solver_lat.so index 0668cfac1..5b69179b2 100755 Binary files a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/libacados_ocp_solver_lat.so and b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/libacados_ocp_solver_lat.so differ diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/main_lat.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/main_lat.c index 53809769a..01fbdc6d6 100644 --- a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/main_lat.c +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/main_lat.c @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * @@ -42,6 +39,9 @@ #include "acados_c/external_function_interface.h" #include "acados_solver_lat.h" +// blasfeo +#include "blasfeo/include/blasfeo_d_aux_ext_dep.h" + #define NX LAT_NX #define NZ LAT_NZ #define NU LAT_NU @@ -105,14 +105,14 @@ int main() double lbx0[NBX0]; double ubx0[NBX0]; - lbx0[0] = 0; - ubx0[0] = 0; - lbx0[1] = 0; - ubx0[1] = 0; - lbx0[2] = 0; - ubx0[2] = 0; - lbx0[3] = 0; - ubx0[3] = 0; + lbx0[0] = 0.0; + ubx0[0] = 0.0; + lbx0[1] = 0.0; + ubx0[1] = 0.0; + lbx0[2] = 0.0; + ubx0[2] = 0.0; + lbx0[3] = 0.0; + ubx0[3] = 0.0; ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "idxbx", idxbx0); ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "lbx", lbx0); @@ -130,8 +130,8 @@ int main() u0[0] = 0.0; // set parameters double p[NP]; - p[0] = 0; - p[1] = 0; + p[0] = 0.0; + p[1] = 0.0; for (int ii = 0; ii <= N; ii++) { diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/main_sim_lat.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/main_sim_lat.c index c536654fd..77bf8dddd 100644 --- a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/main_sim_lat.c +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/main_sim_lat.c @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * @@ -72,10 +69,10 @@ int main() x_current[3] = 0.0; - x_current[0] = 0; - x_current[1] = 0; - x_current[2] = 0; - x_current[3] = 0; + x_current[0] = 0.0; + x_current[1] = 0.0; + x_current[2] = 0.0; + x_current[3] = 0.0; @@ -85,8 +82,8 @@ int main() u0[0] = 0.0; // set parameters double p[NP]; - p[0] = 0; - p[1] = 0; + p[0] = 0.0; + p[1] = 0.0; lat_acados_sim_update_params(capsule, p, NP); diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/make_sfun_lat.m b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/make_sfun_lat.m deleted file mode 100644 index 111c7df92..000000000 --- a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/make_sfun_lat.m +++ /dev/null @@ -1,125 +0,0 @@ -% -% Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, -% Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, -% Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, -% Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl -% -% This file is part of acados. -% -% 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 HOLDER 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.; -% - -SOURCES = { ... - 'lat_model/lat_expl_ode_fun.c', ... - 'lat_model/lat_expl_vde_forw.c',... - 'lat_cost/lat_cost_y_0_fun.c',... - 'lat_cost/lat_cost_y_0_fun_jac_ut_xt.c',... - 'lat_cost/lat_cost_y_0_hess.c',... - 'lat_cost/lat_cost_y_fun.c',... - 'lat_cost/lat_cost_y_fun_jac_ut_xt.c',... - 'lat_cost/lat_cost_y_hess.c',... - 'lat_cost/lat_cost_y_e_fun.c',... - 'lat_cost/lat_cost_y_e_fun_jac_ut_xt.c',... - 'lat_cost/lat_cost_y_e_hess.c',... - 'acados_solver_sfunction_lat.c', ... - 'acados_solver_lat.c' - }; - -INC_PATH = '/data/openpilot/third_party/acados/include'; - -INCS = {['-I', fullfile(INC_PATH, 'blasfeo', 'include')], ... - ['-I', fullfile(INC_PATH, 'hpipm', 'include')], ... - ['-I', fullfile(INC_PATH, 'acados')], ... - ['-I', fullfile(INC_PATH)]}; - - - -CFLAGS = 'CFLAGS=$CFLAGS'; -LDFLAGS = 'LDFLAGS=$LDFLAGS'; -COMPFLAGS = 'COMPFLAGS=$COMPFLAGS'; -COMPDEFINES = 'COMPDEFINES=$COMPDEFINES'; - - - -LIB_PATH = ['-L', fullfile('/data/openpilot/third_party/acados/lib')]; - -LIBS = {'-lacados', '-lhpipm', '-lblasfeo'}; - -% acados linking libraries and flags - - -mex('-v', '-O', CFLAGS, LDFLAGS, COMPFLAGS, COMPDEFINES, INCS{:}, ... - LIB_PATH, LIBS{:}, SOURCES{:}, ... - '-output', 'acados_solver_sfunction_lat' ); - -fprintf( [ '\n\nSuccessfully created sfunction:\nacados_solver_sfunction_lat', '.', ... - eval('mexext')] ); - - -%% print note on usage of s-function -fprintf('\n\nNote: Usage of Sfunction is as follows:\n') -input_note = 'Inputs are:\n'; -i_in = 1; -input_note = strcat(input_note, num2str(i_in), ') lbx_0 - lower bound on x for stage 0,',... - ' size [4]\n '); -i_in = i_in + 1; -input_note = strcat(input_note, num2str(i_in), ') ubx_0 - upper bound on x for stage 0,',... - ' size [4]\n '); -i_in = i_in + 1; -input_note = strcat(input_note, num2str(i_in), ') parameters - concatenated for all shooting nodes 0 to N+1,',... - ' size [66]\n '); -i_in = i_in + 1; -input_note = strcat(input_note, num2str(i_in), ') y_ref_0, size [5]\n '); -i_in = i_in + 1; -input_note = strcat(input_note, num2str(i_in), ') y_ref - concatenated for shooting nodes 1 to N-1,',... - ' size [155]\n '); -i_in = i_in + 1; -input_note = strcat(input_note, num2str(i_in), ') y_ref_e, size [3]\n '); -i_in = i_in + 1; -input_note = strcat(input_note, num2str(i_in), ') lbx for shooting nodes 1 to N-1, size [62]\n '); -i_in = i_in + 1; -input_note = strcat(input_note, num2str(i_in), ') ubx for shooting nodes 1 to N-1, size [62]\n '); -i_in = i_in + 1; - -fprintf(input_note) - -disp(' ') - -output_note = 'Outputs are:\n'; -i_out = 0; -i_out = i_out + 1; -output_note = strcat(output_note, num2str(i_out), ') u0, control input at node 0, size [1]\n '); -i_out = i_out + 1; -output_note = strcat(output_note, num2str(i_out), ') acados solver status (0 = SUCCESS)\n '); -i_out = i_out + 1; -output_note = strcat(output_note, num2str(i_out), ') KKT residual\n '); -i_out = i_out + 1; -output_note = strcat(output_note, num2str(i_out), ') x1, state at node 1\n '); -i_out = i_out + 1; -output_note = strcat(output_note, num2str(i_out), ') CPU time\n '); -i_out = i_out + 1; -output_note = strcat(output_note, num2str(i_out), ') SQP iterations\n '); - -fprintf(output_note) diff --git a/selfdrive/controls/lib/lateral_mpc_lib/lat_mpc.py b/selfdrive/controls/lib/lateral_mpc_lib/lat_mpc.py index 2a58a8667..6afcb99da 100755 --- a/selfdrive/controls/lib/lateral_mpc_lib/lat_mpc.py +++ b/selfdrive/controls/lib/lateral_mpc_lib/lat_mpc.py @@ -129,11 +129,15 @@ def gen_lat_ocp(): class LateralMpc(): - def __init__(self, x0=np.zeros(X_DIM)): + def __init__(self, x0=None): + if x0 is None: + x0 = np.zeros(X_DIM) self.solver = AcadosOcpSolverCython(MODEL_NAME, ACADOS_SOLVER_TYPE, N) self.reset(x0) - def reset(self, x0=np.zeros(X_DIM)): + def reset(self, x0=None): + if x0 is None: + x0 = np.zeros(X_DIM) self.x_sol = np.zeros((N+1, X_DIM)) self.u_sol = np.zeros((N, 1)) self.yref = np.zeros((N+1, COST_DIM)) diff --git a/selfdrive/controls/lib/lateral_planner.py b/selfdrive/controls/lib/lateral_planner.py index d2822df8c..4d17e4166 100644 --- a/selfdrive/controls/lib/lateral_planner.py +++ b/selfdrive/controls/lib/lateral_planner.py @@ -10,6 +10,7 @@ import cereal.messaging as messaging from cereal import log from selfdrive.controls.lib.lane_planner import LanePlanner from common.params import Params +from selfdrive.controls.lib.road_edge_detector import RoadEdgeDetector TRAJECTORY_SIZE = 33 CAMERA_OFFSET = 0.04 @@ -30,9 +31,12 @@ class LateralPlanner: def __init__(self, CP, debug=False): self.DH = DesireHelper() + self.RED = RoadEdgeDetector() + # dp - lanefull params = Params() self._dp_lat_lane_priority_mode = params.get_bool("dp_lat_lane_priority_mode") + self.RED.set_enabled(params.get_bool("dp_lateral_road_edge_detection")) self._dp_lat_lane_priority_mode_active = False self._dp_lat_lane_priority_mode_active_prev = False self.LP = LanePlanner() @@ -61,7 +65,9 @@ class LateralPlanner: self.lat_mpc = LateralMpc() self.reset_mpc(np.zeros(4)) - def reset_mpc(self, x0=np.zeros(4)): + def reset_mpc(self, x0=None): + if x0 is None: + x0 = np.zeros(4) self.x0 = x0 self.lat_mpc.reset(x0=self.x0) @@ -94,7 +100,8 @@ class LateralPlanner: else: lane_change_prob = self.l_lane_change_prob + self.r_lane_change_prob - self.DH.update(sm['carState'], sm['carControl'].latActive, lane_change_prob) + edge_detected_left, edge_detected_right = self.RED.get_road_edge_detected(md.roadEdgeStds, md.laneLineProbs, sm['carState'].leftBlinker, sm['carState'].rightBlinker) + self.DH.update(sm['carState'], sm['carControl'].latActive, lane_change_prob, edge_detected_left, edge_detected_right) path_xyz = self._get_laneless_laneline_d_path_xyz() if self._dp_lat_lane_priority_mode else self.path_xyz self._d_path_w_lines_xyz = path_xyz diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/acados_ocp_long.json b/selfdrive/controls/lib/longitudinal_mpc_lib/acados_ocp_long.json index 07ded706d..4d7f82ba2 100644 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/acados_ocp_long.json +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/acados_ocp_long.json @@ -103,137 +103,11 @@ "usphi_e": [] }, "cost": { - "Vu": [ - [ - 0.0 - ], - [ - 0.0 - ], - [ - 0.0 - ], - [ - 0.0 - ], - [ - 0.0 - ], - [ - 0.0 - ] - ], - "Vu_0": [ - [ - 0.0 - ], - [ - 0.0 - ], - [ - 0.0 - ], - [ - 0.0 - ], - [ - 0.0 - ], - [ - 0.0 - ] - ], - "Vx": [ - [ - 0.0, - 0.0, - 0.0 - ], - [ - 0.0, - 0.0, - 0.0 - ], - [ - 0.0, - 0.0, - 0.0 - ], - [ - 0.0, - 0.0, - 0.0 - ], - [ - 0.0, - 0.0, - 0.0 - ], - [ - 0.0, - 0.0, - 0.0 - ] - ], - "Vx_0": [ - [ - 0.0, - 0.0, - 0.0 - ], - [ - 0.0, - 0.0, - 0.0 - ], - [ - 0.0, - 0.0, - 0.0 - ], - [ - 0.0, - 0.0, - 0.0 - ], - [ - 0.0, - 0.0, - 0.0 - ], - [ - 0.0, - 0.0, - 0.0 - ] - ], - "Vx_e": [ - [ - 0.0, - 0.0, - 0.0 - ], - [ - 0.0, - 0.0, - 0.0 - ], - [ - 0.0, - 0.0, - 0.0 - ], - [ - 0.0, - 0.0, - 0.0 - ], - [ - 0.0, - 0.0, - 0.0 - ] - ], + "Vu": [], + "Vu_0": [], + "Vx": [], + "Vx_0": [], + "Vx_e": [], "Vz": [], "Vz_0": [], "W": [ @@ -431,7 +305,10 @@ ], "zu_e": [] }, - "cython_include_dirs": "/usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/core/include", + "cython_include_dirs": [ + "/usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/core/include", + "/usr/local/pyenv/versions/3.11.4/include/python3.11" + ], "dims": { "N": 12, "nbu": 0, @@ -466,17 +343,52 @@ "ny_e": 5, "nz": 0 }, + "json_file": "/data/openpilot/selfdrive/controls/lib/longitudinal_mpc_lib/acados_ocp_long.json", "model": { + "con_h_expr": "jhpnnagiieahaaaadaaaaaaaaaaaaaaaaaegiaaaaaaaaaaaaaaaeaaaaaaaaaaaaaaabaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaeaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaabaaaaaaaaaaaaaaacaaaaaaaaaaaaaaadaaaaaaaaaaaaaaaeaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaafaaaaaaaghpffghgpgegcaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaafaaaaaaabgpffghgpgegpcaaaaaaaaaaaaaafaaaaaaabgpfngjgogegcaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaafaaaaaaabgpfngbgihchcaaaaaaaaaaaaaaaegeaaaaaaaaaaaaaaaegcaaaaaaaaaaaaaaaegcaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaakaaaaaaaihpfpgcgdhehbgdgmgfgegpcaaaaaaaaaaaaaafaaaaaaaihpffghgpgegdaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaacbaaaaaamgfgbgegpfegbgoghgfgchpfggbgdgehpgchegbaaaaaaaaaaaaaaaegbaaaaaaaaaaaaaaaegeaaaaaaaaaaaaaaaeglaaaaaaaaaaaaaaachbaaaaaaaaaaaaaaaegmcaaaaaaaaaaaaaajgfaaaaaaaegdaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaanaaaaaaamgfgbgegpfehpfggpgmgmgpghhchbaaaaaaaaaaaaaaaegmcaaaaaaaaaaaaaajggaaaaaaaegbaaaaaaaaaaaaaaachbaaaaaaaaaaaaaaaegmcaaaaaaaaaaaaaajgkaaaaaaa", + "con_h_expr_e": null, + "con_phi_expr": null, + "con_phi_expr_e": null, + "con_r_expr": null, + "con_r_expr_e": null, + "con_r_in_phi": null, + "con_r_in_phi_e": null, + "cost_conl_custom_outer_hess": null, + "cost_conl_custom_outer_hess_0": null, + "cost_conl_custom_outer_hess_e": null, + "cost_expr_ext_cost": null, + "cost_expr_ext_cost_0": null, + "cost_expr_ext_cost_custom_hess": null, + "cost_expr_ext_cost_custom_hess_0": null, + "cost_expr_ext_cost_custom_hess_e": null, + "cost_expr_ext_cost_e": null, + "cost_psi_expr": null, + "cost_psi_expr_0": null, + "cost_psi_expr_e": null, + "cost_r_in_psi_expr": null, + "cost_r_in_psi_expr_0": null, + "cost_r_in_psi_expr_e": null, + "cost_y_expr": "jhpnnagiieahaaaadaaaaaaaaaaaaaaaaaegkaaaaaaaaaaaaaaagaaaaaaaaaaaaaaabaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaagaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaabaaaaaaaaaaaaaaacaaaaaaaaaaaaaaadaaaaaaaaaaaaaaaeaaaaaaaaaaaaaaafaaaaaaaaaaaaaaagaaaaaaaaaaaaaaaegeaaaaaaaaaaaaaaaegcaaaaaaaaaaaaaaaegcaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaakaaaaaaaihpfpgcgdhehbgdgmgfgegpcaaaaaaaaaaaaaafaaaaaaaihpffghgpgegbaaaaaaaaaaaaaaaegbaaaaaaaaaaaaaaaegeaaaaaaaaaaaaaaaeglaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaafaaaaaaaghpffghgpgegmcaaaaaaaaaaaaaajgfaaaaaaaegdaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaanaaaaaaamgfgbgegpfehpfggpgmgmgpghhcheaaaaaaaaaaaaaaaegmcaaaaaaaaaaaaaajggaaaaaaaegbaaaaaaaaaaaaaaacheaaaaaaaaaaaaaaaegmcaaaaaaaaaaaaaajgkaaaaaaachcaaaaaaaaaaaaaaacheaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaafaaaaaaabgpffghgpgegcaaaaaaaaaaaaaaachbbaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaagaaaaaaaahchfgghpfbgegpcaaaaaaaaaaaaaafaaaaaaakgpffghgpg", + "cost_y_expr_0": "jhpnnagiieahaaaadaaaaaaaaaaaaaaaaaegkaaaaaaaaaaaaaaagaaaaaaaaaaaaaaabaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaagaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaabaaaaaaaaaaaaaaacaaaaaaaaaaaaaaadaaaaaaaaaaaaaaaeaaaaaaaaaaaaaaafaaaaaaaaaaaaaaagaaaaaaaaaaaaaaaegeaaaaaaaaaaaaaaaegcaaaaaaaaaaaaaaaegcaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaakaaaaaaaihpfpgcgdhehbgdgmgfgegpcaaaaaaaaaaaaaafaaaaaaaihpffghgpgegbaaaaaaaaaaaaaaaegbaaaaaaaaaaaaaaaegeaaaaaaaaaaaaaaaeglaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaafaaaaaaaghpffghgpgegmcaaaaaaaaaaaaaajgfaaaaaaaegdaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaanaaaaaaamgfgbgegpfehpfggpgmgmgpghhcheaaaaaaaaaaaaaaaegmcaaaaaaaaaaaaaajggaaaaaaaegbaaaaaaaaaaaaaaacheaaaaaaaaaaaaaaaegmcaaaaaaaaaaaaaajgkaaaaaaachcaaaaaaaaaaaaaaacheaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaafaaaaaaabgpffghgpgegcaaaaaaaaaaaaaaachbbaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaagaaaaaaaahchfgghpfbgegpcaaaaaaaaaaaaaafaaaaaaakgpffghgpg", + "cost_y_expr_e": "jhpnnagiieahaaaadaaaaaaaaaaaaaaaaaegjaaaaaaaaaaaaaaafaaaaaaaaaaaaaaabaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaafaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaabaaaaaaaaaaaaaaacaaaaaaaaaaaaaaadaaaaaaaaaaaaaaaeaaaaaaaaaaaaaaafaaaaaaaaaaaaaaaegeaaaaaaaaaaaaaaaegcaaaaaaaaaaaaaaaegcaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaakaaaaaaaihpfpgcgdhehbgdgmgfgegpcaaaaaaaaaaaaaafaaaaaaaihpffghgpgegbaaaaaaaaaaaaaaaegbaaaaaaaaaaaaaaaegeaaaaaaaaaaaaaaaeglaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaafaaaaaaaghpffghgpgegmcaaaaaaaaaaaaaajgfaaaaaaaegdaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaanaaaaaaamgfgbgegpfehpfggpgmgmgpghhcheaaaaaaaaaaaaaaaegmcaaaaaaaaaaaaaajggaaaaaaaegbaaaaaaaaaaaaaaacheaaaaaaaaaaaaaaaegmcaaaaaaaaaaaaaajgkaaaaaaachcaaaaaaaaaaaaaaacheaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaafaaaaaaabgpffghgpgegcaaaaaaaaaaaaaaachbbaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaagaaaaaaaahchfgghpfbg", + "disc_dyn_expr": null, "dyn_disc_fun": null, "dyn_disc_fun_jac": null, "dyn_disc_fun_jac_hess": null, "dyn_ext_fun_type": "casadi", - "dyn_source_discrete": null, + "dyn_generic_source": null, + "f_expl_expr": "jhpnnagiieahaaaadaaaaaaaaaaaaaaaaaeghaaaaaaaaaaaaaaadaaaaaaaaaaaaaaabaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaadaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaabaaaaaaaaaaaaaaacaaaaaaaaaaaaaaadaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaafaaaaaaaghpffghgpgegpcaaaaaaaaaaaaaafaaaaaaabgpffghgpgegpcaaaaaaaaaaaaaafaaaaaaakgpffghgpg", + "f_impl_expr": "jhpnnagiieahaaaadaaaaaaaaaaaaaaaaaeghaaaaaaaaaaaaaaadaaaaaaaaaaaaaaabaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaadaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaabaaaaaaaaaaaaaaacaaaaaaaaaaaaaaadaaaaaaaaaaaaaaaegcaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaajaaaaaaaihpffghgpgpfegpgehegpcaaaaaaaaaaaaaafaaaaaaaghpffghgpgegcaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaajaaaaaaaghpffghgpgpfegpgehegpcaaaaaaaaaaaaaafaaaaaaabgpffghgpgegcaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaajaaaaaaabgpffghgpgpfegpgehegpcaaaaaaaaaaaaaafaaaaaaakgpffghgpg", "gnsf": { "nontrivial_f_LO": 1, "purely_linear": 0 }, - "name": "long" + "name": "long", + "p": "jhpnnagiieahaaaadaaaaaaaaaaaaaaaaaegkaaaaaaaaaaaaaaagaaaaaaaaaaaaaaabaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaagaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaabaaaaaaaaaaaaaaacaaaaaaaaaaaaaaadaaaaaaaaaaaaaaaeaaaaaaaaaaaaaaafaaaaaaaaaaaaaaagaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaafaaaaaaabgpfngjgogegpcaaaaaaaaaaaaaafaaaaaaabgpfngbgihegpcaaaaaaaaaaaaaakaaaaaaaihpfpgcgdhehbgdgmgfgegpcaaaaaaaaaaaaaagaaaaaaaahchfgghpfbgegpcaaaaaaaaaaaaaanaaaaaaamgfgbgegpfehpfggpgmgmgpghhegpcaaaaaaaaaaaaaacbaaaaaamgfgbgegpfegbgoghgfgchpfggbgdgehpgch", + "u": "jhpnnagiieahaaaadaaaaaaaaaaaaaaaaaegfaaaaaaaaaaaaaaabaaaaaaaaaaaaaaabaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaabaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaabaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaafaaaaaaakgpffghgpg", + "x": "jhpnnagiieahaaaadaaaaaaaaaaaaaaaaaeghaaaaaaaaaaaaaaadaaaaaaaaaaaaaaabaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaadaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaabaaaaaaaaaaaaaaacaaaaaaaaaaaaaaadaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaafaaaaaaaihpffghgpgegpcaaaaaaaaaaaaaafaaaaaaaghpffghgpgegpcaaaaaaaaaaaaaafaaaaaaabgpffghgpg", + "xdot": "jhpnnagiieahaaaadaaaaaaaaaaaaaaaaaeghaaaaaaaaaaaaaaadaaaaaaaaaaaaaaabaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaadaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaabaaaaaaaaaaaaaaacaaaaaaaaaaaaaaadaaaaaaaaaaaaaaaegpcaaaaaaaaaaaaaajaaaaaaaihpffghgpgpfegpgehegpcaaaaaaaaaaaaaajaaaaaaaghpffghgpgpfegpgehegpcaaaaaaaaaaaaaajaaaaaaabgpffghgpgpfegpgeh", + "z": "jhpnnagiieahaaaadaaaaaaaaaaaaaaaaaegdaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaa" }, "parameter_values": [ -1.2, @@ -487,56 +399,22 @@ 0.75 ], "problem_class": "OCP", - "simulink_opts": { - "inputs": { - "cost_W": 0, - "cost_W_0": 0, - "cost_W_e": 0, - "lbu": 1, - "lbx": 1, - "lbx_0": 1, - "lbx_e": 1, - "lg": 1, - "lh": 1, - "parameter_traj": 1, - "reset_solver": 0, - "u_init": 0, - "ubu": 1, - "ubx": 1, - "ubx_0": 1, - "ubx_e": 1, - "ug": 1, - "uh": 1, - "x_init": 0, - "y_ref": 1, - "y_ref_0": 1, - "y_ref_e": 1 - }, - "outputs": { - "CPU_time": 1, - "CPU_time_lin": 0, - "CPU_time_qp": 0, - "CPU_time_sim": 0, - "KKT_residual": 1, - "solver_status": 1, - "sqp_iter": 1, - "u0": 1, - "utraj": 0, - "x1": 1, - "xtraj": 0 - }, - "samplingtime": "t0" - }, + "shared_lib_ext": ".so", "solver_options": { "Tsim": 0.06944444444444445, "alpha_min": 0.05, "alpha_reduction": 0.7, "collocation_type": "GAUSS_LEGENDRE", + "custom_templates": [], + "custom_update_copy": true, + "custom_update_filename": "", + "custom_update_header_filename": "", "eps_sufficient_descent": 0.0001, "exact_hess_constr": 1, "exact_hess_cost": 1, "exact_hess_dyn": 1, "ext_cost_num_hess": 0, + "ext_fun_compile_flags": "-O2", "full_step_dual": 0, "globalization": "FIXED_STEP", "globalization_use_SOC": 0, @@ -548,6 +426,7 @@ "line_search_use_sufficient_descent": 0, "model_external_shared_lib_dir": null, "model_external_shared_lib_name": null, + "nlp_solver_ext_qp_res": 0, "nlp_solver_max_iter": 100, "nlp_solver_step_length": 1.0, "nlp_solver_tol_comp": 1e-06, @@ -558,13 +437,30 @@ "print_level": 0, "qp_solver": "PARTIAL_CONDENSING_HPIPM", "qp_solver_cond_N": 1, + "qp_solver_cond_ric_alg": 1, "qp_solver_iter_max": 10, + "qp_solver_ric_alg": 1, "qp_solver_tol_comp": 0.001, "qp_solver_tol_eq": 0.001, "qp_solver_tol_ineq": 0.001, "qp_solver_tol_stat": 0.001, "qp_solver_warm_start": 0, "regularize_method": null, + "shooting_nodes": [ + 0.0, + 0.06944444444444445, + 0.2777777777777778, + 0.625, + 1.1111111111111112, + 1.7361111111111114, + 2.5, + 3.4027777777777786, + 4.444444444444445, + 5.625, + 6.9444444444444455, + 8.402777777777777, + 10.0 + ], "sim_method_jac_reuse": [ 0, 0, @@ -580,6 +476,7 @@ 0 ], "sim_method_newton_iter": 3, + "sim_method_newton_tol": 0.0, "sim_method_num_stages": [ 4, 4, diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/Makefile b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/Makefile index 366999c16..411a77be7 100644 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/Makefile +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/Makefile @@ -1,8 +1,5 @@ # -# Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, -# Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, -# Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, -# Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl +# Copyright (c) The acados authors. # # This file is part of acados. # @@ -41,6 +38,7 @@ MODEL_SRC= MODEL_SRC+= long_model/long_expl_ode_fun.c MODEL_SRC+= long_model/long_expl_vde_forw.c +MODEL_SRC+= long_model/long_expl_vde_adj.c MODEL_OBJ := $(MODEL_SRC:.c=.o) # optimal control problem - mostly CasADi exports @@ -56,6 +54,7 @@ OCP_SRC+= long_cost/long_cost_y_hess.c OCP_SRC+= long_cost/long_cost_y_e_fun.c OCP_SRC+= long_cost/long_cost_y_e_fun_jac_ut_xt.c OCP_SRC+= long_cost/long_cost_y_e_hess.c + OCP_SRC+= acados_solver_long.c OCP_OBJ := $(OCP_SRC:.c=.o) @@ -93,7 +92,7 @@ CPPFLAGS+= -I$(INCLUDE_PATH)/hpipm/include # define the c-compiler flags for make's implicit rules -CFLAGS = -fPIC -std=c99 #-fno-diagnostics-show-line-numbers -g +CFLAGS = -fPIC -std=c99 -O2#-fno-diagnostics-show-line-numbers -g # # Debugging # CFLAGS += -g3 @@ -150,11 +149,11 @@ ocp_cython_o: ocp_cython_c $(CC) $(ACADOS_FLAGS) -c -O2 \ -fPIC \ -o acados_ocp_solver_pyx.o \ - -I /usr/include/python3.8 \ -I $(INCLUDE_PATH)/blasfeo/include/ \ -I $(INCLUDE_PATH)/hpipm/include/ \ -I $(INCLUDE_PATH) \ -I /usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/core/include \ + -I /usr/local/pyenv/versions/3.11.4/include/python3.11 \ acados_ocp_solver_pyx.c \ ocp_cython: ocp_cython_o @@ -165,6 +164,33 @@ ocp_cython: ocp_cython_o $(abspath .)/libacados_ocp_solver_long.so \ $(LDFLAGS) $(LDLIBS) +# Sim Cython targets +sim_cython_c: sim_shared_lib + cython \ + -o acados_sim_solver_pyx.c \ + -I $(INCLUDE_PATH)/../interfaces/acados_template/acados_template \ + $(INCLUDE_PATH)/../interfaces/acados_template/acados_template/acados_sim_solver_pyx.pyx \ + -I /data/openpilot/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code \ + +sim_cython_o: sim_cython_c + $(CC) $(ACADOS_FLAGS) -c -O2 \ + -fPIC \ + -o acados_sim_solver_pyx.o \ + -I $(INCLUDE_PATH)/blasfeo/include/ \ + -I $(INCLUDE_PATH)/hpipm/include/ \ + -I $(INCLUDE_PATH) \ + -I /usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/core/include \ + -I /usr/local/pyenv/versions/3.11.4/include/python3.11 \ + acados_sim_solver_pyx.c \ + +sim_cython: sim_cython_o + $(CC) $(ACADOS_FLAGS) -shared \ + -o acados_sim_solver_pyx.so \ + -Wl,-rpath=$(LIB_PATH) \ + acados_sim_solver_pyx.o \ + $(abspath .)/libacados_sim_solver_long.so \ + $(LDFLAGS) $(LDLIBS) + clean: $(RM) $(OBJ) $(EX_OBJ) $(EX_SIM_OBJ) $(RM) $(LIBACADOS_SOLVER) $(LIBACADOS_OCP_SOLVER) $(LIBACADOS_SIM_SOLVER) @@ -179,3 +205,9 @@ clean_ocp_cython: $(RM) acados_solver_long.o $(RM) acados_ocp_solver_pyx.so $(RM) acados_ocp_solver_pyx.o + +clean_sim_cython: + $(RM) libacados_sim_solver_long.so + $(RM) acados_sim_solver_long.o + $(RM) acados_sim_solver_pyx.so + $(RM) acados_sim_solver_pyx.o diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_ocp_solver_pyx.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_ocp_solver_pyx.c index ebe24ee7f..0c47345fd 100644 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_ocp_solver_pyx.c +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_ocp_solver_pyx.c @@ -1781,7 +1781,7 @@ typedef npy_clongdouble __pyx_t_5numpy_clongdouble_t; */ typedef npy_cdouble __pyx_t_5numpy_complex_t; -/* "acados_template/acados_ocp_solver_pyx.pyx":52 +/* "acados_template/acados_ocp_solver_pyx.pyx":49 * * * cdef class AcadosOcpSolverCython: # <<<<<<<<<<<<<< @@ -1798,7 +1798,6 @@ struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython ocp_nlp_out *sens_out; ocp_nlp_in *nlp_in; ocp_nlp_solver *nlp_solver; - int status; int solver_created; PyObject *model_name; int N; @@ -2479,6 +2478,12 @@ static PyObject* __Pyx_ImportFrom(PyObject* module, PyObject* name); /* HasAttr.proto */ static CYTHON_INLINE int __Pyx_HasAttr(PyObject *, PyObject *); +/* PyIntCompare.proto */ +static CYTHON_INLINE int __Pyx_PyInt_BoolEqObjC(PyObject *op1, PyObject *op2, long intval, long inplace); + +/* PyIntCompare.proto */ +static CYTHON_INLINE int __Pyx_PyInt_BoolNeObjC(PyObject *op1, PyObject *op2, long intval, long inplace); + /* IsLittleEndian.proto */ static CYTHON_INLINE int __Pyx_Is_Little_Endian(void); @@ -2528,6 +2533,56 @@ static CYTHON_INLINE PyObject* __Pyx_PyObject_GetSlice( #define __Pyx_PyObject_Str(obj)\ (likely(PyString_CheckExact(obj)) ? __Pyx_NewRef(obj) : PyObject_Str(obj)) +/* PyObjectFormat.proto */ +#if CYTHON_USE_UNICODE_WRITER +static PyObject* __Pyx_PyObject_Format(PyObject* s, PyObject* f); +#else +#define __Pyx_PyObject_Format(s, f) PyObject_Format(s, f) +#endif + +/* py_dict_keys.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyDict_Keys(PyObject* d); + +/* UnpackUnboundCMethod.proto */ +typedef struct { + PyObject *type; + PyObject **method_name; + PyCFunction func; + PyObject *method; + int flag; +} __Pyx_CachedCFunction; + +/* CallUnboundCMethod0.proto */ +static PyObject* __Pyx__CallUnboundCMethod0(__Pyx_CachedCFunction* cfunc, PyObject* self); +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_CallUnboundCMethod0(cfunc, self)\ + (likely((cfunc)->func) ?\ + (likely((cfunc)->flag == METH_NOARGS) ? (*((cfunc)->func))(self, NULL) :\ + (PY_VERSION_HEX >= 0x030600B1 && likely((cfunc)->flag == METH_FASTCALL) ?\ + (PY_VERSION_HEX >= 0x030700A0 ?\ + (*(__Pyx_PyCFunctionFast)(void*)(PyCFunction)(cfunc)->func)(self, &__pyx_empty_tuple, 0) :\ + (*(__Pyx_PyCFunctionFastWithKeywords)(void*)(PyCFunction)(cfunc)->func)(self, &__pyx_empty_tuple, 0, NULL)) :\ + (PY_VERSION_HEX >= 0x030700A0 && (cfunc)->flag == (METH_FASTCALL | METH_KEYWORDS) ?\ + (*(__Pyx_PyCFunctionFastWithKeywords)(void*)(PyCFunction)(cfunc)->func)(self, &__pyx_empty_tuple, 0, NULL) :\ + (likely((cfunc)->flag == (METH_VARARGS | METH_KEYWORDS)) ? ((*(PyCFunctionWithKeywords)(void*)(PyCFunction)(cfunc)->func)(self, __pyx_empty_tuple, NULL)) :\ + ((cfunc)->flag == METH_VARARGS ? (*((cfunc)->func))(self, __pyx_empty_tuple) :\ + __Pyx__CallUnboundCMethod0(cfunc, self)))))) :\ + __Pyx__CallUnboundCMethod0(cfunc, self)) +#else +#define __Pyx_CallUnboundCMethod0(cfunc, self) __Pyx__CallUnboundCMethod0(cfunc, self) +#endif + +/* DictGetItem.proto */ +#if PY_MAJOR_VERSION >= 3 && !CYTHON_COMPILING_IN_PYPY +static PyObject *__Pyx_PyDict_GetItem(PyObject *d, PyObject* key); +#define __Pyx_PyObject_Dict_GetItem(obj, name)\ + (likely(PyDict_CheckExact(obj)) ?\ + __Pyx_PyDict_GetItem(obj, name) : PyObject_GetItem(obj, name)) +#else +#define __Pyx_PyDict_GetItem(d, key) PyObject_GetItem(d, key) +#define __Pyx_PyObject_Dict_GetItem(obj, name) PyObject_GetItem(obj, name) +#endif + /* PyObjectLookupSpecial.proto */ #if CYTHON_USE_PYTYPE_LOOKUP && CYTHON_USE_TYPE_SLOTS #define __Pyx_PyObject_LookupSpecialNoError(obj, attr_name) __Pyx__PyObject_LookupSpecial(obj, attr_name, 0) @@ -2987,15 +3042,15 @@ static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *); /* CIntToPy.proto */ static CYTHON_INLINE PyObject* __Pyx_PyInt_From_int(int value); +/* CIntFromPy.proto */ +static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *); + /* CIntToPy.proto */ static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value); /* CIntFromPy.proto */ static CYTHON_INLINE size_t __Pyx_PyInt_As_size_t(PyObject *); -/* CIntFromPy.proto */ -static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *); - /* CIntFromPy.proto */ static CYTHON_INLINE char __Pyx_PyInt_As_char(PyObject *); @@ -3116,6 +3171,7 @@ static void __pyx_memoryview__slice_assign_scalar(char *, Py_ssize_t *, Py_ssize static PyObject *__pyx_unpickle_Enum__set_state(struct __pyx_MemviewEnum_obj *, PyObject *); /*proto*/ /* #### Code section: typeinfo ### */ static __Pyx_TypeInfo __Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t = { "float64_t", NULL, sizeof(__pyx_t_5numpy_float64_t), { 0 }, 0, 'R', 0, 0 }; +static __Pyx_TypeInfo __Pyx_TypeInfo_nn___pyx_t_5numpy_int32_t = { "int32_t", NULL, sizeof(__pyx_t_5numpy_int32_t), { 0 }, 0, __PYX_IS_UNSIGNED(__pyx_t_5numpy_int32_t) ? 'U' : 'I', __PYX_IS_UNSIGNED(__pyx_t_5numpy_int32_t), 0 }; static __Pyx_TypeInfo __Pyx_TypeInfo_double = { "double", NULL, sizeof(double), { 0 }, 0, 'R', 0, 0 }; static __Pyx_TypeInfo __Pyx_TypeInfo_unsigned_char = { "unsigned char", NULL, sizeof(unsigned char), { 0 }, 0, __PYX_IS_UNSIGNED(unsigned char) ? 'U' : 'I', __PYX_IS_UNSIGNED(unsigned char), 0 }; /* #### Code section: before_global_var ### */ @@ -3126,10 +3182,10 @@ int __pyx_module_is_main_acados_template__acados_ocp_solver_pyx = 0; /* Implementation of "acados_template.acados_ocp_solver_pyx" */ /* #### Code section: global_var ### */ static PyObject *__pyx_builtin_AssertionError; +static PyObject *__pyx_builtin_print; static PyObject *__pyx_builtin_NotImplementedError; static PyObject *__pyx_builtin_range; static PyObject *__pyx_builtin_open; -static PyObject *__pyx_builtin_print; static PyObject *__pyx_builtin_TypeError; static PyObject *__pyx_builtin___import__; static PyObject *__pyx_builtin_ValueError; @@ -3141,12 +3197,15 @@ static PyObject *__pyx_builtin_IndexError; static PyObject *__pyx_builtin_ImportError; /* #### Code section: string_decls ### */ static const char __pyx_k_[] = ": "; +static const char __pyx_k_0[] = "0"; static const char __pyx_k_F[] = "F"; static const char __pyx_k_N[] = "N"; static const char __pyx_k_O[] = "O"; static const char __pyx_k_c[] = "c"; +static const char __pyx_k_d[] = "d"; static const char __pyx_k_f[] = "f"; static const char __pyx_k_i[] = "i"; +static const char __pyx_k_k[] = "k"; static const char __pyx_k_m[] = "m"; static const char __pyx_k_n[] = "n"; static const char __pyx_k_p[] = "p"; @@ -3163,21 +3222,24 @@ static const char __pyx_k__7[] = ")"; static const char __pyx_k_ex[] = "ex"; static const char __pyx_k_gc[] = "gc"; static const char __pyx_k_id[] = "id"; +static const char __pyx_k_lN[] = "lN"; static const char __pyx_k_np[] = "np"; static const char __pyx_k_nx[] = "nx"; static const char __pyx_k_os[] = "os"; static const char __pyx_k_pi[] = "pi"; static const char __pyx_k_sl[] = "sl"; static const char __pyx_k_su[] = "su"; +static const char __pyx_k_u0[] = "u0"; static const char __pyx_k_SQP[] = "SQP"; -static const char __pyx_k__14[] = ""; -static const char __pyx_k__15[] = "_"; -static const char __pyx_k__29[] = ", "; -static const char __pyx_k__84[] = "?"; +static const char __pyx_k__16[] = ""; +static const char __pyx_k__17[] = "_"; +static const char __pyx_k__31[] = ", "; +static const char __pyx_k__94[] = "?"; static const char __pyx_k_abc[] = "abc"; static const char __pyx_k_and[] = " and "; static const char __pyx_k_get[] = "get"; static const char __pyx_k_got[] = " (got "; +static const char __pyx_k_idx[] = "idx"; static const char __pyx_k_int[] = "int"; static const char __pyx_k_key[] = "key"; static const char __pyx_k_lam[] = "lam"; @@ -3198,6 +3260,7 @@ static const char __pyx_k_z_2[] = "z_"; static const char __pyx_k_None[] = "None"; static const char __pyx_k_TODO[] = "TODO!"; static const char __pyx_k_base[] = "base"; +static const char __pyx_k_data[] = "data_"; static const char __pyx_k_dict[] = "__dict__"; static const char __pyx_k_dims[] = "dims"; static const char __pyx_k_dump[] = "dump"; @@ -3234,6 +3297,7 @@ static const char __pyx_k_error[] = "error"; static const char __pyx_k_field[] = "field"; static const char __pyx_k_flags[] = "flags"; static const char __pyx_k_index[] = "index"; +static const char __pyx_k_int32[] = "int32"; static const char __pyx_k_lam_2[] = "lam_"; static const char __pyx_k_numpy[] = "numpy"; static const char __pyx_k_order[] = "order"; @@ -3249,6 +3313,7 @@ static const char __pyx_k_utf_8[] = "utf-8"; static const char __pyx_k_value[] = "value_"; static const char __pyx_k_y_ref[] = "y_ref"; static const char __pyx_k_zeros[] = "zeros"; +static const char __pyx_k_data_2[] = "data"; static const char __pyx_k_enable[] = "enable"; static const char __pyx_k_encode[] = "encode"; static const char __pyx_k_fields[] = "fields"; @@ -3265,12 +3330,14 @@ static const char __pyx_k_reduce[] = "__reduce__"; static const char __pyx_k_res_eq[] = "res_eq"; static const char __pyx_k_stat_m[] = "stat_m"; static const char __pyx_k_stat_n[] = "stat_n"; +static const char __pyx_k_status[] = "status"; static const char __pyx_k_struct[] = "struct"; static const char __pyx_k_tol_eq[] = "tol_eq"; static const char __pyx_k_tolist[] = "tolist"; static const char __pyx_k_unpack[] = "unpack"; static const char __pyx_k_update[] = "update"; static const char __pyx_k_utcnow[] = "utcnow"; +static const char __pyx_k_x0_bar[] = "x0_bar"; static const char __pyx_k_SQP_RTI[] = "SQP_RTI"; static const char __pyx_k_default[] = "default"; static const char __pyx_k_disable[] = "disable"; @@ -3279,6 +3346,7 @@ static const char __pyx_k_float64[] = "float64"; static const char __pyx_k_fortran[] = "fortran"; static const char __pyx_k_iterate[] = "iterate"; static const char __pyx_k_memview[] = "memview"; +static const char __pyx_k_ndarray[] = "ndarray"; static const char __pyx_k_out_mat[] = "out_mat"; static const char __pyx_k_qp_iter[] = "qp_iter"; static const char __pyx_k_time_qp[] = "time_qp"; @@ -3288,12 +3356,15 @@ static const char __pyx_k_Ellipsis[] = "Ellipsis"; static const char __pyx_k_Sequence[] = "Sequence"; static const char __pyx_k_at_stage[] = "\" at stage "; static const char __pyx_k_cost_set[] = "cost_set"; +static const char __pyx_k_data_len[] = "data_len"; static const char __pyx_k_datetime[] = "datetime"; static const char __pyx_k_filename[] = "filename"; static const char __pyx_k_get_cost[] = "get_cost"; static const char __pyx_k_getstate[] = "__getstate__"; +static const char __pyx_k_i_string[] = "i_string"; static const char __pyx_k_itemsize[] = "itemsize"; static const char __pyx_k_min_size[] = "min_size"; +static const char __pyx_k_n_update[] = "n_update"; static const char __pyx_k_pyx_type[] = "__pyx_type"; static const char __pyx_k_register[] = "register"; static const char __pyx_k_res_comp[] = "res_comp"; @@ -3330,6 +3401,7 @@ static const char __pyx_k_time_glob[] = "time_glob"; static const char __pyx_k_IndexError[] = "IndexError"; static const char __pyx_k_ValueError[] = "ValueError"; static const char __pyx_k_full_stats[] = "full_stats"; +static const char __pyx_k_idx_values[] = "idx_values_"; static const char __pyx_k_int_fields[] = "int_fields"; static const char __pyx_k_mem_fields[] = "mem_fields"; static const char __pyx_k_model_name[] = "model_name"; @@ -3354,17 +3426,20 @@ static const char __pyx_k_time_sim_ad[] = "time_sim_ad"; static const char __pyx_k_time_sim_la[] = "time_sim_la"; static const char __pyx_k_value_shape[] = "value_shape"; static const char __pyx_k_double_value[] = "double_value"; -static const char __pyx_k_dynamics_get[] = "dynamics_get"; static const char __pyx_k_get_stat_int[] = "__get_stat_int"; static const char __pyx_k_initializing[] = "_initializing"; static const char __pyx_k_is_coroutine[] = "_is_coroutine"; static const char __pyx_k_load_iterate[] = "load_iterate"; +static const char __pyx_k_param_values[] = "param_values_"; static const char __pyx_k_pyx_checksum[] = "__pyx_checksum"; +static const char __pyx_k_solve_for_x0[] = "solve_for_x0"; static const char __pyx_k_string_value[] = "string_value"; static const char __pyx_k_stringsource[] = ""; static const char __pyx_k_version_info[] = "version_info"; +static const char __pyx_k_Got_sizes_idx[] = " Got sizes idx "; static const char __pyx_k_Y_m_d_H_M_S_f[] = "%Y-%m-%d-%H:%M:%S.%f"; static const char __pyx_k_class_getitem[] = "__class_getitem__"; +static const char __pyx_k_custom_update[] = "custom_update"; static const char __pyx_k_double_fields[] = "double_fields"; static const char __pyx_k_get_residuals[] = "get_residuals"; static const char __pyx_k_globalization[] = "globalization"; @@ -3376,7 +3451,9 @@ static const char __pyx_k_time_qp_xcond[] = "time_qp_xcond"; static const char __pyx_k_AssertionError[] = "AssertionError"; static const char __pyx_k_asfortranarray[] = "asfortranarray"; static const char __pyx_k_full_step_dual[] = "full_step_dual"; +static const char __pyx_k_get_from_qp_in[] = "get_from_qp_in"; static const char __pyx_k_new_time_steps[] = "new_time_steps"; +static const char __pyx_k_param_values_2[] = ", param_values "; static const char __pyx_k_with_dimension[] = " with dimension "; static const char __pyx_k_View_MemoryView[] = "View.MemoryView"; static const char __pyx_k_allocate_buffer[] = "allocate_buffer"; @@ -3394,6 +3471,7 @@ static const char __pyx_k_print_statistics[] = "print_statistics"; static const char __pyx_k_qp_solver_cond_N[] = "qp_solver_cond_N"; static const char __pyx_k_ascontiguousarray[] = "ascontiguousarray"; static const char __pyx_k_pyx_unpickle_Enum[] = "__pyx_unpickle_Enum"; +static const char __pyx_k_set_params_sparse[] = "set_params_sparse"; static const char __pyx_k_asyncio_coroutines[] = "asyncio.coroutines"; static const char __pyx_k_cline_in_traceback[] = "cline_in_traceback"; static const char __pyx_k_constraints_fields[] = "constraints_fields"; @@ -3402,6 +3480,7 @@ static const char __pyx_k_strided_and_direct[] = ""; static const char __pyx_k_NotImplementedError[] = "NotImplementedError"; static const char __pyx_k_get_pointers_solver[] = "__get_pointers_solver"; static const char __pyx_k_initialize_t_slacks[] = "initialize_t_slacks"; +static const char __pyx_k_reset_qp_solver_mem[] = "reset_qp_solver_mem"; static const char __pyx_k_time_qp_solver_call[] = "time_qp_solver_call"; static const char __pyx_k_warm_start_first_qp[] = "warm_start_first_qp"; static const char __pyx_k_strided_and_indirect[] = ""; @@ -3430,13 +3509,15 @@ static const char __pyx_k_time_solution_sensitivities[] = "time_solution_sensiti static const char __pyx_k_unable_to_allocate_array_data[] = "unable to allocate array data."; static const char __pyx_k_AcadosOcpSolverCython_cost_set[] = "AcadosOcpSolverCython.cost_set"; static const char __pyx_k_AcadosOcpSolverCython_get_cost[] = "AcadosOcpSolverCython.get_cost"; +static const char __pyx_k_param_values__must_be_np_array[] = "param_values_ must be np.array."; static const char __pyx_k_strided_and_direct_or_indirect[] = ""; static const char __pyx_k_AcadosOcpSolverCython__get_poin[] = "_AcadosOcpSolverCython__get_pointers_solver"; static const char __pyx_k_AcadosOcpSolverCython__get_stat[] = "_AcadosOcpSolverCython__get_stat_int"; static const char __pyx_k_AcadosOcpSolverCython_get_field[] = "AcadosOcpSolverCython.get(): field {} does not exist at final stage {}."; -static const char __pyx_k_AcadosOcpSolverCython_get_is_an[] = "AcadosOcpSolverCython.get(): {} is an invalid argument. \n Possible values are {}. Exiting."; +static const char __pyx_k_AcadosOcpSolverCython_get_is_an[] = "AcadosOcpSolverCython.get(): {} is an invalid argument. \n Possible values are {}."; static const char __pyx_k_AcadosOcpSolverCython_get_stage[] = "AcadosOcpSolverCython.get(): stage index must be in [0, N], got: {}."; static const char __pyx_k_AcadosOcpSolverCython_get_stats[] = "AcadosOcpSolverCython.get_stats"; +static const char __pyx_k_AcadosOcpSolverCython_solve_for[] = "AcadosOcpSolverCython.solve_for_x0"; static const char __pyx_k_AcadosOcpSolverCython_update_qp[] = "AcadosOcpSolverCython.update_qp_solver_cond_N"; static const char __pyx_k_numpy_core_multiarray_failed_to[] = "numpy.core.multiarray failed to import"; static const char __pyx_k_AcadosOcpSolverCython___get_poin[] = "AcadosOcpSolverCython.__get_pointers_solver"; @@ -3445,16 +3526,18 @@ static const char __pyx_k_AcadosOcpSolverCython___reduce_c[] = "AcadosOcpSolverC static const char __pyx_k_AcadosOcpSolverCython___setstate[] = "AcadosOcpSolverCython.__setstate_cython__"; static const char __pyx_k_AcadosOcpSolverCython_constraint[] = "AcadosOcpSolverCython.constraints_set(): mismatching dimension"; static const char __pyx_k_AcadosOcpSolverCython_cost_set_m[] = "AcadosOcpSolverCython.cost_set(): mismatching dimension"; +static const char __pyx_k_AcadosOcpSolverCython_custom_upd[] = "AcadosOcpSolverCython.custom_update"; static const char __pyx_k_AcadosOcpSolverCython_does_not_s[] = "AcadosOcpSolverCython: does not support set_new_time_steps() since it is only a prototyping feature"; -static const char __pyx_k_AcadosOcpSolverCython_dynamics_g[] = "AcadosOcpSolverCython.dynamics_get"; static const char __pyx_k_AcadosOcpSolverCython_eval_param[] = "AcadosOcpSolverCython.eval_param_sens(): index must be Integer."; +static const char __pyx_k_AcadosOcpSolverCython_get_from_q[] = "AcadosOcpSolverCython.get_from_qp_in"; static const char __pyx_k_AcadosOcpSolverCython_get_residu[] = "AcadosOcpSolverCython.get_residuals"; static const char __pyx_k_AcadosOcpSolverCython_load_itera[] = "AcadosOcpSolverCython.load_iterate"; static const char __pyx_k_AcadosOcpSolverCython_options_se[] = "AcadosOcpSolverCython.options_set() does not support field {}.\n Possible values are {}."; static const char __pyx_k_AcadosOcpSolverCython_print_stat[] = "AcadosOcpSolverCython.print_statistics"; -static const char __pyx_k_AcadosOcpSolverCython_set_is_not[] = "AcadosOcpSolverCython.set(): {} is not a valid argument. \nPossible values are {}. Exiting."; +static const char __pyx_k_AcadosOcpSolverCython_set_is_not[] = "AcadosOcpSolverCython.set(): {} is not a valid argument. \nPossible values are {}."; static const char __pyx_k_AcadosOcpSolverCython_set_mismat[] = "AcadosOcpSolverCython.set(): mismatching dimension for field \"{}\" "; static const char __pyx_k_AcadosOcpSolverCython_set_new_ti[] = "AcadosOcpSolverCython.set_new_time_steps"; +static const char __pyx_k_AcadosOcpSolverCython_set_params[] = "AcadosOcpSolverCython.set_params_sparse"; static const char __pyx_k_AcadosOcpSolverCython_solve_argu[] = "AcadosOcpSolverCython.solve(): argument 'rti_phase' can take only values 0, 1, 2 for SQP-RTI-type solvers"; static const char __pyx_k_AcadosOcpSolverCython_store_iter[] = "AcadosOcpSolverCython.store_iterate"; static const char __pyx_k_All_dimensions_preceding_dimensi[] = "All dimensions preceding dimension %d must be indexed and not sliced"; @@ -3469,13 +3552,19 @@ static const char __pyx_k_Indirect_dimensions_not_supporte[] = "Indirect dimensi static const char __pyx_k_Invalid_mode_expected_c_or_fortr[] = "Invalid mode, expected 'c' or 'fortran', got "; static const char __pyx_k_Out_of_bounds_on_buffer_access_a[] = "Out of bounds on buffer access (axis "; static const char __pyx_k_Unable_to_convert_item_to_object[] = "Unable to convert item to object"; +static const char __pyx_k_Warning_acados_ocp_solver_reache[] = "Warning: acados_ocp_solver reached maximum iterations."; +static const char __pyx_k_acados_acados_ocp_solver_returne[] = "acados acados_ocp_solver returned status "; static const char __pyx_k_acados_template_acados_ocp_solve[] = "acados_template.acados_ocp_solver_pyx"; static const char __pyx_k_alpha_values_are_not_available_f[] = "alpha values are not available for SQP_RTI"; +static const char __pyx_k_constraints_set_value_must_be_nu[] = "constraints_set: value must be numpy array, got "; +static const char __pyx_k_cost_set_value_must_be_numpy_arr[] = "cost_set: value must be numpy array, got "; static const char __pyx_k_got_differing_extents_in_dimensi[] = "got differing extents in dimension "; static const char __pyx_k_line_search_use_sufficient_desce[] = "line_search_use_sufficient_descent"; static const char __pyx_k_load_iterate_failed_file_does_no[] = "load_iterate: failed, file does not exist: "; static const char __pyx_k_no_default___reduce___due_to_non[] = "no default __reduce__ due to non-trivial __cinit__"; static const char __pyx_k_numpy_core_umath_failed_to_impor[] = "numpy.core.umath failed to import"; +static const char __pyx_k_param_values__and_idx_values__mu[] = "param_values_ and idx_values_ must be of the same size."; +static const char __pyx_k_set_value_must_be_numpy_array_go[] = "set: value must be numpy array, got "; static const char __pyx_k_solver_option_must_be_of_type_fl[] = "solver option {} must be of type float. You have {}."; static const char __pyx_k_solver_option_must_be_of_type_in[] = "solver option {} must be of type int. You have {}."; static const char __pyx_k_solver_option_must_be_of_type_st[] = "solver option {} must be of type str. You have {}."; @@ -3535,35 +3624,39 @@ static PyObject *__pyx_pf___pyx_memoryviewslice_2__setstate_cython__(CYTHON_UNUS static PyObject *__pyx_pf_15View_dot_MemoryView___pyx_unpickle_Enum(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v___pyx_type, long __pyx_v___pyx_checksum, PyObject *__pyx_v___pyx_state); /* proto */ static int __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython___cinit__(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_model_name, PyObject *__pyx_v_nlp_solver_type, PyObject *__pyx_v_N); /* proto */ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_2__get_pointers_solver(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6reset(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8set_new_time_steps(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v_new_time_steps); /* proto */ -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10update_qp_solver_cond_N(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v_qp_solver_cond_N); /* proto */ -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12eval_param_sens(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_stage, PyObject *__pyx_v_field); /* proto */ -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14get(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_); /* proto */ -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16print_statistics(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve_for_x0(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_x0_bar); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6solve(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8reset(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_reset_qp_solver_mem); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10custom_update(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_data_); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12set_new_time_steps(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v_new_time_steps); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14update_qp_solver_cond_N(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v_qp_solver_cond_N); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16eval_param_sens(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_stage, PyObject *__pyx_v_field); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18get(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20print_statistics(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ static PyObject *__pyx_lambda_funcdef_lambda(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_x); /* proto */ -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18store_iterate(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_filename, PyObject *__pyx_v_overwrite); /* proto */ -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20load_iterate(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_filename); /* proto */ -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22get_stats(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field_); /* proto */ -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_24__get_stat_int(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field); /* proto */ -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_26__get_stat_double(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field); /* proto */ -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_28__get_stat_matrix(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field, PyObject *__pyx_v_n, PyObject *__pyx_v_m); /* proto */ -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_30get_cost(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_32get_residuals(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_recompute); /* proto */ -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_); /* proto */ -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36cost_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_); /* proto */ -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38constraints_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_); /* proto */ -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40dynamics_get(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_); /* proto */ -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42options_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_); /* proto */ -static void __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_44__del__(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_46__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_48__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22store_iterate(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_filename, PyObject *__pyx_v_overwrite); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_24load_iterate(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_filename); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_26get_stats(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field_); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_28__get_stat_int(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_30__get_stat_double(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_32__get_stat_matrix(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field, PyObject *__pyx_v_n, PyObject *__pyx_v_m); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34get_cost(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36get_residuals(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_recompute); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40cost_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42constraints_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_44get_from_qp_in(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_46options_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_48set_params_sparse(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_idx_values_, PyObject *__pyx_v_param_values_); /* proto */ +static void __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_50__del__(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_52__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_54__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ static PyObject *__pyx_tp_new_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ static PyObject *__pyx_tp_new_array(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ static PyObject *__pyx_tp_new_Enum(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ static PyObject *__pyx_tp_new_memoryview(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ static PyObject *__pyx_tp_new__memoryviewslice(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static __Pyx_CachedCFunction __pyx_umethod_PyDict_Type_keys = {0, 0, 0, 0, 0}; /* #### Code section: late_includes ### */ /* #### Code section: module_state ### */ typedef struct { @@ -3650,6 +3743,7 @@ typedef struct { PyTypeObject *__pyx_memoryview_type; PyTypeObject *__pyx_memoryviewslice_type; PyObject *__pyx_kp_u_; + PyObject *__pyx_kp_u_0; PyObject *__pyx_n_s_ASCII; PyObject *__pyx_n_s_AcadosOcpSolverCython; PyObject *__pyx_n_s_AcadosOcpSolverCython___get_poin; @@ -3666,15 +3760,16 @@ typedef struct { PyObject *__pyx_n_s_AcadosOcpSolverCython_constraint_2; PyObject *__pyx_n_s_AcadosOcpSolverCython_cost_set; PyObject *__pyx_kp_u_AcadosOcpSolverCython_cost_set_m; + PyObject *__pyx_n_s_AcadosOcpSolverCython_custom_upd; PyObject *__pyx_kp_u_AcadosOcpSolverCython_does_not_s; PyObject *__pyx_kp_u_AcadosOcpSolverCython_does_not_s_2; - PyObject *__pyx_n_s_AcadosOcpSolverCython_dynamics_g; PyObject *__pyx_kp_u_AcadosOcpSolverCython_eval_param; PyObject *__pyx_kp_u_AcadosOcpSolverCython_eval_param_2; PyObject *__pyx_n_s_AcadosOcpSolverCython_eval_param_3; PyObject *__pyx_n_s_AcadosOcpSolverCython_get; PyObject *__pyx_n_s_AcadosOcpSolverCython_get_cost; PyObject *__pyx_kp_u_AcadosOcpSolverCython_get_field; + PyObject *__pyx_n_s_AcadosOcpSolverCython_get_from_q; PyObject *__pyx_kp_u_AcadosOcpSolverCython_get_is_an; PyObject *__pyx_n_s_AcadosOcpSolverCython_get_residu; PyObject *__pyx_kp_u_AcadosOcpSolverCython_get_stage; @@ -3688,9 +3783,11 @@ typedef struct { PyObject *__pyx_kp_u_AcadosOcpSolverCython_set_is_not; PyObject *__pyx_kp_u_AcadosOcpSolverCython_set_mismat; PyObject *__pyx_n_s_AcadosOcpSolverCython_set_new_ti; + PyObject *__pyx_n_s_AcadosOcpSolverCython_set_params; PyObject *__pyx_n_s_AcadosOcpSolverCython_solve; PyObject *__pyx_kp_u_AcadosOcpSolverCython_solve_argu; PyObject *__pyx_kp_u_AcadosOcpSolverCython_solve_argu_2; + PyObject *__pyx_n_s_AcadosOcpSolverCython_solve_for; PyObject *__pyx_n_s_AcadosOcpSolverCython_store_iter; PyObject *__pyx_n_s_AcadosOcpSolverCython_update_qp; PyObject *__pyx_kp_s_All_dimensions_preceding_dimensi; @@ -3705,6 +3802,7 @@ typedef struct { PyObject *__pyx_n_s_Ellipsis; PyObject *__pyx_kp_s_Empty_shape_tuple_for_cython_arr; PyObject *__pyx_n_u_F; + PyObject *__pyx_kp_u_Got_sizes_idx; PyObject *__pyx_n_s_ImportError; PyObject *__pyx_kp_s_Incompatible_checksums_0x_x_vs_0; PyObject *__pyx_n_s_IndexError; @@ -3730,16 +3828,18 @@ typedef struct { PyObject *__pyx_kp_s_Unable_to_convert_item_to_object; PyObject *__pyx_n_s_ValueError; PyObject *__pyx_n_s_View_MemoryView; + PyObject *__pyx_kp_u_Warning_acados_ocp_solver_reache; PyObject *__pyx_kp_u_Y_m_d_H_M_S_f; - PyObject *__pyx_kp_u__14; - PyObject *__pyx_n_u__15; + PyObject *__pyx_kp_u__16; + PyObject *__pyx_n_u__17; PyObject *__pyx_kp_u__2; - PyObject *__pyx_kp_u__29; PyObject *__pyx_n_s__3; + PyObject *__pyx_kp_u__31; PyObject *__pyx_kp_u__6; PyObject *__pyx_kp_u__7; - PyObject *__pyx_n_s__84; + PyObject *__pyx_n_s__94; PyObject *__pyx_n_s_abc; + PyObject *__pyx_kp_u_acados_acados_ocp_solver_returne; PyObject *__pyx_n_s_acados_template_acados_ocp_solve; PyObject *__pyx_n_s_allocate_buffer; PyObject *__pyx_n_u_alpha; @@ -3762,11 +3862,18 @@ typedef struct { PyObject *__pyx_kp_s_collections_abc; PyObject *__pyx_n_s_constraints_fields; PyObject *__pyx_n_s_constraints_set; + PyObject *__pyx_kp_u_constraints_set_value_must_be_nu; PyObject *__pyx_kp_s_contiguous_and_direct; PyObject *__pyx_kp_s_contiguous_and_indirect; PyObject *__pyx_n_s_cost_fields; PyObject *__pyx_n_s_cost_set; + PyObject *__pyx_kp_u_cost_set_value_must_be_numpy_arr; PyObject *__pyx_n_s_count; + PyObject *__pyx_n_s_custom_update; + PyObject *__pyx_n_u_d; + PyObject *__pyx_n_s_data; + PyObject *__pyx_n_s_data_2; + PyObject *__pyx_n_s_data_len; PyObject *__pyx_n_s_datetime; PyObject *__pyx_n_s_default; PyObject *__pyx_n_s_dict; @@ -3777,7 +3884,6 @@ typedef struct { PyObject *__pyx_n_s_dtype; PyObject *__pyx_n_s_dtype_is_object; PyObject *__pyx_n_s_dump; - PyObject *__pyx_n_s_dynamics_get; PyObject *__pyx_kp_u_enable; PyObject *__pyx_n_s_encode; PyObject *__pyx_n_s_enter; @@ -3803,6 +3909,7 @@ typedef struct { PyObject *__pyx_kp_u_gc; PyObject *__pyx_n_s_get; PyObject *__pyx_n_s_get_cost; + PyObject *__pyx_n_s_get_from_qp_in; PyObject *__pyx_n_s_get_pointers_solver; PyObject *__pyx_n_s_get_residuals; PyObject *__pyx_n_s_get_stat_double; @@ -3816,13 +3923,17 @@ typedef struct { PyObject *__pyx_kp_u_got; PyObject *__pyx_kp_u_got_differing_extents_in_dimensi; PyObject *__pyx_n_s_i; + PyObject *__pyx_n_s_i_string; PyObject *__pyx_n_s_id; + PyObject *__pyx_n_s_idx; + PyObject *__pyx_n_s_idx_values; PyObject *__pyx_n_s_import; PyObject *__pyx_n_s_indent; PyObject *__pyx_n_s_index; PyObject *__pyx_n_u_initialize_t_slacks; PyObject *__pyx_n_s_initializing; PyObject *__pyx_n_s_int; + PyObject *__pyx_n_s_int32; PyObject *__pyx_n_s_int_fields; PyObject *__pyx_n_s_int_value; PyObject *__pyx_n_s_is_coroutine; @@ -3834,8 +3945,10 @@ typedef struct { PyObject *__pyx_n_s_join; PyObject *__pyx_n_s_json; PyObject *__pyx_kp_u_json_2; + PyObject *__pyx_n_s_k; PyObject *__pyx_n_s_key; PyObject *__pyx_n_s_keys; + PyObject *__pyx_n_s_lN; PyObject *__pyx_n_u_lam; PyObject *__pyx_n_u_lam_2; PyObject *__pyx_n_u_lbu; @@ -3853,8 +3966,10 @@ typedef struct { PyObject *__pyx_n_s_model_name; PyObject *__pyx_n_s_msg; PyObject *__pyx_n_s_n; + PyObject *__pyx_n_s_n_update; PyObject *__pyx_n_s_name; PyObject *__pyx_n_s_name_2; + PyObject *__pyx_n_s_ndarray; PyObject *__pyx_n_s_ndim; PyObject *__pyx_n_s_new; PyObject *__pyx_n_s_new_time_steps; @@ -3876,6 +3991,10 @@ typedef struct { PyObject *__pyx_n_s_overwrite; PyObject *__pyx_n_u_p; PyObject *__pyx_n_s_pack; + PyObject *__pyx_n_s_param_values; + PyObject *__pyx_kp_u_param_values_2; + PyObject *__pyx_kp_u_param_values__and_idx_values__mu; + PyObject *__pyx_kp_u_param_values__must_be_np_array; PyObject *__pyx_n_s_path; PyObject *__pyx_n_u_pi; PyObject *__pyx_n_u_pi_2; @@ -3911,11 +4030,14 @@ typedef struct { PyObject *__pyx_n_b_res_ineq; PyObject *__pyx_n_b_res_stat; PyObject *__pyx_n_s_reset; + PyObject *__pyx_n_s_reset_qp_solver_mem; PyObject *__pyx_n_u_residuals; PyObject *__pyx_n_u_rti_phase; PyObject *__pyx_n_s_self; PyObject *__pyx_n_s_set; PyObject *__pyx_n_s_set_new_time_steps; + PyObject *__pyx_n_s_set_params_sparse; + PyObject *__pyx_kp_u_set_value_must_be_numpy_array_go; PyObject *__pyx_n_s_setstate; PyObject *__pyx_n_s_setstate_cython; PyObject *__pyx_n_s_shape; @@ -3924,6 +4046,7 @@ typedef struct { PyObject *__pyx_n_u_sl_2; PyObject *__pyx_n_s_solution; PyObject *__pyx_n_s_solve; + PyObject *__pyx_n_s_solve_for_x0; PyObject *__pyx_kp_u_solver_option_must_be_of_type_fl; PyObject *__pyx_kp_u_solver_option_must_be_of_type_in; PyObject *__pyx_kp_u_solver_option_must_be_of_type_st; @@ -3939,6 +4062,7 @@ typedef struct { PyObject *__pyx_n_s_stat_n; PyObject *__pyx_n_u_stat_n; PyObject *__pyx_n_u_statistics; + PyObject *__pyx_n_s_status; PyObject *__pyx_n_s_step; PyObject *__pyx_n_u_step_length; PyObject *__pyx_n_s_stop; @@ -3977,6 +4101,7 @@ typedef struct { PyObject *__pyx_n_u_tol_stat; PyObject *__pyx_n_s_tolist; PyObject *__pyx_n_u_u; + PyObject *__pyx_n_s_u0; PyObject *__pyx_n_u_u_2; PyObject *__pyx_n_u_ubu; PyObject *__pyx_n_u_ubx; @@ -3998,6 +4123,7 @@ typedef struct { PyObject *__pyx_n_b_x; PyObject *__pyx_n_s_x; PyObject *__pyx_n_u_x; + PyObject *__pyx_n_s_x0_bar; PyObject *__pyx_n_u_x_2; PyObject *__pyx_n_u_xdot_guess; PyObject *__pyx_n_u_y_ref; @@ -4005,6 +4131,7 @@ typedef struct { PyObject *__pyx_n_u_yref; PyObject *__pyx_n_u_z; PyObject *__pyx_n_u_z_2; + PyObject *__pyx_n_b_z_guess; PyObject *__pyx_n_u_z_guess; PyObject *__pyx_n_s_zeros; PyObject *__pyx_int_0; @@ -4023,13 +4150,13 @@ typedef struct { PyObject *__pyx_tuple__4; PyObject *__pyx_tuple__8; PyObject *__pyx_tuple__9; - PyObject *__pyx_slice__16; + PyObject *__pyx_slice__18; PyObject *__pyx_tuple__10; PyObject *__pyx_tuple__11; PyObject *__pyx_tuple__12; PyObject *__pyx_tuple__13; - PyObject *__pyx_tuple__17; - PyObject *__pyx_tuple__18; + PyObject *__pyx_tuple__14; + PyObject *__pyx_tuple__15; PyObject *__pyx_tuple__19; PyObject *__pyx_tuple__20; PyObject *__pyx_tuple__21; @@ -4040,8 +4167,8 @@ typedef struct { PyObject *__pyx_tuple__26; PyObject *__pyx_tuple__27; PyObject *__pyx_tuple__28; + PyObject *__pyx_tuple__29; PyObject *__pyx_tuple__30; - PyObject *__pyx_tuple__31; PyObject *__pyx_tuple__32; PyObject *__pyx_tuple__33; PyObject *__pyx_tuple__34; @@ -4050,50 +4177,60 @@ typedef struct { PyObject *__pyx_tuple__37; PyObject *__pyx_tuple__38; PyObject *__pyx_tuple__39; + PyObject *__pyx_tuple__40; PyObject *__pyx_tuple__41; - PyObject *__pyx_tuple__45; - PyObject *__pyx_tuple__47; + PyObject *__pyx_tuple__42; + PyObject *__pyx_tuple__44; + PyObject *__pyx_tuple__46; PyObject *__pyx_tuple__49; PyObject *__pyx_tuple__51; - PyObject *__pyx_tuple__52; + PyObject *__pyx_tuple__53; PyObject *__pyx_tuple__55; PyObject *__pyx_tuple__57; - PyObject *__pyx_tuple__58; + PyObject *__pyx_tuple__59; PyObject *__pyx_tuple__60; - PyObject *__pyx_tuple__62; + PyObject *__pyx_tuple__63; PyObject *__pyx_tuple__65; - PyObject *__pyx_tuple__67; - PyObject *__pyx_tuple__69; - PyObject *__pyx_tuple__71; - PyObject *__pyx_tuple__72; - PyObject *__pyx_tuple__74; + PyObject *__pyx_tuple__66; + PyObject *__pyx_tuple__68; + PyObject *__pyx_tuple__70; + PyObject *__pyx_tuple__73; + PyObject *__pyx_tuple__75; PyObject *__pyx_tuple__77; PyObject *__pyx_tuple__79; + PyObject *__pyx_tuple__80; PyObject *__pyx_tuple__82; - PyObject *__pyx_codeobj__40; - PyObject *__pyx_codeobj__42; + PyObject *__pyx_tuple__85; + PyObject *__pyx_tuple__87; + PyObject *__pyx_tuple__89; + PyObject *__pyx_tuple__92; PyObject *__pyx_codeobj__43; - PyObject *__pyx_codeobj__44; - PyObject *__pyx_codeobj__46; + PyObject *__pyx_codeobj__45; + PyObject *__pyx_codeobj__47; PyObject *__pyx_codeobj__48; PyObject *__pyx_codeobj__50; - PyObject *__pyx_codeobj__53; + PyObject *__pyx_codeobj__52; PyObject *__pyx_codeobj__54; PyObject *__pyx_codeobj__56; - PyObject *__pyx_codeobj__59; + PyObject *__pyx_codeobj__58; PyObject *__pyx_codeobj__61; - PyObject *__pyx_codeobj__63; + PyObject *__pyx_codeobj__62; PyObject *__pyx_codeobj__64; - PyObject *__pyx_codeobj__66; - PyObject *__pyx_codeobj__68; - PyObject *__pyx_codeobj__70; - PyObject *__pyx_codeobj__73; - PyObject *__pyx_codeobj__75; + PyObject *__pyx_codeobj__67; + PyObject *__pyx_codeobj__69; + PyObject *__pyx_codeobj__71; + PyObject *__pyx_codeobj__72; + PyObject *__pyx_codeobj__74; PyObject *__pyx_codeobj__76; PyObject *__pyx_codeobj__78; - PyObject *__pyx_codeobj__80; PyObject *__pyx_codeobj__81; PyObject *__pyx_codeobj__83; + PyObject *__pyx_codeobj__84; + PyObject *__pyx_codeobj__86; + PyObject *__pyx_codeobj__88; + PyObject *__pyx_codeobj__90; + PyObject *__pyx_codeobj__91; + PyObject *__pyx_codeobj__93; } __pyx_mstate; #if CYTHON_USE_MODULE_STATE @@ -4163,6 +4300,7 @@ static int __pyx_m_clear(PyObject *m) { Py_CLEAR(clear_module_state->__pyx_memoryviewslice_type); Py_CLEAR(clear_module_state->__pyx_type___pyx_memoryviewslice); Py_CLEAR(clear_module_state->__pyx_kp_u_); + Py_CLEAR(clear_module_state->__pyx_kp_u_0); Py_CLEAR(clear_module_state->__pyx_n_s_ASCII); Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython); Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython___get_poin); @@ -4179,15 +4317,16 @@ static int __pyx_m_clear(PyObject *m) { Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_constraint_2); Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_cost_set); Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_cost_set_m); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_custom_upd); Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_does_not_s); Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_does_not_s_2); - Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_dynamics_g); Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_eval_param); Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_eval_param_2); Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_eval_param_3); Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_get); Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_get_cost); Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_get_field); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_get_from_q); Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_get_is_an); Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_get_residu); Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_get_stage); @@ -4201,9 +4340,11 @@ static int __pyx_m_clear(PyObject *m) { Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_set_is_not); Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_set_mismat); Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_set_new_ti); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_set_params); Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_solve); Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_solve_argu); Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_solve_argu_2); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_solve_for); Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_store_iter); Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_update_qp); Py_CLEAR(clear_module_state->__pyx_kp_s_All_dimensions_preceding_dimensi); @@ -4218,6 +4359,7 @@ static int __pyx_m_clear(PyObject *m) { Py_CLEAR(clear_module_state->__pyx_n_s_Ellipsis); Py_CLEAR(clear_module_state->__pyx_kp_s_Empty_shape_tuple_for_cython_arr); Py_CLEAR(clear_module_state->__pyx_n_u_F); + Py_CLEAR(clear_module_state->__pyx_kp_u_Got_sizes_idx); Py_CLEAR(clear_module_state->__pyx_n_s_ImportError); Py_CLEAR(clear_module_state->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0); Py_CLEAR(clear_module_state->__pyx_n_s_IndexError); @@ -4243,16 +4385,18 @@ static int __pyx_m_clear(PyObject *m) { Py_CLEAR(clear_module_state->__pyx_kp_s_Unable_to_convert_item_to_object); Py_CLEAR(clear_module_state->__pyx_n_s_ValueError); Py_CLEAR(clear_module_state->__pyx_n_s_View_MemoryView); + Py_CLEAR(clear_module_state->__pyx_kp_u_Warning_acados_ocp_solver_reache); Py_CLEAR(clear_module_state->__pyx_kp_u_Y_m_d_H_M_S_f); - Py_CLEAR(clear_module_state->__pyx_kp_u__14); - Py_CLEAR(clear_module_state->__pyx_n_u__15); + Py_CLEAR(clear_module_state->__pyx_kp_u__16); + Py_CLEAR(clear_module_state->__pyx_n_u__17); Py_CLEAR(clear_module_state->__pyx_kp_u__2); - Py_CLEAR(clear_module_state->__pyx_kp_u__29); Py_CLEAR(clear_module_state->__pyx_n_s__3); + Py_CLEAR(clear_module_state->__pyx_kp_u__31); Py_CLEAR(clear_module_state->__pyx_kp_u__6); Py_CLEAR(clear_module_state->__pyx_kp_u__7); - Py_CLEAR(clear_module_state->__pyx_n_s__84); + Py_CLEAR(clear_module_state->__pyx_n_s__94); Py_CLEAR(clear_module_state->__pyx_n_s_abc); + Py_CLEAR(clear_module_state->__pyx_kp_u_acados_acados_ocp_solver_returne); Py_CLEAR(clear_module_state->__pyx_n_s_acados_template_acados_ocp_solve); Py_CLEAR(clear_module_state->__pyx_n_s_allocate_buffer); Py_CLEAR(clear_module_state->__pyx_n_u_alpha); @@ -4275,11 +4419,18 @@ static int __pyx_m_clear(PyObject *m) { Py_CLEAR(clear_module_state->__pyx_kp_s_collections_abc); Py_CLEAR(clear_module_state->__pyx_n_s_constraints_fields); Py_CLEAR(clear_module_state->__pyx_n_s_constraints_set); + Py_CLEAR(clear_module_state->__pyx_kp_u_constraints_set_value_must_be_nu); Py_CLEAR(clear_module_state->__pyx_kp_s_contiguous_and_direct); Py_CLEAR(clear_module_state->__pyx_kp_s_contiguous_and_indirect); Py_CLEAR(clear_module_state->__pyx_n_s_cost_fields); Py_CLEAR(clear_module_state->__pyx_n_s_cost_set); + Py_CLEAR(clear_module_state->__pyx_kp_u_cost_set_value_must_be_numpy_arr); Py_CLEAR(clear_module_state->__pyx_n_s_count); + Py_CLEAR(clear_module_state->__pyx_n_s_custom_update); + Py_CLEAR(clear_module_state->__pyx_n_u_d); + Py_CLEAR(clear_module_state->__pyx_n_s_data); + Py_CLEAR(clear_module_state->__pyx_n_s_data_2); + Py_CLEAR(clear_module_state->__pyx_n_s_data_len); Py_CLEAR(clear_module_state->__pyx_n_s_datetime); Py_CLEAR(clear_module_state->__pyx_n_s_default); Py_CLEAR(clear_module_state->__pyx_n_s_dict); @@ -4290,7 +4441,6 @@ static int __pyx_m_clear(PyObject *m) { Py_CLEAR(clear_module_state->__pyx_n_s_dtype); Py_CLEAR(clear_module_state->__pyx_n_s_dtype_is_object); Py_CLEAR(clear_module_state->__pyx_n_s_dump); - Py_CLEAR(clear_module_state->__pyx_n_s_dynamics_get); Py_CLEAR(clear_module_state->__pyx_kp_u_enable); Py_CLEAR(clear_module_state->__pyx_n_s_encode); Py_CLEAR(clear_module_state->__pyx_n_s_enter); @@ -4316,6 +4466,7 @@ static int __pyx_m_clear(PyObject *m) { Py_CLEAR(clear_module_state->__pyx_kp_u_gc); Py_CLEAR(clear_module_state->__pyx_n_s_get); Py_CLEAR(clear_module_state->__pyx_n_s_get_cost); + Py_CLEAR(clear_module_state->__pyx_n_s_get_from_qp_in); Py_CLEAR(clear_module_state->__pyx_n_s_get_pointers_solver); Py_CLEAR(clear_module_state->__pyx_n_s_get_residuals); Py_CLEAR(clear_module_state->__pyx_n_s_get_stat_double); @@ -4329,13 +4480,17 @@ static int __pyx_m_clear(PyObject *m) { Py_CLEAR(clear_module_state->__pyx_kp_u_got); Py_CLEAR(clear_module_state->__pyx_kp_u_got_differing_extents_in_dimensi); Py_CLEAR(clear_module_state->__pyx_n_s_i); + Py_CLEAR(clear_module_state->__pyx_n_s_i_string); Py_CLEAR(clear_module_state->__pyx_n_s_id); + Py_CLEAR(clear_module_state->__pyx_n_s_idx); + Py_CLEAR(clear_module_state->__pyx_n_s_idx_values); Py_CLEAR(clear_module_state->__pyx_n_s_import); Py_CLEAR(clear_module_state->__pyx_n_s_indent); Py_CLEAR(clear_module_state->__pyx_n_s_index); Py_CLEAR(clear_module_state->__pyx_n_u_initialize_t_slacks); Py_CLEAR(clear_module_state->__pyx_n_s_initializing); Py_CLEAR(clear_module_state->__pyx_n_s_int); + Py_CLEAR(clear_module_state->__pyx_n_s_int32); Py_CLEAR(clear_module_state->__pyx_n_s_int_fields); Py_CLEAR(clear_module_state->__pyx_n_s_int_value); Py_CLEAR(clear_module_state->__pyx_n_s_is_coroutine); @@ -4347,8 +4502,10 @@ static int __pyx_m_clear(PyObject *m) { Py_CLEAR(clear_module_state->__pyx_n_s_join); Py_CLEAR(clear_module_state->__pyx_n_s_json); Py_CLEAR(clear_module_state->__pyx_kp_u_json_2); + Py_CLEAR(clear_module_state->__pyx_n_s_k); Py_CLEAR(clear_module_state->__pyx_n_s_key); Py_CLEAR(clear_module_state->__pyx_n_s_keys); + Py_CLEAR(clear_module_state->__pyx_n_s_lN); Py_CLEAR(clear_module_state->__pyx_n_u_lam); Py_CLEAR(clear_module_state->__pyx_n_u_lam_2); Py_CLEAR(clear_module_state->__pyx_n_u_lbu); @@ -4366,8 +4523,10 @@ static int __pyx_m_clear(PyObject *m) { Py_CLEAR(clear_module_state->__pyx_n_s_model_name); Py_CLEAR(clear_module_state->__pyx_n_s_msg); Py_CLEAR(clear_module_state->__pyx_n_s_n); + Py_CLEAR(clear_module_state->__pyx_n_s_n_update); Py_CLEAR(clear_module_state->__pyx_n_s_name); Py_CLEAR(clear_module_state->__pyx_n_s_name_2); + Py_CLEAR(clear_module_state->__pyx_n_s_ndarray); Py_CLEAR(clear_module_state->__pyx_n_s_ndim); Py_CLEAR(clear_module_state->__pyx_n_s_new); Py_CLEAR(clear_module_state->__pyx_n_s_new_time_steps); @@ -4389,6 +4548,10 @@ static int __pyx_m_clear(PyObject *m) { Py_CLEAR(clear_module_state->__pyx_n_s_overwrite); Py_CLEAR(clear_module_state->__pyx_n_u_p); Py_CLEAR(clear_module_state->__pyx_n_s_pack); + Py_CLEAR(clear_module_state->__pyx_n_s_param_values); + Py_CLEAR(clear_module_state->__pyx_kp_u_param_values_2); + Py_CLEAR(clear_module_state->__pyx_kp_u_param_values__and_idx_values__mu); + Py_CLEAR(clear_module_state->__pyx_kp_u_param_values__must_be_np_array); Py_CLEAR(clear_module_state->__pyx_n_s_path); Py_CLEAR(clear_module_state->__pyx_n_u_pi); Py_CLEAR(clear_module_state->__pyx_n_u_pi_2); @@ -4424,11 +4587,14 @@ static int __pyx_m_clear(PyObject *m) { Py_CLEAR(clear_module_state->__pyx_n_b_res_ineq); Py_CLEAR(clear_module_state->__pyx_n_b_res_stat); Py_CLEAR(clear_module_state->__pyx_n_s_reset); + Py_CLEAR(clear_module_state->__pyx_n_s_reset_qp_solver_mem); Py_CLEAR(clear_module_state->__pyx_n_u_residuals); Py_CLEAR(clear_module_state->__pyx_n_u_rti_phase); Py_CLEAR(clear_module_state->__pyx_n_s_self); Py_CLEAR(clear_module_state->__pyx_n_s_set); Py_CLEAR(clear_module_state->__pyx_n_s_set_new_time_steps); + Py_CLEAR(clear_module_state->__pyx_n_s_set_params_sparse); + Py_CLEAR(clear_module_state->__pyx_kp_u_set_value_must_be_numpy_array_go); Py_CLEAR(clear_module_state->__pyx_n_s_setstate); Py_CLEAR(clear_module_state->__pyx_n_s_setstate_cython); Py_CLEAR(clear_module_state->__pyx_n_s_shape); @@ -4437,6 +4603,7 @@ static int __pyx_m_clear(PyObject *m) { Py_CLEAR(clear_module_state->__pyx_n_u_sl_2); Py_CLEAR(clear_module_state->__pyx_n_s_solution); Py_CLEAR(clear_module_state->__pyx_n_s_solve); + Py_CLEAR(clear_module_state->__pyx_n_s_solve_for_x0); Py_CLEAR(clear_module_state->__pyx_kp_u_solver_option_must_be_of_type_fl); Py_CLEAR(clear_module_state->__pyx_kp_u_solver_option_must_be_of_type_in); Py_CLEAR(clear_module_state->__pyx_kp_u_solver_option_must_be_of_type_st); @@ -4452,6 +4619,7 @@ static int __pyx_m_clear(PyObject *m) { Py_CLEAR(clear_module_state->__pyx_n_s_stat_n); Py_CLEAR(clear_module_state->__pyx_n_u_stat_n); Py_CLEAR(clear_module_state->__pyx_n_u_statistics); + Py_CLEAR(clear_module_state->__pyx_n_s_status); Py_CLEAR(clear_module_state->__pyx_n_s_step); Py_CLEAR(clear_module_state->__pyx_n_u_step_length); Py_CLEAR(clear_module_state->__pyx_n_s_stop); @@ -4490,6 +4658,7 @@ static int __pyx_m_clear(PyObject *m) { Py_CLEAR(clear_module_state->__pyx_n_u_tol_stat); Py_CLEAR(clear_module_state->__pyx_n_s_tolist); Py_CLEAR(clear_module_state->__pyx_n_u_u); + Py_CLEAR(clear_module_state->__pyx_n_s_u0); Py_CLEAR(clear_module_state->__pyx_n_u_u_2); Py_CLEAR(clear_module_state->__pyx_n_u_ubu); Py_CLEAR(clear_module_state->__pyx_n_u_ubx); @@ -4511,6 +4680,7 @@ static int __pyx_m_clear(PyObject *m) { Py_CLEAR(clear_module_state->__pyx_n_b_x); Py_CLEAR(clear_module_state->__pyx_n_s_x); Py_CLEAR(clear_module_state->__pyx_n_u_x); + Py_CLEAR(clear_module_state->__pyx_n_s_x0_bar); Py_CLEAR(clear_module_state->__pyx_n_u_x_2); Py_CLEAR(clear_module_state->__pyx_n_u_xdot_guess); Py_CLEAR(clear_module_state->__pyx_n_u_y_ref); @@ -4518,6 +4688,7 @@ static int __pyx_m_clear(PyObject *m) { Py_CLEAR(clear_module_state->__pyx_n_u_yref); Py_CLEAR(clear_module_state->__pyx_n_u_z); Py_CLEAR(clear_module_state->__pyx_n_u_z_2); + Py_CLEAR(clear_module_state->__pyx_n_b_z_guess); Py_CLEAR(clear_module_state->__pyx_n_u_z_guess); Py_CLEAR(clear_module_state->__pyx_n_s_zeros); Py_CLEAR(clear_module_state->__pyx_int_0); @@ -4536,13 +4707,13 @@ static int __pyx_m_clear(PyObject *m) { Py_CLEAR(clear_module_state->__pyx_tuple__4); Py_CLEAR(clear_module_state->__pyx_tuple__8); Py_CLEAR(clear_module_state->__pyx_tuple__9); - Py_CLEAR(clear_module_state->__pyx_slice__16); + Py_CLEAR(clear_module_state->__pyx_slice__18); Py_CLEAR(clear_module_state->__pyx_tuple__10); Py_CLEAR(clear_module_state->__pyx_tuple__11); Py_CLEAR(clear_module_state->__pyx_tuple__12); Py_CLEAR(clear_module_state->__pyx_tuple__13); - Py_CLEAR(clear_module_state->__pyx_tuple__17); - Py_CLEAR(clear_module_state->__pyx_tuple__18); + Py_CLEAR(clear_module_state->__pyx_tuple__14); + Py_CLEAR(clear_module_state->__pyx_tuple__15); Py_CLEAR(clear_module_state->__pyx_tuple__19); Py_CLEAR(clear_module_state->__pyx_tuple__20); Py_CLEAR(clear_module_state->__pyx_tuple__21); @@ -4553,8 +4724,8 @@ static int __pyx_m_clear(PyObject *m) { Py_CLEAR(clear_module_state->__pyx_tuple__26); Py_CLEAR(clear_module_state->__pyx_tuple__27); Py_CLEAR(clear_module_state->__pyx_tuple__28); + Py_CLEAR(clear_module_state->__pyx_tuple__29); Py_CLEAR(clear_module_state->__pyx_tuple__30); - Py_CLEAR(clear_module_state->__pyx_tuple__31); Py_CLEAR(clear_module_state->__pyx_tuple__32); Py_CLEAR(clear_module_state->__pyx_tuple__33); Py_CLEAR(clear_module_state->__pyx_tuple__34); @@ -4563,50 +4734,60 @@ static int __pyx_m_clear(PyObject *m) { Py_CLEAR(clear_module_state->__pyx_tuple__37); Py_CLEAR(clear_module_state->__pyx_tuple__38); Py_CLEAR(clear_module_state->__pyx_tuple__39); + Py_CLEAR(clear_module_state->__pyx_tuple__40); Py_CLEAR(clear_module_state->__pyx_tuple__41); - Py_CLEAR(clear_module_state->__pyx_tuple__45); - Py_CLEAR(clear_module_state->__pyx_tuple__47); + Py_CLEAR(clear_module_state->__pyx_tuple__42); + Py_CLEAR(clear_module_state->__pyx_tuple__44); + Py_CLEAR(clear_module_state->__pyx_tuple__46); Py_CLEAR(clear_module_state->__pyx_tuple__49); Py_CLEAR(clear_module_state->__pyx_tuple__51); - Py_CLEAR(clear_module_state->__pyx_tuple__52); + Py_CLEAR(clear_module_state->__pyx_tuple__53); Py_CLEAR(clear_module_state->__pyx_tuple__55); Py_CLEAR(clear_module_state->__pyx_tuple__57); - Py_CLEAR(clear_module_state->__pyx_tuple__58); + Py_CLEAR(clear_module_state->__pyx_tuple__59); Py_CLEAR(clear_module_state->__pyx_tuple__60); - Py_CLEAR(clear_module_state->__pyx_tuple__62); + Py_CLEAR(clear_module_state->__pyx_tuple__63); Py_CLEAR(clear_module_state->__pyx_tuple__65); - Py_CLEAR(clear_module_state->__pyx_tuple__67); - Py_CLEAR(clear_module_state->__pyx_tuple__69); - Py_CLEAR(clear_module_state->__pyx_tuple__71); - Py_CLEAR(clear_module_state->__pyx_tuple__72); - Py_CLEAR(clear_module_state->__pyx_tuple__74); + Py_CLEAR(clear_module_state->__pyx_tuple__66); + Py_CLEAR(clear_module_state->__pyx_tuple__68); + Py_CLEAR(clear_module_state->__pyx_tuple__70); + Py_CLEAR(clear_module_state->__pyx_tuple__73); + Py_CLEAR(clear_module_state->__pyx_tuple__75); Py_CLEAR(clear_module_state->__pyx_tuple__77); Py_CLEAR(clear_module_state->__pyx_tuple__79); + Py_CLEAR(clear_module_state->__pyx_tuple__80); Py_CLEAR(clear_module_state->__pyx_tuple__82); - Py_CLEAR(clear_module_state->__pyx_codeobj__40); - Py_CLEAR(clear_module_state->__pyx_codeobj__42); + Py_CLEAR(clear_module_state->__pyx_tuple__85); + Py_CLEAR(clear_module_state->__pyx_tuple__87); + Py_CLEAR(clear_module_state->__pyx_tuple__89); + Py_CLEAR(clear_module_state->__pyx_tuple__92); Py_CLEAR(clear_module_state->__pyx_codeobj__43); - Py_CLEAR(clear_module_state->__pyx_codeobj__44); - Py_CLEAR(clear_module_state->__pyx_codeobj__46); + Py_CLEAR(clear_module_state->__pyx_codeobj__45); + Py_CLEAR(clear_module_state->__pyx_codeobj__47); Py_CLEAR(clear_module_state->__pyx_codeobj__48); Py_CLEAR(clear_module_state->__pyx_codeobj__50); - Py_CLEAR(clear_module_state->__pyx_codeobj__53); + Py_CLEAR(clear_module_state->__pyx_codeobj__52); Py_CLEAR(clear_module_state->__pyx_codeobj__54); Py_CLEAR(clear_module_state->__pyx_codeobj__56); - Py_CLEAR(clear_module_state->__pyx_codeobj__59); + Py_CLEAR(clear_module_state->__pyx_codeobj__58); Py_CLEAR(clear_module_state->__pyx_codeobj__61); - Py_CLEAR(clear_module_state->__pyx_codeobj__63); + Py_CLEAR(clear_module_state->__pyx_codeobj__62); Py_CLEAR(clear_module_state->__pyx_codeobj__64); - Py_CLEAR(clear_module_state->__pyx_codeobj__66); - Py_CLEAR(clear_module_state->__pyx_codeobj__68); - Py_CLEAR(clear_module_state->__pyx_codeobj__70); - Py_CLEAR(clear_module_state->__pyx_codeobj__73); - Py_CLEAR(clear_module_state->__pyx_codeobj__75); + Py_CLEAR(clear_module_state->__pyx_codeobj__67); + Py_CLEAR(clear_module_state->__pyx_codeobj__69); + Py_CLEAR(clear_module_state->__pyx_codeobj__71); + Py_CLEAR(clear_module_state->__pyx_codeobj__72); + Py_CLEAR(clear_module_state->__pyx_codeobj__74); Py_CLEAR(clear_module_state->__pyx_codeobj__76); Py_CLEAR(clear_module_state->__pyx_codeobj__78); - Py_CLEAR(clear_module_state->__pyx_codeobj__80); Py_CLEAR(clear_module_state->__pyx_codeobj__81); Py_CLEAR(clear_module_state->__pyx_codeobj__83); + Py_CLEAR(clear_module_state->__pyx_codeobj__84); + Py_CLEAR(clear_module_state->__pyx_codeobj__86); + Py_CLEAR(clear_module_state->__pyx_codeobj__88); + Py_CLEAR(clear_module_state->__pyx_codeobj__90); + Py_CLEAR(clear_module_state->__pyx_codeobj__91); + Py_CLEAR(clear_module_state->__pyx_codeobj__93); return 0; } #endif @@ -4654,6 +4835,7 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { Py_VISIT(traverse_module_state->__pyx_memoryviewslice_type); Py_VISIT(traverse_module_state->__pyx_type___pyx_memoryviewslice); Py_VISIT(traverse_module_state->__pyx_kp_u_); + Py_VISIT(traverse_module_state->__pyx_kp_u_0); Py_VISIT(traverse_module_state->__pyx_n_s_ASCII); Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython); Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython___get_poin); @@ -4670,15 +4852,16 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_constraint_2); Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_cost_set); Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_cost_set_m); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_custom_upd); Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_does_not_s); Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_does_not_s_2); - Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_dynamics_g); Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_eval_param); Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_eval_param_2); Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_eval_param_3); Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_get); Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_get_cost); Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_get_field); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_get_from_q); Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_get_is_an); Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_get_residu); Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_get_stage); @@ -4692,9 +4875,11 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_set_is_not); Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_set_mismat); Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_set_new_ti); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_set_params); Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_solve); Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_solve_argu); Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_solve_argu_2); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_solve_for); Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_store_iter); Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_update_qp); Py_VISIT(traverse_module_state->__pyx_kp_s_All_dimensions_preceding_dimensi); @@ -4709,6 +4894,7 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { Py_VISIT(traverse_module_state->__pyx_n_s_Ellipsis); Py_VISIT(traverse_module_state->__pyx_kp_s_Empty_shape_tuple_for_cython_arr); Py_VISIT(traverse_module_state->__pyx_n_u_F); + Py_VISIT(traverse_module_state->__pyx_kp_u_Got_sizes_idx); Py_VISIT(traverse_module_state->__pyx_n_s_ImportError); Py_VISIT(traverse_module_state->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0); Py_VISIT(traverse_module_state->__pyx_n_s_IndexError); @@ -4734,16 +4920,18 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { Py_VISIT(traverse_module_state->__pyx_kp_s_Unable_to_convert_item_to_object); Py_VISIT(traverse_module_state->__pyx_n_s_ValueError); Py_VISIT(traverse_module_state->__pyx_n_s_View_MemoryView); + Py_VISIT(traverse_module_state->__pyx_kp_u_Warning_acados_ocp_solver_reache); Py_VISIT(traverse_module_state->__pyx_kp_u_Y_m_d_H_M_S_f); - Py_VISIT(traverse_module_state->__pyx_kp_u__14); - Py_VISIT(traverse_module_state->__pyx_n_u__15); + Py_VISIT(traverse_module_state->__pyx_kp_u__16); + Py_VISIT(traverse_module_state->__pyx_n_u__17); Py_VISIT(traverse_module_state->__pyx_kp_u__2); - Py_VISIT(traverse_module_state->__pyx_kp_u__29); Py_VISIT(traverse_module_state->__pyx_n_s__3); + Py_VISIT(traverse_module_state->__pyx_kp_u__31); Py_VISIT(traverse_module_state->__pyx_kp_u__6); Py_VISIT(traverse_module_state->__pyx_kp_u__7); - Py_VISIT(traverse_module_state->__pyx_n_s__84); + Py_VISIT(traverse_module_state->__pyx_n_s__94); Py_VISIT(traverse_module_state->__pyx_n_s_abc); + Py_VISIT(traverse_module_state->__pyx_kp_u_acados_acados_ocp_solver_returne); Py_VISIT(traverse_module_state->__pyx_n_s_acados_template_acados_ocp_solve); Py_VISIT(traverse_module_state->__pyx_n_s_allocate_buffer); Py_VISIT(traverse_module_state->__pyx_n_u_alpha); @@ -4766,11 +4954,18 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { Py_VISIT(traverse_module_state->__pyx_kp_s_collections_abc); Py_VISIT(traverse_module_state->__pyx_n_s_constraints_fields); Py_VISIT(traverse_module_state->__pyx_n_s_constraints_set); + Py_VISIT(traverse_module_state->__pyx_kp_u_constraints_set_value_must_be_nu); Py_VISIT(traverse_module_state->__pyx_kp_s_contiguous_and_direct); Py_VISIT(traverse_module_state->__pyx_kp_s_contiguous_and_indirect); Py_VISIT(traverse_module_state->__pyx_n_s_cost_fields); Py_VISIT(traverse_module_state->__pyx_n_s_cost_set); + Py_VISIT(traverse_module_state->__pyx_kp_u_cost_set_value_must_be_numpy_arr); Py_VISIT(traverse_module_state->__pyx_n_s_count); + Py_VISIT(traverse_module_state->__pyx_n_s_custom_update); + Py_VISIT(traverse_module_state->__pyx_n_u_d); + Py_VISIT(traverse_module_state->__pyx_n_s_data); + Py_VISIT(traverse_module_state->__pyx_n_s_data_2); + Py_VISIT(traverse_module_state->__pyx_n_s_data_len); Py_VISIT(traverse_module_state->__pyx_n_s_datetime); Py_VISIT(traverse_module_state->__pyx_n_s_default); Py_VISIT(traverse_module_state->__pyx_n_s_dict); @@ -4781,7 +4976,6 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { Py_VISIT(traverse_module_state->__pyx_n_s_dtype); Py_VISIT(traverse_module_state->__pyx_n_s_dtype_is_object); Py_VISIT(traverse_module_state->__pyx_n_s_dump); - Py_VISIT(traverse_module_state->__pyx_n_s_dynamics_get); Py_VISIT(traverse_module_state->__pyx_kp_u_enable); Py_VISIT(traverse_module_state->__pyx_n_s_encode); Py_VISIT(traverse_module_state->__pyx_n_s_enter); @@ -4807,6 +5001,7 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { Py_VISIT(traverse_module_state->__pyx_kp_u_gc); Py_VISIT(traverse_module_state->__pyx_n_s_get); Py_VISIT(traverse_module_state->__pyx_n_s_get_cost); + Py_VISIT(traverse_module_state->__pyx_n_s_get_from_qp_in); Py_VISIT(traverse_module_state->__pyx_n_s_get_pointers_solver); Py_VISIT(traverse_module_state->__pyx_n_s_get_residuals); Py_VISIT(traverse_module_state->__pyx_n_s_get_stat_double); @@ -4820,13 +5015,17 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { Py_VISIT(traverse_module_state->__pyx_kp_u_got); Py_VISIT(traverse_module_state->__pyx_kp_u_got_differing_extents_in_dimensi); Py_VISIT(traverse_module_state->__pyx_n_s_i); + Py_VISIT(traverse_module_state->__pyx_n_s_i_string); Py_VISIT(traverse_module_state->__pyx_n_s_id); + Py_VISIT(traverse_module_state->__pyx_n_s_idx); + Py_VISIT(traverse_module_state->__pyx_n_s_idx_values); Py_VISIT(traverse_module_state->__pyx_n_s_import); Py_VISIT(traverse_module_state->__pyx_n_s_indent); Py_VISIT(traverse_module_state->__pyx_n_s_index); Py_VISIT(traverse_module_state->__pyx_n_u_initialize_t_slacks); Py_VISIT(traverse_module_state->__pyx_n_s_initializing); Py_VISIT(traverse_module_state->__pyx_n_s_int); + Py_VISIT(traverse_module_state->__pyx_n_s_int32); Py_VISIT(traverse_module_state->__pyx_n_s_int_fields); Py_VISIT(traverse_module_state->__pyx_n_s_int_value); Py_VISIT(traverse_module_state->__pyx_n_s_is_coroutine); @@ -4838,8 +5037,10 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { Py_VISIT(traverse_module_state->__pyx_n_s_join); Py_VISIT(traverse_module_state->__pyx_n_s_json); Py_VISIT(traverse_module_state->__pyx_kp_u_json_2); + Py_VISIT(traverse_module_state->__pyx_n_s_k); Py_VISIT(traverse_module_state->__pyx_n_s_key); Py_VISIT(traverse_module_state->__pyx_n_s_keys); + Py_VISIT(traverse_module_state->__pyx_n_s_lN); Py_VISIT(traverse_module_state->__pyx_n_u_lam); Py_VISIT(traverse_module_state->__pyx_n_u_lam_2); Py_VISIT(traverse_module_state->__pyx_n_u_lbu); @@ -4857,8 +5058,10 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { Py_VISIT(traverse_module_state->__pyx_n_s_model_name); Py_VISIT(traverse_module_state->__pyx_n_s_msg); Py_VISIT(traverse_module_state->__pyx_n_s_n); + Py_VISIT(traverse_module_state->__pyx_n_s_n_update); Py_VISIT(traverse_module_state->__pyx_n_s_name); Py_VISIT(traverse_module_state->__pyx_n_s_name_2); + Py_VISIT(traverse_module_state->__pyx_n_s_ndarray); Py_VISIT(traverse_module_state->__pyx_n_s_ndim); Py_VISIT(traverse_module_state->__pyx_n_s_new); Py_VISIT(traverse_module_state->__pyx_n_s_new_time_steps); @@ -4880,6 +5083,10 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { Py_VISIT(traverse_module_state->__pyx_n_s_overwrite); Py_VISIT(traverse_module_state->__pyx_n_u_p); Py_VISIT(traverse_module_state->__pyx_n_s_pack); + Py_VISIT(traverse_module_state->__pyx_n_s_param_values); + Py_VISIT(traverse_module_state->__pyx_kp_u_param_values_2); + Py_VISIT(traverse_module_state->__pyx_kp_u_param_values__and_idx_values__mu); + Py_VISIT(traverse_module_state->__pyx_kp_u_param_values__must_be_np_array); Py_VISIT(traverse_module_state->__pyx_n_s_path); Py_VISIT(traverse_module_state->__pyx_n_u_pi); Py_VISIT(traverse_module_state->__pyx_n_u_pi_2); @@ -4915,11 +5122,14 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { Py_VISIT(traverse_module_state->__pyx_n_b_res_ineq); Py_VISIT(traverse_module_state->__pyx_n_b_res_stat); Py_VISIT(traverse_module_state->__pyx_n_s_reset); + Py_VISIT(traverse_module_state->__pyx_n_s_reset_qp_solver_mem); Py_VISIT(traverse_module_state->__pyx_n_u_residuals); Py_VISIT(traverse_module_state->__pyx_n_u_rti_phase); Py_VISIT(traverse_module_state->__pyx_n_s_self); Py_VISIT(traverse_module_state->__pyx_n_s_set); Py_VISIT(traverse_module_state->__pyx_n_s_set_new_time_steps); + Py_VISIT(traverse_module_state->__pyx_n_s_set_params_sparse); + Py_VISIT(traverse_module_state->__pyx_kp_u_set_value_must_be_numpy_array_go); Py_VISIT(traverse_module_state->__pyx_n_s_setstate); Py_VISIT(traverse_module_state->__pyx_n_s_setstate_cython); Py_VISIT(traverse_module_state->__pyx_n_s_shape); @@ -4928,6 +5138,7 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { Py_VISIT(traverse_module_state->__pyx_n_u_sl_2); Py_VISIT(traverse_module_state->__pyx_n_s_solution); Py_VISIT(traverse_module_state->__pyx_n_s_solve); + Py_VISIT(traverse_module_state->__pyx_n_s_solve_for_x0); Py_VISIT(traverse_module_state->__pyx_kp_u_solver_option_must_be_of_type_fl); Py_VISIT(traverse_module_state->__pyx_kp_u_solver_option_must_be_of_type_in); Py_VISIT(traverse_module_state->__pyx_kp_u_solver_option_must_be_of_type_st); @@ -4943,6 +5154,7 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { Py_VISIT(traverse_module_state->__pyx_n_s_stat_n); Py_VISIT(traverse_module_state->__pyx_n_u_stat_n); Py_VISIT(traverse_module_state->__pyx_n_u_statistics); + Py_VISIT(traverse_module_state->__pyx_n_s_status); Py_VISIT(traverse_module_state->__pyx_n_s_step); Py_VISIT(traverse_module_state->__pyx_n_u_step_length); Py_VISIT(traverse_module_state->__pyx_n_s_stop); @@ -4981,6 +5193,7 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { Py_VISIT(traverse_module_state->__pyx_n_u_tol_stat); Py_VISIT(traverse_module_state->__pyx_n_s_tolist); Py_VISIT(traverse_module_state->__pyx_n_u_u); + Py_VISIT(traverse_module_state->__pyx_n_s_u0); Py_VISIT(traverse_module_state->__pyx_n_u_u_2); Py_VISIT(traverse_module_state->__pyx_n_u_ubu); Py_VISIT(traverse_module_state->__pyx_n_u_ubx); @@ -5002,6 +5215,7 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { Py_VISIT(traverse_module_state->__pyx_n_b_x); Py_VISIT(traverse_module_state->__pyx_n_s_x); Py_VISIT(traverse_module_state->__pyx_n_u_x); + Py_VISIT(traverse_module_state->__pyx_n_s_x0_bar); Py_VISIT(traverse_module_state->__pyx_n_u_x_2); Py_VISIT(traverse_module_state->__pyx_n_u_xdot_guess); Py_VISIT(traverse_module_state->__pyx_n_u_y_ref); @@ -5009,6 +5223,7 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { Py_VISIT(traverse_module_state->__pyx_n_u_yref); Py_VISIT(traverse_module_state->__pyx_n_u_z); Py_VISIT(traverse_module_state->__pyx_n_u_z_2); + Py_VISIT(traverse_module_state->__pyx_n_b_z_guess); Py_VISIT(traverse_module_state->__pyx_n_u_z_guess); Py_VISIT(traverse_module_state->__pyx_n_s_zeros); Py_VISIT(traverse_module_state->__pyx_int_0); @@ -5027,13 +5242,13 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { Py_VISIT(traverse_module_state->__pyx_tuple__4); Py_VISIT(traverse_module_state->__pyx_tuple__8); Py_VISIT(traverse_module_state->__pyx_tuple__9); - Py_VISIT(traverse_module_state->__pyx_slice__16); + Py_VISIT(traverse_module_state->__pyx_slice__18); Py_VISIT(traverse_module_state->__pyx_tuple__10); Py_VISIT(traverse_module_state->__pyx_tuple__11); Py_VISIT(traverse_module_state->__pyx_tuple__12); Py_VISIT(traverse_module_state->__pyx_tuple__13); - Py_VISIT(traverse_module_state->__pyx_tuple__17); - Py_VISIT(traverse_module_state->__pyx_tuple__18); + Py_VISIT(traverse_module_state->__pyx_tuple__14); + Py_VISIT(traverse_module_state->__pyx_tuple__15); Py_VISIT(traverse_module_state->__pyx_tuple__19); Py_VISIT(traverse_module_state->__pyx_tuple__20); Py_VISIT(traverse_module_state->__pyx_tuple__21); @@ -5044,8 +5259,8 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { Py_VISIT(traverse_module_state->__pyx_tuple__26); Py_VISIT(traverse_module_state->__pyx_tuple__27); Py_VISIT(traverse_module_state->__pyx_tuple__28); + Py_VISIT(traverse_module_state->__pyx_tuple__29); Py_VISIT(traverse_module_state->__pyx_tuple__30); - Py_VISIT(traverse_module_state->__pyx_tuple__31); Py_VISIT(traverse_module_state->__pyx_tuple__32); Py_VISIT(traverse_module_state->__pyx_tuple__33); Py_VISIT(traverse_module_state->__pyx_tuple__34); @@ -5054,50 +5269,60 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { Py_VISIT(traverse_module_state->__pyx_tuple__37); Py_VISIT(traverse_module_state->__pyx_tuple__38); Py_VISIT(traverse_module_state->__pyx_tuple__39); + Py_VISIT(traverse_module_state->__pyx_tuple__40); Py_VISIT(traverse_module_state->__pyx_tuple__41); - Py_VISIT(traverse_module_state->__pyx_tuple__45); - Py_VISIT(traverse_module_state->__pyx_tuple__47); + Py_VISIT(traverse_module_state->__pyx_tuple__42); + Py_VISIT(traverse_module_state->__pyx_tuple__44); + Py_VISIT(traverse_module_state->__pyx_tuple__46); Py_VISIT(traverse_module_state->__pyx_tuple__49); Py_VISIT(traverse_module_state->__pyx_tuple__51); - Py_VISIT(traverse_module_state->__pyx_tuple__52); + Py_VISIT(traverse_module_state->__pyx_tuple__53); Py_VISIT(traverse_module_state->__pyx_tuple__55); Py_VISIT(traverse_module_state->__pyx_tuple__57); - Py_VISIT(traverse_module_state->__pyx_tuple__58); + Py_VISIT(traverse_module_state->__pyx_tuple__59); Py_VISIT(traverse_module_state->__pyx_tuple__60); - Py_VISIT(traverse_module_state->__pyx_tuple__62); + Py_VISIT(traverse_module_state->__pyx_tuple__63); Py_VISIT(traverse_module_state->__pyx_tuple__65); - Py_VISIT(traverse_module_state->__pyx_tuple__67); - Py_VISIT(traverse_module_state->__pyx_tuple__69); - Py_VISIT(traverse_module_state->__pyx_tuple__71); - Py_VISIT(traverse_module_state->__pyx_tuple__72); - Py_VISIT(traverse_module_state->__pyx_tuple__74); + Py_VISIT(traverse_module_state->__pyx_tuple__66); + Py_VISIT(traverse_module_state->__pyx_tuple__68); + Py_VISIT(traverse_module_state->__pyx_tuple__70); + Py_VISIT(traverse_module_state->__pyx_tuple__73); + Py_VISIT(traverse_module_state->__pyx_tuple__75); Py_VISIT(traverse_module_state->__pyx_tuple__77); Py_VISIT(traverse_module_state->__pyx_tuple__79); + Py_VISIT(traverse_module_state->__pyx_tuple__80); Py_VISIT(traverse_module_state->__pyx_tuple__82); - Py_VISIT(traverse_module_state->__pyx_codeobj__40); - Py_VISIT(traverse_module_state->__pyx_codeobj__42); + Py_VISIT(traverse_module_state->__pyx_tuple__85); + Py_VISIT(traverse_module_state->__pyx_tuple__87); + Py_VISIT(traverse_module_state->__pyx_tuple__89); + Py_VISIT(traverse_module_state->__pyx_tuple__92); Py_VISIT(traverse_module_state->__pyx_codeobj__43); - Py_VISIT(traverse_module_state->__pyx_codeobj__44); - Py_VISIT(traverse_module_state->__pyx_codeobj__46); + Py_VISIT(traverse_module_state->__pyx_codeobj__45); + Py_VISIT(traverse_module_state->__pyx_codeobj__47); Py_VISIT(traverse_module_state->__pyx_codeobj__48); Py_VISIT(traverse_module_state->__pyx_codeobj__50); - Py_VISIT(traverse_module_state->__pyx_codeobj__53); + Py_VISIT(traverse_module_state->__pyx_codeobj__52); Py_VISIT(traverse_module_state->__pyx_codeobj__54); Py_VISIT(traverse_module_state->__pyx_codeobj__56); - Py_VISIT(traverse_module_state->__pyx_codeobj__59); + Py_VISIT(traverse_module_state->__pyx_codeobj__58); Py_VISIT(traverse_module_state->__pyx_codeobj__61); - Py_VISIT(traverse_module_state->__pyx_codeobj__63); + Py_VISIT(traverse_module_state->__pyx_codeobj__62); Py_VISIT(traverse_module_state->__pyx_codeobj__64); - Py_VISIT(traverse_module_state->__pyx_codeobj__66); - Py_VISIT(traverse_module_state->__pyx_codeobj__68); - Py_VISIT(traverse_module_state->__pyx_codeobj__70); - Py_VISIT(traverse_module_state->__pyx_codeobj__73); - Py_VISIT(traverse_module_state->__pyx_codeobj__75); + Py_VISIT(traverse_module_state->__pyx_codeobj__67); + Py_VISIT(traverse_module_state->__pyx_codeobj__69); + Py_VISIT(traverse_module_state->__pyx_codeobj__71); + Py_VISIT(traverse_module_state->__pyx_codeobj__72); + Py_VISIT(traverse_module_state->__pyx_codeobj__74); Py_VISIT(traverse_module_state->__pyx_codeobj__76); Py_VISIT(traverse_module_state->__pyx_codeobj__78); - Py_VISIT(traverse_module_state->__pyx_codeobj__80); Py_VISIT(traverse_module_state->__pyx_codeobj__81); Py_VISIT(traverse_module_state->__pyx_codeobj__83); + Py_VISIT(traverse_module_state->__pyx_codeobj__84); + Py_VISIT(traverse_module_state->__pyx_codeobj__86); + Py_VISIT(traverse_module_state->__pyx_codeobj__88); + Py_VISIT(traverse_module_state->__pyx_codeobj__90); + Py_VISIT(traverse_module_state->__pyx_codeobj__91); + Py_VISIT(traverse_module_state->__pyx_codeobj__93); return 0; } #endif @@ -5185,6 +5410,7 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #define __pyx_memoryview_type __pyx_mstate_global->__pyx_memoryview_type #define __pyx_memoryviewslice_type __pyx_mstate_global->__pyx_memoryviewslice_type #define __pyx_kp_u_ __pyx_mstate_global->__pyx_kp_u_ +#define __pyx_kp_u_0 __pyx_mstate_global->__pyx_kp_u_0 #define __pyx_n_s_ASCII __pyx_mstate_global->__pyx_n_s_ASCII #define __pyx_n_s_AcadosOcpSolverCython __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython #define __pyx_n_s_AcadosOcpSolverCython___get_poin __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython___get_poin @@ -5201,15 +5427,16 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #define __pyx_n_s_AcadosOcpSolverCython_constraint_2 __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_constraint_2 #define __pyx_n_s_AcadosOcpSolverCython_cost_set __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_cost_set #define __pyx_kp_u_AcadosOcpSolverCython_cost_set_m __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_cost_set_m +#define __pyx_n_s_AcadosOcpSolverCython_custom_upd __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_custom_upd #define __pyx_kp_u_AcadosOcpSolverCython_does_not_s __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_does_not_s #define __pyx_kp_u_AcadosOcpSolverCython_does_not_s_2 __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_does_not_s_2 -#define __pyx_n_s_AcadosOcpSolverCython_dynamics_g __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_dynamics_g #define __pyx_kp_u_AcadosOcpSolverCython_eval_param __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_eval_param #define __pyx_kp_u_AcadosOcpSolverCython_eval_param_2 __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_eval_param_2 #define __pyx_n_s_AcadosOcpSolverCython_eval_param_3 __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_eval_param_3 #define __pyx_n_s_AcadosOcpSolverCython_get __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_get #define __pyx_n_s_AcadosOcpSolverCython_get_cost __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_get_cost #define __pyx_kp_u_AcadosOcpSolverCython_get_field __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_get_field +#define __pyx_n_s_AcadosOcpSolverCython_get_from_q __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_get_from_q #define __pyx_kp_u_AcadosOcpSolverCython_get_is_an __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_get_is_an #define __pyx_n_s_AcadosOcpSolverCython_get_residu __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_get_residu #define __pyx_kp_u_AcadosOcpSolverCython_get_stage __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_get_stage @@ -5223,9 +5450,11 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #define __pyx_kp_u_AcadosOcpSolverCython_set_is_not __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_set_is_not #define __pyx_kp_u_AcadosOcpSolverCython_set_mismat __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_set_mismat #define __pyx_n_s_AcadosOcpSolverCython_set_new_ti __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_set_new_ti +#define __pyx_n_s_AcadosOcpSolverCython_set_params __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_set_params #define __pyx_n_s_AcadosOcpSolverCython_solve __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_solve #define __pyx_kp_u_AcadosOcpSolverCython_solve_argu __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_solve_argu #define __pyx_kp_u_AcadosOcpSolverCython_solve_argu_2 __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_solve_argu_2 +#define __pyx_n_s_AcadosOcpSolverCython_solve_for __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_solve_for #define __pyx_n_s_AcadosOcpSolverCython_store_iter __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_store_iter #define __pyx_n_s_AcadosOcpSolverCython_update_qp __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_update_qp #define __pyx_kp_s_All_dimensions_preceding_dimensi __pyx_mstate_global->__pyx_kp_s_All_dimensions_preceding_dimensi @@ -5240,6 +5469,7 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #define __pyx_n_s_Ellipsis __pyx_mstate_global->__pyx_n_s_Ellipsis #define __pyx_kp_s_Empty_shape_tuple_for_cython_arr __pyx_mstate_global->__pyx_kp_s_Empty_shape_tuple_for_cython_arr #define __pyx_n_u_F __pyx_mstate_global->__pyx_n_u_F +#define __pyx_kp_u_Got_sizes_idx __pyx_mstate_global->__pyx_kp_u_Got_sizes_idx #define __pyx_n_s_ImportError __pyx_mstate_global->__pyx_n_s_ImportError #define __pyx_kp_s_Incompatible_checksums_0x_x_vs_0 __pyx_mstate_global->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0 #define __pyx_n_s_IndexError __pyx_mstate_global->__pyx_n_s_IndexError @@ -5265,16 +5495,18 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #define __pyx_kp_s_Unable_to_convert_item_to_object __pyx_mstate_global->__pyx_kp_s_Unable_to_convert_item_to_object #define __pyx_n_s_ValueError __pyx_mstate_global->__pyx_n_s_ValueError #define __pyx_n_s_View_MemoryView __pyx_mstate_global->__pyx_n_s_View_MemoryView +#define __pyx_kp_u_Warning_acados_ocp_solver_reache __pyx_mstate_global->__pyx_kp_u_Warning_acados_ocp_solver_reache #define __pyx_kp_u_Y_m_d_H_M_S_f __pyx_mstate_global->__pyx_kp_u_Y_m_d_H_M_S_f -#define __pyx_kp_u__14 __pyx_mstate_global->__pyx_kp_u__14 -#define __pyx_n_u__15 __pyx_mstate_global->__pyx_n_u__15 +#define __pyx_kp_u__16 __pyx_mstate_global->__pyx_kp_u__16 +#define __pyx_n_u__17 __pyx_mstate_global->__pyx_n_u__17 #define __pyx_kp_u__2 __pyx_mstate_global->__pyx_kp_u__2 -#define __pyx_kp_u__29 __pyx_mstate_global->__pyx_kp_u__29 #define __pyx_n_s__3 __pyx_mstate_global->__pyx_n_s__3 +#define __pyx_kp_u__31 __pyx_mstate_global->__pyx_kp_u__31 #define __pyx_kp_u__6 __pyx_mstate_global->__pyx_kp_u__6 #define __pyx_kp_u__7 __pyx_mstate_global->__pyx_kp_u__7 -#define __pyx_n_s__84 __pyx_mstate_global->__pyx_n_s__84 +#define __pyx_n_s__94 __pyx_mstate_global->__pyx_n_s__94 #define __pyx_n_s_abc __pyx_mstate_global->__pyx_n_s_abc +#define __pyx_kp_u_acados_acados_ocp_solver_returne __pyx_mstate_global->__pyx_kp_u_acados_acados_ocp_solver_returne #define __pyx_n_s_acados_template_acados_ocp_solve __pyx_mstate_global->__pyx_n_s_acados_template_acados_ocp_solve #define __pyx_n_s_allocate_buffer __pyx_mstate_global->__pyx_n_s_allocate_buffer #define __pyx_n_u_alpha __pyx_mstate_global->__pyx_n_u_alpha @@ -5297,11 +5529,18 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #define __pyx_kp_s_collections_abc __pyx_mstate_global->__pyx_kp_s_collections_abc #define __pyx_n_s_constraints_fields __pyx_mstate_global->__pyx_n_s_constraints_fields #define __pyx_n_s_constraints_set __pyx_mstate_global->__pyx_n_s_constraints_set +#define __pyx_kp_u_constraints_set_value_must_be_nu __pyx_mstate_global->__pyx_kp_u_constraints_set_value_must_be_nu #define __pyx_kp_s_contiguous_and_direct __pyx_mstate_global->__pyx_kp_s_contiguous_and_direct #define __pyx_kp_s_contiguous_and_indirect __pyx_mstate_global->__pyx_kp_s_contiguous_and_indirect #define __pyx_n_s_cost_fields __pyx_mstate_global->__pyx_n_s_cost_fields #define __pyx_n_s_cost_set __pyx_mstate_global->__pyx_n_s_cost_set +#define __pyx_kp_u_cost_set_value_must_be_numpy_arr __pyx_mstate_global->__pyx_kp_u_cost_set_value_must_be_numpy_arr #define __pyx_n_s_count __pyx_mstate_global->__pyx_n_s_count +#define __pyx_n_s_custom_update __pyx_mstate_global->__pyx_n_s_custom_update +#define __pyx_n_u_d __pyx_mstate_global->__pyx_n_u_d +#define __pyx_n_s_data __pyx_mstate_global->__pyx_n_s_data +#define __pyx_n_s_data_2 __pyx_mstate_global->__pyx_n_s_data_2 +#define __pyx_n_s_data_len __pyx_mstate_global->__pyx_n_s_data_len #define __pyx_n_s_datetime __pyx_mstate_global->__pyx_n_s_datetime #define __pyx_n_s_default __pyx_mstate_global->__pyx_n_s_default #define __pyx_n_s_dict __pyx_mstate_global->__pyx_n_s_dict @@ -5312,7 +5551,6 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #define __pyx_n_s_dtype __pyx_mstate_global->__pyx_n_s_dtype #define __pyx_n_s_dtype_is_object __pyx_mstate_global->__pyx_n_s_dtype_is_object #define __pyx_n_s_dump __pyx_mstate_global->__pyx_n_s_dump -#define __pyx_n_s_dynamics_get __pyx_mstate_global->__pyx_n_s_dynamics_get #define __pyx_kp_u_enable __pyx_mstate_global->__pyx_kp_u_enable #define __pyx_n_s_encode __pyx_mstate_global->__pyx_n_s_encode #define __pyx_n_s_enter __pyx_mstate_global->__pyx_n_s_enter @@ -5338,6 +5576,7 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #define __pyx_kp_u_gc __pyx_mstate_global->__pyx_kp_u_gc #define __pyx_n_s_get __pyx_mstate_global->__pyx_n_s_get #define __pyx_n_s_get_cost __pyx_mstate_global->__pyx_n_s_get_cost +#define __pyx_n_s_get_from_qp_in __pyx_mstate_global->__pyx_n_s_get_from_qp_in #define __pyx_n_s_get_pointers_solver __pyx_mstate_global->__pyx_n_s_get_pointers_solver #define __pyx_n_s_get_residuals __pyx_mstate_global->__pyx_n_s_get_residuals #define __pyx_n_s_get_stat_double __pyx_mstate_global->__pyx_n_s_get_stat_double @@ -5351,13 +5590,17 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #define __pyx_kp_u_got __pyx_mstate_global->__pyx_kp_u_got #define __pyx_kp_u_got_differing_extents_in_dimensi __pyx_mstate_global->__pyx_kp_u_got_differing_extents_in_dimensi #define __pyx_n_s_i __pyx_mstate_global->__pyx_n_s_i +#define __pyx_n_s_i_string __pyx_mstate_global->__pyx_n_s_i_string #define __pyx_n_s_id __pyx_mstate_global->__pyx_n_s_id +#define __pyx_n_s_idx __pyx_mstate_global->__pyx_n_s_idx +#define __pyx_n_s_idx_values __pyx_mstate_global->__pyx_n_s_idx_values #define __pyx_n_s_import __pyx_mstate_global->__pyx_n_s_import #define __pyx_n_s_indent __pyx_mstate_global->__pyx_n_s_indent #define __pyx_n_s_index __pyx_mstate_global->__pyx_n_s_index #define __pyx_n_u_initialize_t_slacks __pyx_mstate_global->__pyx_n_u_initialize_t_slacks #define __pyx_n_s_initializing __pyx_mstate_global->__pyx_n_s_initializing #define __pyx_n_s_int __pyx_mstate_global->__pyx_n_s_int +#define __pyx_n_s_int32 __pyx_mstate_global->__pyx_n_s_int32 #define __pyx_n_s_int_fields __pyx_mstate_global->__pyx_n_s_int_fields #define __pyx_n_s_int_value __pyx_mstate_global->__pyx_n_s_int_value #define __pyx_n_s_is_coroutine __pyx_mstate_global->__pyx_n_s_is_coroutine @@ -5369,8 +5612,10 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #define __pyx_n_s_join __pyx_mstate_global->__pyx_n_s_join #define __pyx_n_s_json __pyx_mstate_global->__pyx_n_s_json #define __pyx_kp_u_json_2 __pyx_mstate_global->__pyx_kp_u_json_2 +#define __pyx_n_s_k __pyx_mstate_global->__pyx_n_s_k #define __pyx_n_s_key __pyx_mstate_global->__pyx_n_s_key #define __pyx_n_s_keys __pyx_mstate_global->__pyx_n_s_keys +#define __pyx_n_s_lN __pyx_mstate_global->__pyx_n_s_lN #define __pyx_n_u_lam __pyx_mstate_global->__pyx_n_u_lam #define __pyx_n_u_lam_2 __pyx_mstate_global->__pyx_n_u_lam_2 #define __pyx_n_u_lbu __pyx_mstate_global->__pyx_n_u_lbu @@ -5388,8 +5633,10 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #define __pyx_n_s_model_name __pyx_mstate_global->__pyx_n_s_model_name #define __pyx_n_s_msg __pyx_mstate_global->__pyx_n_s_msg #define __pyx_n_s_n __pyx_mstate_global->__pyx_n_s_n +#define __pyx_n_s_n_update __pyx_mstate_global->__pyx_n_s_n_update #define __pyx_n_s_name __pyx_mstate_global->__pyx_n_s_name #define __pyx_n_s_name_2 __pyx_mstate_global->__pyx_n_s_name_2 +#define __pyx_n_s_ndarray __pyx_mstate_global->__pyx_n_s_ndarray #define __pyx_n_s_ndim __pyx_mstate_global->__pyx_n_s_ndim #define __pyx_n_s_new __pyx_mstate_global->__pyx_n_s_new #define __pyx_n_s_new_time_steps __pyx_mstate_global->__pyx_n_s_new_time_steps @@ -5411,6 +5658,10 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #define __pyx_n_s_overwrite __pyx_mstate_global->__pyx_n_s_overwrite #define __pyx_n_u_p __pyx_mstate_global->__pyx_n_u_p #define __pyx_n_s_pack __pyx_mstate_global->__pyx_n_s_pack +#define __pyx_n_s_param_values __pyx_mstate_global->__pyx_n_s_param_values +#define __pyx_kp_u_param_values_2 __pyx_mstate_global->__pyx_kp_u_param_values_2 +#define __pyx_kp_u_param_values__and_idx_values__mu __pyx_mstate_global->__pyx_kp_u_param_values__and_idx_values__mu +#define __pyx_kp_u_param_values__must_be_np_array __pyx_mstate_global->__pyx_kp_u_param_values__must_be_np_array #define __pyx_n_s_path __pyx_mstate_global->__pyx_n_s_path #define __pyx_n_u_pi __pyx_mstate_global->__pyx_n_u_pi #define __pyx_n_u_pi_2 __pyx_mstate_global->__pyx_n_u_pi_2 @@ -5446,11 +5697,14 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #define __pyx_n_b_res_ineq __pyx_mstate_global->__pyx_n_b_res_ineq #define __pyx_n_b_res_stat __pyx_mstate_global->__pyx_n_b_res_stat #define __pyx_n_s_reset __pyx_mstate_global->__pyx_n_s_reset +#define __pyx_n_s_reset_qp_solver_mem __pyx_mstate_global->__pyx_n_s_reset_qp_solver_mem #define __pyx_n_u_residuals __pyx_mstate_global->__pyx_n_u_residuals #define __pyx_n_u_rti_phase __pyx_mstate_global->__pyx_n_u_rti_phase #define __pyx_n_s_self __pyx_mstate_global->__pyx_n_s_self #define __pyx_n_s_set __pyx_mstate_global->__pyx_n_s_set #define __pyx_n_s_set_new_time_steps __pyx_mstate_global->__pyx_n_s_set_new_time_steps +#define __pyx_n_s_set_params_sparse __pyx_mstate_global->__pyx_n_s_set_params_sparse +#define __pyx_kp_u_set_value_must_be_numpy_array_go __pyx_mstate_global->__pyx_kp_u_set_value_must_be_numpy_array_go #define __pyx_n_s_setstate __pyx_mstate_global->__pyx_n_s_setstate #define __pyx_n_s_setstate_cython __pyx_mstate_global->__pyx_n_s_setstate_cython #define __pyx_n_s_shape __pyx_mstate_global->__pyx_n_s_shape @@ -5459,6 +5713,7 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #define __pyx_n_u_sl_2 __pyx_mstate_global->__pyx_n_u_sl_2 #define __pyx_n_s_solution __pyx_mstate_global->__pyx_n_s_solution #define __pyx_n_s_solve __pyx_mstate_global->__pyx_n_s_solve +#define __pyx_n_s_solve_for_x0 __pyx_mstate_global->__pyx_n_s_solve_for_x0 #define __pyx_kp_u_solver_option_must_be_of_type_fl __pyx_mstate_global->__pyx_kp_u_solver_option_must_be_of_type_fl #define __pyx_kp_u_solver_option_must_be_of_type_in __pyx_mstate_global->__pyx_kp_u_solver_option_must_be_of_type_in #define __pyx_kp_u_solver_option_must_be_of_type_st __pyx_mstate_global->__pyx_kp_u_solver_option_must_be_of_type_st @@ -5474,6 +5729,7 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #define __pyx_n_s_stat_n __pyx_mstate_global->__pyx_n_s_stat_n #define __pyx_n_u_stat_n __pyx_mstate_global->__pyx_n_u_stat_n #define __pyx_n_u_statistics __pyx_mstate_global->__pyx_n_u_statistics +#define __pyx_n_s_status __pyx_mstate_global->__pyx_n_s_status #define __pyx_n_s_step __pyx_mstate_global->__pyx_n_s_step #define __pyx_n_u_step_length __pyx_mstate_global->__pyx_n_u_step_length #define __pyx_n_s_stop __pyx_mstate_global->__pyx_n_s_stop @@ -5512,6 +5768,7 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #define __pyx_n_u_tol_stat __pyx_mstate_global->__pyx_n_u_tol_stat #define __pyx_n_s_tolist __pyx_mstate_global->__pyx_n_s_tolist #define __pyx_n_u_u __pyx_mstate_global->__pyx_n_u_u +#define __pyx_n_s_u0 __pyx_mstate_global->__pyx_n_s_u0 #define __pyx_n_u_u_2 __pyx_mstate_global->__pyx_n_u_u_2 #define __pyx_n_u_ubu __pyx_mstate_global->__pyx_n_u_ubu #define __pyx_n_u_ubx __pyx_mstate_global->__pyx_n_u_ubx @@ -5533,6 +5790,7 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #define __pyx_n_b_x __pyx_mstate_global->__pyx_n_b_x #define __pyx_n_s_x __pyx_mstate_global->__pyx_n_s_x #define __pyx_n_u_x __pyx_mstate_global->__pyx_n_u_x +#define __pyx_n_s_x0_bar __pyx_mstate_global->__pyx_n_s_x0_bar #define __pyx_n_u_x_2 __pyx_mstate_global->__pyx_n_u_x_2 #define __pyx_n_u_xdot_guess __pyx_mstate_global->__pyx_n_u_xdot_guess #define __pyx_n_u_y_ref __pyx_mstate_global->__pyx_n_u_y_ref @@ -5540,6 +5798,7 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #define __pyx_n_u_yref __pyx_mstate_global->__pyx_n_u_yref #define __pyx_n_u_z __pyx_mstate_global->__pyx_n_u_z #define __pyx_n_u_z_2 __pyx_mstate_global->__pyx_n_u_z_2 +#define __pyx_n_b_z_guess __pyx_mstate_global->__pyx_n_b_z_guess #define __pyx_n_u_z_guess __pyx_mstate_global->__pyx_n_u_z_guess #define __pyx_n_s_zeros __pyx_mstate_global->__pyx_n_s_zeros #define __pyx_int_0 __pyx_mstate_global->__pyx_int_0 @@ -5558,13 +5817,13 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #define __pyx_tuple__4 __pyx_mstate_global->__pyx_tuple__4 #define __pyx_tuple__8 __pyx_mstate_global->__pyx_tuple__8 #define __pyx_tuple__9 __pyx_mstate_global->__pyx_tuple__9 -#define __pyx_slice__16 __pyx_mstate_global->__pyx_slice__16 +#define __pyx_slice__18 __pyx_mstate_global->__pyx_slice__18 #define __pyx_tuple__10 __pyx_mstate_global->__pyx_tuple__10 #define __pyx_tuple__11 __pyx_mstate_global->__pyx_tuple__11 #define __pyx_tuple__12 __pyx_mstate_global->__pyx_tuple__12 #define __pyx_tuple__13 __pyx_mstate_global->__pyx_tuple__13 -#define __pyx_tuple__17 __pyx_mstate_global->__pyx_tuple__17 -#define __pyx_tuple__18 __pyx_mstate_global->__pyx_tuple__18 +#define __pyx_tuple__14 __pyx_mstate_global->__pyx_tuple__14 +#define __pyx_tuple__15 __pyx_mstate_global->__pyx_tuple__15 #define __pyx_tuple__19 __pyx_mstate_global->__pyx_tuple__19 #define __pyx_tuple__20 __pyx_mstate_global->__pyx_tuple__20 #define __pyx_tuple__21 __pyx_mstate_global->__pyx_tuple__21 @@ -5575,8 +5834,8 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #define __pyx_tuple__26 __pyx_mstate_global->__pyx_tuple__26 #define __pyx_tuple__27 __pyx_mstate_global->__pyx_tuple__27 #define __pyx_tuple__28 __pyx_mstate_global->__pyx_tuple__28 +#define __pyx_tuple__29 __pyx_mstate_global->__pyx_tuple__29 #define __pyx_tuple__30 __pyx_mstate_global->__pyx_tuple__30 -#define __pyx_tuple__31 __pyx_mstate_global->__pyx_tuple__31 #define __pyx_tuple__32 __pyx_mstate_global->__pyx_tuple__32 #define __pyx_tuple__33 __pyx_mstate_global->__pyx_tuple__33 #define __pyx_tuple__34 __pyx_mstate_global->__pyx_tuple__34 @@ -5585,50 +5844,60 @@ static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { #define __pyx_tuple__37 __pyx_mstate_global->__pyx_tuple__37 #define __pyx_tuple__38 __pyx_mstate_global->__pyx_tuple__38 #define __pyx_tuple__39 __pyx_mstate_global->__pyx_tuple__39 +#define __pyx_tuple__40 __pyx_mstate_global->__pyx_tuple__40 #define __pyx_tuple__41 __pyx_mstate_global->__pyx_tuple__41 -#define __pyx_tuple__45 __pyx_mstate_global->__pyx_tuple__45 -#define __pyx_tuple__47 __pyx_mstate_global->__pyx_tuple__47 +#define __pyx_tuple__42 __pyx_mstate_global->__pyx_tuple__42 +#define __pyx_tuple__44 __pyx_mstate_global->__pyx_tuple__44 +#define __pyx_tuple__46 __pyx_mstate_global->__pyx_tuple__46 #define __pyx_tuple__49 __pyx_mstate_global->__pyx_tuple__49 #define __pyx_tuple__51 __pyx_mstate_global->__pyx_tuple__51 -#define __pyx_tuple__52 __pyx_mstate_global->__pyx_tuple__52 +#define __pyx_tuple__53 __pyx_mstate_global->__pyx_tuple__53 #define __pyx_tuple__55 __pyx_mstate_global->__pyx_tuple__55 #define __pyx_tuple__57 __pyx_mstate_global->__pyx_tuple__57 -#define __pyx_tuple__58 __pyx_mstate_global->__pyx_tuple__58 +#define __pyx_tuple__59 __pyx_mstate_global->__pyx_tuple__59 #define __pyx_tuple__60 __pyx_mstate_global->__pyx_tuple__60 -#define __pyx_tuple__62 __pyx_mstate_global->__pyx_tuple__62 +#define __pyx_tuple__63 __pyx_mstate_global->__pyx_tuple__63 #define __pyx_tuple__65 __pyx_mstate_global->__pyx_tuple__65 -#define __pyx_tuple__67 __pyx_mstate_global->__pyx_tuple__67 -#define __pyx_tuple__69 __pyx_mstate_global->__pyx_tuple__69 -#define __pyx_tuple__71 __pyx_mstate_global->__pyx_tuple__71 -#define __pyx_tuple__72 __pyx_mstate_global->__pyx_tuple__72 -#define __pyx_tuple__74 __pyx_mstate_global->__pyx_tuple__74 +#define __pyx_tuple__66 __pyx_mstate_global->__pyx_tuple__66 +#define __pyx_tuple__68 __pyx_mstate_global->__pyx_tuple__68 +#define __pyx_tuple__70 __pyx_mstate_global->__pyx_tuple__70 +#define __pyx_tuple__73 __pyx_mstate_global->__pyx_tuple__73 +#define __pyx_tuple__75 __pyx_mstate_global->__pyx_tuple__75 #define __pyx_tuple__77 __pyx_mstate_global->__pyx_tuple__77 #define __pyx_tuple__79 __pyx_mstate_global->__pyx_tuple__79 +#define __pyx_tuple__80 __pyx_mstate_global->__pyx_tuple__80 #define __pyx_tuple__82 __pyx_mstate_global->__pyx_tuple__82 -#define __pyx_codeobj__40 __pyx_mstate_global->__pyx_codeobj__40 -#define __pyx_codeobj__42 __pyx_mstate_global->__pyx_codeobj__42 +#define __pyx_tuple__85 __pyx_mstate_global->__pyx_tuple__85 +#define __pyx_tuple__87 __pyx_mstate_global->__pyx_tuple__87 +#define __pyx_tuple__89 __pyx_mstate_global->__pyx_tuple__89 +#define __pyx_tuple__92 __pyx_mstate_global->__pyx_tuple__92 #define __pyx_codeobj__43 __pyx_mstate_global->__pyx_codeobj__43 -#define __pyx_codeobj__44 __pyx_mstate_global->__pyx_codeobj__44 -#define __pyx_codeobj__46 __pyx_mstate_global->__pyx_codeobj__46 +#define __pyx_codeobj__45 __pyx_mstate_global->__pyx_codeobj__45 +#define __pyx_codeobj__47 __pyx_mstate_global->__pyx_codeobj__47 #define __pyx_codeobj__48 __pyx_mstate_global->__pyx_codeobj__48 #define __pyx_codeobj__50 __pyx_mstate_global->__pyx_codeobj__50 -#define __pyx_codeobj__53 __pyx_mstate_global->__pyx_codeobj__53 +#define __pyx_codeobj__52 __pyx_mstate_global->__pyx_codeobj__52 #define __pyx_codeobj__54 __pyx_mstate_global->__pyx_codeobj__54 #define __pyx_codeobj__56 __pyx_mstate_global->__pyx_codeobj__56 -#define __pyx_codeobj__59 __pyx_mstate_global->__pyx_codeobj__59 +#define __pyx_codeobj__58 __pyx_mstate_global->__pyx_codeobj__58 #define __pyx_codeobj__61 __pyx_mstate_global->__pyx_codeobj__61 -#define __pyx_codeobj__63 __pyx_mstate_global->__pyx_codeobj__63 +#define __pyx_codeobj__62 __pyx_mstate_global->__pyx_codeobj__62 #define __pyx_codeobj__64 __pyx_mstate_global->__pyx_codeobj__64 -#define __pyx_codeobj__66 __pyx_mstate_global->__pyx_codeobj__66 -#define __pyx_codeobj__68 __pyx_mstate_global->__pyx_codeobj__68 -#define __pyx_codeobj__70 __pyx_mstate_global->__pyx_codeobj__70 -#define __pyx_codeobj__73 __pyx_mstate_global->__pyx_codeobj__73 -#define __pyx_codeobj__75 __pyx_mstate_global->__pyx_codeobj__75 +#define __pyx_codeobj__67 __pyx_mstate_global->__pyx_codeobj__67 +#define __pyx_codeobj__69 __pyx_mstate_global->__pyx_codeobj__69 +#define __pyx_codeobj__71 __pyx_mstate_global->__pyx_codeobj__71 +#define __pyx_codeobj__72 __pyx_mstate_global->__pyx_codeobj__72 +#define __pyx_codeobj__74 __pyx_mstate_global->__pyx_codeobj__74 #define __pyx_codeobj__76 __pyx_mstate_global->__pyx_codeobj__76 #define __pyx_codeobj__78 __pyx_mstate_global->__pyx_codeobj__78 -#define __pyx_codeobj__80 __pyx_mstate_global->__pyx_codeobj__80 #define __pyx_codeobj__81 __pyx_mstate_global->__pyx_codeobj__81 #define __pyx_codeobj__83 __pyx_mstate_global->__pyx_codeobj__83 +#define __pyx_codeobj__84 __pyx_mstate_global->__pyx_codeobj__84 +#define __pyx_codeobj__86 __pyx_mstate_global->__pyx_codeobj__86 +#define __pyx_codeobj__88 __pyx_mstate_global->__pyx_codeobj__88 +#define __pyx_codeobj__90 __pyx_mstate_global->__pyx_codeobj__90 +#define __pyx_codeobj__91 __pyx_mstate_global->__pyx_codeobj__91 +#define __pyx_codeobj__93 __pyx_mstate_global->__pyx_codeobj__93 /* #### Code section: module_code ### */ /* "carray.to_py":114 @@ -20419,7 +20688,7 @@ static CYTHON_INLINE NPY_DATETIMEUNIT __pyx_f_5numpy_get_datetime64_unit(PyObjec return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":74 +/* "acados_template/acados_ocp_solver_pyx.pyx":70 * cdef str nlp_solver_type * * def __cinit__(self, model_name, nlp_solver_type, N): # <<<<<<<<<<<<<< @@ -20460,26 +20729,26 @@ static int __pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverC switch (__pyx_nargs) { case 0: if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_model_name)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 74, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 70, __pyx_L3_error) else goto __pyx_L5_argtuple_error; CYTHON_FALLTHROUGH; case 1: if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_nlp_solver_type)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 74, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 70, __pyx_L3_error) else { - __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 3, 3, 1); __PYX_ERR(0, 74, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 3, 3, 1); __PYX_ERR(0, 70, __pyx_L3_error) } CYTHON_FALLTHROUGH; case 2: if (likely((values[2] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_N)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 74, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 70, __pyx_L3_error) else { - __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 3, 3, 2); __PYX_ERR(0, 74, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 3, 3, 2); __PYX_ERR(0, 70, __pyx_L3_error) } } if (unlikely(kw_args > 0)) { const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__cinit__") < 0)) __PYX_ERR(0, 74, __pyx_L3_error) + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__cinit__") < 0)) __PYX_ERR(0, 70, __pyx_L3_error) } } else if (unlikely(__pyx_nargs != 3)) { goto __pyx_L5_argtuple_error; @@ -20494,7 +20763,7 @@ static int __pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverC } goto __pyx_L4_argument_unpacking_done; __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 74, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 70, __pyx_L3_error) __pyx_L3_error:; __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); __Pyx_RefNannyFinishContext(); @@ -20520,7 +20789,7 @@ static int __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverC int __pyx_clineno = 0; __Pyx_RefNannySetupContext("__cinit__", 0); - /* "acados_template/acados_ocp_solver_pyx.pyx":76 + /* "acados_template/acados_ocp_solver_pyx.pyx":72 * def __cinit__(self, model_name, nlp_solver_type, N): * * self.solver_created = False # <<<<<<<<<<<<<< @@ -20529,24 +20798,24 @@ static int __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverC */ __pyx_v_self->solver_created = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":78 + /* "acados_template/acados_ocp_solver_pyx.pyx":74 * self.solver_created = False * * self.N = N # <<<<<<<<<<<<<< * self.model_name = model_name * self.nlp_solver_type = nlp_solver_type */ - __pyx_t_1 = __Pyx_PyInt_As_int(__pyx_v_N); if (unlikely((__pyx_t_1 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 78, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyInt_As_int(__pyx_v_N); if (unlikely((__pyx_t_1 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 74, __pyx_L1_error) __pyx_v_self->N = __pyx_t_1; - /* "acados_template/acados_ocp_solver_pyx.pyx":79 + /* "acados_template/acados_ocp_solver_pyx.pyx":75 * * self.N = N * self.model_name = model_name # <<<<<<<<<<<<<< * self.nlp_solver_type = nlp_solver_type * */ - if (!(likely(PyUnicode_CheckExact(__pyx_v_model_name))||((__pyx_v_model_name) == Py_None) || __Pyx_RaiseUnexpectedTypeError("unicode", __pyx_v_model_name))) __PYX_ERR(0, 79, __pyx_L1_error) + if (!(likely(PyUnicode_CheckExact(__pyx_v_model_name))||((__pyx_v_model_name) == Py_None) || __Pyx_RaiseUnexpectedTypeError("unicode", __pyx_v_model_name))) __PYX_ERR(0, 75, __pyx_L1_error) __pyx_t_2 = __pyx_v_model_name; __Pyx_INCREF(__pyx_t_2); __Pyx_GIVEREF(__pyx_t_2); @@ -20555,14 +20824,14 @@ static int __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverC __pyx_v_self->model_name = ((PyObject*)__pyx_t_2); __pyx_t_2 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":80 + /* "acados_template/acados_ocp_solver_pyx.pyx":76 * self.N = N * self.model_name = model_name * self.nlp_solver_type = nlp_solver_type # <<<<<<<<<<<<<< * * # create capsule */ - if (!(likely(PyUnicode_CheckExact(__pyx_v_nlp_solver_type))||((__pyx_v_nlp_solver_type) == Py_None) || __Pyx_RaiseUnexpectedTypeError("unicode", __pyx_v_nlp_solver_type))) __PYX_ERR(0, 80, __pyx_L1_error) + if (!(likely(PyUnicode_CheckExact(__pyx_v_nlp_solver_type))||((__pyx_v_nlp_solver_type) == Py_None) || __Pyx_RaiseUnexpectedTypeError("unicode", __pyx_v_nlp_solver_type))) __PYX_ERR(0, 76, __pyx_L1_error) __pyx_t_2 = __pyx_v_nlp_solver_type; __Pyx_INCREF(__pyx_t_2); __Pyx_GIVEREF(__pyx_t_2); @@ -20571,7 +20840,7 @@ static int __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverC __pyx_v_self->nlp_solver_type = ((PyObject*)__pyx_t_2); __pyx_t_2 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":83 + /* "acados_template/acados_ocp_solver_pyx.pyx":79 * * # create capsule * self.capsule = acados_solver.acados_create_capsule() # <<<<<<<<<<<<<< @@ -20580,7 +20849,7 @@ static int __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverC */ __pyx_v_self->capsule = long_acados_create_capsule(); - /* "acados_template/acados_ocp_solver_pyx.pyx":86 + /* "acados_template/acados_ocp_solver_pyx.pyx":82 * * # create solver * assert acados_solver.acados_create(self.capsule) == 0 # <<<<<<<<<<<<<< @@ -20592,14 +20861,14 @@ static int __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverC __pyx_t_3 = (long_acados_create(__pyx_v_self->capsule) == 0); if (unlikely(!__pyx_t_3)) { __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); - __PYX_ERR(0, 86, __pyx_L1_error) + __PYX_ERR(0, 82, __pyx_L1_error) } } #else - if ((1)); else __PYX_ERR(0, 86, __pyx_L1_error) + if ((1)); else __PYX_ERR(0, 82, __pyx_L1_error) #endif - /* "acados_template/acados_ocp_solver_pyx.pyx":87 + /* "acados_template/acados_ocp_solver_pyx.pyx":83 * # create solver * assert acados_solver.acados_create(self.capsule) == 0 * self.solver_created = True # <<<<<<<<<<<<<< @@ -20608,14 +20877,14 @@ static int __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverC */ __pyx_v_self->solver_created = 1; - /* "acados_template/acados_ocp_solver_pyx.pyx":90 + /* "acados_template/acados_ocp_solver_pyx.pyx":86 * * # get pointers solver * self.__get_pointers_solver() # <<<<<<<<<<<<<< - * self.status = 0 + * * */ - __pyx_t_4 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_AcadosOcpSolverCython__get_poin); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 90, __pyx_L1_error) + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_AcadosOcpSolverCython__get_poin); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 86, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); __pyx_t_5 = NULL; __pyx_t_1 = 0; @@ -20633,22 +20902,13 @@ static int __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverC PyObject *__pyx_callargs[1] = {__pyx_t_5, }; __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_1, 0+__pyx_t_1); __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; - if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 90, __pyx_L1_error) + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 86, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; } __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":91 - * # get pointers solver - * self.__get_pointers_solver() - * self.status = 0 # <<<<<<<<<<<<<< - * - * - */ - __pyx_v_self->status = 0; - - /* "acados_template/acados_ocp_solver_pyx.pyx":74 + /* "acados_template/acados_ocp_solver_pyx.pyx":70 * cdef str nlp_solver_type * * def __cinit__(self, model_name, nlp_solver_type, N): # <<<<<<<<<<<<<< @@ -20670,7 +20930,7 @@ static int __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverC return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":94 +/* "acados_template/acados_ocp_solver_pyx.pyx":89 * * * def __get_pointers_solver(self): # <<<<<<<<<<<<<< @@ -20717,7 +20977,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __Pyx_RefNannyDeclarations __Pyx_RefNannySetupContext("_AcadosOcpSolverCython__get_pointers_solver", 0); - /* "acados_template/acados_ocp_solver_pyx.pyx":99 + /* "acados_template/acados_ocp_solver_pyx.pyx":94 * """ * # get pointers solver * self.nlp_opts = acados_solver.acados_get_nlp_opts(self.capsule) # <<<<<<<<<<<<<< @@ -20726,7 +20986,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ __pyx_v_self->nlp_opts = long_acados_get_nlp_opts(__pyx_v_self->capsule); - /* "acados_template/acados_ocp_solver_pyx.pyx":100 + /* "acados_template/acados_ocp_solver_pyx.pyx":95 * # get pointers solver * self.nlp_opts = acados_solver.acados_get_nlp_opts(self.capsule) * self.nlp_dims = acados_solver.acados_get_nlp_dims(self.capsule) # <<<<<<<<<<<<<< @@ -20735,7 +20995,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ __pyx_v_self->nlp_dims = long_acados_get_nlp_dims(__pyx_v_self->capsule); - /* "acados_template/acados_ocp_solver_pyx.pyx":101 + /* "acados_template/acados_ocp_solver_pyx.pyx":96 * self.nlp_opts = acados_solver.acados_get_nlp_opts(self.capsule) * self.nlp_dims = acados_solver.acados_get_nlp_dims(self.capsule) * self.nlp_config = acados_solver.acados_get_nlp_config(self.capsule) # <<<<<<<<<<<<<< @@ -20744,7 +21004,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ __pyx_v_self->nlp_config = long_acados_get_nlp_config(__pyx_v_self->capsule); - /* "acados_template/acados_ocp_solver_pyx.pyx":102 + /* "acados_template/acados_ocp_solver_pyx.pyx":97 * self.nlp_dims = acados_solver.acados_get_nlp_dims(self.capsule) * self.nlp_config = acados_solver.acados_get_nlp_config(self.capsule) * self.nlp_out = acados_solver.acados_get_nlp_out(self.capsule) # <<<<<<<<<<<<<< @@ -20753,7 +21013,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ __pyx_v_self->nlp_out = long_acados_get_nlp_out(__pyx_v_self->capsule); - /* "acados_template/acados_ocp_solver_pyx.pyx":103 + /* "acados_template/acados_ocp_solver_pyx.pyx":98 * self.nlp_config = acados_solver.acados_get_nlp_config(self.capsule) * self.nlp_out = acados_solver.acados_get_nlp_out(self.capsule) * self.sens_out = acados_solver.acados_get_sens_out(self.capsule) # <<<<<<<<<<<<<< @@ -20762,7 +21022,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ __pyx_v_self->sens_out = long_acados_get_sens_out(__pyx_v_self->capsule); - /* "acados_template/acados_ocp_solver_pyx.pyx":104 + /* "acados_template/acados_ocp_solver_pyx.pyx":99 * self.nlp_out = acados_solver.acados_get_nlp_out(self.capsule) * self.sens_out = acados_solver.acados_get_sens_out(self.capsule) * self.nlp_in = acados_solver.acados_get_nlp_in(self.capsule) # <<<<<<<<<<<<<< @@ -20771,7 +21031,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ __pyx_v_self->nlp_in = long_acados_get_nlp_in(__pyx_v_self->capsule); - /* "acados_template/acados_ocp_solver_pyx.pyx":105 + /* "acados_template/acados_ocp_solver_pyx.pyx":100 * self.sens_out = acados_solver.acados_get_sens_out(self.capsule) * self.nlp_in = acados_solver.acados_get_nlp_in(self.capsule) * self.nlp_solver = acados_solver.acados_get_nlp_solver(self.capsule) # <<<<<<<<<<<<<< @@ -20780,7 +21040,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ __pyx_v_self->nlp_solver = long_acados_get_nlp_solver(__pyx_v_self->capsule); - /* "acados_template/acados_ocp_solver_pyx.pyx":94 + /* "acados_template/acados_ocp_solver_pyx.pyx":89 * * * def __get_pointers_solver(self): # <<<<<<<<<<<<<< @@ -20795,7 +21055,316 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":108 +/* "acados_template/acados_ocp_solver_pyx.pyx":103 + * + * + * def solve_for_x0(self, x0_bar): # <<<<<<<<<<<<<< + * """ + * Wrapper around `solve()` which sets initial state constraint, solves the OCP, and returns u0. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve_for_x0(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve_for_x0, "\n Wrapper around `solve()` which sets initial state constraint, solves the OCP, and returns u0.\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve_for_x0 = {"solve_for_x0", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve_for_x0, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve_for_x0}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve_for_x0(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_x0_bar = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("solve_for_x0 (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_x0_bar,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_x0_bar)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 103, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "solve_for_x0") < 0)) __PYX_ERR(0, 103, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_x0_bar = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("solve_for_x0", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 103, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.solve_for_x0", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve_for_x0(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_x0_bar); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve_for_x0(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_x0_bar) { + PyObject *__pyx_v_status = NULL; + PyObject *__pyx_v_u0 = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("solve_for_x0", 0); + + /* "acados_template/acados_ocp_solver_pyx.pyx":107 + * Wrapper around `solve()` which sets initial state constraint, solves the OCP, and returns u0. + * """ + * self.set(0, "lbx", x0_bar) # <<<<<<<<<<<<<< + * self.set(0, "ubx", x0_bar) + * + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_set); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 107, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[4] = {__pyx_t_3, __pyx_int_0, __pyx_n_u_lbx, __pyx_v_x0_bar}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 3+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 107, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":108 + * """ + * self.set(0, "lbx", x0_bar) + * self.set(0, "ubx", x0_bar) # <<<<<<<<<<<<<< + * + * status = self.solve() + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_set); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 108, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[4] = {__pyx_t_3, __pyx_int_0, __pyx_n_u_ubx, __pyx_v_x0_bar}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 3+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 108, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":110 + * self.set(0, "ubx", x0_bar) + * + * status = self.solve() # <<<<<<<<<<<<<< + * + * if status == 2: + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_solve); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 110, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[1] = {__pyx_t_3, }; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 0+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 110, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_v_status = __pyx_t_1; + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":112 + * status = self.solve() + * + * if status == 2: # <<<<<<<<<<<<<< + * print("Warning: acados_ocp_solver reached maximum iterations.") + * elif status != 0: + */ + __pyx_t_5 = (__Pyx_PyInt_BoolEqObjC(__pyx_v_status, __pyx_int_2, 2, 0)); if (unlikely((__pyx_t_5 < 0))) __PYX_ERR(0, 112, __pyx_L1_error) + if (__pyx_t_5) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":113 + * + * if status == 2: + * print("Warning: acados_ocp_solver reached maximum iterations.") # <<<<<<<<<<<<<< + * elif status != 0: + * raise Exception(f'acados acados_ocp_solver returned status {status}') + */ + __pyx_t_1 = __Pyx_PyObject_Call(__pyx_builtin_print, __pyx_tuple__11, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 113, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":112 + * status = self.solve() + * + * if status == 2: # <<<<<<<<<<<<<< + * print("Warning: acados_ocp_solver reached maximum iterations.") + * elif status != 0: + */ + goto __pyx_L3; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":114 + * if status == 2: + * print("Warning: acados_ocp_solver reached maximum iterations.") + * elif status != 0: # <<<<<<<<<<<<<< + * raise Exception(f'acados acados_ocp_solver returned status {status}') + * + */ + __pyx_t_5 = (__Pyx_PyInt_BoolNeObjC(__pyx_v_status, __pyx_int_0, 0, 0)); if (unlikely((__pyx_t_5 < 0))) __PYX_ERR(0, 114, __pyx_L1_error) + if (unlikely(__pyx_t_5)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":115 + * print("Warning: acados_ocp_solver reached maximum iterations.") + * elif status != 0: + * raise Exception(f'acados acados_ocp_solver returned status {status}') # <<<<<<<<<<<<<< + * + * u0 = self.get(0, "u") + */ + __pyx_t_1 = __Pyx_PyObject_FormatSimple(__pyx_v_status, __pyx_empty_unicode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 115, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyUnicode_Concat(__pyx_kp_u_acados_acados_ocp_solver_returne, __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 115, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 115, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 115, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":114 + * if status == 2: + * print("Warning: acados_ocp_solver reached maximum iterations.") + * elif status != 0: # <<<<<<<<<<<<<< + * raise Exception(f'acados acados_ocp_solver returned status {status}') + * + */ + } + __pyx_L3:; + + /* "acados_template/acados_ocp_solver_pyx.pyx":117 + * raise Exception(f'acados acados_ocp_solver returned status {status}') + * + * u0 = self.get(0, "u") # <<<<<<<<<<<<<< + * return u0 + * + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 117, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_Call(__pyx_t_1, __pyx_tuple__12, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 117, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_u0 = __pyx_t_2; + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":118 + * + * u0 = self.get(0, "u") + * return u0 # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_u0); + __pyx_r = __pyx_v_u0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":103 + * + * + * def solve_for_x0(self, x0_bar): # <<<<<<<<<<<<<< + * """ + * Wrapper around `solve()` which sets initial state constraint, solves the OCP, and returns u0. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.solve_for_x0", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_status); + __Pyx_XDECREF(__pyx_v_u0); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":121 * * * def solve(self): # <<<<<<<<<<<<<< @@ -20804,16 +21373,16 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ /* Python wrapper */ -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve(PyObject *__pyx_v_self, +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7solve(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else PyObject *__pyx_args, PyObject *__pyx_kwds #endif ); /*proto*/ -PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve, "\n Solve the ocp with current input.\n "); -static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve = {"solve", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve}; -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve(PyObject *__pyx_v_self, +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6solve, "\n Solve the ocp with current input.\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7solve = {"solve", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7solve, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6solve}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7solve(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else @@ -20830,14 +21399,14 @@ PyObject *__pyx_args, PyObject *__pyx_kwds if (unlikely(__pyx_nargs > 0)) { __Pyx_RaiseArgtupleInvalid("solve", 1, 0, 0, __pyx_nargs); return NULL;} if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "solve", 0))) return NULL; - __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6solve(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); /* function exit code */ __Pyx_RefNannyFinishContext(); return __pyx_r; } -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6solve(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { PyObject *__pyx_r = NULL; __Pyx_RefNannyDeclarations PyObject *__pyx_t_1 = NULL; @@ -20846,7 +21415,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS int __pyx_clineno = 0; __Pyx_RefNannySetupContext("solve", 0); - /* "acados_template/acados_ocp_solver_pyx.pyx":112 + /* "acados_template/acados_ocp_solver_pyx.pyx":125 * Solve the ocp with current input. * """ * return acados_solver.acados_solve(self.capsule) # <<<<<<<<<<<<<< @@ -20854,13 +21423,13 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS * */ __Pyx_XDECREF(__pyx_r); - __pyx_t_1 = __Pyx_PyInt_From_int(long_acados_solve(__pyx_v_self->capsule)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 112, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyInt_From_int(long_acados_solve(__pyx_v_self->capsule)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 125, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __pyx_r = __pyx_t_1; __pyx_t_1 = 0; goto __pyx_L0; - /* "acados_template/acados_ocp_solver_pyx.pyx":108 + /* "acados_template/acados_ocp_solver_pyx.pyx":121 * * * def solve(self): # <<<<<<<<<<<<<< @@ -20879,82 +21448,128 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":115 +/* "acados_template/acados_ocp_solver_pyx.pyx":128 * * - * def reset(self): # <<<<<<<<<<<<<< + * def reset(self, reset_qp_solver_mem=1): # <<<<<<<<<<<<<< * """ * Sets current iterate to all zeros. */ /* Python wrapper */ -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7reset(PyObject *__pyx_v_self, +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9reset(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else PyObject *__pyx_args, PyObject *__pyx_kwds #endif ); /*proto*/ -PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6reset, "\n Sets current iterate to all zeros.\n "); -static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7reset = {"reset", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7reset, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6reset}; -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7reset(PyObject *__pyx_v_self, +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8reset, "\n Sets current iterate to all zeros.\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9reset = {"reset", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9reset, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8reset}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9reset(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else PyObject *__pyx_args, PyObject *__pyx_kwds #endif ) { + PyObject *__pyx_v_reset_qp_solver_mem = 0; #if !CYTHON_METH_FASTCALL CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); #endif CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; PyObject *__pyx_r = 0; __Pyx_RefNannyDeclarations __Pyx_RefNannySetupContext("reset (wrapper)", 0); - if (unlikely(__pyx_nargs > 0)) { - __Pyx_RaiseArgtupleInvalid("reset", 1, 0, 0, __pyx_nargs); return NULL;} - if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "reset", 0))) return NULL; - __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6reset(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_reset_qp_solver_mem,0}; + PyObject* values[1] = {0}; + values[0] = ((PyObject *)__pyx_int_1); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_reset_qp_solver_mem); + if (value) { values[0] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 128, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "reset") < 0)) __PYX_ERR(0, 128, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_reset_qp_solver_mem = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("reset", 0, 0, 1, __pyx_nargs); __PYX_ERR(0, 128, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.reset", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8reset(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_reset_qp_solver_mem); /* function exit code */ __Pyx_RefNannyFinishContext(); return __pyx_r; } -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6reset(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8reset(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_reset_qp_solver_mem) { PyObject *__pyx_r = NULL; __Pyx_RefNannyDeclarations - PyObject *__pyx_t_1 = NULL; + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; int __pyx_lineno = 0; const char *__pyx_filename = NULL; int __pyx_clineno = 0; __Pyx_RefNannySetupContext("reset", 0); - /* "acados_template/acados_ocp_solver_pyx.pyx":119 + /* "acados_template/acados_ocp_solver_pyx.pyx":132 * Sets current iterate to all zeros. * """ - * return acados_solver.acados_reset(self.capsule) # <<<<<<<<<<<<<< + * return acados_solver.acados_reset(self.capsule, reset_qp_solver_mem) # <<<<<<<<<<<<<< * * */ __Pyx_XDECREF(__pyx_r); - __pyx_t_1 = __Pyx_PyInt_From_int(long_acados_reset(__pyx_v_self->capsule)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 119, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_r = __pyx_t_1; - __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyInt_As_int(__pyx_v_reset_qp_solver_mem); if (unlikely((__pyx_t_1 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 132, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyInt_From_int(long_acados_reset(__pyx_v_self->capsule, __pyx_t_1)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 132, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; goto __pyx_L0; - /* "acados_template/acados_ocp_solver_pyx.pyx":115 + /* "acados_template/acados_ocp_solver_pyx.pyx":128 * * - * def reset(self): # <<<<<<<<<<<<<< + * def reset(self, reset_qp_solver_mem=1): # <<<<<<<<<<<<<< * """ * Sets current iterate to all zeros. */ /* function exit code */ __pyx_L1_error:; - __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.reset", __pyx_clineno, __pyx_lineno, __pyx_filename); __pyx_r = NULL; __pyx_L0:; @@ -20963,7 +21578,214 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":122 +/* "acados_template/acados_ocp_solver_pyx.pyx":135 + * + * + * def custom_update(self, data_): # <<<<<<<<<<<<<< + * """ + * A custom function that can be implemented by a user to be called between solver calls. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11custom_update(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10custom_update, "\n A custom function that can be implemented by a user to be called between solver calls.\n By default this does nothing.\n The idea is to have a convenient wrapper to do complex updates of parameters and numerical data efficiently in C,\n in a function that is compiled into the solver library and can be conveniently used in the Python environment.\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11custom_update = {"custom_update", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11custom_update, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10custom_update}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11custom_update(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_data_ = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("custom_update (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_data,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_data)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 135, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "custom_update") < 0)) __PYX_ERR(0, 135, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_data_ = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("custom_update", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 135, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.custom_update", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10custom_update(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_data_); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10custom_update(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_data_) { + Py_ssize_t __pyx_v_data_len; + PyArrayObject *__pyx_v_data = 0; + __Pyx_LocalBuf_ND __pyx_pybuffernd_data; + __Pyx_Buffer __pyx_pybuffer_data; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyArrayObject *__pyx_t_7 = NULL; + char *__pyx_t_8; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("custom_update", 0); + __pyx_pybuffer_data.pybuffer.buf = NULL; + __pyx_pybuffer_data.refcount = 0; + __pyx_pybuffernd_data.data = NULL; + __pyx_pybuffernd_data.rcbuffer = &__pyx_pybuffer_data; + + /* "acados_template/acados_ocp_solver_pyx.pyx":142 + * in a function that is compiled into the solver library and can be conveniently used in the Python environment. + * """ + * data_len = len(data_) # <<<<<<<<<<<<<< + * cdef cnp.ndarray[cnp.float64_t, ndim=1] data = np.ascontiguousarray(data_, dtype=np.float64) + * + */ + __pyx_t_1 = PyObject_Length(__pyx_v_data_); if (unlikely(__pyx_t_1 == ((Py_ssize_t)-1))) __PYX_ERR(0, 142, __pyx_L1_error) + __pyx_v_data_len = __pyx_t_1; + + /* "acados_template/acados_ocp_solver_pyx.pyx":143 + * """ + * data_len = len(data_) + * cdef cnp.ndarray[cnp.float64_t, ndim=1] data = np.ascontiguousarray(data_, dtype=np.float64) # <<<<<<<<<<<<<< + * + * return acados_solver.acados_custom_update(self.capsule, data.data, data_len) + */ + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_np); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = PyTuple_New(1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_INCREF(__pyx_v_data_); + __Pyx_GIVEREF(__pyx_v_data_); + PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_v_data_); + __pyx_t_4 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GetModuleGlobalName(__pyx_t_5, __pyx_n_s_np); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_float64); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (PyDict_SetItem(__pyx_t_4, __pyx_n_s_dtype, __pyx_t_6) < 0) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __pyx_t_6 = __Pyx_PyObject_Call(__pyx_t_3, __pyx_t_2, __pyx_t_4); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (!(likely(((__pyx_t_6) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_6, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 143, __pyx_L1_error) + __pyx_t_7 = ((PyArrayObject *)__pyx_t_6); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_data.rcbuffer->pybuffer, (PyObject*)__pyx_t_7, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 1, 0, __pyx_stack) == -1)) { + __pyx_v_data = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_data.rcbuffer->pybuffer.buf = NULL; + __PYX_ERR(0, 143, __pyx_L1_error) + } else {__pyx_pybuffernd_data.diminfo[0].strides = __pyx_pybuffernd_data.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_data.diminfo[0].shape = __pyx_pybuffernd_data.rcbuffer->pybuffer.shape[0]; + } + } + __pyx_t_7 = 0; + __pyx_v_data = ((PyArrayObject *)__pyx_t_6); + __pyx_t_6 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":145 + * cdef cnp.ndarray[cnp.float64_t, ndim=1] data = np.ascontiguousarray(data_, dtype=np.float64) + * + * return acados_solver.acados_custom_update(self.capsule, data.data, data_len) # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_8 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_data)); if (unlikely(__pyx_t_8 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 145, __pyx_L1_error) + __pyx_t_6 = __Pyx_PyInt_From_int(long_acados_custom_update(__pyx_v_self->capsule, ((double *)__pyx_t_8), __pyx_v_data_len)); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 145, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_r = __pyx_t_6; + __pyx_t_6 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":135 + * + * + * def custom_update(self, data_): # <<<<<<<<<<<<<< + * """ + * A custom function that can be implemented by a user to be called between solver calls. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + { PyObject *__pyx_type, *__pyx_value, *__pyx_tb; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&__pyx_type, &__pyx_value, &__pyx_tb); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_data.rcbuffer->pybuffer); + __Pyx_ErrRestore(__pyx_type, __pyx_value, __pyx_tb);} + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.custom_update", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + goto __pyx_L2; + __pyx_L0:; + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_data.rcbuffer->pybuffer); + __pyx_L2:; + __Pyx_XDECREF((PyObject *)__pyx_v_data); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":148 * * * def set_new_time_steps(self, new_time_steps): # <<<<<<<<<<<<<< @@ -20972,16 +21794,16 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ /* Python wrapper */ -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9set_new_time_steps(PyObject *__pyx_v_self, +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13set_new_time_steps(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else PyObject *__pyx_args, PyObject *__pyx_kwds #endif ); /*proto*/ -PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8set_new_time_steps, "\n Set new time steps.\n Recreates the solver if N changes.\n\n :param new_time_steps: 1 dimensional np array of new time steps for the solver\n\n .. note:: This allows for different use-cases: either set a new size of time-steps or a new distribution of\n the shooting nodes without changing the number, e.g., to reach a different final time. Both cases\n do not require a new code export and compilation.\n "); -static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9set_new_time_steps = {"set_new_time_steps", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9set_new_time_steps, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8set_new_time_steps}; -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9set_new_time_steps(PyObject *__pyx_v_self, +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12set_new_time_steps, "\n Set new time steps.\n Recreates the solver if N changes.\n\n :param new_time_steps: 1 dimensional np array of new time steps for the solver\n\n .. note:: This allows for different use-cases: either set a new size of time-steps or a new distribution of\n the shooting nodes without changing the number, e.g., to reach a different final time. Both cases\n do not require a new code export and compilation.\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13set_new_time_steps = {"set_new_time_steps", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13set_new_time_steps, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12set_new_time_steps}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13set_new_time_steps(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else @@ -21014,12 +21836,12 @@ PyObject *__pyx_args, PyObject *__pyx_kwds switch (__pyx_nargs) { case 0: if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_new_time_steps)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 122, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 148, __pyx_L3_error) else goto __pyx_L5_argtuple_error; } if (unlikely(kw_args > 0)) { const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "set_new_time_steps") < 0)) __PYX_ERR(0, 122, __pyx_L3_error) + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "set_new_time_steps") < 0)) __PYX_ERR(0, 148, __pyx_L3_error) } } else if (unlikely(__pyx_nargs != 1)) { goto __pyx_L5_argtuple_error; @@ -21030,20 +21852,20 @@ PyObject *__pyx_args, PyObject *__pyx_kwds } goto __pyx_L4_argument_unpacking_done; __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("set_new_time_steps", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 122, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("set_new_time_steps", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 148, __pyx_L3_error) __pyx_L3_error:; __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.set_new_time_steps", __pyx_clineno, __pyx_lineno, __pyx_filename); __Pyx_RefNannyFinishContext(); return NULL; __pyx_L4_argument_unpacking_done:; - __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8set_new_time_steps(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_new_time_steps); + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12set_new_time_steps(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_new_time_steps); /* function exit code */ __Pyx_RefNannyFinishContext(); return __pyx_r; } -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8set_new_time_steps(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v_new_time_steps) { +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12set_new_time_steps(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v_new_time_steps) { PyObject *__pyx_r = NULL; __Pyx_RefNannyDeclarations PyObject *__pyx_t_1 = NULL; @@ -21052,20 +21874,20 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS int __pyx_clineno = 0; __Pyx_RefNannySetupContext("set_new_time_steps", 0); - /* "acados_template/acados_ocp_solver_pyx.pyx":134 + /* "acados_template/acados_ocp_solver_pyx.pyx":160 * """ * * raise NotImplementedError("AcadosOcpSolverCython: does not support set_new_time_steps() since it is only a prototyping feature") # <<<<<<<<<<<<<< * # # unlikely but still possible * # if not self.solver_created: */ - __pyx_t_1 = __Pyx_PyObject_Call(__pyx_builtin_NotImplementedError, __pyx_tuple__11, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 134, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_Call(__pyx_builtin_NotImplementedError, __pyx_tuple__13, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 160, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_Raise(__pyx_t_1, 0, 0, 0); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __PYX_ERR(0, 134, __pyx_L1_error) + __PYX_ERR(0, 160, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":122 + /* "acados_template/acados_ocp_solver_pyx.pyx":148 * * * def set_new_time_steps(self, new_time_steps): # <<<<<<<<<<<<<< @@ -21083,7 +21905,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":173 +/* "acados_template/acados_ocp_solver_pyx.pyx":199 * * * def update_qp_solver_cond_N(self, qp_solver_cond_N: int): # <<<<<<<<<<<<<< @@ -21092,16 +21914,16 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ /* Python wrapper */ -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11update_qp_solver_cond_N(PyObject *__pyx_v_self, +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15update_qp_solver_cond_N(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else PyObject *__pyx_args, PyObject *__pyx_kwds #endif ); /*proto*/ -PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10update_qp_solver_cond_N, "\n Recreate solver with new value `qp_solver_cond_N` with a partial condensing QP solver.\n This function is relevant for code reuse, i.e., if either `set_new_time_steps(...)` is used or\n the influence of a different `qp_solver_cond_N` is studied without code export and compilation.\n :param qp_solver_cond_N: new number of condensing stages for the solver\n\n .. note:: This function can only be used in combination with a partial condensing QP solver.\n\n .. note:: After `set_new_time_steps(...)` is used and depending on the new number of time steps it might be\n necessary to change `qp_solver_cond_N` as well (using this function), i.e., typically\n `qp_solver_cond_N < N`.\n "); -static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11update_qp_solver_cond_N = {"update_qp_solver_cond_N", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11update_qp_solver_cond_N, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10update_qp_solver_cond_N}; -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11update_qp_solver_cond_N(PyObject *__pyx_v_self, +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14update_qp_solver_cond_N, "\n Recreate solver with new value `qp_solver_cond_N` with a partial condensing QP solver.\n This function is relevant for code reuse, i.e., if either `set_new_time_steps(...)` is used or\n the influence of a different `qp_solver_cond_N` is studied without code export and compilation.\n :param qp_solver_cond_N: new number of condensing stages for the solver\n\n .. note:: This function can only be used in combination with a partial condensing QP solver.\n\n .. note:: After `set_new_time_steps(...)` is used and depending on the new number of time steps it might be\n necessary to change `qp_solver_cond_N` as well (using this function), i.e., typically\n `qp_solver_cond_N < N`.\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15update_qp_solver_cond_N = {"update_qp_solver_cond_N", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15update_qp_solver_cond_N, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14update_qp_solver_cond_N}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15update_qp_solver_cond_N(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else @@ -21134,12 +21956,12 @@ PyObject *__pyx_args, PyObject *__pyx_kwds switch (__pyx_nargs) { case 0: if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_qp_solver_cond_N)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 173, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 199, __pyx_L3_error) else goto __pyx_L5_argtuple_error; } if (unlikely(kw_args > 0)) { const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "update_qp_solver_cond_N") < 0)) __PYX_ERR(0, 173, __pyx_L3_error) + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "update_qp_solver_cond_N") < 0)) __PYX_ERR(0, 199, __pyx_L3_error) } } else if (unlikely(__pyx_nargs != 1)) { goto __pyx_L5_argtuple_error; @@ -21150,14 +21972,14 @@ PyObject *__pyx_args, PyObject *__pyx_kwds } goto __pyx_L4_argument_unpacking_done; __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("update_qp_solver_cond_N", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 173, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("update_qp_solver_cond_N", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 199, __pyx_L3_error) __pyx_L3_error:; __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.update_qp_solver_cond_N", __pyx_clineno, __pyx_lineno, __pyx_filename); __Pyx_RefNannyFinishContext(); return NULL; __pyx_L4_argument_unpacking_done:; - if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_qp_solver_cond_N), (&PyInt_Type), 0, "qp_solver_cond_N", 1))) __PYX_ERR(0, 173, __pyx_L1_error) - __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10update_qp_solver_cond_N(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_qp_solver_cond_N); + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_qp_solver_cond_N), (&PyInt_Type), 0, "qp_solver_cond_N", 1))) __PYX_ERR(0, 199, __pyx_L1_error) + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14update_qp_solver_cond_N(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_qp_solver_cond_N); /* function exit code */ goto __pyx_L0; @@ -21168,7 +21990,7 @@ PyObject *__pyx_args, PyObject *__pyx_kwds return __pyx_r; } -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10update_qp_solver_cond_N(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v_qp_solver_cond_N) { +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14update_qp_solver_cond_N(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v_qp_solver_cond_N) { PyObject *__pyx_r = NULL; __Pyx_RefNannyDeclarations PyObject *__pyx_t_1 = NULL; @@ -21177,20 +21999,20 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS int __pyx_clineno = 0; __Pyx_RefNannySetupContext("update_qp_solver_cond_N", 0); - /* "acados_template/acados_ocp_solver_pyx.pyx":186 + /* "acados_template/acados_ocp_solver_pyx.pyx":212 * `qp_solver_cond_N < N`. * """ * raise NotImplementedError("AcadosOcpSolverCython: does not support update_qp_solver_cond_N() since it is only a prototyping feature") # <<<<<<<<<<<<<< * * # # unlikely but still possible */ - __pyx_t_1 = __Pyx_PyObject_Call(__pyx_builtin_NotImplementedError, __pyx_tuple__12, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 186, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_Call(__pyx_builtin_NotImplementedError, __pyx_tuple__14, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 212, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_Raise(__pyx_t_1, 0, 0, 0); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __PYX_ERR(0, 186, __pyx_L1_error) + __PYX_ERR(0, 212, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":173 + /* "acados_template/acados_ocp_solver_pyx.pyx":199 * * * def update_qp_solver_cond_N(self, qp_solver_cond_N: int): # <<<<<<<<<<<<<< @@ -21208,7 +22030,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":207 +/* "acados_template/acados_ocp_solver_pyx.pyx":233 * * * def eval_param_sens(self, index, stage=0, field="ex"): # <<<<<<<<<<<<<< @@ -21217,16 +22039,16 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ /* Python wrapper */ -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13eval_param_sens(PyObject *__pyx_v_self, +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17eval_param_sens(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else PyObject *__pyx_args, PyObject *__pyx_kwds #endif ); /*proto*/ -PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12eval_param_sens, "\n Calculate the sensitivity of the curent solution with respect to the initial state component of index\n\n :param index: integer corresponding to initial state index in range(nx)\n "); -static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13eval_param_sens = {"eval_param_sens", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13eval_param_sens, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12eval_param_sens}; -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13eval_param_sens(PyObject *__pyx_v_self, +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16eval_param_sens, "\n Calculate the sensitivity of the curent solution with respect to the initial state component of index\n\n :param index: integer corresponding to initial state index in range(nx)\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17eval_param_sens = {"eval_param_sens", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17eval_param_sens, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16eval_param_sens}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17eval_param_sens(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else @@ -21267,26 +22089,26 @@ PyObject *__pyx_args, PyObject *__pyx_kwds switch (__pyx_nargs) { case 0: if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_index)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 207, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 233, __pyx_L3_error) else goto __pyx_L5_argtuple_error; CYTHON_FALLTHROUGH; case 1: if (kw_args > 0) { PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_stage); if (value) { values[1] = value; kw_args--; } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 207, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 233, __pyx_L3_error) } CYTHON_FALLTHROUGH; case 2: if (kw_args > 0) { PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field); if (value) { values[2] = value; kw_args--; } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 207, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 233, __pyx_L3_error) } } if (unlikely(kw_args > 0)) { const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "eval_param_sens") < 0)) __PYX_ERR(0, 207, __pyx_L3_error) + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "eval_param_sens") < 0)) __PYX_ERR(0, 233, __pyx_L3_error) } } else { switch (__pyx_nargs) { @@ -21305,20 +22127,20 @@ PyObject *__pyx_args, PyObject *__pyx_kwds } goto __pyx_L4_argument_unpacking_done; __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("eval_param_sens", 0, 1, 3, __pyx_nargs); __PYX_ERR(0, 207, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("eval_param_sens", 0, 1, 3, __pyx_nargs); __PYX_ERR(0, 233, __pyx_L3_error) __pyx_L3_error:; __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.eval_param_sens", __pyx_clineno, __pyx_lineno, __pyx_filename); __Pyx_RefNannyFinishContext(); return NULL; __pyx_L4_argument_unpacking_done:; - __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12eval_param_sens(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_index, __pyx_v_stage, __pyx_v_field); + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16eval_param_sens(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_index, __pyx_v_stage, __pyx_v_field); /* function exit code */ __Pyx_RefNannyFinishContext(); return __pyx_r; } -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12eval_param_sens(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_stage, PyObject *__pyx_v_field) { +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16eval_param_sens(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_stage, PyObject *__pyx_v_field) { PyObject *__pyx_v_field_ = NULL; int __pyx_v_nx; PyObject *__pyx_r = NULL; @@ -21340,7 +22162,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __Pyx_RefNannySetupContext("eval_param_sens", 0); __Pyx_INCREF(__pyx_v_field); - /* "acados_template/acados_ocp_solver_pyx.pyx":214 + /* "acados_template/acados_ocp_solver_pyx.pyx":240 * """ * * field_ = field # <<<<<<<<<<<<<< @@ -21350,14 +22172,14 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __Pyx_INCREF(__pyx_v_field); __pyx_v_field_ = __pyx_v_field; - /* "acados_template/acados_ocp_solver_pyx.pyx":215 + /* "acados_template/acados_ocp_solver_pyx.pyx":241 * * field_ = field * field = field_.encode('utf-8') # <<<<<<<<<<<<<< * * # checks */ - __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_field_, __pyx_n_s_encode); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 215, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_field_, __pyx_n_s_encode); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 241, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __pyx_t_3 = NULL; __pyx_t_4 = 0; @@ -21375,14 +22197,14 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_kp_u_utf_8}; __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; - if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 215, __pyx_L1_error) + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 241, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; } __Pyx_DECREF_SET(__pyx_v_field, __pyx_t_1); __pyx_t_1 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":218 + /* "acados_template/acados_ocp_solver_pyx.pyx":244 * * # checks * if not isinstance(index, int): # <<<<<<<<<<<<<< @@ -21393,20 +22215,20 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_t_6 = (!__pyx_t_5); if (unlikely(__pyx_t_6)) { - /* "acados_template/acados_ocp_solver_pyx.pyx":219 + /* "acados_template/acados_ocp_solver_pyx.pyx":245 * # checks * if not isinstance(index, int): * raise Exception('AcadosOcpSolverCython.eval_param_sens(): index must be Integer.') # <<<<<<<<<<<<<< * * cdef int nx = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, self.nlp_dims, self.nlp_out, 0, "x".encode('utf-8')) */ - __pyx_t_1 = __Pyx_PyObject_Call(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_tuple__13, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 219, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_Call(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_tuple__15, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 245, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_Raise(__pyx_t_1, 0, 0, 0); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __PYX_ERR(0, 219, __pyx_L1_error) + __PYX_ERR(0, 245, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":218 + /* "acados_template/acados_ocp_solver_pyx.pyx":244 * * # checks * if not isinstance(index, int): # <<<<<<<<<<<<<< @@ -21415,49 +22237,49 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":221 + /* "acados_template/acados_ocp_solver_pyx.pyx":247 * raise Exception('AcadosOcpSolverCython.eval_param_sens(): index must be Integer.') * * cdef int nx = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, self.nlp_dims, self.nlp_out, 0, "x".encode('utf-8')) # <<<<<<<<<<<<<< * * if index < 0 or index > nx: */ - __pyx_t_7 = __Pyx_PyBytes_AsString(__pyx_n_b_x); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 221, __pyx_L1_error) + __pyx_t_7 = __Pyx_PyBytes_AsString(__pyx_n_b_x); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 247, __pyx_L1_error) __pyx_v_nx = ocp_nlp_dims_get_from_attr(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, 0, __pyx_t_7); - /* "acados_template/acados_ocp_solver_pyx.pyx":223 + /* "acados_template/acados_ocp_solver_pyx.pyx":249 * cdef int nx = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, self.nlp_dims, self.nlp_out, 0, "x".encode('utf-8')) * * if index < 0 or index > nx: # <<<<<<<<<<<<<< * raise Exception(f'AcadosOcpSolverCython.eval_param_sens(): index must be in [0, nx-1], got: {index}.') * */ - __pyx_t_1 = PyObject_RichCompare(__pyx_v_index, __pyx_int_0, Py_LT); __Pyx_XGOTREF(__pyx_t_1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 223, __pyx_L1_error) - __pyx_t_5 = __Pyx_PyObject_IsTrue(__pyx_t_1); if (unlikely((__pyx_t_5 < 0))) __PYX_ERR(0, 223, __pyx_L1_error) + __pyx_t_1 = PyObject_RichCompare(__pyx_v_index, __pyx_int_0, Py_LT); __Pyx_XGOTREF(__pyx_t_1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 249, __pyx_L1_error) + __pyx_t_5 = __Pyx_PyObject_IsTrue(__pyx_t_1); if (unlikely((__pyx_t_5 < 0))) __PYX_ERR(0, 249, __pyx_L1_error) __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; if (!__pyx_t_5) { } else { __pyx_t_6 = __pyx_t_5; goto __pyx_L5_bool_binop_done; } - __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_nx); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 223, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_nx); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 249, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); - __pyx_t_2 = PyObject_RichCompare(__pyx_v_index, __pyx_t_1, Py_GT); __Pyx_XGOTREF(__pyx_t_2); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 223, __pyx_L1_error) + __pyx_t_2 = PyObject_RichCompare(__pyx_v_index, __pyx_t_1, Py_GT); __Pyx_XGOTREF(__pyx_t_2); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 249, __pyx_L1_error) __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_5 = __Pyx_PyObject_IsTrue(__pyx_t_2); if (unlikely((__pyx_t_5 < 0))) __PYX_ERR(0, 223, __pyx_L1_error) + __pyx_t_5 = __Pyx_PyObject_IsTrue(__pyx_t_2); if (unlikely((__pyx_t_5 < 0))) __PYX_ERR(0, 249, __pyx_L1_error) __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; __pyx_t_6 = __pyx_t_5; __pyx_L5_bool_binop_done:; if (unlikely(__pyx_t_6)) { - /* "acados_template/acados_ocp_solver_pyx.pyx":224 + /* "acados_template/acados_ocp_solver_pyx.pyx":250 * * if index < 0 or index > nx: * raise Exception(f'AcadosOcpSolverCython.eval_param_sens(): index must be in [0, nx-1], got: {index}.') # <<<<<<<<<<<<<< * * # actual eval_param */ - __pyx_t_2 = PyTuple_New(3); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 224, __pyx_L1_error) + __pyx_t_2 = PyTuple_New(3); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 250, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __pyx_t_8 = 0; __pyx_t_9 = 127; @@ -21465,7 +22287,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_t_8 += 74; __Pyx_GIVEREF(__pyx_kp_u_AcadosOcpSolverCython_eval_param_2); PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_kp_u_AcadosOcpSolverCython_eval_param_2); - __pyx_t_1 = __Pyx_PyObject_FormatSimple(__pyx_v_index, __pyx_empty_unicode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 224, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_FormatSimple(__pyx_v_index, __pyx_empty_unicode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 250, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __pyx_t_9 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) > __pyx_t_9) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) : __pyx_t_9; __pyx_t_8 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); @@ -21476,17 +22298,17 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_t_8 += 1; __Pyx_GIVEREF(__pyx_kp_u__2); PyTuple_SET_ITEM(__pyx_t_2, 2, __pyx_kp_u__2); - __pyx_t_1 = __Pyx_PyUnicode_Join(__pyx_t_2, 3, __pyx_t_8, __pyx_t_9); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 224, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyUnicode_Join(__pyx_t_2, 3, __pyx_t_8, __pyx_t_9); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 250, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - __pyx_t_2 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 224, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 250, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; __Pyx_Raise(__pyx_t_2, 0, 0, 0); __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - __PYX_ERR(0, 224, __pyx_L1_error) + __PYX_ERR(0, 250, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":223 + /* "acados_template/acados_ocp_solver_pyx.pyx":249 * cdef int nx = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, self.nlp_dims, self.nlp_out, 0, "x".encode('utf-8')) * * if index < 0 or index > nx: # <<<<<<<<<<<<<< @@ -21495,19 +22317,19 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":227 + /* "acados_template/acados_ocp_solver_pyx.pyx":253 * * # actual eval_param * acados_solver_common.ocp_nlp_eval_param_sens(self.nlp_solver, field, stage, index, self.sens_out) # <<<<<<<<<<<<<< * * return */ - __pyx_t_10 = __Pyx_PyObject_AsWritableString(__pyx_v_field); if (unlikely((!__pyx_t_10) && PyErr_Occurred())) __PYX_ERR(0, 227, __pyx_L1_error) - __pyx_t_4 = __Pyx_PyInt_As_int(__pyx_v_stage); if (unlikely((__pyx_t_4 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 227, __pyx_L1_error) - __pyx_t_11 = __Pyx_PyInt_As_int(__pyx_v_index); if (unlikely((__pyx_t_11 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 227, __pyx_L1_error) + __pyx_t_10 = __Pyx_PyObject_AsWritableString(__pyx_v_field); if (unlikely((!__pyx_t_10) && PyErr_Occurred())) __PYX_ERR(0, 253, __pyx_L1_error) + __pyx_t_4 = __Pyx_PyInt_As_int(__pyx_v_stage); if (unlikely((__pyx_t_4 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 253, __pyx_L1_error) + __pyx_t_11 = __Pyx_PyInt_As_int(__pyx_v_index); if (unlikely((__pyx_t_11 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 253, __pyx_L1_error) ocp_nlp_eval_param_sens(__pyx_v_self->nlp_solver, __pyx_t_10, __pyx_t_4, __pyx_t_11, __pyx_v_self->sens_out); - /* "acados_template/acados_ocp_solver_pyx.pyx":229 + /* "acados_template/acados_ocp_solver_pyx.pyx":255 * acados_solver_common.ocp_nlp_eval_param_sens(self.nlp_solver, field, stage, index, self.sens_out) * * return # <<<<<<<<<<<<<< @@ -21518,7 +22340,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_r = Py_None; __Pyx_INCREF(Py_None); goto __pyx_L0; - /* "acados_template/acados_ocp_solver_pyx.pyx":207 + /* "acados_template/acados_ocp_solver_pyx.pyx":233 * * * def eval_param_sens(self, index, stage=0, field="ex"): # <<<<<<<<<<<<<< @@ -21541,7 +22363,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":232 +/* "acados_template/acados_ocp_solver_pyx.pyx":258 * * * def get(self, int stage, str field_): # <<<<<<<<<<<<<< @@ -21550,16 +22372,16 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ /* Python wrapper */ -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15get(PyObject *__pyx_v_self, +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19get(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else PyObject *__pyx_args, PyObject *__pyx_kwds #endif ); /*proto*/ -PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14get, "\n Get the last solution of the solver:\n\n :param stage: integer corresponding to shooting node\n :param field: string in ['x', 'u', 'z', 'pi', 'lam', 't', 'sl', 'su',]\n\n .. note:: regarding lam, t: \n\n the inequalities are internally organized in the following order: \n\n [ lbu lbx lg lh lphi ubu ubx ug uh uphi; \n\n lsbu lsbx lsg lsh lsphi usbu usbx usg ush usphi]\n\n .. note:: pi: multipliers for dynamics equality constraints \n\n lam: multipliers for inequalities \n\n t: slack variables corresponding to evaluation of all inequalities (at the solution) \n\n sl: slack variables of soft lower inequality constraints \n\n su: slack variables of soft upper inequality constraints \n\n "); -static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15get = {"get", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15get, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14get}; -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15get(PyObject *__pyx_v_self, +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18get, "\n Get the last solution of the solver:\n\n :param stage: integer corresponding to shooting node\n :param field: string in ['x', 'u', 'z', 'pi', 'lam', 't', 'sl', 'su',]\n\n .. note:: regarding lam, t: \n\n the inequalities are internally organized in the following order: \n\n [ lbu lbx lg lh lphi ubu ubx ug uh uphi; \n\n lsbu lsbx lsg lsh lsphi usbu usbx usg ush usphi]\n\n .. note:: pi: multipliers for dynamics equality constraints \n\n lam: multipliers for inequalities \n\n t: slack variables corresponding to evaluation of all inequalities (at the solution) \n\n sl: slack variables of soft lower inequality constraints \n\n su: slack variables of soft upper inequality constraints \n\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19get = {"get", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19get, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18get}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19get(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else @@ -21595,19 +22417,19 @@ PyObject *__pyx_args, PyObject *__pyx_kwds switch (__pyx_nargs) { case 0: if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_stage)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 232, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 258, __pyx_L3_error) else goto __pyx_L5_argtuple_error; CYTHON_FALLTHROUGH; case 1: if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field_2)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 232, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 258, __pyx_L3_error) else { - __Pyx_RaiseArgtupleInvalid("get", 1, 2, 2, 1); __PYX_ERR(0, 232, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("get", 1, 2, 2, 1); __PYX_ERR(0, 258, __pyx_L3_error) } } if (unlikely(kw_args > 0)) { const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "get") < 0)) __PYX_ERR(0, 232, __pyx_L3_error) + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "get") < 0)) __PYX_ERR(0, 258, __pyx_L3_error) } } else if (unlikely(__pyx_nargs != 2)) { goto __pyx_L5_argtuple_error; @@ -21615,19 +22437,19 @@ PyObject *__pyx_args, PyObject *__pyx_kwds values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); } - __pyx_v_stage = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_stage == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 232, __pyx_L3_error) + __pyx_v_stage = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_stage == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 258, __pyx_L3_error) __pyx_v_field_ = ((PyObject*)values[1]); } goto __pyx_L4_argument_unpacking_done; __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("get", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 232, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("get", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 258, __pyx_L3_error) __pyx_L3_error:; __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.get", __pyx_clineno, __pyx_lineno, __pyx_filename); __Pyx_RefNannyFinishContext(); return NULL; __pyx_L4_argument_unpacking_done:; - if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 232, __pyx_L1_error) - __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14get(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_stage, __pyx_v_field_); + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 258, __pyx_L1_error) + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18get(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_stage, __pyx_v_field_); /* function exit code */ goto __pyx_L0; @@ -21638,7 +22460,7 @@ PyObject *__pyx_args, PyObject *__pyx_kwds return __pyx_r; } -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14get(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_) { +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18get(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_) { PyObject *__pyx_v_out_fields = NULL; PyObject *__pyx_v_field = NULL; int __pyx_v_dims; @@ -21667,14 +22489,14 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_pybuffernd_out.data = NULL; __pyx_pybuffernd_out.rcbuffer = &__pyx_pybuffer_out; - /* "acados_template/acados_ocp_solver_pyx.pyx":251 + /* "acados_template/acados_ocp_solver_pyx.pyx":277 * """ * * out_fields = ['x', 'u', 'z', 'pi', 'lam', 't', 'sl', 'su'] # <<<<<<<<<<<<<< * field = field_.encode('utf-8') * */ - __pyx_t_1 = PyList_New(8); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 251, __pyx_L1_error) + __pyx_t_1 = PyList_New(8); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 277, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_INCREF(__pyx_n_u_x); __Pyx_GIVEREF(__pyx_n_u_x); @@ -21703,7 +22525,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_v_out_fields = ((PyObject*)__pyx_t_1); __pyx_t_1 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":252 + /* "acados_template/acados_ocp_solver_pyx.pyx":278 * * out_fields = ['x', 'u', 'z', 'pi', 'lam', 't', 'sl', 'su'] * field = field_.encode('utf-8') # <<<<<<<<<<<<<< @@ -21712,31 +22534,31 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ if (unlikely(__pyx_v_field_ == Py_None)) { PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "encode"); - __PYX_ERR(0, 252, __pyx_L1_error) + __PYX_ERR(0, 278, __pyx_L1_error) } - __pyx_t_1 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 252, __pyx_L1_error) + __pyx_t_1 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 278, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __pyx_v_field = __pyx_t_1; __pyx_t_1 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":254 + /* "acados_template/acados_ocp_solver_pyx.pyx":280 * field = field_.encode('utf-8') * * if field_ not in out_fields: # <<<<<<<<<<<<<< * raise Exception('AcadosOcpSolverCython.get(): {} is an invalid argument.\ - * \n Possible values are {}. Exiting.'.format(field_, out_fields)) + * \n Possible values are {}.'.format(field_, out_fields)) */ - __pyx_t_2 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_out_fields, Py_NE)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 254, __pyx_L1_error) + __pyx_t_2 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_out_fields, Py_NE)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 280, __pyx_L1_error) if (unlikely(__pyx_t_2)) { - /* "acados_template/acados_ocp_solver_pyx.pyx":256 + /* "acados_template/acados_ocp_solver_pyx.pyx":282 * if field_ not in out_fields: * raise Exception('AcadosOcpSolverCython.get(): {} is an invalid argument.\ - * \n Possible values are {}. Exiting.'.format(field_, out_fields)) # <<<<<<<<<<<<<< + * \n Possible values are {}.'.format(field_, out_fields)) # <<<<<<<<<<<<<< * * if stage < 0 or stage > self.N: */ - __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_get_is_an, __pyx_n_s_format); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 256, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_get_is_an, __pyx_n_s_format); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 282, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __pyx_t_4 = NULL; __pyx_t_5 = 0; @@ -21754,36 +22576,36 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_callargs[3] = {__pyx_t_4, __pyx_v_field_, __pyx_v_out_fields}; __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_5, 2+__pyx_t_5); __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; - if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 256, __pyx_L1_error) + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 282, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; } - /* "acados_template/acados_ocp_solver_pyx.pyx":255 + /* "acados_template/acados_ocp_solver_pyx.pyx":281 * * if field_ not in out_fields: * raise Exception('AcadosOcpSolverCython.get(): {} is an invalid argument.\ # <<<<<<<<<<<<<< - * \n Possible values are {}. Exiting.'.format(field_, out_fields)) + * \n Possible values are {}.'.format(field_, out_fields)) * */ - __pyx_t_3 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 255, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 281, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; __Pyx_Raise(__pyx_t_3, 0, 0, 0); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - __PYX_ERR(0, 255, __pyx_L1_error) + __PYX_ERR(0, 281, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":254 + /* "acados_template/acados_ocp_solver_pyx.pyx":280 * field = field_.encode('utf-8') * * if field_ not in out_fields: # <<<<<<<<<<<<<< * raise Exception('AcadosOcpSolverCython.get(): {} is an invalid argument.\ - * \n Possible values are {}. Exiting.'.format(field_, out_fields)) + * \n Possible values are {}.'.format(field_, out_fields)) */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":258 - * \n Possible values are {}. Exiting.'.format(field_, out_fields)) + /* "acados_template/acados_ocp_solver_pyx.pyx":284 + * \n Possible values are {}.'.format(field_, out_fields)) * * if stage < 0 or stage > self.N: # <<<<<<<<<<<<<< * raise Exception('AcadosOcpSolverCython.get(): stage index must be in [0, N], got: {}.'.format(self.N)) @@ -21800,16 +22622,16 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_L5_bool_binop_done:; if (unlikely(__pyx_t_2)) { - /* "acados_template/acados_ocp_solver_pyx.pyx":259 + /* "acados_template/acados_ocp_solver_pyx.pyx":285 * * if stage < 0 or stage > self.N: * raise Exception('AcadosOcpSolverCython.get(): stage index must be in [0, N], got: {}.'.format(self.N)) # <<<<<<<<<<<<<< * * if stage == self.N and field_ == 'pi': */ - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_get_stage, __pyx_n_s_format); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 259, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_get_stage, __pyx_n_s_format); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 285, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); - __pyx_t_4 = __Pyx_PyInt_From_int(__pyx_v_self->N); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 259, __pyx_L1_error) + __pyx_t_4 = __Pyx_PyInt_From_int(__pyx_v_self->N); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 285, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); __pyx_t_7 = NULL; __pyx_t_5 = 0; @@ -21828,19 +22650,19 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_5, 1+__pyx_t_5); __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 259, __pyx_L1_error) + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 285, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; } - __pyx_t_1 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 259, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 285, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; __Pyx_Raise(__pyx_t_1, 0, 0, 0); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __PYX_ERR(0, 259, __pyx_L1_error) + __PYX_ERR(0, 285, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":258 - * \n Possible values are {}. Exiting.'.format(field_, out_fields)) + /* "acados_template/acados_ocp_solver_pyx.pyx":284 + * \n Possible values are {}.'.format(field_, out_fields)) * * if stage < 0 or stage > self.N: # <<<<<<<<<<<<<< * raise Exception('AcadosOcpSolverCython.get(): stage index must be in [0, N], got: {}.'.format(self.N)) @@ -21848,7 +22670,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":261 + /* "acados_template/acados_ocp_solver_pyx.pyx":287 * raise Exception('AcadosOcpSolverCython.get(): stage index must be in [0, N], got: {}.'.format(self.N)) * * if stage == self.N and field_ == 'pi': # <<<<<<<<<<<<<< @@ -21861,21 +22683,21 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_t_2 = __pyx_t_6; goto __pyx_L8_bool_binop_done; } - __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_pi, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 261, __pyx_L1_error) + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_pi, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 287, __pyx_L1_error) __pyx_t_2 = __pyx_t_6; __pyx_L8_bool_binop_done:; if (unlikely(__pyx_t_2)) { - /* "acados_template/acados_ocp_solver_pyx.pyx":263 + /* "acados_template/acados_ocp_solver_pyx.pyx":289 * if stage == self.N and field_ == 'pi': * raise Exception('AcadosOcpSolverCython.get(): field {} does not exist at final stage {}.'\ * .format(field_, stage)) # <<<<<<<<<<<<<< * * cdef int dims = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, */ - __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_get_field, __pyx_n_s_format); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 263, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_get_field, __pyx_n_s_format); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 289, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); - __pyx_t_4 = __Pyx_PyInt_From_int(__pyx_v_stage); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 263, __pyx_L1_error) + __pyx_t_4 = __Pyx_PyInt_From_int(__pyx_v_stage); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 289, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); __pyx_t_7 = NULL; __pyx_t_5 = 0; @@ -21894,26 +22716,26 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_5, 2+__pyx_t_5); __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 263, __pyx_L1_error) + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 289, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; } - /* "acados_template/acados_ocp_solver_pyx.pyx":262 + /* "acados_template/acados_ocp_solver_pyx.pyx":288 * * if stage == self.N and field_ == 'pi': * raise Exception('AcadosOcpSolverCython.get(): field {} does not exist at final stage {}.'\ # <<<<<<<<<<<<<< * .format(field_, stage)) * */ - __pyx_t_3 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 262, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 288, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; __Pyx_Raise(__pyx_t_3, 0, 0, 0); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - __PYX_ERR(0, 262, __pyx_L1_error) + __PYX_ERR(0, 288, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":261 + /* "acados_template/acados_ocp_solver_pyx.pyx":287 * raise Exception('AcadosOcpSolverCython.get(): stage index must be in [0, N], got: {}.'.format(self.N)) * * if stage == self.N and field_ == 'pi': # <<<<<<<<<<<<<< @@ -21922,16 +22744,16 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":266 + /* "acados_template/acados_ocp_solver_pyx.pyx":292 * * cdef int dims = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, * self.nlp_dims, self.nlp_out, stage, field) # <<<<<<<<<<<<<< * * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((dims,)) */ - __pyx_t_8 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_8) && PyErr_Occurred())) __PYX_ERR(0, 266, __pyx_L1_error) + __pyx_t_8 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_8) && PyErr_Occurred())) __PYX_ERR(0, 292, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":265 + /* "acados_template/acados_ocp_solver_pyx.pyx":291 * .format(field_, stage)) * * cdef int dims = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, # <<<<<<<<<<<<<< @@ -21940,21 +22762,21 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ __pyx_v_dims = ocp_nlp_dims_get_from_attr(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_8); - /* "acados_template/acados_ocp_solver_pyx.pyx":268 + /* "acados_template/acados_ocp_solver_pyx.pyx":294 * self.nlp_dims, self.nlp_out, stage, field) * * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((dims,)) # <<<<<<<<<<<<<< * acados_solver_common.ocp_nlp_out_get(self.nlp_config, \ * self.nlp_dims, self.nlp_out, stage, field, out.data) */ - __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 268, __pyx_L1_error) + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 294, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); - __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_zeros); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 268, __pyx_L1_error) + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_zeros); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 294, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_dims); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 268, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_dims); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 294, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); - __pyx_t_7 = PyTuple_New(1); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 268, __pyx_L1_error) + __pyx_t_7 = PyTuple_New(1); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 294, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); __Pyx_GIVEREF(__pyx_t_1); PyTuple_SET_ITEM(__pyx_t_7, 0, __pyx_t_1); @@ -21976,17 +22798,17 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_5, 1+__pyx_t_5); __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 268, __pyx_L1_error) + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 294, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; } - if (!(likely(((__pyx_t_3) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_3, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 268, __pyx_L1_error) + if (!(likely(((__pyx_t_3) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_3, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 294, __pyx_L1_error) __pyx_t_9 = ((PyArrayObject *)__pyx_t_3); { __Pyx_BufFmt_StackElem __pyx_stack[1]; if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_out.rcbuffer->pybuffer, (PyObject*)__pyx_t_9, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 1, 0, __pyx_stack) == -1)) { __pyx_v_out = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_out.rcbuffer->pybuffer.buf = NULL; - __PYX_ERR(0, 268, __pyx_L1_error) + __PYX_ERR(0, 294, __pyx_L1_error) } else {__pyx_pybuffernd_out.diminfo[0].strides = __pyx_pybuffernd_out.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_out.diminfo[0].shape = __pyx_pybuffernd_out.rcbuffer->pybuffer.shape[0]; } } @@ -21994,17 +22816,17 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_v_out = ((PyArrayObject *)__pyx_t_3); __pyx_t_3 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":270 + /* "acados_template/acados_ocp_solver_pyx.pyx":296 * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((dims,)) * acados_solver_common.ocp_nlp_out_get(self.nlp_config, \ * self.nlp_dims, self.nlp_out, stage, field, out.data) # <<<<<<<<<<<<<< * * return out */ - __pyx_t_10 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_10) && PyErr_Occurred())) __PYX_ERR(0, 270, __pyx_L1_error) - __pyx_t_11 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_out)); if (unlikely(__pyx_t_11 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 270, __pyx_L1_error) + __pyx_t_10 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_10) && PyErr_Occurred())) __PYX_ERR(0, 296, __pyx_L1_error) + __pyx_t_11 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_out)); if (unlikely(__pyx_t_11 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 296, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":269 + /* "acados_template/acados_ocp_solver_pyx.pyx":295 * * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((dims,)) * acados_solver_common.ocp_nlp_out_get(self.nlp_config, \ # <<<<<<<<<<<<<< @@ -22013,7 +22835,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ ocp_nlp_out_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_10, ((void *)__pyx_t_11)); - /* "acados_template/acados_ocp_solver_pyx.pyx":272 + /* "acados_template/acados_ocp_solver_pyx.pyx":298 * self.nlp_dims, self.nlp_out, stage, field, out.data) * * return out # <<<<<<<<<<<<<< @@ -22025,7 +22847,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_r = ((PyObject *)__pyx_v_out); goto __pyx_L0; - /* "acados_template/acados_ocp_solver_pyx.pyx":232 + /* "acados_template/acados_ocp_solver_pyx.pyx":258 * * * def get(self, int stage, str field_): # <<<<<<<<<<<<<< @@ -22059,7 +22881,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":275 +/* "acados_template/acados_ocp_solver_pyx.pyx":301 * * * def print_statistics(self): # <<<<<<<<<<<<<< @@ -22068,16 +22890,16 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ /* Python wrapper */ -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17print_statistics(PyObject *__pyx_v_self, +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21print_statistics(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else PyObject *__pyx_args, PyObject *__pyx_kwds #endif ); /*proto*/ -PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16print_statistics, "\n prints statistics of previous solver run as a table:\n - iter: iteration number\n - res_stat: stationarity residual\n - res_eq: residual wrt equality constraints (dynamics)\n - res_ineq: residual wrt inequality constraints (constraints)\n - res_comp: residual wrt complementarity conditions\n - qp_stat: status of QP solver\n - qp_iter: number of QP iterations\n - qp_res_stat: stationarity residual of the last QP solution\n - qp_res_eq: residual wrt equality constraints (dynamics) of the last QP solution\n - qp_res_ineq: residual wrt inequality constraints (constraints) of the last QP solution\n - qp_res_comp: residual wrt complementarity conditions of the last QP solution\n "); -static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17print_statistics = {"print_statistics", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17print_statistics, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16print_statistics}; -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17print_statistics(PyObject *__pyx_v_self, +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20print_statistics, "\n prints statistics of previous solver run as a table:\n - iter: iteration number\n - res_stat: stationarity residual\n - res_eq: residual wrt equality constraints (dynamics)\n - res_ineq: residual wrt inequality constraints (constraints)\n - res_comp: residual wrt complementarity conditions\n - qp_stat: status of QP solver\n - qp_iter: number of QP iterations\n - qp_res_stat: stationarity residual of the last QP solution\n - qp_res_eq: residual wrt equality constraints (dynamics) of the last QP solution\n - qp_res_ineq: residual wrt inequality constraints (constraints) of the last QP solution\n - qp_res_comp: residual wrt complementarity conditions of the last QP solution\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21print_statistics = {"print_statistics", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21print_statistics, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20print_statistics}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21print_statistics(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else @@ -22094,19 +22916,19 @@ PyObject *__pyx_args, PyObject *__pyx_kwds if (unlikely(__pyx_nargs > 0)) { __Pyx_RaiseArgtupleInvalid("print_statistics", 1, 0, 0, __pyx_nargs); return NULL;} if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "print_statistics", 0))) return NULL; - __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16print_statistics(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20print_statistics(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); /* function exit code */ __Pyx_RefNannyFinishContext(); return __pyx_r; } -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16print_statistics(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20print_statistics(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { PyObject *__pyx_r = NULL; __Pyx_RefNannyDeclarations __Pyx_RefNannySetupContext("print_statistics", 0); - /* "acados_template/acados_ocp_solver_pyx.pyx":290 + /* "acados_template/acados_ocp_solver_pyx.pyx":316 * - qp_res_comp: residual wrt complementarity conditions of the last QP solution * """ * acados_solver.acados_print_stats(self.capsule) # <<<<<<<<<<<<<< @@ -22115,7 +22937,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ long_acados_print_stats(__pyx_v_self->capsule); - /* "acados_template/acados_ocp_solver_pyx.pyx":275 + /* "acados_template/acados_ocp_solver_pyx.pyx":301 * * * def print_statistics(self): # <<<<<<<<<<<<<< @@ -22130,7 +22952,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":293 +/* "acados_template/acados_ocp_solver_pyx.pyx":319 * * * def store_iterate(self, filename='', overwrite=False): # <<<<<<<<<<<<<< @@ -22139,16 +22961,16 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ /* Python wrapper */ -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19store_iterate(PyObject *__pyx_v_self, +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23store_iterate(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else PyObject *__pyx_args, PyObject *__pyx_kwds #endif ); /*proto*/ -PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18store_iterate, "\n Stores the current iterate of the ocp solver in a json file.\n\n :param filename: if not set, use model_name + timestamp + '.json'\n :param overwrite: if false and filename exists add timestamp to filename\n "); -static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19store_iterate = {"store_iterate", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19store_iterate, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18store_iterate}; -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19store_iterate(PyObject *__pyx_v_self, +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22store_iterate, "\n Stores the current iterate of the ocp solver in a json file.\n\n :param filename: if not set, use model_name + timestamp + '.json'\n :param overwrite: if false and filename exists add timestamp to filename\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23store_iterate = {"store_iterate", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23store_iterate, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22store_iterate}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23store_iterate(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else @@ -22170,7 +22992,7 @@ PyObject *__pyx_args, PyObject *__pyx_kwds { PyObject **__pyx_pyargnames[] = {&__pyx_n_s_filename,&__pyx_n_s_overwrite,0}; PyObject* values[2] = {0,0}; - values[0] = ((PyObject *)__pyx_kp_u__14); + values[0] = ((PyObject *)__pyx_kp_u__16); values[1] = ((PyObject *)Py_False); if (__pyx_kwds) { Py_ssize_t kw_args; @@ -22188,19 +23010,19 @@ PyObject *__pyx_args, PyObject *__pyx_kwds if (kw_args > 0) { PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_filename); if (value) { values[0] = value; kw_args--; } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 293, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 319, __pyx_L3_error) } CYTHON_FALLTHROUGH; case 1: if (kw_args > 0) { PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_overwrite); if (value) { values[1] = value; kw_args--; } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 293, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 319, __pyx_L3_error) } } if (unlikely(kw_args > 0)) { const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "store_iterate") < 0)) __PYX_ERR(0, 293, __pyx_L3_error) + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "store_iterate") < 0)) __PYX_ERR(0, 319, __pyx_L3_error) } } else { switch (__pyx_nargs) { @@ -22217,20 +23039,20 @@ PyObject *__pyx_args, PyObject *__pyx_kwds } goto __pyx_L4_argument_unpacking_done; __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("store_iterate", 0, 0, 2, __pyx_nargs); __PYX_ERR(0, 293, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("store_iterate", 0, 0, 2, __pyx_nargs); __PYX_ERR(0, 319, __pyx_L3_error) __pyx_L3_error:; __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.store_iterate", __pyx_clineno, __pyx_lineno, __pyx_filename); __Pyx_RefNannyFinishContext(); return NULL; __pyx_L4_argument_unpacking_done:; - __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18store_iterate(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_filename, __pyx_v_overwrite); + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22store_iterate(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_filename, __pyx_v_overwrite); /* function exit code */ __Pyx_RefNannyFinishContext(); return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":326 +/* "acados_template/acados_ocp_solver_pyx.pyx":358 * # save * with open(filename, 'w') as f: * json.dump(solution, f, default=lambda x: x.tolist(), indent=4, sort_keys=True) # <<<<<<<<<<<<<< @@ -22280,12 +23102,12 @@ PyObject *__pyx_args, PyObject *__pyx_kwds switch (__pyx_nargs) { case 0: if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_x)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 326, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 358, __pyx_L3_error) else goto __pyx_L5_argtuple_error; } if (unlikely(kw_args > 0)) { const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "lambda") < 0)) __PYX_ERR(0, 326, __pyx_L3_error) + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "lambda") < 0)) __PYX_ERR(0, 358, __pyx_L3_error) } } else if (unlikely(__pyx_nargs != 1)) { goto __pyx_L5_argtuple_error; @@ -22296,7 +23118,7 @@ PyObject *__pyx_args, PyObject *__pyx_kwds } goto __pyx_L4_argument_unpacking_done; __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("lambda", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 326, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("lambda", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 358, __pyx_L3_error) __pyx_L3_error:; __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.store_iterate.lambda", __pyx_clineno, __pyx_lineno, __pyx_filename); __Pyx_RefNannyFinishContext(); @@ -22321,7 +23143,7 @@ static PyObject *__pyx_lambda_funcdef_lambda(CYTHON_UNUSED PyObject *__pyx_self, int __pyx_clineno = 0; __Pyx_RefNannySetupContext("lambda", 0); __Pyx_XDECREF(__pyx_r); - __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_x, __pyx_n_s_tolist); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 326, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_x, __pyx_n_s_tolist); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 358, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __pyx_t_3 = NULL; __pyx_t_4 = 0; @@ -22339,7 +23161,7 @@ static PyObject *__pyx_lambda_funcdef_lambda(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_callargs[1] = {__pyx_t_3, }; __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 0+__pyx_t_4); __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; - if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 326, __pyx_L1_error) + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 358, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; } @@ -22360,7 +23182,7 @@ static PyObject *__pyx_lambda_funcdef_lambda(CYTHON_UNUSED PyObject *__pyx_self, return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":293 +/* "acados_template/acados_ocp_solver_pyx.pyx":319 * * * def store_iterate(self, filename='', overwrite=False): # <<<<<<<<<<<<<< @@ -22368,10 +23190,13 @@ static PyObject *__pyx_lambda_funcdef_lambda(CYTHON_UNUSED PyObject *__pyx_self, * Stores the current iterate of the ocp solver in a json file. */ -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18store_iterate(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_filename, PyObject *__pyx_v_overwrite) { +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22store_iterate(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_filename, PyObject *__pyx_v_overwrite) { PyObject *__pyx_v_json = NULL; PyObject *__pyx_v_solution = NULL; - PyObject *__pyx_v_i = NULL; + Py_ssize_t __pyx_v_lN; + long __pyx_v_i; + PyObject *__pyx_v_i_string = NULL; + PyObject *__pyx_v_k = NULL; PyObject *__pyx_v_f = NULL; PyObject *__pyx_r = NULL; __Pyx_RefNannyDeclarations @@ -22383,63 +23208,67 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS int __pyx_t_6; PyObject *__pyx_t_7 = NULL; Py_ssize_t __pyx_t_8; - PyObject *(*__pyx_t_9)(PyObject *); - PyObject *__pyx_t_10 = NULL; - PyObject *__pyx_t_11 = NULL; - PyObject *__pyx_t_12 = NULL; - PyObject *__pyx_t_13 = NULL; + long __pyx_t_9; + long __pyx_t_10; + long __pyx_t_11; + Py_UCS4 __pyx_t_12; + Py_ssize_t __pyx_t_13; PyObject *__pyx_t_14 = NULL; PyObject *__pyx_t_15 = NULL; + PyObject *__pyx_t_16 = NULL; + PyObject *__pyx_t_17 = NULL; + PyObject *__pyx_t_18 = NULL; + PyObject *__pyx_t_19 = NULL; int __pyx_lineno = 0; const char *__pyx_filename = NULL; int __pyx_clineno = 0; __Pyx_RefNannySetupContext("store_iterate", 0); __Pyx_INCREF(__pyx_v_filename); - /* "acados_template/acados_ocp_solver_pyx.pyx":300 + /* "acados_template/acados_ocp_solver_pyx.pyx":326 * :param overwrite: if false and filename exists add timestamp to filename * """ * import json # <<<<<<<<<<<<<< * if filename == '': * filename += self.model_name + '_' + 'iterate' + '.json' */ - __pyx_t_1 = __Pyx_ImportDottedModule(__pyx_n_s_json, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 300, __pyx_L1_error) + __pyx_t_1 = __Pyx_ImportDottedModule(__pyx_n_s_json, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 326, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __pyx_v_json = __pyx_t_1; __pyx_t_1 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":301 + /* "acados_template/acados_ocp_solver_pyx.pyx":327 * """ * import json * if filename == '': # <<<<<<<<<<<<<< * filename += self.model_name + '_' + 'iterate' + '.json' * */ - __pyx_t_2 = (__Pyx_PyUnicode_Equals(__pyx_v_filename, __pyx_kp_u__14, Py_EQ)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 301, __pyx_L1_error) + __pyx_t_2 = (__Pyx_PyUnicode_Equals(__pyx_v_filename, __pyx_kp_u__16, Py_EQ)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 327, __pyx_L1_error) if (__pyx_t_2) { - /* "acados_template/acados_ocp_solver_pyx.pyx":302 + /* "acados_template/acados_ocp_solver_pyx.pyx":328 * import json * if filename == '': * filename += self.model_name + '_' + 'iterate' + '.json' # <<<<<<<<<<<<<< * * if not overwrite: */ - __pyx_t_1 = __Pyx_PyUnicode_ConcatSafe(__pyx_v_self->model_name, __pyx_n_u__15); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 302, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyUnicode_ConcatSafe(__pyx_v_self->model_name, __pyx_n_u__17); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 328, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); - __pyx_t_3 = __Pyx_PyUnicode_ConcatInPlace(__pyx_t_1, __pyx_n_u_iterate); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 302, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyUnicode_ConcatInPlace(__pyx_t_1, __pyx_n_u_iterate); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 328, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_1 = __Pyx_PyUnicode_ConcatInPlace(__pyx_t_3, __pyx_kp_u_json_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 302, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyUnicode_ConcatInPlace(__pyx_t_3, __pyx_kp_u_json_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 328, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - __pyx_t_3 = PyNumber_InPlaceAdd(__pyx_v_filename, __pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 302, __pyx_L1_error) + __pyx_t_3 = PyNumber_InPlaceAdd(__pyx_v_filename, __pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 328, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; __Pyx_DECREF_SET(__pyx_v_filename, __pyx_t_3); __pyx_t_3 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":301 + /* "acados_template/acados_ocp_solver_pyx.pyx":327 * """ * import json * if filename == '': # <<<<<<<<<<<<<< @@ -22448,30 +23277,30 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":304 + /* "acados_template/acados_ocp_solver_pyx.pyx":330 * filename += self.model_name + '_' + 'iterate' + '.json' * * if not overwrite: # <<<<<<<<<<<<<< * # append timestamp * if os.path.isfile(filename): */ - __pyx_t_2 = __Pyx_PyObject_IsTrue(__pyx_v_overwrite); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 304, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_IsTrue(__pyx_v_overwrite); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 330, __pyx_L1_error) __pyx_t_4 = (!__pyx_t_2); if (__pyx_t_4) { - /* "acados_template/acados_ocp_solver_pyx.pyx":306 + /* "acados_template/acados_ocp_solver_pyx.pyx":332 * if not overwrite: * # append timestamp * if os.path.isfile(filename): # <<<<<<<<<<<<<< * filename = filename[:-5] * filename += datetime.utcnow().strftime('%Y-%m-%d-%H:%M:%S.%f') + '.json' */ - __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_os); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 306, __pyx_L1_error) + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_os); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 332, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); - __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_path); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 306, __pyx_L1_error) + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_path); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 332, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_5); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_isfile); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 306, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_isfile); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 332, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; __pyx_t_5 = NULL; @@ -22490,36 +23319,36 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_callargs[2] = {__pyx_t_5, __pyx_v_filename}; __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 1+__pyx_t_6); __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; - if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 306, __pyx_L1_error) + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 332, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; } - __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_t_3); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 306, __pyx_L1_error) + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_t_3); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 332, __pyx_L1_error) __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; if (__pyx_t_4) { - /* "acados_template/acados_ocp_solver_pyx.pyx":307 + /* "acados_template/acados_ocp_solver_pyx.pyx":333 * # append timestamp * if os.path.isfile(filename): * filename = filename[:-5] # <<<<<<<<<<<<<< * filename += datetime.utcnow().strftime('%Y-%m-%d-%H:%M:%S.%f') + '.json' * */ - __pyx_t_3 = __Pyx_PyObject_GetSlice(__pyx_v_filename, 0, -5L, NULL, NULL, &__pyx_slice__16, 0, 1, 1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 307, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyObject_GetSlice(__pyx_v_filename, 0, -5L, NULL, NULL, &__pyx_slice__18, 0, 1, 1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 333, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_DECREF_SET(__pyx_v_filename, __pyx_t_3); __pyx_t_3 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":308 + /* "acados_template/acados_ocp_solver_pyx.pyx":334 * if os.path.isfile(filename): * filename = filename[:-5] * filename += datetime.utcnow().strftime('%Y-%m-%d-%H:%M:%S.%f') + '.json' # <<<<<<<<<<<<<< * * # get iterate: */ - __Pyx_GetModuleGlobalName(__pyx_t_5, __pyx_n_s_datetime); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 308, __pyx_L1_error) + __Pyx_GetModuleGlobalName(__pyx_t_5, __pyx_n_s_datetime); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 334, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_5); - __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_utcnow); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 308, __pyx_L1_error) + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_utcnow); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 334, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; __pyx_t_5 = NULL; @@ -22538,11 +23367,11 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_callargs[1] = {__pyx_t_5, }; __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_7, __pyx_callargs+1-__pyx_t_6, 0+__pyx_t_6); __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; - if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 308, __pyx_L1_error) + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 334, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; } - __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_strftime); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 308, __pyx_L1_error) + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_strftime); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 334, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; __pyx_t_1 = NULL; @@ -22561,20 +23390,20 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_callargs[2] = {__pyx_t_1, __pyx_kp_u_Y_m_d_H_M_S_f}; __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_7, __pyx_callargs+1-__pyx_t_6, 1+__pyx_t_6); __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; - if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 308, __pyx_L1_error) + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 334, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; } - __pyx_t_7 = PyNumber_Add(__pyx_t_3, __pyx_kp_u_json_2); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 308, __pyx_L1_error) + __pyx_t_7 = PyNumber_Add(__pyx_t_3, __pyx_kp_u_json_2); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 334, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - __pyx_t_3 = PyNumber_InPlaceAdd(__pyx_v_filename, __pyx_t_7); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 308, __pyx_L1_error) + __pyx_t_3 = PyNumber_InPlaceAdd(__pyx_v_filename, __pyx_t_7); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 334, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; __Pyx_DECREF_SET(__pyx_v_filename, __pyx_t_3); __pyx_t_3 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":306 + /* "acados_template/acados_ocp_solver_pyx.pyx":332 * if not overwrite: * # append timestamp * if os.path.isfile(filename): # <<<<<<<<<<<<<< @@ -22583,7 +23412,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":304 + /* "acados_template/acados_ocp_solver_pyx.pyx":330 * filename += self.model_name + '_' + 'iterate' + '.json' * * if not overwrite: # <<<<<<<<<<<<<< @@ -22592,453 +23421,475 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":311 + /* "acados_template/acados_ocp_solver_pyx.pyx":337 * * # get iterate: * solution = dict() # <<<<<<<<<<<<<< * - * for i in range(self.N+1): + * lN = len(str(self.N+1)) */ - __pyx_t_3 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 311, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 337, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __pyx_v_solution = ((PyObject*)__pyx_t_3); __pyx_t_3 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":313 + /* "acados_template/acados_ocp_solver_pyx.pyx":339 * solution = dict() * - * for i in range(self.N+1): # <<<<<<<<<<<<<< - * solution['x_'+str(i)] = self.get(i,'x') - * solution['u_'+str(i)] = self.get(i,'u') + * lN = len(str(self.N+1)) # <<<<<<<<<<<<<< + * for i in range(self.N+1): + * i_string = f'{i:0{lN}d}' */ - __pyx_t_3 = __Pyx_PyInt_From_long((__pyx_v_self->N + 1)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 313, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyInt_From_long((__pyx_v_self->N + 1)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 339, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); - __pyx_t_7 = __Pyx_PyObject_CallOneArg(__pyx_builtin_range, __pyx_t_3); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 313, __pyx_L1_error) + __pyx_t_7 = __Pyx_PyObject_Str(__pyx_t_3); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 339, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - if (likely(PyList_CheckExact(__pyx_t_7)) || PyTuple_CheckExact(__pyx_t_7)) { - __pyx_t_3 = __pyx_t_7; __Pyx_INCREF(__pyx_t_3); __pyx_t_8 = 0; - __pyx_t_9 = NULL; - } else { - __pyx_t_8 = -1; __pyx_t_3 = PyObject_GetIter(__pyx_t_7); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 313, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __pyx_t_9 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_3); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 313, __pyx_L1_error) - } + __pyx_t_8 = PyObject_Length(__pyx_t_7); if (unlikely(__pyx_t_8 == ((Py_ssize_t)-1))) __PYX_ERR(0, 339, __pyx_L1_error) __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - for (;;) { - if (likely(!__pyx_t_9)) { - if (likely(PyList_CheckExact(__pyx_t_3))) { - if (__pyx_t_8 >= PyList_GET_SIZE(__pyx_t_3)) break; - #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - __pyx_t_7 = PyList_GET_ITEM(__pyx_t_3, __pyx_t_8); __Pyx_INCREF(__pyx_t_7); __pyx_t_8++; if (unlikely((0 < 0))) __PYX_ERR(0, 313, __pyx_L1_error) - #else - __pyx_t_7 = PySequence_ITEM(__pyx_t_3, __pyx_t_8); __pyx_t_8++; if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 313, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - #endif - } else { - if (__pyx_t_8 >= PyTuple_GET_SIZE(__pyx_t_3)) break; - #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - __pyx_t_7 = PyTuple_GET_ITEM(__pyx_t_3, __pyx_t_8); __Pyx_INCREF(__pyx_t_7); __pyx_t_8++; if (unlikely((0 < 0))) __PYX_ERR(0, 313, __pyx_L1_error) - #else - __pyx_t_7 = PySequence_ITEM(__pyx_t_3, __pyx_t_8); __pyx_t_8++; if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 313, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - #endif - } - } else { - __pyx_t_7 = __pyx_t_9(__pyx_t_3); - if (unlikely(!__pyx_t_7)) { - PyObject* exc_type = PyErr_Occurred(); - if (exc_type) { - if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); - else __PYX_ERR(0, 313, __pyx_L1_error) - } - break; - } - __Pyx_GOTREF(__pyx_t_7); - } - __Pyx_XDECREF_SET(__pyx_v_i, __pyx_t_7); - __pyx_t_7 = 0; + __pyx_v_lN = __pyx_t_8; - /* "acados_template/acados_ocp_solver_pyx.pyx":314 - * - * for i in range(self.N+1): - * solution['x_'+str(i)] = self.get(i,'x') # <<<<<<<<<<<<<< - * solution['u_'+str(i)] = self.get(i,'u') - * solution['z_'+str(i)] = self.get(i,'z') - */ - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 314, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_5 = NULL; - __pyx_t_6 = 0; - if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { - __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); - if (likely(__pyx_t_5)) { - PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); - __Pyx_INCREF(__pyx_t_5); - __Pyx_INCREF(function); - __Pyx_DECREF_SET(__pyx_t_1, function); - __pyx_t_6 = 1; - } - } - { - PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_v_i, __pyx_n_u_x}; - __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); - __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; - if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 314, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - } - __pyx_t_1 = __Pyx_PyObject_Str(__pyx_v_i); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 314, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_5 = PyNumber_Add(__pyx_n_u_x_2, __pyx_t_1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 314, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_5, __pyx_t_7) < 0))) __PYX_ERR(0, 314, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - - /* "acados_template/acados_ocp_solver_pyx.pyx":315 - * for i in range(self.N+1): - * solution['x_'+str(i)] = self.get(i,'x') - * solution['u_'+str(i)] = self.get(i,'u') # <<<<<<<<<<<<<< - * solution['z_'+str(i)] = self.get(i,'z') - * solution['lam_'+str(i)] = self.get(i,'lam') - */ - __pyx_t_5 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 315, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __pyx_t_1 = NULL; - __pyx_t_6 = 0; - if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_5))) { - __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_5); - if (likely(__pyx_t_1)) { - PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); - __Pyx_INCREF(__pyx_t_1); - __Pyx_INCREF(function); - __Pyx_DECREF_SET(__pyx_t_5, function); - __pyx_t_6 = 1; - } - } - { - PyObject *__pyx_callargs[3] = {__pyx_t_1, __pyx_v_i, __pyx_n_u_u}; - __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); - __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; - if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 315, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - } - __pyx_t_5 = __Pyx_PyObject_Str(__pyx_v_i); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 315, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __pyx_t_1 = PyNumber_Add(__pyx_n_u_u_2, __pyx_t_5); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 315, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_7) < 0))) __PYX_ERR(0, 315, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - - /* "acados_template/acados_ocp_solver_pyx.pyx":316 - * solution['x_'+str(i)] = self.get(i,'x') - * solution['u_'+str(i)] = self.get(i,'u') - * solution['z_'+str(i)] = self.get(i,'z') # <<<<<<<<<<<<<< - * solution['lam_'+str(i)] = self.get(i,'lam') - * solution['t_'+str(i)] = self.get(i, 't') - */ - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 316, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_5 = NULL; - __pyx_t_6 = 0; - if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { - __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); - if (likely(__pyx_t_5)) { - PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); - __Pyx_INCREF(__pyx_t_5); - __Pyx_INCREF(function); - __Pyx_DECREF_SET(__pyx_t_1, function); - __pyx_t_6 = 1; - } - } - { - PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_v_i, __pyx_n_u_z}; - __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); - __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; - if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 316, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - } - __pyx_t_1 = __Pyx_PyObject_Str(__pyx_v_i); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 316, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_5 = PyNumber_Add(__pyx_n_u_z_2, __pyx_t_1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 316, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_5, __pyx_t_7) < 0))) __PYX_ERR(0, 316, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - - /* "acados_template/acados_ocp_solver_pyx.pyx":317 - * solution['u_'+str(i)] = self.get(i,'u') - * solution['z_'+str(i)] = self.get(i,'z') - * solution['lam_'+str(i)] = self.get(i,'lam') # <<<<<<<<<<<<<< - * solution['t_'+str(i)] = self.get(i, 't') - * solution['sl_'+str(i)] = self.get(i, 'sl') - */ - __pyx_t_5 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 317, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __pyx_t_1 = NULL; - __pyx_t_6 = 0; - if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_5))) { - __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_5); - if (likely(__pyx_t_1)) { - PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); - __Pyx_INCREF(__pyx_t_1); - __Pyx_INCREF(function); - __Pyx_DECREF_SET(__pyx_t_5, function); - __pyx_t_6 = 1; - } - } - { - PyObject *__pyx_callargs[3] = {__pyx_t_1, __pyx_v_i, __pyx_n_u_lam}; - __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); - __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; - if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 317, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - } - __pyx_t_5 = __Pyx_PyObject_Str(__pyx_v_i); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 317, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __pyx_t_1 = PyNumber_Add(__pyx_n_u_lam_2, __pyx_t_5); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 317, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_7) < 0))) __PYX_ERR(0, 317, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - - /* "acados_template/acados_ocp_solver_pyx.pyx":318 - * solution['z_'+str(i)] = self.get(i,'z') - * solution['lam_'+str(i)] = self.get(i,'lam') - * solution['t_'+str(i)] = self.get(i, 't') # <<<<<<<<<<<<<< - * solution['sl_'+str(i)] = self.get(i, 'sl') - * solution['su_'+str(i)] = self.get(i, 'su') - */ - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 318, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_5 = NULL; - __pyx_t_6 = 0; - if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { - __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); - if (likely(__pyx_t_5)) { - PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); - __Pyx_INCREF(__pyx_t_5); - __Pyx_INCREF(function); - __Pyx_DECREF_SET(__pyx_t_1, function); - __pyx_t_6 = 1; - } - } - { - PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_v_i, __pyx_n_u_t}; - __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); - __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; - if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 318, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - } - __pyx_t_1 = __Pyx_PyObject_Str(__pyx_v_i); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 318, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_5 = PyNumber_Add(__pyx_n_u_t_2, __pyx_t_1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 318, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_5, __pyx_t_7) < 0))) __PYX_ERR(0, 318, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - - /* "acados_template/acados_ocp_solver_pyx.pyx":319 - * solution['lam_'+str(i)] = self.get(i,'lam') - * solution['t_'+str(i)] = self.get(i, 't') - * solution['sl_'+str(i)] = self.get(i, 'sl') # <<<<<<<<<<<<<< - * solution['su_'+str(i)] = self.get(i, 'su') - * for i in range(self.N): - */ - __pyx_t_5 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 319, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __pyx_t_1 = NULL; - __pyx_t_6 = 0; - if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_5))) { - __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_5); - if (likely(__pyx_t_1)) { - PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); - __Pyx_INCREF(__pyx_t_1); - __Pyx_INCREF(function); - __Pyx_DECREF_SET(__pyx_t_5, function); - __pyx_t_6 = 1; - } - } - { - PyObject *__pyx_callargs[3] = {__pyx_t_1, __pyx_v_i, __pyx_n_u_sl}; - __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); - __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; - if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 319, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - } - __pyx_t_5 = __Pyx_PyObject_Str(__pyx_v_i); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 319, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __pyx_t_1 = PyNumber_Add(__pyx_n_u_sl_2, __pyx_t_5); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 319, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_7) < 0))) __PYX_ERR(0, 319, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - - /* "acados_template/acados_ocp_solver_pyx.pyx":320 - * solution['t_'+str(i)] = self.get(i, 't') - * solution['sl_'+str(i)] = self.get(i, 'sl') - * solution['su_'+str(i)] = self.get(i, 'su') # <<<<<<<<<<<<<< - * for i in range(self.N): - * solution['pi_'+str(i)] = self.get(i,'pi') - */ - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 320, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_5 = NULL; - __pyx_t_6 = 0; - if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { - __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); - if (likely(__pyx_t_5)) { - PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); - __Pyx_INCREF(__pyx_t_5); - __Pyx_INCREF(function); - __Pyx_DECREF_SET(__pyx_t_1, function); - __pyx_t_6 = 1; - } - } - { - PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_v_i, __pyx_n_u_su}; - __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); - __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; - if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 320, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - } - __pyx_t_1 = __Pyx_PyObject_Str(__pyx_v_i); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 320, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_5 = PyNumber_Add(__pyx_n_u_su_2, __pyx_t_1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 320, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_5, __pyx_t_7) < 0))) __PYX_ERR(0, 320, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - - /* "acados_template/acados_ocp_solver_pyx.pyx":313 - * solution = dict() + /* "acados_template/acados_ocp_solver_pyx.pyx":340 * + * lN = len(str(self.N+1)) * for i in range(self.N+1): # <<<<<<<<<<<<<< - * solution['x_'+str(i)] = self.get(i,'x') - * solution['u_'+str(i)] = self.get(i,'u') + * i_string = f'{i:0{lN}d}' + * solution['x_'+i_string] = self.get(i,'x') */ - } - __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_9 = (__pyx_v_self->N + 1); + __pyx_t_10 = __pyx_t_9; + for (__pyx_t_11 = 0; __pyx_t_11 < __pyx_t_10; __pyx_t_11+=1) { + __pyx_v_i = __pyx_t_11; - /* "acados_template/acados_ocp_solver_pyx.pyx":321 - * solution['sl_'+str(i)] = self.get(i, 'sl') - * solution['su_'+str(i)] = self.get(i, 'su') - * for i in range(self.N): # <<<<<<<<<<<<<< - * solution['pi_'+str(i)] = self.get(i,'pi') + /* "acados_template/acados_ocp_solver_pyx.pyx":341 + * lN = len(str(self.N+1)) + * for i in range(self.N+1): + * i_string = f'{i:0{lN}d}' # <<<<<<<<<<<<<< + * solution['x_'+i_string] = self.get(i,'x') + * solution['u_'+i_string] = self.get(i,'u') + */ + __pyx_t_7 = __Pyx_PyInt_From_long(__pyx_v_i); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 341, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 341, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_8 = 0; + __pyx_t_12 = 127; + __Pyx_INCREF(__pyx_kp_u_0); + __pyx_t_8 += 1; + __Pyx_GIVEREF(__pyx_kp_u_0); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_kp_u_0); + __pyx_t_1 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_lN, 0, ' ', 'd'); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 341, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_8 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1); + __pyx_t_1 = 0; + __Pyx_INCREF(__pyx_n_u_d); + __pyx_t_8 += 1; + __Pyx_GIVEREF(__pyx_n_u_d); + PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_n_u_d); + __pyx_t_1 = __Pyx_PyUnicode_Join(__pyx_t_3, 3, __pyx_t_8, __pyx_t_12); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 341, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PyObject_Format(__pyx_t_7, __pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 341, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF_SET(__pyx_v_i_string, ((PyObject*)__pyx_t_3)); + __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":342 + * for i in range(self.N+1): + * i_string = f'{i:0{lN}d}' + * solution['x_'+i_string] = self.get(i,'x') # <<<<<<<<<<<<<< + * solution['u_'+i_string] = self.get(i,'u') + * solution['z_'+i_string] = self.get(i,'z') + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 342, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = __Pyx_PyInt_From_long(__pyx_v_i); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 342, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_t_7, __pyx_n_u_x}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 342, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyUnicode_Concat(__pyx_n_u_x_2, __pyx_v_i_string); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 342, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_3) < 0))) __PYX_ERR(0, 342, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":343 + * i_string = f'{i:0{lN}d}' + * solution['x_'+i_string] = self.get(i,'x') + * solution['u_'+i_string] = self.get(i,'u') # <<<<<<<<<<<<<< + * solution['z_'+i_string] = self.get(i,'z') + * solution['lam_'+i_string] = self.get(i,'lam') + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 343, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = __Pyx_PyInt_From_long(__pyx_v_i); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 343, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_t_7, __pyx_n_u_u}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 343, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyUnicode_Concat(__pyx_n_u_u_2, __pyx_v_i_string); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 343, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_3) < 0))) __PYX_ERR(0, 343, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":344 + * solution['x_'+i_string] = self.get(i,'x') + * solution['u_'+i_string] = self.get(i,'u') + * solution['z_'+i_string] = self.get(i,'z') # <<<<<<<<<<<<<< + * solution['lam_'+i_string] = self.get(i,'lam') + * solution['t_'+i_string] = self.get(i, 't') + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 344, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = __Pyx_PyInt_From_long(__pyx_v_i); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 344, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_t_7, __pyx_n_u_z}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 344, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyUnicode_Concat(__pyx_n_u_z_2, __pyx_v_i_string); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 344, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_3) < 0))) __PYX_ERR(0, 344, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":345 + * solution['u_'+i_string] = self.get(i,'u') + * solution['z_'+i_string] = self.get(i,'z') + * solution['lam_'+i_string] = self.get(i,'lam') # <<<<<<<<<<<<<< + * solution['t_'+i_string] = self.get(i, 't') + * solution['sl_'+i_string] = self.get(i, 'sl') + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 345, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = __Pyx_PyInt_From_long(__pyx_v_i); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 345, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_t_7, __pyx_n_u_lam}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 345, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyUnicode_Concat(__pyx_n_u_lam_2, __pyx_v_i_string); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 345, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_3) < 0))) __PYX_ERR(0, 345, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":346 + * solution['z_'+i_string] = self.get(i,'z') + * solution['lam_'+i_string] = self.get(i,'lam') + * solution['t_'+i_string] = self.get(i, 't') # <<<<<<<<<<<<<< + * solution['sl_'+i_string] = self.get(i, 'sl') + * solution['su_'+i_string] = self.get(i, 'su') + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 346, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = __Pyx_PyInt_From_long(__pyx_v_i); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 346, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_t_7, __pyx_n_u_t}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 346, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyUnicode_Concat(__pyx_n_u_t_2, __pyx_v_i_string); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 346, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_3) < 0))) __PYX_ERR(0, 346, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":347 + * solution['lam_'+i_string] = self.get(i,'lam') + * solution['t_'+i_string] = self.get(i, 't') + * solution['sl_'+i_string] = self.get(i, 'sl') # <<<<<<<<<<<<<< + * solution['su_'+i_string] = self.get(i, 'su') + * if i < self.N: + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 347, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = __Pyx_PyInt_From_long(__pyx_v_i); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 347, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_t_7, __pyx_n_u_sl}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 347, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyUnicode_Concat(__pyx_n_u_sl_2, __pyx_v_i_string); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 347, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_3) < 0))) __PYX_ERR(0, 347, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":348 + * solution['t_'+i_string] = self.get(i, 't') + * solution['sl_'+i_string] = self.get(i, 'sl') + * solution['su_'+i_string] = self.get(i, 'su') # <<<<<<<<<<<<<< + * if i < self.N: + * solution['pi_'+i_string] = self.get(i,'pi') + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 348, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = __Pyx_PyInt_From_long(__pyx_v_i); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 348, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_t_7, __pyx_n_u_su}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 348, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyUnicode_Concat(__pyx_n_u_su_2, __pyx_v_i_string); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 348, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_3) < 0))) __PYX_ERR(0, 348, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":349 + * solution['sl_'+i_string] = self.get(i, 'sl') + * solution['su_'+i_string] = self.get(i, 'su') + * if i < self.N: # <<<<<<<<<<<<<< + * solution['pi_'+i_string] = self.get(i,'pi') * */ - __pyx_t_3 = __Pyx_PyInt_From_int(__pyx_v_self->N); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 321, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __pyx_t_7 = __Pyx_PyObject_CallOneArg(__pyx_builtin_range, __pyx_t_3); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 321, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - if (likely(PyList_CheckExact(__pyx_t_7)) || PyTuple_CheckExact(__pyx_t_7)) { - __pyx_t_3 = __pyx_t_7; __Pyx_INCREF(__pyx_t_3); __pyx_t_8 = 0; - __pyx_t_9 = NULL; - } else { - __pyx_t_8 = -1; __pyx_t_3 = PyObject_GetIter(__pyx_t_7); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 321, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __pyx_t_9 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_3); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 321, __pyx_L1_error) - } - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - for (;;) { - if (likely(!__pyx_t_9)) { - if (likely(PyList_CheckExact(__pyx_t_3))) { - if (__pyx_t_8 >= PyList_GET_SIZE(__pyx_t_3)) break; - #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - __pyx_t_7 = PyList_GET_ITEM(__pyx_t_3, __pyx_t_8); __Pyx_INCREF(__pyx_t_7); __pyx_t_8++; if (unlikely((0 < 0))) __PYX_ERR(0, 321, __pyx_L1_error) - #else - __pyx_t_7 = PySequence_ITEM(__pyx_t_3, __pyx_t_8); __pyx_t_8++; if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 321, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - #endif - } else { - if (__pyx_t_8 >= PyTuple_GET_SIZE(__pyx_t_3)) break; - #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS - __pyx_t_7 = PyTuple_GET_ITEM(__pyx_t_3, __pyx_t_8); __Pyx_INCREF(__pyx_t_7); __pyx_t_8++; if (unlikely((0 < 0))) __PYX_ERR(0, 321, __pyx_L1_error) - #else - __pyx_t_7 = PySequence_ITEM(__pyx_t_3, __pyx_t_8); __pyx_t_8++; if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 321, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - #endif - } - } else { - __pyx_t_7 = __pyx_t_9(__pyx_t_3); - if (unlikely(!__pyx_t_7)) { - PyObject* exc_type = PyErr_Occurred(); - if (exc_type) { - if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); - else __PYX_ERR(0, 321, __pyx_L1_error) - } - break; - } - __Pyx_GOTREF(__pyx_t_7); - } - __Pyx_XDECREF_SET(__pyx_v_i, __pyx_t_7); - __pyx_t_7 = 0; + __pyx_t_4 = (__pyx_v_i < __pyx_v_self->N); + if (__pyx_t_4) { - /* "acados_template/acados_ocp_solver_pyx.pyx":322 - * solution['su_'+str(i)] = self.get(i, 'su') - * for i in range(self.N): - * solution['pi_'+str(i)] = self.get(i,'pi') # <<<<<<<<<<<<<< + /* "acados_template/acados_ocp_solver_pyx.pyx":350 + * solution['su_'+i_string] = self.get(i, 'su') + * if i < self.N: + * solution['pi_'+i_string] = self.get(i,'pi') # <<<<<<<<<<<<<< + * + * for k in list(solution.keys()): + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 350, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = __Pyx_PyInt_From_long(__pyx_v_i); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 350, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_t_7, __pyx_n_u_pi}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 350, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyUnicode_Concat(__pyx_n_u_pi_2, __pyx_v_i_string); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 350, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_3) < 0))) __PYX_ERR(0, 350, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":349 + * solution['sl_'+i_string] = self.get(i, 'sl') + * solution['su_'+i_string] = self.get(i, 'su') + * if i < self.N: # <<<<<<<<<<<<<< + * solution['pi_'+i_string] = self.get(i,'pi') + * + */ + } + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":352 + * solution['pi_'+i_string] = self.get(i,'pi') + * + * for k in list(solution.keys()): # <<<<<<<<<<<<<< + * if len(solution[k]) == 0: + * del solution[k] + */ + __pyx_t_3 = __Pyx_PyDict_Keys(__pyx_v_solution); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 352, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = __Pyx_PySequence_ListKeepNew(__pyx_t_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 352, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __pyx_t_1; __Pyx_INCREF(__pyx_t_3); __pyx_t_8 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + for (;;) { + if (__pyx_t_8 >= PyList_GET_SIZE(__pyx_t_3)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_1 = PyList_GET_ITEM(__pyx_t_3, __pyx_t_8); __Pyx_INCREF(__pyx_t_1); __pyx_t_8++; if (unlikely((0 < 0))) __PYX_ERR(0, 352, __pyx_L1_error) + #else + __pyx_t_1 = PySequence_ITEM(__pyx_t_3, __pyx_t_8); __pyx_t_8++; if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 352, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + #endif + __Pyx_XDECREF_SET(__pyx_v_k, __pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":353 + * + * for k in list(solution.keys()): + * if len(solution[k]) == 0: # <<<<<<<<<<<<<< + * del solution[k] + * + */ + __pyx_t_1 = __Pyx_PyDict_GetItem(__pyx_v_solution, __pyx_v_k); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 353, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_13 = PyObject_Length(__pyx_t_1); if (unlikely(__pyx_t_13 == ((Py_ssize_t)-1))) __PYX_ERR(0, 353, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_4 = (__pyx_t_13 == 0); + if (__pyx_t_4) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":354 + * for k in list(solution.keys()): + * if len(solution[k]) == 0: + * del solution[k] # <<<<<<<<<<<<<< * * # save */ - __pyx_t_5 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 322, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __pyx_t_1 = NULL; - __pyx_t_6 = 0; - if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_5))) { - __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_5); - if (likely(__pyx_t_1)) { - PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); - __Pyx_INCREF(__pyx_t_1); - __Pyx_INCREF(function); - __Pyx_DECREF_SET(__pyx_t_5, function); - __pyx_t_6 = 1; - } - } - { - PyObject *__pyx_callargs[3] = {__pyx_t_1, __pyx_v_i, __pyx_n_u_pi}; - __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); - __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; - if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 322, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - } - __pyx_t_5 = __Pyx_PyObject_Str(__pyx_v_i); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 322, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __pyx_t_1 = PyNumber_Add(__pyx_n_u_pi_2, __pyx_t_5); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 322, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_7) < 0))) __PYX_ERR(0, 322, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely((PyDict_DelItem(__pyx_v_solution, __pyx_v_k) < 0))) __PYX_ERR(0, 354, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":321 - * solution['sl_'+str(i)] = self.get(i, 'sl') - * solution['su_'+str(i)] = self.get(i, 'su') - * for i in range(self.N): # <<<<<<<<<<<<<< - * solution['pi_'+str(i)] = self.get(i,'pi') + /* "acados_template/acados_ocp_solver_pyx.pyx":353 * + * for k in list(solution.keys()): + * if len(solution[k]) == 0: # <<<<<<<<<<<<<< + * del solution[k] + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":352 + * solution['pi_'+i_string] = self.get(i,'pi') + * + * for k in list(solution.keys()): # <<<<<<<<<<<<<< + * if len(solution[k]) == 0: + * del solution[k] */ } __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":325 + /* "acados_template/acados_ocp_solver_pyx.pyx":357 * * # save * with open(filename, 'w') as f: # <<<<<<<<<<<<<< @@ -23046,7 +23897,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS * print("stored current iterate in ", os.path.join(os.getcwd(), filename)) */ /*with:*/ { - __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 325, __pyx_L1_error) + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 357, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_INCREF(__pyx_v_filename); __Pyx_GIVEREF(__pyx_v_filename); @@ -23054,81 +23905,81 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __Pyx_INCREF(__pyx_n_u_w); __Pyx_GIVEREF(__pyx_n_u_w); PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_n_u_w); - __pyx_t_7 = __Pyx_PyObject_Call(__pyx_builtin_open, __pyx_t_3, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 325, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - __pyx_t_10 = __Pyx_PyObject_LookupSpecial(__pyx_t_7, __pyx_n_s_exit); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 325, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_10); - __pyx_t_1 = __Pyx_PyObject_LookupSpecial(__pyx_t_7, __pyx_n_s_enter); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 325, __pyx_L12_error) + __pyx_t_1 = __Pyx_PyObject_Call(__pyx_builtin_open, __pyx_t_3, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 357, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_14 = __Pyx_PyObject_LookupSpecial(__pyx_t_1, __pyx_n_s_exit); if (unlikely(!__pyx_t_14)) __PYX_ERR(0, 357, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_14); + __pyx_t_7 = __Pyx_PyObject_LookupSpecial(__pyx_t_1, __pyx_n_s_enter); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 357, __pyx_L13_error) + __Pyx_GOTREF(__pyx_t_7); __pyx_t_5 = NULL; __pyx_t_6 = 0; - if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { - __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_7))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_7); if (likely(__pyx_t_5)) { - PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_7); __Pyx_INCREF(__pyx_t_5); __Pyx_INCREF(function); - __Pyx_DECREF_SET(__pyx_t_1, function); + __Pyx_DECREF_SET(__pyx_t_7, function); __pyx_t_6 = 1; } } { PyObject *__pyx_callargs[1] = {__pyx_t_5, }; - __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 0+__pyx_t_6); + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_7, __pyx_callargs+1-__pyx_t_6, 0+__pyx_t_6); __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; - if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 325, __pyx_L12_error) + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 357, __pyx_L13_error) __Pyx_GOTREF(__pyx_t_3); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; } - __pyx_t_1 = __pyx_t_3; + __pyx_t_7 = __pyx_t_3; __pyx_t_3 = 0; - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; /*try:*/ { { __Pyx_PyThreadState_declare __Pyx_PyThreadState_assign - __Pyx_ExceptionSave(&__pyx_t_11, &__pyx_t_12, &__pyx_t_13); - __Pyx_XGOTREF(__pyx_t_11); - __Pyx_XGOTREF(__pyx_t_12); - __Pyx_XGOTREF(__pyx_t_13); + __Pyx_ExceptionSave(&__pyx_t_15, &__pyx_t_16, &__pyx_t_17); + __Pyx_XGOTREF(__pyx_t_15); + __Pyx_XGOTREF(__pyx_t_16); + __Pyx_XGOTREF(__pyx_t_17); /*try:*/ { - __pyx_v_f = __pyx_t_1; - __pyx_t_1 = 0; + __pyx_v_f = __pyx_t_7; + __pyx_t_7 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":326 + /* "acados_template/acados_ocp_solver_pyx.pyx":358 * # save * with open(filename, 'w') as f: * json.dump(solution, f, default=lambda x: x.tolist(), indent=4, sort_keys=True) # <<<<<<<<<<<<<< * print("stored current iterate in ", os.path.join(os.getcwd(), filename)) * */ - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_json, __pyx_n_s_dump); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 326, __pyx_L16_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_7 = PyTuple_New(2); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 326, __pyx_L16_error) + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_v_json, __pyx_n_s_dump); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 358, __pyx_L17_error) __Pyx_GOTREF(__pyx_t_7); + __pyx_t_1 = PyTuple_New(2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 358, __pyx_L17_error) + __Pyx_GOTREF(__pyx_t_1); __Pyx_INCREF(__pyx_v_solution); __Pyx_GIVEREF(__pyx_v_solution); - PyTuple_SET_ITEM(__pyx_t_7, 0, __pyx_v_solution); + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v_solution); __Pyx_INCREF(__pyx_v_f); __Pyx_GIVEREF(__pyx_v_f); - PyTuple_SET_ITEM(__pyx_t_7, 1, __pyx_v_f); - __pyx_t_3 = __Pyx_PyDict_NewPresized(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 326, __pyx_L16_error) + PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_v_f); + __pyx_t_3 = __Pyx_PyDict_NewPresized(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 358, __pyx_L17_error) __Pyx_GOTREF(__pyx_t_3); - __pyx_t_5 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13store_iterate_lambda, 0, __pyx_n_s_store_iterate_locals_lambda, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, NULL); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 326, __pyx_L16_error) + __pyx_t_5 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13store_iterate_lambda, 0, __pyx_n_s_store_iterate_locals_lambda, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, NULL); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 358, __pyx_L17_error) __Pyx_GOTREF(__pyx_t_5); - if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_default, __pyx_t_5) < 0) __PYX_ERR(0, 326, __pyx_L16_error) + if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_default, __pyx_t_5) < 0) __PYX_ERR(0, 358, __pyx_L17_error) __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_indent, __pyx_int_4) < 0) __PYX_ERR(0, 326, __pyx_L16_error) - if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_sort_keys, Py_True) < 0) __PYX_ERR(0, 326, __pyx_L16_error) - __pyx_t_5 = __Pyx_PyObject_Call(__pyx_t_1, __pyx_t_7, __pyx_t_3); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 326, __pyx_L16_error) + if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_indent, __pyx_int_4) < 0) __PYX_ERR(0, 358, __pyx_L17_error) + if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_sort_keys, Py_True) < 0) __PYX_ERR(0, 358, __pyx_L17_error) + __pyx_t_5 = __Pyx_PyObject_Call(__pyx_t_7, __pyx_t_1, __pyx_t_3); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 358, __pyx_L17_error) __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":325 + /* "acados_template/acados_ocp_solver_pyx.pyx":357 * * # save * with open(filename, 'w') as f: # <<<<<<<<<<<<<< @@ -23136,154 +23987,154 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS * print("stored current iterate in ", os.path.join(os.getcwd(), filename)) */ } - __Pyx_XDECREF(__pyx_t_11); __pyx_t_11 = 0; - __Pyx_XDECREF(__pyx_t_12); __pyx_t_12 = 0; - __Pyx_XDECREF(__pyx_t_13); __pyx_t_13 = 0; - goto __pyx_L21_try_end; - __pyx_L16_error:; + __Pyx_XDECREF(__pyx_t_15); __pyx_t_15 = 0; + __Pyx_XDECREF(__pyx_t_16); __pyx_t_16 = 0; + __Pyx_XDECREF(__pyx_t_17); __pyx_t_17 = 0; + goto __pyx_L22_try_end; + __pyx_L17_error:; __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; /*except:*/ { __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.store_iterate", __pyx_clineno, __pyx_lineno, __pyx_filename); - if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_3, &__pyx_t_7) < 0) __PYX_ERR(0, 325, __pyx_L18_except_error) + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_3, &__pyx_t_1) < 0) __PYX_ERR(0, 357, __pyx_L19_except_error) __Pyx_XGOTREF(__pyx_t_5); __Pyx_XGOTREF(__pyx_t_3); - __Pyx_XGOTREF(__pyx_t_7); - __pyx_t_1 = PyTuple_Pack(3, __pyx_t_5, __pyx_t_3, __pyx_t_7); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 325, __pyx_L18_except_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_14 = __Pyx_PyObject_Call(__pyx_t_10, __pyx_t_1, NULL); - __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - if (unlikely(!__pyx_t_14)) __PYX_ERR(0, 325, __pyx_L18_except_error) - __Pyx_GOTREF(__pyx_t_14); - __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_t_14); + __Pyx_XGOTREF(__pyx_t_1); + __pyx_t_7 = PyTuple_Pack(3, __pyx_t_5, __pyx_t_3, __pyx_t_1); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 357, __pyx_L19_except_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_18 = __Pyx_PyObject_Call(__pyx_t_14, __pyx_t_7, NULL); __Pyx_DECREF(__pyx_t_14); __pyx_t_14 = 0; - if (__pyx_t_4 < 0) __PYX_ERR(0, 325, __pyx_L18_except_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_18)) __PYX_ERR(0, 357, __pyx_L19_except_error) + __Pyx_GOTREF(__pyx_t_18); + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_t_18); + __Pyx_DECREF(__pyx_t_18); __pyx_t_18 = 0; + if (__pyx_t_4 < 0) __PYX_ERR(0, 357, __pyx_L19_except_error) __pyx_t_2 = (!__pyx_t_4); if (unlikely(__pyx_t_2)) { __Pyx_GIVEREF(__pyx_t_5); __Pyx_GIVEREF(__pyx_t_3); - __Pyx_XGIVEREF(__pyx_t_7); - __Pyx_ErrRestoreWithState(__pyx_t_5, __pyx_t_3, __pyx_t_7); - __pyx_t_5 = 0; __pyx_t_3 = 0; __pyx_t_7 = 0; - __PYX_ERR(0, 325, __pyx_L18_except_error) + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_ErrRestoreWithState(__pyx_t_5, __pyx_t_3, __pyx_t_1); + __pyx_t_5 = 0; __pyx_t_3 = 0; __pyx_t_1 = 0; + __PYX_ERR(0, 357, __pyx_L19_except_error) } __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; - __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; - goto __pyx_L17_exception_handled; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + goto __pyx_L18_exception_handled; } - __pyx_L18_except_error:; - __Pyx_XGIVEREF(__pyx_t_11); - __Pyx_XGIVEREF(__pyx_t_12); - __Pyx_XGIVEREF(__pyx_t_13); - __Pyx_ExceptionReset(__pyx_t_11, __pyx_t_12, __pyx_t_13); + __pyx_L19_except_error:; + __Pyx_XGIVEREF(__pyx_t_15); + __Pyx_XGIVEREF(__pyx_t_16); + __Pyx_XGIVEREF(__pyx_t_17); + __Pyx_ExceptionReset(__pyx_t_15, __pyx_t_16, __pyx_t_17); goto __pyx_L1_error; - __pyx_L17_exception_handled:; - __Pyx_XGIVEREF(__pyx_t_11); - __Pyx_XGIVEREF(__pyx_t_12); - __Pyx_XGIVEREF(__pyx_t_13); - __Pyx_ExceptionReset(__pyx_t_11, __pyx_t_12, __pyx_t_13); - __pyx_L21_try_end:; + __pyx_L18_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_15); + __Pyx_XGIVEREF(__pyx_t_16); + __Pyx_XGIVEREF(__pyx_t_17); + __Pyx_ExceptionReset(__pyx_t_15, __pyx_t_16, __pyx_t_17); + __pyx_L22_try_end:; } } /*finally:*/ { /*normal exit:*/{ - if (__pyx_t_10) { - __pyx_t_13 = __Pyx_PyObject_Call(__pyx_t_10, __pyx_tuple__17, NULL); - __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; - if (unlikely(!__pyx_t_13)) __PYX_ERR(0, 325, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_13); - __Pyx_DECREF(__pyx_t_13); __pyx_t_13 = 0; + if (__pyx_t_14) { + __pyx_t_17 = __Pyx_PyObject_Call(__pyx_t_14, __pyx_tuple__19, NULL); + __Pyx_DECREF(__pyx_t_14); __pyx_t_14 = 0; + if (unlikely(!__pyx_t_17)) __PYX_ERR(0, 357, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_17); + __Pyx_DECREF(__pyx_t_17); __pyx_t_17 = 0; } - goto __pyx_L15; + goto __pyx_L16; } - __pyx_L15:; + __pyx_L16:; } - goto __pyx_L25; - __pyx_L12_error:; - __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + goto __pyx_L26; + __pyx_L13_error:; + __Pyx_DECREF(__pyx_t_14); __pyx_t_14 = 0; goto __pyx_L1_error; - __pyx_L25:; + __pyx_L26:; } - /* "acados_template/acados_ocp_solver_pyx.pyx":327 + /* "acados_template/acados_ocp_solver_pyx.pyx":359 * with open(filename, 'w') as f: * json.dump(solution, f, default=lambda x: x.tolist(), indent=4, sort_keys=True) * print("stored current iterate in ", os.path.join(os.getcwd(), filename)) # <<<<<<<<<<<<<< * * */ - __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_os); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 327, __pyx_L1_error) + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_os); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 359, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); - __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_path); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 327, __pyx_L1_error) + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_path); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 359, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_5); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_join); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 327, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_join); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 359, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_os); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 327, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_15 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_getcwd); if (unlikely(!__pyx_t_15)) __PYX_ERR(0, 327, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_15); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_1 = NULL; + __Pyx_GetModuleGlobalName(__pyx_t_7, __pyx_n_s_os); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 359, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_19 = __Pyx_PyObject_GetAttrStr(__pyx_t_7, __pyx_n_s_getcwd); if (unlikely(!__pyx_t_19)) __PYX_ERR(0, 359, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_19); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __pyx_t_7 = NULL; __pyx_t_6 = 0; - if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_15))) { - __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_15); - if (likely(__pyx_t_1)) { - PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_15); - __Pyx_INCREF(__pyx_t_1); + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_19))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_19); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_19); + __Pyx_INCREF(__pyx_t_7); __Pyx_INCREF(function); - __Pyx_DECREF_SET(__pyx_t_15, function); + __Pyx_DECREF_SET(__pyx_t_19, function); __pyx_t_6 = 1; } } { - PyObject *__pyx_callargs[1] = {__pyx_t_1, }; - __pyx_t_5 = __Pyx_PyObject_FastCall(__pyx_t_15, __pyx_callargs+1-__pyx_t_6, 0+__pyx_t_6); - __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; - if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 327, __pyx_L1_error) + PyObject *__pyx_callargs[1] = {__pyx_t_7, }; + __pyx_t_5 = __Pyx_PyObject_FastCall(__pyx_t_19, __pyx_callargs+1-__pyx_t_6, 0+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 359, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_15); __pyx_t_15 = 0; + __Pyx_DECREF(__pyx_t_19); __pyx_t_19 = 0; } - __pyx_t_15 = NULL; + __pyx_t_19 = NULL; __pyx_t_6 = 0; if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_3))) { - __pyx_t_15 = PyMethod_GET_SELF(__pyx_t_3); - if (likely(__pyx_t_15)) { + __pyx_t_19 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_19)) { PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); - __Pyx_INCREF(__pyx_t_15); + __Pyx_INCREF(__pyx_t_19); __Pyx_INCREF(function); __Pyx_DECREF_SET(__pyx_t_3, function); __pyx_t_6 = 1; } } { - PyObject *__pyx_callargs[3] = {__pyx_t_15, __pyx_t_5, __pyx_v_filename}; - __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); - __Pyx_XDECREF(__pyx_t_15); __pyx_t_15 = 0; + PyObject *__pyx_callargs[3] = {__pyx_t_19, __pyx_t_5, __pyx_v_filename}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_19); __pyx_t_19 = 0; __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 327, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 359, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; } - __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 327, __pyx_L1_error) + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 359, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_INCREF(__pyx_kp_u_stored_current_iterate_in); __Pyx_GIVEREF(__pyx_kp_u_stored_current_iterate_in); PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_kp_u_stored_current_iterate_in); - __Pyx_GIVEREF(__pyx_t_7); - PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_7); - __pyx_t_7 = 0; - __pyx_t_7 = __Pyx_PyObject_Call(__pyx_builtin_print, __pyx_t_3, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 327, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1); + __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_Call(__pyx_builtin_print, __pyx_t_3, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 359, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":293 + /* "acados_template/acados_ocp_solver_pyx.pyx":319 * * * def store_iterate(self, filename='', overwrite=False): # <<<<<<<<<<<<<< @@ -23299,13 +24150,14 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __Pyx_XDECREF(__pyx_t_3); __Pyx_XDECREF(__pyx_t_5); __Pyx_XDECREF(__pyx_t_7); - __Pyx_XDECREF(__pyx_t_15); + __Pyx_XDECREF(__pyx_t_19); __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.store_iterate", __pyx_clineno, __pyx_lineno, __pyx_filename); __pyx_r = NULL; __pyx_L0:; __Pyx_XDECREF(__pyx_v_json); __Pyx_XDECREF(__pyx_v_solution); - __Pyx_XDECREF(__pyx_v_i); + __Pyx_XDECREF(__pyx_v_i_string); + __Pyx_XDECREF(__pyx_v_k); __Pyx_XDECREF(__pyx_v_f); __Pyx_XDECREF(__pyx_v_filename); __Pyx_XGIVEREF(__pyx_r); @@ -23313,7 +24165,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":330 +/* "acados_template/acados_ocp_solver_pyx.pyx":362 * * * def load_iterate(self, filename): # <<<<<<<<<<<<<< @@ -23322,16 +24174,16 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ /* Python wrapper */ -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21load_iterate(PyObject *__pyx_v_self, +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25load_iterate(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else PyObject *__pyx_args, PyObject *__pyx_kwds #endif ); /*proto*/ -PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20load_iterate, "\n Loads the iterate stored in json file with filename into the ocp solver.\n "); -static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21load_iterate = {"load_iterate", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21load_iterate, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20load_iterate}; -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21load_iterate(PyObject *__pyx_v_self, +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_24load_iterate, "\n Loads the iterate stored in json file with filename into the ocp solver.\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25load_iterate = {"load_iterate", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25load_iterate, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_24load_iterate}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25load_iterate(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else @@ -23364,12 +24216,12 @@ PyObject *__pyx_args, PyObject *__pyx_kwds switch (__pyx_nargs) { case 0: if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_filename)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 330, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 362, __pyx_L3_error) else goto __pyx_L5_argtuple_error; } if (unlikely(kw_args > 0)) { const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "load_iterate") < 0)) __PYX_ERR(0, 330, __pyx_L3_error) + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "load_iterate") < 0)) __PYX_ERR(0, 362, __pyx_L3_error) } } else if (unlikely(__pyx_nargs != 1)) { goto __pyx_L5_argtuple_error; @@ -23380,20 +24232,20 @@ PyObject *__pyx_args, PyObject *__pyx_kwds } goto __pyx_L4_argument_unpacking_done; __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("load_iterate", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 330, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("load_iterate", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 362, __pyx_L3_error) __pyx_L3_error:; __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.load_iterate", __pyx_clineno, __pyx_lineno, __pyx_filename); __Pyx_RefNannyFinishContext(); return NULL; __pyx_L4_argument_unpacking_done:; - __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20load_iterate(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_filename); + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_24load_iterate(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_filename); /* function exit code */ __Pyx_RefNannyFinishContext(); return __pyx_r; } -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20load_iterate(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_filename) { +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_24load_iterate(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_filename) { PyObject *__pyx_v_json = NULL; PyObject *__pyx_v_f = NULL; PyObject *__pyx_v_solution = NULL; @@ -23427,31 +24279,31 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS int __pyx_clineno = 0; __Pyx_RefNannySetupContext("load_iterate", 0); - /* "acados_template/acados_ocp_solver_pyx.pyx":334 + /* "acados_template/acados_ocp_solver_pyx.pyx":366 * Loads the iterate stored in json file with filename into the ocp solver. * """ * import json # <<<<<<<<<<<<<< * if not os.path.isfile(filename): * raise Exception('load_iterate: failed, file does not exist: ' + os.path.join(os.getcwd(), filename)) */ - __pyx_t_1 = __Pyx_ImportDottedModule(__pyx_n_s_json, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 334, __pyx_L1_error) + __pyx_t_1 = __Pyx_ImportDottedModule(__pyx_n_s_json, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 366, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __pyx_v_json = __pyx_t_1; __pyx_t_1 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":335 + /* "acados_template/acados_ocp_solver_pyx.pyx":367 * """ * import json * if not os.path.isfile(filename): # <<<<<<<<<<<<<< * raise Exception('load_iterate: failed, file does not exist: ' + os.path.join(os.getcwd(), filename)) * */ - __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_os); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 335, __pyx_L1_error) + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_os); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 367, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); - __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_path); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 335, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_path); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 367, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_isfile); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 335, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_isfile); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 367, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; __pyx_t_3 = NULL; @@ -23470,33 +24322,33 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_filename}; __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; - if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 335, __pyx_L1_error) + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 367, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; } - __pyx_t_5 = __Pyx_PyObject_IsTrue(__pyx_t_1); if (unlikely((__pyx_t_5 < 0))) __PYX_ERR(0, 335, __pyx_L1_error) + __pyx_t_5 = __Pyx_PyObject_IsTrue(__pyx_t_1); if (unlikely((__pyx_t_5 < 0))) __PYX_ERR(0, 367, __pyx_L1_error) __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; __pyx_t_6 = (!__pyx_t_5); if (unlikely(__pyx_t_6)) { - /* "acados_template/acados_ocp_solver_pyx.pyx":336 + /* "acados_template/acados_ocp_solver_pyx.pyx":368 * import json * if not os.path.isfile(filename): * raise Exception('load_iterate: failed, file does not exist: ' + os.path.join(os.getcwd(), filename)) # <<<<<<<<<<<<<< * * with open(filename, 'r') as f: */ - __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_os); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 336, __pyx_L1_error) + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_os); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 368, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); - __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_path); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 336, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_path); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 368, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_join); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 336, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_join); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 368, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - __Pyx_GetModuleGlobalName(__pyx_t_7, __pyx_n_s_os); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 336, __pyx_L1_error) + __Pyx_GetModuleGlobalName(__pyx_t_7, __pyx_n_s_os); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 368, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); - __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_t_7, __pyx_n_s_getcwd); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 336, __pyx_L1_error) + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_t_7, __pyx_n_s_getcwd); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 368, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_8); __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; __pyx_t_7 = NULL; @@ -23515,7 +24367,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_callargs[1] = {__pyx_t_7, }; __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_8, __pyx_callargs+1-__pyx_t_4, 0+__pyx_t_4); __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; - if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 336, __pyx_L1_error) + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 368, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; } @@ -23536,21 +24388,21 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 2+__pyx_t_4); __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 336, __pyx_L1_error) + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 368, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; } - __pyx_t_2 = PyNumber_Add(__pyx_kp_u_load_iterate_failed_file_does_no, __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 336, __pyx_L1_error) + __pyx_t_2 = PyNumber_Add(__pyx_kp_u_load_iterate_failed_file_does_no, __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 368, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_1 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 336, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 368, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; __Pyx_Raise(__pyx_t_1, 0, 0, 0); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __PYX_ERR(0, 336, __pyx_L1_error) + __PYX_ERR(0, 368, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":335 + /* "acados_template/acados_ocp_solver_pyx.pyx":367 * """ * import json * if not os.path.isfile(filename): # <<<<<<<<<<<<<< @@ -23559,7 +24411,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":338 + /* "acados_template/acados_ocp_solver_pyx.pyx":370 * raise Exception('load_iterate: failed, file does not exist: ' + os.path.join(os.getcwd(), filename)) * * with open(filename, 'r') as f: # <<<<<<<<<<<<<< @@ -23567,7 +24419,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS * */ /*with:*/ { - __pyx_t_1 = PyTuple_New(2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 338, __pyx_L1_error) + __pyx_t_1 = PyTuple_New(2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 370, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_INCREF(__pyx_v_filename); __Pyx_GIVEREF(__pyx_v_filename); @@ -23575,12 +24427,12 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __Pyx_INCREF(__pyx_n_u_r); __Pyx_GIVEREF(__pyx_n_u_r); PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_n_u_r); - __pyx_t_2 = __Pyx_PyObject_Call(__pyx_builtin_open, __pyx_t_1, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 338, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_Call(__pyx_builtin_open, __pyx_t_1, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 370, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_9 = __Pyx_PyObject_LookupSpecial(__pyx_t_2, __pyx_n_s_exit); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 338, __pyx_L1_error) + __pyx_t_9 = __Pyx_PyObject_LookupSpecial(__pyx_t_2, __pyx_n_s_exit); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 370, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_9); - __pyx_t_3 = __Pyx_PyObject_LookupSpecial(__pyx_t_2, __pyx_n_s_enter); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 338, __pyx_L4_error) + __pyx_t_3 = __Pyx_PyObject_LookupSpecial(__pyx_t_2, __pyx_n_s_enter); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 370, __pyx_L4_error) __Pyx_GOTREF(__pyx_t_3); __pyx_t_8 = NULL; __pyx_t_4 = 0; @@ -23598,7 +24450,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_callargs[1] = {__pyx_t_8, }; __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_4, 0+__pyx_t_4); __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; - if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 338, __pyx_L4_error) + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 370, __pyx_L4_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; } @@ -23617,14 +24469,14 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_v_f = __pyx_t_3; __pyx_t_3 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":339 + /* "acados_template/acados_ocp_solver_pyx.pyx":371 * * with open(filename, 'r') as f: * solution = json.load(f) # <<<<<<<<<<<<<< * * for key in solution.keys(): */ - __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_json, __pyx_n_s_load); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 339, __pyx_L8_error) + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_json, __pyx_n_s_load); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 371, __pyx_L8_error) __Pyx_GOTREF(__pyx_t_2); __pyx_t_1 = NULL; __pyx_t_4 = 0; @@ -23642,14 +24494,14 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_callargs[2] = {__pyx_t_1, __pyx_v_f}; __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; - if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 339, __pyx_L8_error) + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 371, __pyx_L8_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; } __pyx_v_solution = __pyx_t_3; __pyx_t_3 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":338 + /* "acados_template/acados_ocp_solver_pyx.pyx":370 * raise Exception('load_iterate: failed, file does not exist: ' + os.path.join(os.getcwd(), filename)) * * with open(filename, 'r') as f: # <<<<<<<<<<<<<< @@ -23669,20 +24521,20 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; /*except:*/ { __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.load_iterate", __pyx_clineno, __pyx_lineno, __pyx_filename); - if (__Pyx_GetException(&__pyx_t_3, &__pyx_t_2, &__pyx_t_1) < 0) __PYX_ERR(0, 338, __pyx_L10_except_error) + if (__Pyx_GetException(&__pyx_t_3, &__pyx_t_2, &__pyx_t_1) < 0) __PYX_ERR(0, 370, __pyx_L10_except_error) __Pyx_XGOTREF(__pyx_t_3); __Pyx_XGOTREF(__pyx_t_2); __Pyx_XGOTREF(__pyx_t_1); - __pyx_t_8 = PyTuple_Pack(3, __pyx_t_3, __pyx_t_2, __pyx_t_1); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 338, __pyx_L10_except_error) + __pyx_t_8 = PyTuple_Pack(3, __pyx_t_3, __pyx_t_2, __pyx_t_1); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 370, __pyx_L10_except_error) __Pyx_GOTREF(__pyx_t_8); __pyx_t_13 = __Pyx_PyObject_Call(__pyx_t_9, __pyx_t_8, NULL); __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; - if (unlikely(!__pyx_t_13)) __PYX_ERR(0, 338, __pyx_L10_except_error) + if (unlikely(!__pyx_t_13)) __PYX_ERR(0, 370, __pyx_L10_except_error) __Pyx_GOTREF(__pyx_t_13); __pyx_t_6 = __Pyx_PyObject_IsTrue(__pyx_t_13); __Pyx_DECREF(__pyx_t_13); __pyx_t_13 = 0; - if (__pyx_t_6 < 0) __PYX_ERR(0, 338, __pyx_L10_except_error) + if (__pyx_t_6 < 0) __PYX_ERR(0, 370, __pyx_L10_except_error) __pyx_t_5 = (!__pyx_t_6); if (unlikely(__pyx_t_5)) { __Pyx_GIVEREF(__pyx_t_3); @@ -23690,7 +24542,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __Pyx_XGIVEREF(__pyx_t_1); __Pyx_ErrRestoreWithState(__pyx_t_3, __pyx_t_2, __pyx_t_1); __pyx_t_3 = 0; __pyx_t_2 = 0; __pyx_t_1 = 0; - __PYX_ERR(0, 338, __pyx_L10_except_error) + __PYX_ERR(0, 370, __pyx_L10_except_error) } __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; @@ -23714,9 +24566,9 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS /*finally:*/ { /*normal exit:*/{ if (__pyx_t_9) { - __pyx_t_12 = __Pyx_PyObject_Call(__pyx_t_9, __pyx_tuple__17, NULL); + __pyx_t_12 = __Pyx_PyObject_Call(__pyx_t_9, __pyx_tuple__19, NULL); __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; - if (unlikely(!__pyx_t_12)) __PYX_ERR(0, 338, __pyx_L1_error) + if (unlikely(!__pyx_t_12)) __PYX_ERR(0, 370, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_12); __Pyx_DECREF(__pyx_t_12); __pyx_t_12 = 0; } @@ -23731,7 +24583,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_L17:; } - /* "acados_template/acados_ocp_solver_pyx.pyx":341 + /* "acados_template/acados_ocp_solver_pyx.pyx":373 * solution = json.load(f) * * for key in solution.keys(): # <<<<<<<<<<<<<< @@ -23739,12 +24591,12 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS * self.set(int(stage), field, np.array(solution[key])) */ __pyx_t_14 = 0; - if (unlikely(!__pyx_v_solution)) { __Pyx_RaiseUnboundLocalError("solution"); __PYX_ERR(0, 341, __pyx_L1_error) } + if (unlikely(!__pyx_v_solution)) { __Pyx_RaiseUnboundLocalError("solution"); __PYX_ERR(0, 373, __pyx_L1_error) } if (unlikely(__pyx_v_solution == Py_None)) { PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "keys"); - __PYX_ERR(0, 341, __pyx_L1_error) + __PYX_ERR(0, 373, __pyx_L1_error) } - __pyx_t_2 = __Pyx_dict_iterator(__pyx_v_solution, 0, __pyx_n_s_keys, (&__pyx_t_15), (&__pyx_t_4)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 341, __pyx_L1_error) + __pyx_t_2 = __Pyx_dict_iterator(__pyx_v_solution, 0, __pyx_n_s_keys, (&__pyx_t_15), (&__pyx_t_4)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 373, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = __pyx_t_2; @@ -23752,19 +24604,19 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS while (1) { __pyx_t_16 = __Pyx_dict_iter_next(__pyx_t_1, __pyx_t_15, &__pyx_t_14, &__pyx_t_2, NULL, NULL, __pyx_t_4); if (unlikely(__pyx_t_16 == 0)) break; - if (unlikely(__pyx_t_16 == -1)) __PYX_ERR(0, 341, __pyx_L1_error) + if (unlikely(__pyx_t_16 == -1)) __PYX_ERR(0, 373, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_XDECREF_SET(__pyx_v_key, __pyx_t_2); __pyx_t_2 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":342 + /* "acados_template/acados_ocp_solver_pyx.pyx":374 * * for key in solution.keys(): * (field, stage) = key.split('_') # <<<<<<<<<<<<<< * self.set(int(stage), field, np.array(solution[key])) * */ - __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_v_key, __pyx_n_s_split); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 342, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_v_key, __pyx_n_s_split); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 374, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __pyx_t_8 = NULL; __pyx_t_16 = 0; @@ -23779,10 +24631,10 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS } } { - PyObject *__pyx_callargs[2] = {__pyx_t_8, __pyx_n_u__15}; + PyObject *__pyx_callargs[2] = {__pyx_t_8, __pyx_n_u__17}; __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_16, 1+__pyx_t_16); __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; - if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 342, __pyx_L1_error) + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 374, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; } @@ -23792,7 +24644,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS if (unlikely(size != 2)) { if (size > 2) __Pyx_RaiseTooManyValuesError(2); else if (size >= 0) __Pyx_RaiseNeedMoreValuesError(size); - __PYX_ERR(0, 342, __pyx_L1_error) + __PYX_ERR(0, 374, __pyx_L1_error) } #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS if (likely(PyTuple_CheckExact(sequence))) { @@ -23805,15 +24657,15 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __Pyx_INCREF(__pyx_t_3); __Pyx_INCREF(__pyx_t_8); #else - __pyx_t_3 = PySequence_ITEM(sequence, 0); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 342, __pyx_L1_error) + __pyx_t_3 = PySequence_ITEM(sequence, 0); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 374, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); - __pyx_t_8 = PySequence_ITEM(sequence, 1); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 342, __pyx_L1_error) + __pyx_t_8 = PySequence_ITEM(sequence, 1); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 374, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_8); #endif __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; } else { Py_ssize_t index = -1; - __pyx_t_7 = PyObject_GetIter(__pyx_t_2); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 342, __pyx_L1_error) + __pyx_t_7 = PyObject_GetIter(__pyx_t_2); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 374, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; __pyx_t_17 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_7); @@ -23821,7 +24673,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __Pyx_GOTREF(__pyx_t_3); index = 1; __pyx_t_8 = __pyx_t_17(__pyx_t_7); if (unlikely(!__pyx_t_8)) goto __pyx_L20_unpacking_failed; __Pyx_GOTREF(__pyx_t_8); - if (__Pyx_IternextUnpackEndCheck(__pyx_t_17(__pyx_t_7), 2) < 0) __PYX_ERR(0, 342, __pyx_L1_error) + if (__Pyx_IternextUnpackEndCheck(__pyx_t_17(__pyx_t_7), 2) < 0) __PYX_ERR(0, 374, __pyx_L1_error) __pyx_t_17 = NULL; __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; goto __pyx_L21_unpacking_done; @@ -23829,7 +24681,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; __pyx_t_17 = NULL; if (__Pyx_IterFinish() == 0) __Pyx_RaiseNeedMoreValuesError(index); - __PYX_ERR(0, 342, __pyx_L1_error) + __PYX_ERR(0, 374, __pyx_L1_error) __pyx_L21_unpacking_done:; } __Pyx_XDECREF_SET(__pyx_v_field, __pyx_t_3); @@ -23837,24 +24689,24 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __Pyx_XDECREF_SET(__pyx_v_stage, __pyx_t_8); __pyx_t_8 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":343 + /* "acados_template/acados_ocp_solver_pyx.pyx":375 * for key in solution.keys(): * (field, stage) = key.split('_') * self.set(int(stage), field, np.array(solution[key])) # <<<<<<<<<<<<<< * * */ - __pyx_t_8 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_set); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 343, __pyx_L1_error) + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_set); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 375, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_8); - __pyx_t_3 = __Pyx_PyNumber_Int(__pyx_v_stage); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 343, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyNumber_Int(__pyx_v_stage); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 375, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); - __Pyx_GetModuleGlobalName(__pyx_t_18, __pyx_n_s_np); if (unlikely(!__pyx_t_18)) __PYX_ERR(0, 343, __pyx_L1_error) + __Pyx_GetModuleGlobalName(__pyx_t_18, __pyx_n_s_np); if (unlikely(!__pyx_t_18)) __PYX_ERR(0, 375, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_18); - __pyx_t_19 = __Pyx_PyObject_GetAttrStr(__pyx_t_18, __pyx_n_s_array); if (unlikely(!__pyx_t_19)) __PYX_ERR(0, 343, __pyx_L1_error) + __pyx_t_19 = __Pyx_PyObject_GetAttrStr(__pyx_t_18, __pyx_n_s_array); if (unlikely(!__pyx_t_19)) __PYX_ERR(0, 375, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_19); __Pyx_DECREF(__pyx_t_18); __pyx_t_18 = 0; - if (unlikely(!__pyx_v_solution)) { __Pyx_RaiseUnboundLocalError("solution"); __PYX_ERR(0, 343, __pyx_L1_error) } - __pyx_t_18 = __Pyx_PyObject_GetItem(__pyx_v_solution, __pyx_v_key); if (unlikely(!__pyx_t_18)) __PYX_ERR(0, 343, __pyx_L1_error) + if (unlikely(!__pyx_v_solution)) { __Pyx_RaiseUnboundLocalError("solution"); __PYX_ERR(0, 375, __pyx_L1_error) } + __pyx_t_18 = __Pyx_PyObject_GetItem(__pyx_v_solution, __pyx_v_key); if (unlikely(!__pyx_t_18)) __PYX_ERR(0, 375, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_18); __pyx_t_20 = NULL; __pyx_t_16 = 0; @@ -23873,7 +24725,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_19, __pyx_callargs+1-__pyx_t_16, 1+__pyx_t_16); __Pyx_XDECREF(__pyx_t_20); __pyx_t_20 = 0; __Pyx_DECREF(__pyx_t_18); __pyx_t_18 = 0; - if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 343, __pyx_L1_error) + if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 375, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); __Pyx_DECREF(__pyx_t_19); __pyx_t_19 = 0; } @@ -23895,7 +24747,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __Pyx_XDECREF(__pyx_t_19); __pyx_t_19 = 0; __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 343, __pyx_L1_error) + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 375, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; } @@ -23903,7 +24755,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS } __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":330 + /* "acados_template/acados_ocp_solver_pyx.pyx":362 * * * def load_iterate(self, filename): # <<<<<<<<<<<<<< @@ -23937,7 +24789,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":346 +/* "acados_template/acados_ocp_solver_pyx.pyx":378 * * * def get_stats(self, field_): # <<<<<<<<<<<<<< @@ -23946,16 +24798,16 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ /* Python wrapper */ -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23get_stats(PyObject *__pyx_v_self, +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27get_stats(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else PyObject *__pyx_args, PyObject *__pyx_kwds #endif ); /*proto*/ -PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22get_stats, "\n Get the information of the last solver call.\n\n :param field: string in ['statistics', 'time_tot', 'time_lin', 'time_sim', 'time_sim_ad', 'time_sim_la', 'time_qp', 'time_qp_solver_call', 'time_reg', 'sqp_iter']\n Available fileds:\n - time_tot: total CPU time previous call\n - time_lin: CPU time for linearization\n - time_sim: CPU time for integrator\n - time_sim_ad: CPU time for integrator contribution of external function calls\n - time_sim_la: CPU time for integrator contribution of linear algebra\n - time_qp: CPU time qp solution\n - time_qp_solver_call: CPU time inside qp solver (without converting the QP)\n - time_qp_xcond: time_glob: CPU time globalization\n - time_solution_sensitivities: CPU time for previous call to eval_param_sens\n - time_reg: CPU time regularization\n - sqp_iter: number of SQP iterations\n - qp_iter: vector of QP iterations for last SQP call\n - statistics: table with info about last iteration\n - stat_m: number of rows in statistics matrix\n - stat_n: number of columns in statistics matrix\n - residuals: residuals of last iterate\n - alpha: step sizes of SQP iterations\n "); -static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23get_stats = {"get_stats", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23get_stats, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22get_stats}; -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23get_stats(PyObject *__pyx_v_self, +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_26get_stats, "\n Get the information of the last solver call.\n\n :param field: string in ['statistics', 'time_tot', 'time_lin', 'time_sim', 'time_sim_ad', 'time_sim_la', 'time_qp', 'time_qp_solver_call', 'time_reg', 'sqp_iter']\n Available fileds:\n - time_tot: total CPU time previous call\n - time_lin: CPU time for linearization\n - time_sim: CPU time for integrator\n - time_sim_ad: CPU time for integrator contribution of external function calls\n - time_sim_la: CPU time for integrator contribution of linear algebra\n - time_qp: CPU time qp solution\n - time_qp_solver_call: CPU time inside qp solver (without converting the QP)\n - time_qp_xcond: time_glob: CPU time globalization\n - time_solution_sensitivities: CPU time for previous call to eval_param_sens\n - time_reg: CPU time regularization\n - sqp_iter: number of SQP iterations\n - qp_iter: vector of QP iterations for last SQP call\n - statistics: table with info about last iteration\n - stat_m: number of rows in statistics matrix\n - stat_n: number of columns in statistics matrix\n - residuals: residuals of last iterate\n - alpha: step sizes of SQP iterations\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27get_stats = {"get_stats", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27get_stats, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_26get_stats}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27get_stats(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else @@ -23988,12 +24840,12 @@ PyObject *__pyx_args, PyObject *__pyx_kwds switch (__pyx_nargs) { case 0: if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field_2)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 346, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 378, __pyx_L3_error) else goto __pyx_L5_argtuple_error; } if (unlikely(kw_args > 0)) { const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "get_stats") < 0)) __PYX_ERR(0, 346, __pyx_L3_error) + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "get_stats") < 0)) __PYX_ERR(0, 378, __pyx_L3_error) } } else if (unlikely(__pyx_nargs != 1)) { goto __pyx_L5_argtuple_error; @@ -24004,20 +24856,20 @@ PyObject *__pyx_args, PyObject *__pyx_kwds } goto __pyx_L4_argument_unpacking_done; __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("get_stats", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 346, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("get_stats", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 378, __pyx_L3_error) __pyx_L3_error:; __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.get_stats", __pyx_clineno, __pyx_lineno, __pyx_filename); __Pyx_RefNannyFinishContext(); return NULL; __pyx_L4_argument_unpacking_done:; - __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22get_stats(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_field_); + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_26get_stats(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_field_); /* function exit code */ __Pyx_RefNannyFinishContext(); return __pyx_r; } -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22get_stats(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field_) { +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_26get_stats(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field_) { PyObject *__pyx_v_double_fields = NULL; CYTHON_UNUSED PyObject *__pyx_v_fields = NULL; PyObject *__pyx_v_field = NULL; @@ -24040,14 +24892,14 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS int __pyx_clineno = 0; __Pyx_RefNannySetupContext("get_stats", 0); - /* "acados_template/acados_ocp_solver_pyx.pyx":371 + /* "acados_template/acados_ocp_solver_pyx.pyx":403 * """ * * double_fields = ['time_tot', # <<<<<<<<<<<<<< * 'time_lin', * 'time_sim', */ - __pyx_t_1 = PyList_New(11); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 371, __pyx_L1_error) + __pyx_t_1 = PyList_New(11); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 403, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_INCREF(__pyx_n_u_time_tot); __Pyx_GIVEREF(__pyx_n_u_time_tot); @@ -24085,14 +24937,14 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_v_double_fields = ((PyObject*)__pyx_t_1); __pyx_t_1 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":383 + /* "acados_template/acados_ocp_solver_pyx.pyx":415 * 'time_reg' * ] * fields = double_fields + [ # <<<<<<<<<<<<<< * 'sqp_iter', * 'qp_iter', */ - __pyx_t_1 = PyList_New(7); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 383, __pyx_L1_error) + __pyx_t_1 = PyList_New(7); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 415, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_INCREF(__pyx_n_u_sqp_iter); __Pyx_GIVEREF(__pyx_n_u_sqp_iter); @@ -24115,20 +24967,20 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __Pyx_INCREF(__pyx_n_u_alpha); __Pyx_GIVEREF(__pyx_n_u_alpha); PyList_SET_ITEM(__pyx_t_1, 6, __pyx_n_u_alpha); - __pyx_t_2 = PyNumber_Add(__pyx_v_double_fields, __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 383, __pyx_L1_error) + __pyx_t_2 = PyNumber_Add(__pyx_v_double_fields, __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 415, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; __pyx_v_fields = ((PyObject*)__pyx_t_2); __pyx_t_2 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":392 + /* "acados_template/acados_ocp_solver_pyx.pyx":424 * 'alpha', * ] * field = field_.encode('utf-8') # <<<<<<<<<<<<<< * * if field_ in ['sqp_iter', 'stat_m', 'stat_n']: */ - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_field_, __pyx_n_s_encode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 392, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_field_, __pyx_n_s_encode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 424, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __pyx_t_3 = NULL; __pyx_t_4 = 0; @@ -24146,14 +24998,14 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_kp_u_utf_8}; __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; - if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 392, __pyx_L1_error) + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 424, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; } __pyx_v_field = __pyx_t_2; __pyx_t_2 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":394 + /* "acados_template/acados_ocp_solver_pyx.pyx":426 * field = field_.encode('utf-8') * * if field_ in ['sqp_iter', 'stat_m', 'stat_n']: # <<<<<<<<<<<<<< @@ -24162,26 +25014,26 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ __Pyx_INCREF(__pyx_v_field_); __pyx_t_2 = __pyx_v_field_; - __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_t_2, __pyx_n_u_sqp_iter, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 394, __pyx_L1_error) + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_t_2, __pyx_n_u_sqp_iter, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 426, __pyx_L1_error) if (!__pyx_t_6) { } else { __pyx_t_5 = __pyx_t_6; goto __pyx_L4_bool_binop_done; } - __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_t_2, __pyx_n_u_stat_m, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 394, __pyx_L1_error) + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_t_2, __pyx_n_u_stat_m, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 426, __pyx_L1_error) if (!__pyx_t_6) { } else { __pyx_t_5 = __pyx_t_6; goto __pyx_L4_bool_binop_done; } - __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_t_2, __pyx_n_u_stat_n, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 394, __pyx_L1_error) + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_t_2, __pyx_n_u_stat_n, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 426, __pyx_L1_error) __pyx_t_5 = __pyx_t_6; __pyx_L4_bool_binop_done:; __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; __pyx_t_6 = __pyx_t_5; if (__pyx_t_6) { - /* "acados_template/acados_ocp_solver_pyx.pyx":395 + /* "acados_template/acados_ocp_solver_pyx.pyx":427 * * if field_ in ['sqp_iter', 'stat_m', 'stat_n']: * return self.__get_stat_int(field) # <<<<<<<<<<<<<< @@ -24189,7 +25041,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS * elif field_ in double_fields: */ __Pyx_XDECREF(__pyx_r); - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_AcadosOcpSolverCython__get_stat); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 395, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_AcadosOcpSolverCython__get_stat); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 427, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __pyx_t_3 = NULL; __pyx_t_4 = 0; @@ -24207,7 +25059,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_field}; __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; - if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 395, __pyx_L1_error) + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 427, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; } @@ -24215,7 +25067,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_t_2 = 0; goto __pyx_L0; - /* "acados_template/acados_ocp_solver_pyx.pyx":394 + /* "acados_template/acados_ocp_solver_pyx.pyx":426 * field = field_.encode('utf-8') * * if field_ in ['sqp_iter', 'stat_m', 'stat_n']: # <<<<<<<<<<<<<< @@ -24224,17 +25076,17 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":397 + /* "acados_template/acados_ocp_solver_pyx.pyx":429 * return self.__get_stat_int(field) * * elif field_ in double_fields: # <<<<<<<<<<<<<< * return self.__get_stat_double(field) * */ - __pyx_t_6 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_double_fields, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 397, __pyx_L1_error) + __pyx_t_6 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_double_fields, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 429, __pyx_L1_error) if (__pyx_t_6) { - /* "acados_template/acados_ocp_solver_pyx.pyx":398 + /* "acados_template/acados_ocp_solver_pyx.pyx":430 * * elif field_ in double_fields: * return self.__get_stat_double(field) # <<<<<<<<<<<<<< @@ -24242,7 +25094,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS * elif field_ == 'statistics': */ __Pyx_XDECREF(__pyx_r); - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_AcadosOcpSolverCython__get_stat_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 398, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_AcadosOcpSolverCython__get_stat_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 430, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __pyx_t_3 = NULL; __pyx_t_4 = 0; @@ -24260,7 +25112,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_field}; __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; - if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 398, __pyx_L1_error) + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 430, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; } @@ -24268,7 +25120,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_t_2 = 0; goto __pyx_L0; - /* "acados_template/acados_ocp_solver_pyx.pyx":397 + /* "acados_template/acados_ocp_solver_pyx.pyx":429 * return self.__get_stat_int(field) * * elif field_ in double_fields: # <<<<<<<<<<<<<< @@ -24277,24 +25129,24 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":400 + /* "acados_template/acados_ocp_solver_pyx.pyx":432 * return self.__get_stat_double(field) * * elif field_ == 'statistics': # <<<<<<<<<<<<<< * sqp_iter = self.get_stats("sqp_iter") * stat_m = self.get_stats("stat_m") */ - __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_statistics, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 400, __pyx_L1_error) + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_statistics, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 432, __pyx_L1_error) if (__pyx_t_6) { - /* "acados_template/acados_ocp_solver_pyx.pyx":401 + /* "acados_template/acados_ocp_solver_pyx.pyx":433 * * elif field_ == 'statistics': * sqp_iter = self.get_stats("sqp_iter") # <<<<<<<<<<<<<< * stat_m = self.get_stats("stat_m") * stat_n = self.get_stats("stat_n") */ - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_stats); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 401, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_stats); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 433, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __pyx_t_3 = NULL; __pyx_t_4 = 0; @@ -24312,21 +25164,21 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_n_u_sqp_iter}; __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; - if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 401, __pyx_L1_error) + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 433, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; } __pyx_v_sqp_iter = __pyx_t_2; __pyx_t_2 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":402 + /* "acados_template/acados_ocp_solver_pyx.pyx":434 * elif field_ == 'statistics': * sqp_iter = self.get_stats("sqp_iter") * stat_m = self.get_stats("stat_m") # <<<<<<<<<<<<<< * stat_n = self.get_stats("stat_n") * min_size = min([stat_m, sqp_iter+1]) */ - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_stats); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 402, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_stats); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 434, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __pyx_t_3 = NULL; __pyx_t_4 = 0; @@ -24344,21 +25196,21 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_n_u_stat_m}; __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; - if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 402, __pyx_L1_error) + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 434, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; } __pyx_v_stat_m = __pyx_t_2; __pyx_t_2 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":403 + /* "acados_template/acados_ocp_solver_pyx.pyx":435 * sqp_iter = self.get_stats("sqp_iter") * stat_m = self.get_stats("stat_m") * stat_n = self.get_stats("stat_n") # <<<<<<<<<<<<<< * min_size = min([stat_m, sqp_iter+1]) * return self.__get_stat_matrix(field, stat_n+1, min_size) */ - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_stats); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 403, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_stats); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 435, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __pyx_t_3 = NULL; __pyx_t_4 = 0; @@ -24376,26 +25228,26 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_n_u_stat_n}; __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; - if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 403, __pyx_L1_error) + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 435, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; } __pyx_v_stat_n = __pyx_t_2; __pyx_t_2 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":404 + /* "acados_template/acados_ocp_solver_pyx.pyx":436 * stat_m = self.get_stats("stat_m") * stat_n = self.get_stats("stat_n") * min_size = min([stat_m, sqp_iter+1]) # <<<<<<<<<<<<<< * return self.__get_stat_matrix(field, stat_n+1, min_size) * */ - __pyx_t_2 = __Pyx_PyInt_AddObjC(__pyx_v_sqp_iter, __pyx_int_1, 1, 0, 0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 404, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyInt_AddObjC(__pyx_v_sqp_iter, __pyx_int_1, 1, 0, 0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 436, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_INCREF(__pyx_v_stat_m); __pyx_t_1 = __pyx_v_stat_m; - __pyx_t_7 = PyObject_RichCompare(__pyx_t_2, __pyx_t_1, Py_LT); __Pyx_XGOTREF(__pyx_t_7); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 404, __pyx_L1_error) - __pyx_t_6 = __Pyx_PyObject_IsTrue(__pyx_t_7); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 404, __pyx_L1_error) + __pyx_t_7 = PyObject_RichCompare(__pyx_t_2, __pyx_t_1, Py_LT); __Pyx_XGOTREF(__pyx_t_7); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 436, __pyx_L1_error) + __pyx_t_6 = __Pyx_PyObject_IsTrue(__pyx_t_7); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 436, __pyx_L1_error) __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; if (__pyx_t_6) { __Pyx_INCREF(__pyx_t_2); @@ -24412,7 +25264,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_v_min_size = __pyx_t_2; __pyx_t_2 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":405 + /* "acados_template/acados_ocp_solver_pyx.pyx":437 * stat_n = self.get_stats("stat_n") * min_size = min([stat_m, sqp_iter+1]) * return self.__get_stat_matrix(field, stat_n+1, min_size) # <<<<<<<<<<<<<< @@ -24420,9 +25272,9 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS * elif field_ == 'qp_iter': */ __Pyx_XDECREF(__pyx_r); - __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_AcadosOcpSolverCython__get_stat_3); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 405, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_AcadosOcpSolverCython__get_stat_3); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 437, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); - __pyx_t_1 = __Pyx_PyInt_AddObjC(__pyx_v_stat_n, __pyx_int_1, 1, 0, 0); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 405, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyInt_AddObjC(__pyx_v_stat_n, __pyx_int_1, 1, 0, 0); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 437, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __pyx_t_7 = NULL; __pyx_t_4 = 0; @@ -24441,7 +25293,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_4, 3+__pyx_t_4); __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 405, __pyx_L1_error) + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 437, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; } @@ -24449,7 +25301,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_t_2 = 0; goto __pyx_L0; - /* "acados_template/acados_ocp_solver_pyx.pyx":400 + /* "acados_template/acados_ocp_solver_pyx.pyx":432 * return self.__get_stat_double(field) * * elif field_ == 'statistics': # <<<<<<<<<<<<<< @@ -24458,24 +25310,24 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":407 + /* "acados_template/acados_ocp_solver_pyx.pyx":439 * return self.__get_stat_matrix(field, stat_n+1, min_size) * * elif field_ == 'qp_iter': # <<<<<<<<<<<<<< * full_stats = self.get_stats('statistics') * if self.nlp_solver_type == 'SQP': */ - __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_qp_iter, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 407, __pyx_L1_error) + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_qp_iter, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 439, __pyx_L1_error) if (__pyx_t_6) { - /* "acados_template/acados_ocp_solver_pyx.pyx":408 + /* "acados_template/acados_ocp_solver_pyx.pyx":440 * * elif field_ == 'qp_iter': * full_stats = self.get_stats('statistics') # <<<<<<<<<<<<<< * if self.nlp_solver_type == 'SQP': * return full_stats[6, :] */ - __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_stats); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 408, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_stats); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 440, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __pyx_t_1 = NULL; __pyx_t_4 = 0; @@ -24493,24 +25345,24 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_callargs[2] = {__pyx_t_1, __pyx_n_u_statistics}; __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; - if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 408, __pyx_L1_error) + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 440, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; } __pyx_v_full_stats = __pyx_t_2; __pyx_t_2 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":409 + /* "acados_template/acados_ocp_solver_pyx.pyx":441 * elif field_ == 'qp_iter': * full_stats = self.get_stats('statistics') * if self.nlp_solver_type == 'SQP': # <<<<<<<<<<<<<< * return full_stats[6, :] * elif self.nlp_solver_type == 'SQP_RTI': */ - __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_self->nlp_solver_type, __pyx_n_u_SQP, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 409, __pyx_L1_error) + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_self->nlp_solver_type, __pyx_n_u_SQP, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 441, __pyx_L1_error) if (__pyx_t_6) { - /* "acados_template/acados_ocp_solver_pyx.pyx":410 + /* "acados_template/acados_ocp_solver_pyx.pyx":442 * full_stats = self.get_stats('statistics') * if self.nlp_solver_type == 'SQP': * return full_stats[6, :] # <<<<<<<<<<<<<< @@ -24518,13 +25370,13 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS * return full_stats[2, :] */ __Pyx_XDECREF(__pyx_r); - __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_v_full_stats, __pyx_tuple__18); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 410, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_v_full_stats, __pyx_tuple__20); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 442, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __pyx_r = __pyx_t_2; __pyx_t_2 = 0; goto __pyx_L0; - /* "acados_template/acados_ocp_solver_pyx.pyx":409 + /* "acados_template/acados_ocp_solver_pyx.pyx":441 * elif field_ == 'qp_iter': * full_stats = self.get_stats('statistics') * if self.nlp_solver_type == 'SQP': # <<<<<<<<<<<<<< @@ -24533,17 +25385,17 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":411 + /* "acados_template/acados_ocp_solver_pyx.pyx":443 * if self.nlp_solver_type == 'SQP': * return full_stats[6, :] * elif self.nlp_solver_type == 'SQP_RTI': # <<<<<<<<<<<<<< * return full_stats[2, :] * */ - __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_self->nlp_solver_type, __pyx_n_u_SQP_RTI, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 411, __pyx_L1_error) + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_self->nlp_solver_type, __pyx_n_u_SQP_RTI, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 443, __pyx_L1_error) if (__pyx_t_6) { - /* "acados_template/acados_ocp_solver_pyx.pyx":412 + /* "acados_template/acados_ocp_solver_pyx.pyx":444 * return full_stats[6, :] * elif self.nlp_solver_type == 'SQP_RTI': * return full_stats[2, :] # <<<<<<<<<<<<<< @@ -24551,13 +25403,13 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS * elif field_ == 'alpha': */ __Pyx_XDECREF(__pyx_r); - __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_v_full_stats, __pyx_tuple__19); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 412, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_v_full_stats, __pyx_tuple__21); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 444, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __pyx_r = __pyx_t_2; __pyx_t_2 = 0; goto __pyx_L0; - /* "acados_template/acados_ocp_solver_pyx.pyx":411 + /* "acados_template/acados_ocp_solver_pyx.pyx":443 * if self.nlp_solver_type == 'SQP': * return full_stats[6, :] * elif self.nlp_solver_type == 'SQP_RTI': # <<<<<<<<<<<<<< @@ -24566,7 +25418,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":407 + /* "acados_template/acados_ocp_solver_pyx.pyx":439 * return self.__get_stat_matrix(field, stat_n+1, min_size) * * elif field_ == 'qp_iter': # <<<<<<<<<<<<<< @@ -24576,24 +25428,24 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS goto __pyx_L3; } - /* "acados_template/acados_ocp_solver_pyx.pyx":414 + /* "acados_template/acados_ocp_solver_pyx.pyx":446 * return full_stats[2, :] * * elif field_ == 'alpha': # <<<<<<<<<<<<<< * full_stats = self.get_stats('statistics') * if self.nlp_solver_type == 'SQP': */ - __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_alpha, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 414, __pyx_L1_error) + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_alpha, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 446, __pyx_L1_error) if (__pyx_t_6) { - /* "acados_template/acados_ocp_solver_pyx.pyx":415 + /* "acados_template/acados_ocp_solver_pyx.pyx":447 * * elif field_ == 'alpha': * full_stats = self.get_stats('statistics') # <<<<<<<<<<<<<< * if self.nlp_solver_type == 'SQP': * return full_stats[7, :] */ - __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_stats); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 415, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_stats); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 447, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __pyx_t_1 = NULL; __pyx_t_4 = 0; @@ -24611,24 +25463,24 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_callargs[2] = {__pyx_t_1, __pyx_n_u_statistics}; __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; - if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 415, __pyx_L1_error) + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 447, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; } __pyx_v_full_stats = __pyx_t_2; __pyx_t_2 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":416 + /* "acados_template/acados_ocp_solver_pyx.pyx":448 * elif field_ == 'alpha': * full_stats = self.get_stats('statistics') * if self.nlp_solver_type == 'SQP': # <<<<<<<<<<<<<< * return full_stats[7, :] * else: # self.nlp_solver_type == 'SQP_RTI': */ - __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_self->nlp_solver_type, __pyx_n_u_SQP, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 416, __pyx_L1_error) + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_self->nlp_solver_type, __pyx_n_u_SQP, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 448, __pyx_L1_error) if (likely(__pyx_t_6)) { - /* "acados_template/acados_ocp_solver_pyx.pyx":417 + /* "acados_template/acados_ocp_solver_pyx.pyx":449 * full_stats = self.get_stats('statistics') * if self.nlp_solver_type == 'SQP': * return full_stats[7, :] # <<<<<<<<<<<<<< @@ -24636,13 +25488,13 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS * raise Exception("alpha values are not available for SQP_RTI") */ __Pyx_XDECREF(__pyx_r); - __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_v_full_stats, __pyx_tuple__20); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 417, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_v_full_stats, __pyx_tuple__22); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 449, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __pyx_r = __pyx_t_2; __pyx_t_2 = 0; goto __pyx_L0; - /* "acados_template/acados_ocp_solver_pyx.pyx":416 + /* "acados_template/acados_ocp_solver_pyx.pyx":448 * elif field_ == 'alpha': * full_stats = self.get_stats('statistics') * if self.nlp_solver_type == 'SQP': # <<<<<<<<<<<<<< @@ -24651,7 +25503,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":419 + /* "acados_template/acados_ocp_solver_pyx.pyx":451 * return full_stats[7, :] * else: # self.nlp_solver_type == 'SQP_RTI': * raise Exception("alpha values are not available for SQP_RTI") # <<<<<<<<<<<<<< @@ -24659,14 +25511,14 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS * elif field_ == 'residuals': */ /*else*/ { - __pyx_t_2 = __Pyx_PyObject_Call(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_tuple__21, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 419, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_Call(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_tuple__23, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 451, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_Raise(__pyx_t_2, 0, 0, 0); __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - __PYX_ERR(0, 419, __pyx_L1_error) + __PYX_ERR(0, 451, __pyx_L1_error) } - /* "acados_template/acados_ocp_solver_pyx.pyx":414 + /* "acados_template/acados_ocp_solver_pyx.pyx":446 * return full_stats[2, :] * * elif field_ == 'alpha': # <<<<<<<<<<<<<< @@ -24675,17 +25527,17 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":421 + /* "acados_template/acados_ocp_solver_pyx.pyx":453 * raise Exception("alpha values are not available for SQP_RTI") * * elif field_ == 'residuals': # <<<<<<<<<<<<<< * return self.get_residuals() * */ - __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_residuals, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 421, __pyx_L1_error) + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_residuals, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 453, __pyx_L1_error) if (likely(__pyx_t_6)) { - /* "acados_template/acados_ocp_solver_pyx.pyx":422 + /* "acados_template/acados_ocp_solver_pyx.pyx":454 * * elif field_ == 'residuals': * return self.get_residuals() # <<<<<<<<<<<<<< @@ -24693,7 +25545,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS * else: */ __Pyx_XDECREF(__pyx_r); - __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_residuals); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 422, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_residuals); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 454, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __pyx_t_1 = NULL; __pyx_t_4 = 0; @@ -24711,7 +25563,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_callargs[1] = {__pyx_t_1, }; __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_4, 0+__pyx_t_4); __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; - if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 422, __pyx_L1_error) + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 454, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; } @@ -24719,7 +25571,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_t_2 = 0; goto __pyx_L0; - /* "acados_template/acados_ocp_solver_pyx.pyx":421 + /* "acados_template/acados_ocp_solver_pyx.pyx":453 * raise Exception("alpha values are not available for SQP_RTI") * * elif field_ == 'residuals': # <<<<<<<<<<<<<< @@ -24728,7 +25580,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":425 + /* "acados_template/acados_ocp_solver_pyx.pyx":457 * * else: * raise NotImplementedError("TODO!") # <<<<<<<<<<<<<< @@ -24736,15 +25588,15 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS * */ /*else*/ { - __pyx_t_2 = __Pyx_PyObject_Call(__pyx_builtin_NotImplementedError, __pyx_tuple__22, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 425, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_Call(__pyx_builtin_NotImplementedError, __pyx_tuple__24, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 457, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_Raise(__pyx_t_2, 0, 0, 0); __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; - __PYX_ERR(0, 425, __pyx_L1_error) + __PYX_ERR(0, 457, __pyx_L1_error) } __pyx_L3:; - /* "acados_template/acados_ocp_solver_pyx.pyx":346 + /* "acados_template/acados_ocp_solver_pyx.pyx":378 * * * def get_stats(self, field_): # <<<<<<<<<<<<<< @@ -24776,7 +25628,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":428 +/* "acados_template/acados_ocp_solver_pyx.pyx":460 * * * def __get_stat_int(self, field): # <<<<<<<<<<<<<< @@ -24785,15 +25637,15 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ /* Python wrapper */ -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25_AcadosOcpSolverCython__get_stat_int(PyObject *__pyx_v_self, +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_int(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else PyObject *__pyx_args, PyObject *__pyx_kwds #endif ); /*proto*/ -static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25_AcadosOcpSolverCython__get_stat_int = {"_AcadosOcpSolverCython__get_stat_int", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25_AcadosOcpSolverCython__get_stat_int, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25_AcadosOcpSolverCython__get_stat_int(PyObject *__pyx_v_self, +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_int = {"_AcadosOcpSolverCython__get_stat_int", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_int, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_int(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else @@ -24826,12 +25678,12 @@ PyObject *__pyx_args, PyObject *__pyx_kwds switch (__pyx_nargs) { case 0: if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 428, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 460, __pyx_L3_error) else goto __pyx_L5_argtuple_error; } if (unlikely(kw_args > 0)) { const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "_AcadosOcpSolverCython__get_stat_int") < 0)) __PYX_ERR(0, 428, __pyx_L3_error) + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "_AcadosOcpSolverCython__get_stat_int") < 0)) __PYX_ERR(0, 460, __pyx_L3_error) } } else if (unlikely(__pyx_nargs != 1)) { goto __pyx_L5_argtuple_error; @@ -24842,20 +25694,20 @@ PyObject *__pyx_args, PyObject *__pyx_kwds } goto __pyx_L4_argument_unpacking_done; __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("_AcadosOcpSolverCython__get_stat_int", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 428, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("_AcadosOcpSolverCython__get_stat_int", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 460, __pyx_L3_error) __pyx_L3_error:; __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython._AcadosOcpSolverCython__get_stat_int", __pyx_clineno, __pyx_lineno, __pyx_filename); __Pyx_RefNannyFinishContext(); return NULL; __pyx_L4_argument_unpacking_done:; - __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_24__get_stat_int(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_field); + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_28__get_stat_int(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_field); /* function exit code */ __Pyx_RefNannyFinishContext(); return __pyx_r; } -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_24__get_stat_int(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field) { +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_28__get_stat_int(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field) { int __pyx_v_out; PyObject *__pyx_r = NULL; __Pyx_RefNannyDeclarations @@ -24866,17 +25718,17 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS int __pyx_clineno = 0; __Pyx_RefNannySetupContext("_AcadosOcpSolverCython__get_stat_int", 0); - /* "acados_template/acados_ocp_solver_pyx.pyx":430 + /* "acados_template/acados_ocp_solver_pyx.pyx":462 * def __get_stat_int(self, field): * cdef int out * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &out) # <<<<<<<<<<<<<< * return out * */ - __pyx_t_1 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_1) && PyErr_Occurred())) __PYX_ERR(0, 430, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_1) && PyErr_Occurred())) __PYX_ERR(0, 462, __pyx_L1_error) ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_t_1, ((void *)(&__pyx_v_out))); - /* "acados_template/acados_ocp_solver_pyx.pyx":431 + /* "acados_template/acados_ocp_solver_pyx.pyx":463 * cdef int out * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &out) * return out # <<<<<<<<<<<<<< @@ -24884,13 +25736,13 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS * def __get_stat_double(self, field): */ __Pyx_XDECREF(__pyx_r); - __pyx_t_2 = __Pyx_PyInt_From_int(__pyx_v_out); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 431, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyInt_From_int(__pyx_v_out); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 463, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __pyx_r = __pyx_t_2; __pyx_t_2 = 0; goto __pyx_L0; - /* "acados_template/acados_ocp_solver_pyx.pyx":428 + /* "acados_template/acados_ocp_solver_pyx.pyx":460 * * * def __get_stat_int(self, field): # <<<<<<<<<<<<<< @@ -24909,7 +25761,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":433 +/* "acados_template/acados_ocp_solver_pyx.pyx":465 * return out * * def __get_stat_double(self, field): # <<<<<<<<<<<<<< @@ -24918,15 +25770,15 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ /* Python wrapper */ -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27_AcadosOcpSolverCython__get_stat_double(PyObject *__pyx_v_self, +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31_AcadosOcpSolverCython__get_stat_double(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else PyObject *__pyx_args, PyObject *__pyx_kwds #endif ); /*proto*/ -static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27_AcadosOcpSolverCython__get_stat_double = {"_AcadosOcpSolverCython__get_stat_double", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27_AcadosOcpSolverCython__get_stat_double, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27_AcadosOcpSolverCython__get_stat_double(PyObject *__pyx_v_self, +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31_AcadosOcpSolverCython__get_stat_double = {"_AcadosOcpSolverCython__get_stat_double", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31_AcadosOcpSolverCython__get_stat_double, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31_AcadosOcpSolverCython__get_stat_double(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else @@ -24959,12 +25811,12 @@ PyObject *__pyx_args, PyObject *__pyx_kwds switch (__pyx_nargs) { case 0: if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 433, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 465, __pyx_L3_error) else goto __pyx_L5_argtuple_error; } if (unlikely(kw_args > 0)) { const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "_AcadosOcpSolverCython__get_stat_double") < 0)) __PYX_ERR(0, 433, __pyx_L3_error) + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "_AcadosOcpSolverCython__get_stat_double") < 0)) __PYX_ERR(0, 465, __pyx_L3_error) } } else if (unlikely(__pyx_nargs != 1)) { goto __pyx_L5_argtuple_error; @@ -24975,20 +25827,20 @@ PyObject *__pyx_args, PyObject *__pyx_kwds } goto __pyx_L4_argument_unpacking_done; __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("_AcadosOcpSolverCython__get_stat_double", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 433, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("_AcadosOcpSolverCython__get_stat_double", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 465, __pyx_L3_error) __pyx_L3_error:; __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython._AcadosOcpSolverCython__get_stat_double", __pyx_clineno, __pyx_lineno, __pyx_filename); __Pyx_RefNannyFinishContext(); return NULL; __pyx_L4_argument_unpacking_done:; - __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_26__get_stat_double(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_field); + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_30__get_stat_double(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_field); /* function exit code */ __Pyx_RefNannyFinishContext(); return __pyx_r; } -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_26__get_stat_double(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field) { +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_30__get_stat_double(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field) { PyArrayObject *__pyx_v_out = 0; __Pyx_LocalBuf_ND __pyx_pybuffernd_out; __Pyx_Buffer __pyx_pybuffer_out; @@ -25010,16 +25862,16 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_pybuffernd_out.data = NULL; __pyx_pybuffernd_out.rcbuffer = &__pyx_pybuffer_out; - /* "acados_template/acados_ocp_solver_pyx.pyx":434 + /* "acados_template/acados_ocp_solver_pyx.pyx":466 * * def __get_stat_double(self, field): * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) # <<<<<<<<<<<<<< * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) * return out */ - __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_np); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 434, __pyx_L1_error) + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_np); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 466, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); - __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_zeros); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 434, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_zeros); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 466, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; __pyx_t_2 = NULL; @@ -25035,20 +25887,20 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS } } { - PyObject *__pyx_callargs[2] = {__pyx_t_2, __pyx_tuple__23}; + PyObject *__pyx_callargs[2] = {__pyx_t_2, __pyx_tuple__25}; __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; - if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 434, __pyx_L1_error) + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 466, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; } - if (!(likely(((__pyx_t_1) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_1, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 434, __pyx_L1_error) + if (!(likely(((__pyx_t_1) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_1, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 466, __pyx_L1_error) __pyx_t_5 = ((PyArrayObject *)__pyx_t_1); { __Pyx_BufFmt_StackElem __pyx_stack[1]; if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_out.rcbuffer->pybuffer, (PyObject*)__pyx_t_5, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 1, 0, __pyx_stack) == -1)) { __pyx_v_out = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_out.rcbuffer->pybuffer.buf = NULL; - __PYX_ERR(0, 434, __pyx_L1_error) + __PYX_ERR(0, 466, __pyx_L1_error) } else {__pyx_pybuffernd_out.diminfo[0].strides = __pyx_pybuffernd_out.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_out.diminfo[0].shape = __pyx_pybuffernd_out.rcbuffer->pybuffer.shape[0]; } } @@ -25056,18 +25908,18 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_v_out = ((PyArrayObject *)__pyx_t_1); __pyx_t_1 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":435 + /* "acados_template/acados_ocp_solver_pyx.pyx":467 * def __get_stat_double(self, field): * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) # <<<<<<<<<<<<<< * return out * */ - __pyx_t_6 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_6) && PyErr_Occurred())) __PYX_ERR(0, 435, __pyx_L1_error) - __pyx_t_7 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_out)); if (unlikely(__pyx_t_7 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 435, __pyx_L1_error) + __pyx_t_6 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_6) && PyErr_Occurred())) __PYX_ERR(0, 467, __pyx_L1_error) + __pyx_t_7 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_out)); if (unlikely(__pyx_t_7 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 467, __pyx_L1_error) ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_t_6, ((void *)__pyx_t_7)); - /* "acados_template/acados_ocp_solver_pyx.pyx":436 + /* "acados_template/acados_ocp_solver_pyx.pyx":468 * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) * return out # <<<<<<<<<<<<<< @@ -25079,7 +25931,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_r = ((PyObject *)__pyx_v_out); goto __pyx_L0; - /* "acados_template/acados_ocp_solver_pyx.pyx":433 + /* "acados_template/acados_ocp_solver_pyx.pyx":465 * return out * * def __get_stat_double(self, field): # <<<<<<<<<<<<<< @@ -25110,7 +25962,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":438 +/* "acados_template/acados_ocp_solver_pyx.pyx":470 * return out * * def __get_stat_matrix(self, field, n, m): # <<<<<<<<<<<<<< @@ -25119,15 +25971,15 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ /* Python wrapper */ -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_matrix(PyObject *__pyx_v_self, +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33_AcadosOcpSolverCython__get_stat_matrix(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else PyObject *__pyx_args, PyObject *__pyx_kwds #endif ); /*proto*/ -static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_matrix = {"_AcadosOcpSolverCython__get_stat_matrix", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_matrix, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_matrix(PyObject *__pyx_v_self, +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33_AcadosOcpSolverCython__get_stat_matrix = {"_AcadosOcpSolverCython__get_stat_matrix", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33_AcadosOcpSolverCython__get_stat_matrix, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33_AcadosOcpSolverCython__get_stat_matrix(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else @@ -25166,26 +26018,26 @@ PyObject *__pyx_args, PyObject *__pyx_kwds switch (__pyx_nargs) { case 0: if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 438, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 470, __pyx_L3_error) else goto __pyx_L5_argtuple_error; CYTHON_FALLTHROUGH; case 1: if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_n)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 438, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 470, __pyx_L3_error) else { - __Pyx_RaiseArgtupleInvalid("_AcadosOcpSolverCython__get_stat_matrix", 1, 3, 3, 1); __PYX_ERR(0, 438, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("_AcadosOcpSolverCython__get_stat_matrix", 1, 3, 3, 1); __PYX_ERR(0, 470, __pyx_L3_error) } CYTHON_FALLTHROUGH; case 2: if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_m)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 438, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 470, __pyx_L3_error) else { - __Pyx_RaiseArgtupleInvalid("_AcadosOcpSolverCython__get_stat_matrix", 1, 3, 3, 2); __PYX_ERR(0, 438, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("_AcadosOcpSolverCython__get_stat_matrix", 1, 3, 3, 2); __PYX_ERR(0, 470, __pyx_L3_error) } } if (unlikely(kw_args > 0)) { const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "_AcadosOcpSolverCython__get_stat_matrix") < 0)) __PYX_ERR(0, 438, __pyx_L3_error) + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "_AcadosOcpSolverCython__get_stat_matrix") < 0)) __PYX_ERR(0, 470, __pyx_L3_error) } } else if (unlikely(__pyx_nargs != 3)) { goto __pyx_L5_argtuple_error; @@ -25200,20 +26052,20 @@ PyObject *__pyx_args, PyObject *__pyx_kwds } goto __pyx_L4_argument_unpacking_done; __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("_AcadosOcpSolverCython__get_stat_matrix", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 438, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("_AcadosOcpSolverCython__get_stat_matrix", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 470, __pyx_L3_error) __pyx_L3_error:; __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython._AcadosOcpSolverCython__get_stat_matrix", __pyx_clineno, __pyx_lineno, __pyx_filename); __Pyx_RefNannyFinishContext(); return NULL; __pyx_L4_argument_unpacking_done:; - __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_28__get_stat_matrix(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_field, __pyx_v_n, __pyx_v_m); + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_32__get_stat_matrix(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_field, __pyx_v_n, __pyx_v_m); /* function exit code */ __Pyx_RefNannyFinishContext(); return __pyx_r; } -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_28__get_stat_matrix(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field, PyObject *__pyx_v_n, PyObject *__pyx_v_m) { +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_32__get_stat_matrix(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field, PyObject *__pyx_v_n, PyObject *__pyx_v_m) { PyArrayObject *__pyx_v_out_mat = 0; __Pyx_LocalBuf_ND __pyx_pybuffernd_out_mat; __Pyx_Buffer __pyx_pybuffer_out_mat; @@ -25237,24 +26089,24 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_pybuffernd_out_mat.data = NULL; __pyx_pybuffernd_out_mat.rcbuffer = &__pyx_pybuffer_out_mat; - /* "acados_template/acados_ocp_solver_pyx.pyx":439 + /* "acados_template/acados_ocp_solver_pyx.pyx":471 * * def __get_stat_matrix(self, field, n, m): * cdef cnp.ndarray[cnp.float64_t, ndim=2] out_mat = np.ascontiguousarray(np.zeros((n, m)), dtype=np.float64) # <<<<<<<<<<<<<< * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_mat.data) * return out_mat */ - __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 439, __pyx_L1_error) + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 471, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); - __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 439, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 471, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_np); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 439, __pyx_L1_error) + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_np); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 471, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); - __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_zeros); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 439, __pyx_L1_error) + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_zeros); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 471, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 439, __pyx_L1_error) + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 471, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_INCREF(__pyx_v_n); __Pyx_GIVEREF(__pyx_v_n); @@ -25279,36 +26131,36 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_6, 1+__pyx_t_6); __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 439, __pyx_L1_error) + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 471, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; } - __pyx_t_4 = PyTuple_New(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 439, __pyx_L1_error) + __pyx_t_4 = PyTuple_New(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 471, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); __Pyx_GIVEREF(__pyx_t_1); PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_1); __pyx_t_1 = 0; - __pyx_t_1 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 439, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 471, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); - __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_np); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 439, __pyx_L1_error) + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_np); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 471, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); - __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_float64); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 439, __pyx_L1_error) + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_float64); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 471, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_5); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - if (PyDict_SetItem(__pyx_t_1, __pyx_n_s_dtype, __pyx_t_5) < 0) __PYX_ERR(0, 439, __pyx_L1_error) + if (PyDict_SetItem(__pyx_t_1, __pyx_n_s_dtype, __pyx_t_5) < 0) __PYX_ERR(0, 471, __pyx_L1_error) __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __pyx_t_5 = __Pyx_PyObject_Call(__pyx_t_2, __pyx_t_4, __pyx_t_1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 439, __pyx_L1_error) + __pyx_t_5 = __Pyx_PyObject_Call(__pyx_t_2, __pyx_t_4, __pyx_t_1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 471, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_5); __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - if (!(likely(((__pyx_t_5) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_5, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 439, __pyx_L1_error) + if (!(likely(((__pyx_t_5) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_5, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 471, __pyx_L1_error) __pyx_t_7 = ((PyArrayObject *)__pyx_t_5); { __Pyx_BufFmt_StackElem __pyx_stack[1]; if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_out_mat.rcbuffer->pybuffer, (PyObject*)__pyx_t_7, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 2, 0, __pyx_stack) == -1)) { __pyx_v_out_mat = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_out_mat.rcbuffer->pybuffer.buf = NULL; - __PYX_ERR(0, 439, __pyx_L1_error) + __PYX_ERR(0, 471, __pyx_L1_error) } else {__pyx_pybuffernd_out_mat.diminfo[0].strides = __pyx_pybuffernd_out_mat.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_out_mat.diminfo[0].shape = __pyx_pybuffernd_out_mat.rcbuffer->pybuffer.shape[0]; __pyx_pybuffernd_out_mat.diminfo[1].strides = __pyx_pybuffernd_out_mat.rcbuffer->pybuffer.strides[1]; __pyx_pybuffernd_out_mat.diminfo[1].shape = __pyx_pybuffernd_out_mat.rcbuffer->pybuffer.shape[1]; } } @@ -25316,18 +26168,18 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_v_out_mat = ((PyArrayObject *)__pyx_t_5); __pyx_t_5 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":440 + /* "acados_template/acados_ocp_solver_pyx.pyx":472 * def __get_stat_matrix(self, field, n, m): * cdef cnp.ndarray[cnp.float64_t, ndim=2] out_mat = np.ascontiguousarray(np.zeros((n, m)), dtype=np.float64) * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_mat.data) # <<<<<<<<<<<<<< * return out_mat * */ - __pyx_t_8 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_8) && PyErr_Occurred())) __PYX_ERR(0, 440, __pyx_L1_error) - __pyx_t_9 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_out_mat)); if (unlikely(__pyx_t_9 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 440, __pyx_L1_error) + __pyx_t_8 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_8) && PyErr_Occurred())) __PYX_ERR(0, 472, __pyx_L1_error) + __pyx_t_9 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_out_mat)); if (unlikely(__pyx_t_9 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 472, __pyx_L1_error) ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_t_8, ((void *)__pyx_t_9)); - /* "acados_template/acados_ocp_solver_pyx.pyx":441 + /* "acados_template/acados_ocp_solver_pyx.pyx":473 * cdef cnp.ndarray[cnp.float64_t, ndim=2] out_mat = np.ascontiguousarray(np.zeros((n, m)), dtype=np.float64) * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_mat.data) * return out_mat # <<<<<<<<<<<<<< @@ -25339,7 +26191,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_r = ((PyObject *)__pyx_v_out_mat); goto __pyx_L0; - /* "acados_template/acados_ocp_solver_pyx.pyx":438 + /* "acados_template/acados_ocp_solver_pyx.pyx":470 * return out * * def __get_stat_matrix(self, field, n, m): # <<<<<<<<<<<<<< @@ -25372,7 +26224,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":444 +/* "acados_template/acados_ocp_solver_pyx.pyx":476 * * * def get_cost(self): # <<<<<<<<<<<<<< @@ -25381,16 +26233,16 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ /* Python wrapper */ -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31get_cost(PyObject *__pyx_v_self, +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35get_cost(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else PyObject *__pyx_args, PyObject *__pyx_kwds #endif ); /*proto*/ -PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_30get_cost, "\n Returns the cost value of the current solution.\n "); -static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31get_cost = {"get_cost", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31get_cost, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_30get_cost}; -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31get_cost(PyObject *__pyx_v_self, +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34get_cost, "\n Returns the cost value of the current solution.\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35get_cost = {"get_cost", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35get_cost, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34get_cost}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35get_cost(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else @@ -25407,14 +26259,14 @@ PyObject *__pyx_args, PyObject *__pyx_kwds if (unlikely(__pyx_nargs > 0)) { __Pyx_RaiseArgtupleInvalid("get_cost", 1, 0, 0, __pyx_nargs); return NULL;} if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "get_cost", 0))) return NULL; - __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_30get_cost(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34get_cost(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); /* function exit code */ __Pyx_RefNannyFinishContext(); return __pyx_r; } -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_30get_cost(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34get_cost(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { double __pyx_v_out; PyObject *__pyx_r = NULL; __Pyx_RefNannyDeclarations @@ -25424,7 +26276,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS int __pyx_clineno = 0; __Pyx_RefNannySetupContext("get_cost", 0); - /* "acados_template/acados_ocp_solver_pyx.pyx":449 + /* "acados_template/acados_ocp_solver_pyx.pyx":481 * """ * # compute cost internally * acados_solver_common.ocp_nlp_eval_cost(self.nlp_solver, self.nlp_in, self.nlp_out) # <<<<<<<<<<<<<< @@ -25433,7 +26285,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ ocp_nlp_eval_cost(__pyx_v_self->nlp_solver, __pyx_v_self->nlp_in, __pyx_v_self->nlp_out); - /* "acados_template/acados_ocp_solver_pyx.pyx":455 + /* "acados_template/acados_ocp_solver_pyx.pyx":487 * * # call getter * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, "cost_value", &out) # <<<<<<<<<<<<<< @@ -25442,7 +26294,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, ((char const *)"cost_value"), ((void *)(&__pyx_v_out))); - /* "acados_template/acados_ocp_solver_pyx.pyx":457 + /* "acados_template/acados_ocp_solver_pyx.pyx":489 * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, "cost_value", &out) * * return out # <<<<<<<<<<<<<< @@ -25450,13 +26302,13 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS * */ __Pyx_XDECREF(__pyx_r); - __pyx_t_1 = PyFloat_FromDouble(__pyx_v_out); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 457, __pyx_L1_error) + __pyx_t_1 = PyFloat_FromDouble(__pyx_v_out); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 489, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __pyx_r = __pyx_t_1; __pyx_t_1 = 0; goto __pyx_L0; - /* "acados_template/acados_ocp_solver_pyx.pyx":444 + /* "acados_template/acados_ocp_solver_pyx.pyx":476 * * * def get_cost(self): # <<<<<<<<<<<<<< @@ -25475,7 +26327,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":460 +/* "acados_template/acados_ocp_solver_pyx.pyx":492 * * * def get_residuals(self, recompute=False): # <<<<<<<<<<<<<< @@ -25484,16 +26336,16 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ /* Python wrapper */ -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33get_residuals(PyObject *__pyx_v_self, +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37get_residuals(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else PyObject *__pyx_args, PyObject *__pyx_kwds #endif ); /*proto*/ -PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_32get_residuals, "\n Returns an array of the form [res_stat, res_eq, res_ineq, res_comp].\n "); -static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33get_residuals = {"get_residuals", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33get_residuals, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_32get_residuals}; -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33get_residuals(PyObject *__pyx_v_self, +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36get_residuals, "\n Returns an array of the form [res_stat, res_eq, res_ineq, res_comp].\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37get_residuals = {"get_residuals", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37get_residuals, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36get_residuals}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37get_residuals(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else @@ -25529,12 +26381,12 @@ PyObject *__pyx_args, PyObject *__pyx_kwds if (kw_args > 0) { PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_recompute); if (value) { values[0] = value; kw_args--; } - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 460, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 492, __pyx_L3_error) } } if (unlikely(kw_args > 0)) { const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "get_residuals") < 0)) __PYX_ERR(0, 460, __pyx_L3_error) + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "get_residuals") < 0)) __PYX_ERR(0, 492, __pyx_L3_error) } } else { switch (__pyx_nargs) { @@ -25548,20 +26400,20 @@ PyObject *__pyx_args, PyObject *__pyx_kwds } goto __pyx_L4_argument_unpacking_done; __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("get_residuals", 0, 0, 1, __pyx_nargs); __PYX_ERR(0, 460, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("get_residuals", 0, 0, 1, __pyx_nargs); __PYX_ERR(0, 492, __pyx_L3_error) __pyx_L3_error:; __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.get_residuals", __pyx_clineno, __pyx_lineno, __pyx_filename); __Pyx_RefNannyFinishContext(); return NULL; __pyx_L4_argument_unpacking_done:; - __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_32get_residuals(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_recompute); + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36get_residuals(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_recompute); /* function exit code */ __Pyx_RefNannyFinishContext(); return __pyx_r; } -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_32get_residuals(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_recompute) { +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36get_residuals(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_recompute) { PyArrayObject *__pyx_v_out = 0; double __pyx_v_double_value; PyObject *__pyx_v_field = NULL; @@ -25590,25 +26442,25 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_pybuffernd_out.data = NULL; __pyx_pybuffernd_out.rcbuffer = &__pyx_pybuffer_out; - /* "acados_template/acados_ocp_solver_pyx.pyx":465 + /* "acados_template/acados_ocp_solver_pyx.pyx":497 * """ * # compute residuals if RTI * if self.nlp_solver_type == 'SQP_RTI' or recompute: # <<<<<<<<<<<<<< * acados_solver_common.ocp_nlp_eval_residuals(self.nlp_solver, self.nlp_in, self.nlp_out) * */ - __pyx_t_2 = (__Pyx_PyUnicode_Equals(__pyx_v_self->nlp_solver_type, __pyx_n_u_SQP_RTI, Py_EQ)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 465, __pyx_L1_error) + __pyx_t_2 = (__Pyx_PyUnicode_Equals(__pyx_v_self->nlp_solver_type, __pyx_n_u_SQP_RTI, Py_EQ)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 497, __pyx_L1_error) if (!__pyx_t_2) { } else { __pyx_t_1 = __pyx_t_2; goto __pyx_L4_bool_binop_done; } - __pyx_t_2 = __Pyx_PyObject_IsTrue(__pyx_v_recompute); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 465, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_IsTrue(__pyx_v_recompute); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 497, __pyx_L1_error) __pyx_t_1 = __pyx_t_2; __pyx_L4_bool_binop_done:; if (__pyx_t_1) { - /* "acados_template/acados_ocp_solver_pyx.pyx":466 + /* "acados_template/acados_ocp_solver_pyx.pyx":498 * # compute residuals if RTI * if self.nlp_solver_type == 'SQP_RTI' or recompute: * acados_solver_common.ocp_nlp_eval_residuals(self.nlp_solver, self.nlp_in, self.nlp_out) # <<<<<<<<<<<<<< @@ -25617,7 +26469,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ ocp_nlp_eval_residuals(__pyx_v_self->nlp_solver, __pyx_v_self->nlp_in, __pyx_v_self->nlp_out); - /* "acados_template/acados_ocp_solver_pyx.pyx":465 + /* "acados_template/acados_ocp_solver_pyx.pyx":497 * """ * # compute residuals if RTI * if self.nlp_solver_type == 'SQP_RTI' or recompute: # <<<<<<<<<<<<<< @@ -25626,33 +26478,33 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":469 + /* "acados_template/acados_ocp_solver_pyx.pyx":501 * * # create output array * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.ascontiguousarray(np.zeros((4,), dtype=np.float64)) # <<<<<<<<<<<<<< * cdef double double_value * */ - __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_np); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 469, __pyx_L1_error) + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_np); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 501, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); - __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 469, __pyx_L1_error) + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 501, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_5); __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_np); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 469, __pyx_L1_error) + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_np); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 501, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); - __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_zeros); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 469, __pyx_L1_error) + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_zeros); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 501, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_6); __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __pyx_t_4 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 469, __pyx_L1_error) + __pyx_t_4 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 501, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); - __Pyx_GetModuleGlobalName(__pyx_t_7, __pyx_n_s_np); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 469, __pyx_L1_error) + __Pyx_GetModuleGlobalName(__pyx_t_7, __pyx_n_s_np); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 501, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); - __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_t_7, __pyx_n_s_float64); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 469, __pyx_L1_error) + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_t_7, __pyx_n_s_float64); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 501, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_8); __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - if (PyDict_SetItem(__pyx_t_4, __pyx_n_s_dtype, __pyx_t_8) < 0) __PYX_ERR(0, 469, __pyx_L1_error) + if (PyDict_SetItem(__pyx_t_4, __pyx_n_s_dtype, __pyx_t_8) < 0) __PYX_ERR(0, 501, __pyx_L1_error) __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; - __pyx_t_8 = __Pyx_PyObject_Call(__pyx_t_6, __pyx_tuple__25, __pyx_t_4); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 469, __pyx_L1_error) + __pyx_t_8 = __Pyx_PyObject_Call(__pyx_t_6, __pyx_tuple__27, __pyx_t_4); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 501, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_8); __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; @@ -25673,17 +26525,17 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_9, 1+__pyx_t_9); __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; - if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 469, __pyx_L1_error) + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 501, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; } - if (!(likely(((__pyx_t_3) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_3, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 469, __pyx_L1_error) + if (!(likely(((__pyx_t_3) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_3, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 501, __pyx_L1_error) __pyx_t_10 = ((PyArrayObject *)__pyx_t_3); { __Pyx_BufFmt_StackElem __pyx_stack[1]; if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_out.rcbuffer->pybuffer, (PyObject*)__pyx_t_10, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES| PyBUF_WRITABLE, 1, 0, __pyx_stack) == -1)) { __pyx_v_out = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_out.rcbuffer->pybuffer.buf = NULL; - __PYX_ERR(0, 469, __pyx_L1_error) + __PYX_ERR(0, 501, __pyx_L1_error) } else {__pyx_pybuffernd_out.diminfo[0].strides = __pyx_pybuffernd_out.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_out.diminfo[0].shape = __pyx_pybuffernd_out.rcbuffer->pybuffer.shape[0]; } } @@ -25691,7 +26543,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_v_out = ((PyArrayObject *)__pyx_t_3); __pyx_t_3 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":472 + /* "acados_template/acados_ocp_solver_pyx.pyx":504 * cdef double double_value * * field = "res_stat".encode('utf-8') # <<<<<<<<<<<<<< @@ -25701,17 +26553,17 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __Pyx_INCREF(__pyx_n_b_res_stat); __pyx_v_field = __pyx_n_b_res_stat; - /* "acados_template/acados_ocp_solver_pyx.pyx":473 + /* "acados_template/acados_ocp_solver_pyx.pyx":505 * * field = "res_stat".encode('utf-8') * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) # <<<<<<<<<<<<<< * out[0] = double_value * */ - __pyx_t_11 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_11) && PyErr_Occurred())) __PYX_ERR(0, 473, __pyx_L1_error) + __pyx_t_11 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_11) && PyErr_Occurred())) __PYX_ERR(0, 505, __pyx_L1_error) ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_t_11, ((void *)(&__pyx_v_double_value))); - /* "acados_template/acados_ocp_solver_pyx.pyx":474 + /* "acados_template/acados_ocp_solver_pyx.pyx":506 * field = "res_stat".encode('utf-8') * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) * out[0] = double_value # <<<<<<<<<<<<<< @@ -25726,11 +26578,11 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS } else if (unlikely(__pyx_t_12 >= __pyx_pybuffernd_out.diminfo[0].shape)) __pyx_t_9 = 0; if (unlikely(__pyx_t_9 != -1)) { __Pyx_RaiseBufferIndexError(__pyx_t_9); - __PYX_ERR(0, 474, __pyx_L1_error) + __PYX_ERR(0, 506, __pyx_L1_error) } *__Pyx_BufPtrStrided1d(__pyx_t_5numpy_float64_t *, __pyx_pybuffernd_out.rcbuffer->pybuffer.buf, __pyx_t_12, __pyx_pybuffernd_out.diminfo[0].strides) = __pyx_v_double_value; - /* "acados_template/acados_ocp_solver_pyx.pyx":476 + /* "acados_template/acados_ocp_solver_pyx.pyx":508 * out[0] = double_value * * field = "res_eq".encode('utf-8') # <<<<<<<<<<<<<< @@ -25740,17 +26592,17 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __Pyx_INCREF(__pyx_n_b_res_eq); __Pyx_DECREF_SET(__pyx_v_field, __pyx_n_b_res_eq); - /* "acados_template/acados_ocp_solver_pyx.pyx":477 + /* "acados_template/acados_ocp_solver_pyx.pyx":509 * * field = "res_eq".encode('utf-8') * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) # <<<<<<<<<<<<<< * out[1] = double_value * */ - __pyx_t_11 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_11) && PyErr_Occurred())) __PYX_ERR(0, 477, __pyx_L1_error) + __pyx_t_11 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_11) && PyErr_Occurred())) __PYX_ERR(0, 509, __pyx_L1_error) ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_t_11, ((void *)(&__pyx_v_double_value))); - /* "acados_template/acados_ocp_solver_pyx.pyx":478 + /* "acados_template/acados_ocp_solver_pyx.pyx":510 * field = "res_eq".encode('utf-8') * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) * out[1] = double_value # <<<<<<<<<<<<<< @@ -25765,11 +26617,11 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS } else if (unlikely(__pyx_t_12 >= __pyx_pybuffernd_out.diminfo[0].shape)) __pyx_t_9 = 0; if (unlikely(__pyx_t_9 != -1)) { __Pyx_RaiseBufferIndexError(__pyx_t_9); - __PYX_ERR(0, 478, __pyx_L1_error) + __PYX_ERR(0, 510, __pyx_L1_error) } *__Pyx_BufPtrStrided1d(__pyx_t_5numpy_float64_t *, __pyx_pybuffernd_out.rcbuffer->pybuffer.buf, __pyx_t_12, __pyx_pybuffernd_out.diminfo[0].strides) = __pyx_v_double_value; - /* "acados_template/acados_ocp_solver_pyx.pyx":480 + /* "acados_template/acados_ocp_solver_pyx.pyx":512 * out[1] = double_value * * field = "res_ineq".encode('utf-8') # <<<<<<<<<<<<<< @@ -25779,17 +26631,17 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __Pyx_INCREF(__pyx_n_b_res_ineq); __Pyx_DECREF_SET(__pyx_v_field, __pyx_n_b_res_ineq); - /* "acados_template/acados_ocp_solver_pyx.pyx":481 + /* "acados_template/acados_ocp_solver_pyx.pyx":513 * * field = "res_ineq".encode('utf-8') * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) # <<<<<<<<<<<<<< * out[2] = double_value * */ - __pyx_t_11 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_11) && PyErr_Occurred())) __PYX_ERR(0, 481, __pyx_L1_error) + __pyx_t_11 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_11) && PyErr_Occurred())) __PYX_ERR(0, 513, __pyx_L1_error) ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_t_11, ((void *)(&__pyx_v_double_value))); - /* "acados_template/acados_ocp_solver_pyx.pyx":482 + /* "acados_template/acados_ocp_solver_pyx.pyx":514 * field = "res_ineq".encode('utf-8') * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) * out[2] = double_value # <<<<<<<<<<<<<< @@ -25804,11 +26656,11 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS } else if (unlikely(__pyx_t_12 >= __pyx_pybuffernd_out.diminfo[0].shape)) __pyx_t_9 = 0; if (unlikely(__pyx_t_9 != -1)) { __Pyx_RaiseBufferIndexError(__pyx_t_9); - __PYX_ERR(0, 482, __pyx_L1_error) + __PYX_ERR(0, 514, __pyx_L1_error) } *__Pyx_BufPtrStrided1d(__pyx_t_5numpy_float64_t *, __pyx_pybuffernd_out.rcbuffer->pybuffer.buf, __pyx_t_12, __pyx_pybuffernd_out.diminfo[0].strides) = __pyx_v_double_value; - /* "acados_template/acados_ocp_solver_pyx.pyx":484 + /* "acados_template/acados_ocp_solver_pyx.pyx":516 * out[2] = double_value * * field = "res_comp".encode('utf-8') # <<<<<<<<<<<<<< @@ -25818,17 +26670,17 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __Pyx_INCREF(__pyx_n_b_res_comp); __Pyx_DECREF_SET(__pyx_v_field, __pyx_n_b_res_comp); - /* "acados_template/acados_ocp_solver_pyx.pyx":485 + /* "acados_template/acados_ocp_solver_pyx.pyx":517 * * field = "res_comp".encode('utf-8') * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) # <<<<<<<<<<<<<< * out[3] = double_value * */ - __pyx_t_11 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_11) && PyErr_Occurred())) __PYX_ERR(0, 485, __pyx_L1_error) + __pyx_t_11 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_11) && PyErr_Occurred())) __PYX_ERR(0, 517, __pyx_L1_error) ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_t_11, ((void *)(&__pyx_v_double_value))); - /* "acados_template/acados_ocp_solver_pyx.pyx":486 + /* "acados_template/acados_ocp_solver_pyx.pyx":518 * field = "res_comp".encode('utf-8') * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) * out[3] = double_value # <<<<<<<<<<<<<< @@ -25843,11 +26695,11 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS } else if (unlikely(__pyx_t_12 >= __pyx_pybuffernd_out.diminfo[0].shape)) __pyx_t_9 = 0; if (unlikely(__pyx_t_9 != -1)) { __Pyx_RaiseBufferIndexError(__pyx_t_9); - __PYX_ERR(0, 486, __pyx_L1_error) + __PYX_ERR(0, 518, __pyx_L1_error) } *__Pyx_BufPtrStrided1d(__pyx_t_5numpy_float64_t *, __pyx_pybuffernd_out.rcbuffer->pybuffer.buf, __pyx_t_12, __pyx_pybuffernd_out.diminfo[0].strides) = __pyx_v_double_value; - /* "acados_template/acados_ocp_solver_pyx.pyx":488 + /* "acados_template/acados_ocp_solver_pyx.pyx":520 * out[3] = double_value * * return out # <<<<<<<<<<<<<< @@ -25859,7 +26711,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_r = ((PyObject *)__pyx_v_out); goto __pyx_L0; - /* "acados_template/acados_ocp_solver_pyx.pyx":460 + /* "acados_template/acados_ocp_solver_pyx.pyx":492 * * * def get_residuals(self, recompute=False): # <<<<<<<<<<<<<< @@ -25894,7 +26746,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":492 +/* "acados_template/acados_ocp_solver_pyx.pyx":524 * * # Note: this function should not be used anymore, better use cost_set, constraints_set * def set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< @@ -25903,16 +26755,16 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ /* Python wrapper */ -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35set(PyObject *__pyx_v_self, +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39set(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else PyObject *__pyx_args, PyObject *__pyx_kwds #endif ); /*proto*/ -PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34set, "\n Set numerical data inside the solver.\n\n :param stage: integer corresponding to shooting node\n :param field: string in ['x', 'u', 'pi', 'lam', 't', 'p']\n\n .. note:: regarding lam, t: \n\n the inequalities are internally organized in the following order: \n\n [ lbu lbx lg lh lphi ubu ubx ug uh uphi; \n\n lsbu lsbx lsg lsh lsphi usbu usbx usg ush usphi]\n\n .. note:: pi: multipliers for dynamics equality constraints \n\n lam: multipliers for inequalities \n\n t: slack variables corresponding to evaluation of all inequalities (at the solution) \n\n sl: slack variables of soft lower inequality constraints \n\n su: slack variables of soft upper inequality constraints \n\n "); -static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35set = {"set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34set}; -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35set(PyObject *__pyx_v_self, +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38set, "\n Set numerical data inside the solver.\n\n :param stage: integer corresponding to shooting node\n :param field: string in ['x', 'u', 'pi', 'lam', 't', 'p']\n\n .. note:: regarding lam, t: \n\n the inequalities are internally organized in the following order: \n\n [ lbu lbx lg lh lphi ubu ubx ug uh uphi; \n\n lsbu lsbx lsg lsh lsphi usbu usbx usg ush usphi]\n\n .. note:: pi: multipliers for dynamics equality constraints \n\n lam: multipliers for inequalities \n\n t: slack variables corresponding to evaluation of all inequalities (at the solution) \n\n sl: slack variables of soft lower inequality constraints \n\n su: slack variables of soft upper inequality constraints \n\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39set = {"set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38set}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39set(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else @@ -25951,26 +26803,26 @@ PyObject *__pyx_args, PyObject *__pyx_kwds switch (__pyx_nargs) { case 0: if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_stage)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 492, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 524, __pyx_L3_error) else goto __pyx_L5_argtuple_error; CYTHON_FALLTHROUGH; case 1: if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field_2)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 492, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 524, __pyx_L3_error) else { - __Pyx_RaiseArgtupleInvalid("set", 1, 3, 3, 1); __PYX_ERR(0, 492, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("set", 1, 3, 3, 1); __PYX_ERR(0, 524, __pyx_L3_error) } CYTHON_FALLTHROUGH; case 2: if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_value)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 492, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 524, __pyx_L3_error) else { - __Pyx_RaiseArgtupleInvalid("set", 1, 3, 3, 2); __PYX_ERR(0, 492, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("set", 1, 3, 3, 2); __PYX_ERR(0, 524, __pyx_L3_error) } } if (unlikely(kw_args > 0)) { const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "set") < 0)) __PYX_ERR(0, 492, __pyx_L3_error) + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "set") < 0)) __PYX_ERR(0, 524, __pyx_L3_error) } } else if (unlikely(__pyx_nargs != 3)) { goto __pyx_L5_argtuple_error; @@ -25979,20 +26831,20 @@ PyObject *__pyx_args, PyObject *__pyx_kwds values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); } - __pyx_v_stage = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_stage == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 492, __pyx_L3_error) + __pyx_v_stage = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_stage == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 524, __pyx_L3_error) __pyx_v_field_ = ((PyObject*)values[1]); __pyx_v_value_ = values[2]; } goto __pyx_L4_argument_unpacking_done; __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("set", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 492, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("set", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 524, __pyx_L3_error) __pyx_L3_error:; __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.set", __pyx_clineno, __pyx_lineno, __pyx_filename); __Pyx_RefNannyFinishContext(); return NULL; __pyx_L4_argument_unpacking_done:; - if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 492, __pyx_L1_error) - __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34set(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_stage, __pyx_v_field_, __pyx_v_value_); + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 524, __pyx_L1_error) + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38set(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_stage, __pyx_v_field_, __pyx_v_value_); /* function exit code */ goto __pyx_L0; @@ -26003,7 +26855,7 @@ PyObject *__pyx_args, PyObject *__pyx_kwds return __pyx_r; } -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_) { +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_) { PyObject *__pyx_v_cost_fields = NULL; PyObject *__pyx_v_constraints_fields = NULL; PyObject *__pyx_v_out_fields = NULL; @@ -26018,19 +26870,22 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __Pyx_RefNannyDeclarations PyObject *__pyx_t_1 = NULL; PyObject *__pyx_t_2 = NULL; - PyObject *__pyx_t_3 = NULL; - PyObject *__pyx_t_4 = NULL; - PyObject *__pyx_t_5 = NULL; - PyArrayObject *__pyx_t_6 = NULL; - int __pyx_t_7; - char *__pyx_t_8; - npy_intp *__pyx_t_9; - int __pyx_t_10; - char const *__pyx_t_11; - char const *__pyx_t_12; - char const *__pyx_t_13; + int __pyx_t_3; + int __pyx_t_4; + Py_ssize_t __pyx_t_5; + Py_UCS4 __pyx_t_6; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + PyObject *__pyx_t_9 = NULL; + PyArrayObject *__pyx_t_10 = NULL; + char *__pyx_t_11; + npy_intp *__pyx_t_12; + int __pyx_t_13; char const *__pyx_t_14; char const *__pyx_t_15; + char const *__pyx_t_16; + char const *__pyx_t_17; + char const *__pyx_t_18; int __pyx_lineno = 0; const char *__pyx_filename = NULL; int __pyx_clineno = 0; @@ -26040,103 +26895,165 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_pybuffernd_value.data = NULL; __pyx_pybuffernd_value.rcbuffer = &__pyx_pybuffer_value; - /* "acados_template/acados_ocp_solver_pyx.pyx":511 + /* "acados_template/acados_ocp_solver_pyx.pyx":543 * su: slack variables of soft upper inequality constraints \n * """ + * if not isinstance(value_, np.ndarray): # <<<<<<<<<<<<<< + * raise Exception(f"set: value must be numpy array, got {type(value_)}.") + * cost_fields = ['y_ref', 'yref'] + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 543, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_ndarray); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 543, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_3 = PyObject_IsInstance(__pyx_v_value_, __pyx_t_2); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(0, 543, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_4 = (!__pyx_t_3); + if (unlikely(__pyx_t_4)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":544 + * """ + * if not isinstance(value_, np.ndarray): + * raise Exception(f"set: value must be numpy array, got {type(value_)}.") # <<<<<<<<<<<<<< + * cost_fields = ['y_ref', 'yref'] + * constraints_fields = ['lbx', 'ubx', 'lbu', 'ubu'] + */ + __pyx_t_2 = PyTuple_New(3); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 544, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_5 = 0; + __pyx_t_6 = 127; + __Pyx_INCREF(__pyx_kp_u_set_value_must_be_numpy_array_go); + __pyx_t_5 += 36; + __Pyx_GIVEREF(__pyx_kp_u_set_value_must_be_numpy_array_go); + PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_kp_u_set_value_must_be_numpy_array_go); + __pyx_t_1 = __Pyx_PyObject_FormatSimple(((PyObject *)Py_TYPE(__pyx_v_value_)), __pyx_empty_unicode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 544, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_2, 1, __pyx_t_1); + __pyx_t_1 = 0; + __Pyx_INCREF(__pyx_kp_u__2); + __pyx_t_5 += 1; + __Pyx_GIVEREF(__pyx_kp_u__2); + PyTuple_SET_ITEM(__pyx_t_2, 2, __pyx_kp_u__2); + __pyx_t_1 = __Pyx_PyUnicode_Join(__pyx_t_2, 3, __pyx_t_5, __pyx_t_6); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 544, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 544, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 544, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":543 + * su: slack variables of soft upper inequality constraints \n + * """ + * if not isinstance(value_, np.ndarray): # <<<<<<<<<<<<<< + * raise Exception(f"set: value must be numpy array, got {type(value_)}.") + * cost_fields = ['y_ref', 'yref'] + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":545 + * if not isinstance(value_, np.ndarray): + * raise Exception(f"set: value must be numpy array, got {type(value_)}.") * cost_fields = ['y_ref', 'yref'] # <<<<<<<<<<<<<< * constraints_fields = ['lbx', 'ubx', 'lbu', 'ubu'] * out_fields = ['x', 'u', 'pi', 'lam', 't', 'z', 'sl', 'su'] */ - __pyx_t_1 = PyList_New(2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 511, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = PyList_New(2); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 545, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); __Pyx_INCREF(__pyx_n_u_y_ref); __Pyx_GIVEREF(__pyx_n_u_y_ref); - PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_u_y_ref); + PyList_SET_ITEM(__pyx_t_2, 0, __pyx_n_u_y_ref); __Pyx_INCREF(__pyx_n_u_yref); __Pyx_GIVEREF(__pyx_n_u_yref); - PyList_SET_ITEM(__pyx_t_1, 1, __pyx_n_u_yref); - __pyx_v_cost_fields = ((PyObject*)__pyx_t_1); - __pyx_t_1 = 0; + PyList_SET_ITEM(__pyx_t_2, 1, __pyx_n_u_yref); + __pyx_v_cost_fields = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":512 - * """ + /* "acados_template/acados_ocp_solver_pyx.pyx":546 + * raise Exception(f"set: value must be numpy array, got {type(value_)}.") * cost_fields = ['y_ref', 'yref'] * constraints_fields = ['lbx', 'ubx', 'lbu', 'ubu'] # <<<<<<<<<<<<<< * out_fields = ['x', 'u', 'pi', 'lam', 't', 'z', 'sl', 'su'] * mem_fields = ['xdot_guess', 'z_guess'] */ - __pyx_t_1 = PyList_New(4); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 512, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = PyList_New(4); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 546, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); __Pyx_INCREF(__pyx_n_u_lbx); __Pyx_GIVEREF(__pyx_n_u_lbx); - PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_u_lbx); + PyList_SET_ITEM(__pyx_t_2, 0, __pyx_n_u_lbx); __Pyx_INCREF(__pyx_n_u_ubx); __Pyx_GIVEREF(__pyx_n_u_ubx); - PyList_SET_ITEM(__pyx_t_1, 1, __pyx_n_u_ubx); + PyList_SET_ITEM(__pyx_t_2, 1, __pyx_n_u_ubx); __Pyx_INCREF(__pyx_n_u_lbu); __Pyx_GIVEREF(__pyx_n_u_lbu); - PyList_SET_ITEM(__pyx_t_1, 2, __pyx_n_u_lbu); + PyList_SET_ITEM(__pyx_t_2, 2, __pyx_n_u_lbu); __Pyx_INCREF(__pyx_n_u_ubu); __Pyx_GIVEREF(__pyx_n_u_ubu); - PyList_SET_ITEM(__pyx_t_1, 3, __pyx_n_u_ubu); - __pyx_v_constraints_fields = ((PyObject*)__pyx_t_1); - __pyx_t_1 = 0; + PyList_SET_ITEM(__pyx_t_2, 3, __pyx_n_u_ubu); + __pyx_v_constraints_fields = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":513 + /* "acados_template/acados_ocp_solver_pyx.pyx":547 * cost_fields = ['y_ref', 'yref'] * constraints_fields = ['lbx', 'ubx', 'lbu', 'ubu'] * out_fields = ['x', 'u', 'pi', 'lam', 't', 'z', 'sl', 'su'] # <<<<<<<<<<<<<< * mem_fields = ['xdot_guess', 'z_guess'] * */ - __pyx_t_1 = PyList_New(8); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 513, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = PyList_New(8); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 547, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); __Pyx_INCREF(__pyx_n_u_x); __Pyx_GIVEREF(__pyx_n_u_x); - PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_u_x); + PyList_SET_ITEM(__pyx_t_2, 0, __pyx_n_u_x); __Pyx_INCREF(__pyx_n_u_u); __Pyx_GIVEREF(__pyx_n_u_u); - PyList_SET_ITEM(__pyx_t_1, 1, __pyx_n_u_u); + PyList_SET_ITEM(__pyx_t_2, 1, __pyx_n_u_u); __Pyx_INCREF(__pyx_n_u_pi); __Pyx_GIVEREF(__pyx_n_u_pi); - PyList_SET_ITEM(__pyx_t_1, 2, __pyx_n_u_pi); + PyList_SET_ITEM(__pyx_t_2, 2, __pyx_n_u_pi); __Pyx_INCREF(__pyx_n_u_lam); __Pyx_GIVEREF(__pyx_n_u_lam); - PyList_SET_ITEM(__pyx_t_1, 3, __pyx_n_u_lam); + PyList_SET_ITEM(__pyx_t_2, 3, __pyx_n_u_lam); __Pyx_INCREF(__pyx_n_u_t); __Pyx_GIVEREF(__pyx_n_u_t); - PyList_SET_ITEM(__pyx_t_1, 4, __pyx_n_u_t); + PyList_SET_ITEM(__pyx_t_2, 4, __pyx_n_u_t); __Pyx_INCREF(__pyx_n_u_z); __Pyx_GIVEREF(__pyx_n_u_z); - PyList_SET_ITEM(__pyx_t_1, 5, __pyx_n_u_z); + PyList_SET_ITEM(__pyx_t_2, 5, __pyx_n_u_z); __Pyx_INCREF(__pyx_n_u_sl); __Pyx_GIVEREF(__pyx_n_u_sl); - PyList_SET_ITEM(__pyx_t_1, 6, __pyx_n_u_sl); + PyList_SET_ITEM(__pyx_t_2, 6, __pyx_n_u_sl); __Pyx_INCREF(__pyx_n_u_su); __Pyx_GIVEREF(__pyx_n_u_su); - PyList_SET_ITEM(__pyx_t_1, 7, __pyx_n_u_su); - __pyx_v_out_fields = ((PyObject*)__pyx_t_1); - __pyx_t_1 = 0; + PyList_SET_ITEM(__pyx_t_2, 7, __pyx_n_u_su); + __pyx_v_out_fields = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":514 + /* "acados_template/acados_ocp_solver_pyx.pyx":548 * constraints_fields = ['lbx', 'ubx', 'lbu', 'ubu'] * out_fields = ['x', 'u', 'pi', 'lam', 't', 'z', 'sl', 'su'] * mem_fields = ['xdot_guess', 'z_guess'] # <<<<<<<<<<<<<< * * field = field_.encode('utf-8') */ - __pyx_t_1 = PyList_New(2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 514, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = PyList_New(2); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 548, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); __Pyx_INCREF(__pyx_n_u_xdot_guess); __Pyx_GIVEREF(__pyx_n_u_xdot_guess); - PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_u_xdot_guess); + PyList_SET_ITEM(__pyx_t_2, 0, __pyx_n_u_xdot_guess); __Pyx_INCREF(__pyx_n_u_z_guess); __Pyx_GIVEREF(__pyx_n_u_z_guess); - PyList_SET_ITEM(__pyx_t_1, 1, __pyx_n_u_z_guess); - __pyx_v_mem_fields = ((PyObject*)__pyx_t_1); - __pyx_t_1 = 0; + PyList_SET_ITEM(__pyx_t_2, 1, __pyx_n_u_z_guess); + __pyx_v_mem_fields = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":516 + /* "acados_template/acados_ocp_solver_pyx.pyx":550 * mem_fields = ['xdot_guess', 'z_guess'] * * field = field_.encode('utf-8') # <<<<<<<<<<<<<< @@ -26145,69 +27062,69 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ if (unlikely(__pyx_v_field_ == Py_None)) { PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "encode"); - __PYX_ERR(0, 516, __pyx_L1_error) + __PYX_ERR(0, 550, __pyx_L1_error) } - __pyx_t_1 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 516, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_v_field = __pyx_t_1; - __pyx_t_1 = 0; + __pyx_t_2 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 550, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_v_field = __pyx_t_2; + __pyx_t_2 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":518 + /* "acados_template/acados_ocp_solver_pyx.pyx":552 * field = field_.encode('utf-8') * * cdef cnp.ndarray[cnp.float64_t, ndim=1] value = np.ascontiguousarray(value_, dtype=np.float64) # <<<<<<<<<<<<<< * * # treat parameters separately */ - __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 518, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 518, __pyx_L1_error) + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_np); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 552, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_1 = PyTuple_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 518, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 552, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = PyTuple_New(1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 552, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); __Pyx_INCREF(__pyx_v_value_); __Pyx_GIVEREF(__pyx_v_value_); - PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v_value_); - __pyx_t_3 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 518, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_np); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 518, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_float64); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 518, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_dtype, __pyx_t_5) < 0) __PYX_ERR(0, 518, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __pyx_t_5 = __Pyx_PyObject_Call(__pyx_t_2, __pyx_t_1, __pyx_t_3); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 518, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_v_value_); + __pyx_t_7 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 552, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_GetModuleGlobalName(__pyx_t_8, __pyx_n_s_np); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 552, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_9 = __Pyx_PyObject_GetAttrStr(__pyx_t_8, __pyx_n_s_float64); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 552, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + if (PyDict_SetItem(__pyx_t_7, __pyx_n_s_dtype, __pyx_t_9) < 0) __PYX_ERR(0, 552, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + __pyx_t_9 = __Pyx_PyObject_Call(__pyx_t_1, __pyx_t_2, __pyx_t_7); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 552, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - if (!(likely(((__pyx_t_5) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_5, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 518, __pyx_L1_error) - __pyx_t_6 = ((PyArrayObject *)__pyx_t_5); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (!(likely(((__pyx_t_9) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_9, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 552, __pyx_L1_error) + __pyx_t_10 = ((PyArrayObject *)__pyx_t_9); { __Pyx_BufFmt_StackElem __pyx_stack[1]; - if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_value.rcbuffer->pybuffer, (PyObject*)__pyx_t_6, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 1, 0, __pyx_stack) == -1)) { + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_value.rcbuffer->pybuffer, (PyObject*)__pyx_t_10, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 1, 0, __pyx_stack) == -1)) { __pyx_v_value = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_value.rcbuffer->pybuffer.buf = NULL; - __PYX_ERR(0, 518, __pyx_L1_error) + __PYX_ERR(0, 552, __pyx_L1_error) } else {__pyx_pybuffernd_value.diminfo[0].strides = __pyx_pybuffernd_value.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_value.diminfo[0].shape = __pyx_pybuffernd_value.rcbuffer->pybuffer.shape[0]; } } - __pyx_t_6 = 0; - __pyx_v_value = ((PyArrayObject *)__pyx_t_5); - __pyx_t_5 = 0; + __pyx_t_10 = 0; + __pyx_v_value = ((PyArrayObject *)__pyx_t_9); + __pyx_t_9 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":521 + /* "acados_template/acados_ocp_solver_pyx.pyx":555 * * # treat parameters separately * if field_ == 'p': # <<<<<<<<<<<<<< * assert acados_solver.acados_update_params(self.capsule, stage, value.data, value.shape[0]) == 0 * else: */ - __pyx_t_7 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_p, Py_EQ)); if (unlikely((__pyx_t_7 < 0))) __PYX_ERR(0, 521, __pyx_L1_error) - if (__pyx_t_7) { + __pyx_t_4 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_p, Py_EQ)); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 555, __pyx_L1_error) + if (__pyx_t_4) { - /* "acados_template/acados_ocp_solver_pyx.pyx":522 + /* "acados_template/acados_ocp_solver_pyx.pyx":556 * # treat parameters separately * if field_ == 'p': * assert acados_solver.acados_update_params(self.capsule, stage, value.data, value.shape[0]) == 0 # <<<<<<<<<<<<<< @@ -26216,247 +27133,247 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ #ifndef CYTHON_WITHOUT_ASSERTIONS if (unlikely(__pyx_assertions_enabled())) { - __pyx_t_8 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_8 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 522, __pyx_L1_error) - __pyx_t_9 = __pyx_f_5numpy_7ndarray_5shape_shape(((PyArrayObject *)__pyx_v_value)); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 522, __pyx_L1_error) - __pyx_t_7 = (long_acados_update_params(__pyx_v_self->capsule, __pyx_v_stage, ((double *)__pyx_t_8), (__pyx_t_9[0])) == 0); - if (unlikely(!__pyx_t_7)) { + __pyx_t_11 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_11 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 556, __pyx_L1_error) + __pyx_t_12 = __pyx_f_5numpy_7ndarray_5shape_shape(((PyArrayObject *)__pyx_v_value)); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 556, __pyx_L1_error) + __pyx_t_4 = (long_acados_update_params(__pyx_v_self->capsule, __pyx_v_stage, ((double *)__pyx_t_11), (__pyx_t_12[0])) == 0); + if (unlikely(!__pyx_t_4)) { __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); - __PYX_ERR(0, 522, __pyx_L1_error) + __PYX_ERR(0, 556, __pyx_L1_error) } } #else - if ((1)); else __PYX_ERR(0, 522, __pyx_L1_error) + if ((1)); else __PYX_ERR(0, 556, __pyx_L1_error) #endif - /* "acados_template/acados_ocp_solver_pyx.pyx":521 + /* "acados_template/acados_ocp_solver_pyx.pyx":555 * * # treat parameters separately * if field_ == 'p': # <<<<<<<<<<<<<< * assert acados_solver.acados_update_params(self.capsule, stage, value.data, value.shape[0]) == 0 * else: */ - goto __pyx_L3; + goto __pyx_L4; } - /* "acados_template/acados_ocp_solver_pyx.pyx":524 + /* "acados_template/acados_ocp_solver_pyx.pyx":558 * assert acados_solver.acados_update_params(self.capsule, stage, value.data, value.shape[0]) == 0 * else: * if field_ not in constraints_fields + cost_fields + out_fields: # <<<<<<<<<<<<<< * raise Exception("AcadosOcpSolverCython.set(): {} is not a valid argument.\ - * \nPossible values are {}. Exiting.".format(field, \ + * \nPossible values are {}.".format(field, \ */ /*else*/ { - __pyx_t_5 = PyNumber_Add(__pyx_v_constraints_fields, __pyx_v_cost_fields); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 524, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __pyx_t_3 = PyNumber_Add(__pyx_t_5, __pyx_v_out_fields); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 524, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __pyx_t_7 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_t_3, Py_NE)); if (unlikely((__pyx_t_7 < 0))) __PYX_ERR(0, 524, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - if (unlikely(__pyx_t_7)) { + __pyx_t_9 = PyNumber_Add(__pyx_v_constraints_fields, __pyx_v_cost_fields); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 558, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __pyx_t_7 = PyNumber_Add(__pyx_t_9, __pyx_v_out_fields); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 558, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + __pyx_t_4 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_t_7, Py_NE)); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 558, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(__pyx_t_4)) { - /* "acados_template/acados_ocp_solver_pyx.pyx":526 + /* "acados_template/acados_ocp_solver_pyx.pyx":560 * if field_ not in constraints_fields + cost_fields + out_fields: * raise Exception("AcadosOcpSolverCython.set(): {} is not a valid argument.\ - * \nPossible values are {}. Exiting.".format(field, \ # <<<<<<<<<<<<<< + * \nPossible values are {}.".format(field, \ # <<<<<<<<<<<<<< * constraints_fields + cost_fields + out_fields + ['p'])) * */ - __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_set_is_not, __pyx_n_s_format); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 526, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); + __pyx_t_9 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_set_is_not, __pyx_n_s_format); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 560, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); - /* "acados_template/acados_ocp_solver_pyx.pyx":527 + /* "acados_template/acados_ocp_solver_pyx.pyx":561 * raise Exception("AcadosOcpSolverCython.set(): {} is not a valid argument.\ - * \nPossible values are {}. Exiting.".format(field, \ + * \nPossible values are {}.".format(field, \ * constraints_fields + cost_fields + out_fields + ['p'])) # <<<<<<<<<<<<<< * * dims = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, */ - __pyx_t_1 = PyNumber_Add(__pyx_v_constraints_fields, __pyx_v_cost_fields); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 527, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_2 = PyNumber_Add(__pyx_t_1, __pyx_v_out_fields); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 527, __pyx_L1_error) + __pyx_t_2 = PyNumber_Add(__pyx_v_constraints_fields, __pyx_v_cost_fields); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 561, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_2); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_1 = PyList_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 527, __pyx_L1_error) + __pyx_t_1 = PyNumber_Add(__pyx_t_2, __pyx_v_out_fields); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 561, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = PyList_New(1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 561, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); __Pyx_INCREF(__pyx_n_u_p); __Pyx_GIVEREF(__pyx_n_u_p); - PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_u_p); - __pyx_t_4 = PyNumber_Add(__pyx_t_2, __pyx_t_1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 527, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + PyList_SET_ITEM(__pyx_t_2, 0, __pyx_n_u_p); + __pyx_t_8 = PyNumber_Add(__pyx_t_1, __pyx_t_2); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 561, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_1 = NULL; - __pyx_t_10 = 0; - if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_5))) { - __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_5); - if (likely(__pyx_t_1)) { - PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); - __Pyx_INCREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = NULL; + __pyx_t_13 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_9))) { + __pyx_t_2 = PyMethod_GET_SELF(__pyx_t_9); + if (likely(__pyx_t_2)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_9); + __Pyx_INCREF(__pyx_t_2); __Pyx_INCREF(function); - __Pyx_DECREF_SET(__pyx_t_5, function); - __pyx_t_10 = 1; + __Pyx_DECREF_SET(__pyx_t_9, function); + __pyx_t_13 = 1; } } { - PyObject *__pyx_callargs[3] = {__pyx_t_1, __pyx_v_field, __pyx_t_4}; - __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_10, 2+__pyx_t_10); - __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 526, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + PyObject *__pyx_callargs[3] = {__pyx_t_2, __pyx_v_field, __pyx_t_8}; + __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_9, __pyx_callargs+1-__pyx_t_13, 2+__pyx_t_13); + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 560, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; } - /* "acados_template/acados_ocp_solver_pyx.pyx":525 + /* "acados_template/acados_ocp_solver_pyx.pyx":559 * else: * if field_ not in constraints_fields + cost_fields + out_fields: * raise Exception("AcadosOcpSolverCython.set(): {} is not a valid argument.\ # <<<<<<<<<<<<<< - * \nPossible values are {}. Exiting.".format(field, \ + * \nPossible values are {}.".format(field, \ * constraints_fields + cost_fields + out_fields + ['p'])) */ - __pyx_t_5 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_3); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 525, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - __Pyx_Raise(__pyx_t_5, 0, 0, 0); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __PYX_ERR(0, 525, __pyx_L1_error) + __pyx_t_9 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_7); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 559, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_Raise(__pyx_t_9, 0, 0, 0); + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + __PYX_ERR(0, 559, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":524 + /* "acados_template/acados_ocp_solver_pyx.pyx":558 * assert acados_solver.acados_update_params(self.capsule, stage, value.data, value.shape[0]) == 0 * else: * if field_ not in constraints_fields + cost_fields + out_fields: # <<<<<<<<<<<<<< * raise Exception("AcadosOcpSolverCython.set(): {} is not a valid argument.\ - * \nPossible values are {}. Exiting.".format(field, \ + * \nPossible values are {}.".format(field, \ */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":530 + /* "acados_template/acados_ocp_solver_pyx.pyx":564 * * dims = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, * self.nlp_dims, self.nlp_out, stage, field) # <<<<<<<<<<<<<< * * if value_.shape[0] != dims: */ - __pyx_t_11 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_11) && PyErr_Occurred())) __PYX_ERR(0, 530, __pyx_L1_error) + __pyx_t_14 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_14) && PyErr_Occurred())) __PYX_ERR(0, 564, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":529 + /* "acados_template/acados_ocp_solver_pyx.pyx":563 * constraints_fields + cost_fields + out_fields + ['p'])) * * dims = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, # <<<<<<<<<<<<<< * self.nlp_dims, self.nlp_out, stage, field) * */ - __pyx_t_5 = __Pyx_PyInt_From_int(ocp_nlp_dims_get_from_attr(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_11)); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 529, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __pyx_v_dims = __pyx_t_5; - __pyx_t_5 = 0; + __pyx_t_9 = __Pyx_PyInt_From_int(ocp_nlp_dims_get_from_attr(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_14)); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 563, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __pyx_v_dims = __pyx_t_9; + __pyx_t_9 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":532 + /* "acados_template/acados_ocp_solver_pyx.pyx":566 * self.nlp_dims, self.nlp_out, stage, field) * * if value_.shape[0] != dims: # <<<<<<<<<<<<<< * msg = 'AcadosOcpSolverCython.set(): mismatching dimension for field "{}" '.format(field_) * msg += 'with dimension {} (you have {})'.format(dims, value_.shape[0]) */ - __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_v_value_, __pyx_n_s_shape); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 532, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __pyx_t_3 = __Pyx_GetItemInt(__pyx_t_5, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 532, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __pyx_t_5 = PyObject_RichCompare(__pyx_t_3, __pyx_v_dims, Py_NE); __Pyx_XGOTREF(__pyx_t_5); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 532, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - __pyx_t_7 = __Pyx_PyObject_IsTrue(__pyx_t_5); if (unlikely((__pyx_t_7 < 0))) __PYX_ERR(0, 532, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - if (unlikely(__pyx_t_7)) { + __pyx_t_9 = __Pyx_PyObject_GetAttrStr(__pyx_v_value_, __pyx_n_s_shape); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 566, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __pyx_t_7 = __Pyx_GetItemInt(__pyx_t_9, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 566, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + __pyx_t_9 = PyObject_RichCompare(__pyx_t_7, __pyx_v_dims, Py_NE); __Pyx_XGOTREF(__pyx_t_9); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 566, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_t_9); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 566, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + if (unlikely(__pyx_t_4)) { - /* "acados_template/acados_ocp_solver_pyx.pyx":533 + /* "acados_template/acados_ocp_solver_pyx.pyx":567 * * if value_.shape[0] != dims: * msg = 'AcadosOcpSolverCython.set(): mismatching dimension for field "{}" '.format(field_) # <<<<<<<<<<<<<< * msg += 'with dimension {} (you have {})'.format(dims, value_.shape[0]) * raise Exception(msg) */ - __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_set_mismat, __pyx_n_s_format); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 533, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __pyx_t_4 = NULL; - __pyx_t_10 = 0; - if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_3))) { - __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_3); - if (likely(__pyx_t_4)) { - PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); - __Pyx_INCREF(__pyx_t_4); + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_set_mismat, __pyx_n_s_format); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 567, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_8 = NULL; + __pyx_t_13 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_7))) { + __pyx_t_8 = PyMethod_GET_SELF(__pyx_t_7); + if (likely(__pyx_t_8)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_7); + __Pyx_INCREF(__pyx_t_8); __Pyx_INCREF(function); - __Pyx_DECREF_SET(__pyx_t_3, function); - __pyx_t_10 = 1; + __Pyx_DECREF_SET(__pyx_t_7, function); + __pyx_t_13 = 1; } } { - PyObject *__pyx_callargs[2] = {__pyx_t_4, __pyx_v_field_}; - __pyx_t_5 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_10, 1+__pyx_t_10); - __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; - if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 533, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + PyObject *__pyx_callargs[2] = {__pyx_t_8, __pyx_v_field_}; + __pyx_t_9 = __Pyx_PyObject_FastCall(__pyx_t_7, __pyx_callargs+1-__pyx_t_13, 1+__pyx_t_13); + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 567, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; } - __pyx_v_msg = __pyx_t_5; - __pyx_t_5 = 0; + __pyx_v_msg = __pyx_t_9; + __pyx_t_9 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":534 + /* "acados_template/acados_ocp_solver_pyx.pyx":568 * if value_.shape[0] != dims: * msg = 'AcadosOcpSolverCython.set(): mismatching dimension for field "{}" '.format(field_) * msg += 'with dimension {} (you have {})'.format(dims, value_.shape[0]) # <<<<<<<<<<<<<< * raise Exception(msg) * */ - __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_with_dimension_you_have, __pyx_n_s_format); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 534, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_v_value_, __pyx_n_s_shape); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 534, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_4); - __pyx_t_1 = __Pyx_GetItemInt(__pyx_t_4, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 534, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __pyx_t_4 = NULL; - __pyx_t_10 = 0; - if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_3))) { - __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_3); - if (likely(__pyx_t_4)) { - PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); - __Pyx_INCREF(__pyx_t_4); + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_with_dimension_you_have, __pyx_n_s_format); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 568, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_value_, __pyx_n_s_shape); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 568, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_2 = __Pyx_GetItemInt(__pyx_t_8, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 568, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_t_8 = NULL; + __pyx_t_13 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_7))) { + __pyx_t_8 = PyMethod_GET_SELF(__pyx_t_7); + if (likely(__pyx_t_8)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_7); + __Pyx_INCREF(__pyx_t_8); __Pyx_INCREF(function); - __Pyx_DECREF_SET(__pyx_t_3, function); - __pyx_t_10 = 1; + __Pyx_DECREF_SET(__pyx_t_7, function); + __pyx_t_13 = 1; } } { - PyObject *__pyx_callargs[3] = {__pyx_t_4, __pyx_v_dims, __pyx_t_1}; - __pyx_t_5 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_10, 2+__pyx_t_10); - __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 534, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + PyObject *__pyx_callargs[3] = {__pyx_t_8, __pyx_v_dims, __pyx_t_2}; + __pyx_t_9 = __Pyx_PyObject_FastCall(__pyx_t_7, __pyx_callargs+1-__pyx_t_13, 2+__pyx_t_13); + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 568, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; } - __pyx_t_3 = PyNumber_InPlaceAdd(__pyx_v_msg, __pyx_t_5); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 534, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __Pyx_DECREF_SET(__pyx_v_msg, __pyx_t_3); - __pyx_t_3 = 0; + __pyx_t_7 = PyNumber_InPlaceAdd(__pyx_v_msg, __pyx_t_9); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 568, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + __Pyx_DECREF_SET(__pyx_v_msg, __pyx_t_7); + __pyx_t_7 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":535 + /* "acados_template/acados_ocp_solver_pyx.pyx":569 * msg = 'AcadosOcpSolverCython.set(): mismatching dimension for field "{}" '.format(field_) * msg += 'with dimension {} (you have {})'.format(dims, value_.shape[0]) * raise Exception(msg) # <<<<<<<<<<<<<< * * if field_ in constraints_fields: */ - __pyx_t_3 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_v_msg); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 535, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_3); - __Pyx_Raise(__pyx_t_3, 0, 0, 0); - __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; - __PYX_ERR(0, 535, __pyx_L1_error) + __pyx_t_7 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_v_msg); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 569, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_Raise(__pyx_t_7, 0, 0, 0); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __PYX_ERR(0, 569, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":532 + /* "acados_template/acados_ocp_solver_pyx.pyx":566 * self.nlp_dims, self.nlp_out, stage, field) * * if value_.shape[0] != dims: # <<<<<<<<<<<<<< @@ -26465,153 +27382,153 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":537 + /* "acados_template/acados_ocp_solver_pyx.pyx":571 * raise Exception(msg) * * if field_ in constraints_fields: # <<<<<<<<<<<<<< * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, * self.nlp_dims, self.nlp_in, stage, field, value.data) */ - __pyx_t_7 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_constraints_fields, Py_EQ)); if (unlikely((__pyx_t_7 < 0))) __PYX_ERR(0, 537, __pyx_L1_error) - if (__pyx_t_7) { + __pyx_t_4 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_constraints_fields, Py_EQ)); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 571, __pyx_L1_error) + if (__pyx_t_4) { - /* "acados_template/acados_ocp_solver_pyx.pyx":539 + /* "acados_template/acados_ocp_solver_pyx.pyx":573 * if field_ in constraints_fields: * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, * self.nlp_dims, self.nlp_in, stage, field, value.data) # <<<<<<<<<<<<<< * elif field_ in cost_fields: * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, */ - __pyx_t_12 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_12) && PyErr_Occurred())) __PYX_ERR(0, 539, __pyx_L1_error) - __pyx_t_8 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_8 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 539, __pyx_L1_error) + __pyx_t_15 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_15) && PyErr_Occurred())) __PYX_ERR(0, 573, __pyx_L1_error) + __pyx_t_11 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_11 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 573, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":538 + /* "acados_template/acados_ocp_solver_pyx.pyx":572 * * if field_ in constraints_fields: * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, # <<<<<<<<<<<<<< * self.nlp_dims, self.nlp_in, stage, field, value.data) * elif field_ in cost_fields: */ - (void)(ocp_nlp_constraints_model_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_in, __pyx_v_stage, __pyx_t_12, ((void *)__pyx_t_8))); + (void)(ocp_nlp_constraints_model_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_in, __pyx_v_stage, __pyx_t_15, ((void *)__pyx_t_11))); - /* "acados_template/acados_ocp_solver_pyx.pyx":537 + /* "acados_template/acados_ocp_solver_pyx.pyx":571 * raise Exception(msg) * * if field_ in constraints_fields: # <<<<<<<<<<<<<< * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, * self.nlp_dims, self.nlp_in, stage, field, value.data) */ - goto __pyx_L6; + goto __pyx_L7; } - /* "acados_template/acados_ocp_solver_pyx.pyx":540 + /* "acados_template/acados_ocp_solver_pyx.pyx":574 * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, * self.nlp_dims, self.nlp_in, stage, field, value.data) * elif field_ in cost_fields: # <<<<<<<<<<<<<< * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, * self.nlp_dims, self.nlp_in, stage, field, value.data) */ - __pyx_t_7 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_cost_fields, Py_EQ)); if (unlikely((__pyx_t_7 < 0))) __PYX_ERR(0, 540, __pyx_L1_error) - if (__pyx_t_7) { + __pyx_t_4 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_cost_fields, Py_EQ)); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 574, __pyx_L1_error) + if (__pyx_t_4) { - /* "acados_template/acados_ocp_solver_pyx.pyx":542 + /* "acados_template/acados_ocp_solver_pyx.pyx":576 * elif field_ in cost_fields: * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, * self.nlp_dims, self.nlp_in, stage, field, value.data) # <<<<<<<<<<<<<< * elif field_ in out_fields: * acados_solver_common.ocp_nlp_out_set(self.nlp_config, */ - __pyx_t_13 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_13) && PyErr_Occurred())) __PYX_ERR(0, 542, __pyx_L1_error) - __pyx_t_8 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_8 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 542, __pyx_L1_error) + __pyx_t_16 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_16) && PyErr_Occurred())) __PYX_ERR(0, 576, __pyx_L1_error) + __pyx_t_11 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_11 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 576, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":541 + /* "acados_template/acados_ocp_solver_pyx.pyx":575 * self.nlp_dims, self.nlp_in, stage, field, value.data) * elif field_ in cost_fields: * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, # <<<<<<<<<<<<<< * self.nlp_dims, self.nlp_in, stage, field, value.data) * elif field_ in out_fields: */ - (void)(ocp_nlp_cost_model_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_in, __pyx_v_stage, __pyx_t_13, ((void *)__pyx_t_8))); + (void)(ocp_nlp_cost_model_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_in, __pyx_v_stage, __pyx_t_16, ((void *)__pyx_t_11))); - /* "acados_template/acados_ocp_solver_pyx.pyx":540 + /* "acados_template/acados_ocp_solver_pyx.pyx":574 * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, * self.nlp_dims, self.nlp_in, stage, field, value.data) * elif field_ in cost_fields: # <<<<<<<<<<<<<< * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, * self.nlp_dims, self.nlp_in, stage, field, value.data) */ - goto __pyx_L6; + goto __pyx_L7; } - /* "acados_template/acados_ocp_solver_pyx.pyx":543 + /* "acados_template/acados_ocp_solver_pyx.pyx":577 * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, * self.nlp_dims, self.nlp_in, stage, field, value.data) * elif field_ in out_fields: # <<<<<<<<<<<<<< * acados_solver_common.ocp_nlp_out_set(self.nlp_config, * self.nlp_dims, self.nlp_out, stage, field, value.data) */ - __pyx_t_7 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_out_fields, Py_EQ)); if (unlikely((__pyx_t_7 < 0))) __PYX_ERR(0, 543, __pyx_L1_error) - if (__pyx_t_7) { + __pyx_t_4 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_out_fields, Py_EQ)); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 577, __pyx_L1_error) + if (__pyx_t_4) { - /* "acados_template/acados_ocp_solver_pyx.pyx":545 + /* "acados_template/acados_ocp_solver_pyx.pyx":579 * elif field_ in out_fields: * acados_solver_common.ocp_nlp_out_set(self.nlp_config, * self.nlp_dims, self.nlp_out, stage, field, value.data) # <<<<<<<<<<<<<< * elif field_ in mem_fields: * acados_solver_common.ocp_nlp_set(self.nlp_config, \ */ - __pyx_t_14 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_14) && PyErr_Occurred())) __PYX_ERR(0, 545, __pyx_L1_error) - __pyx_t_8 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_8 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 545, __pyx_L1_error) + __pyx_t_17 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_17) && PyErr_Occurred())) __PYX_ERR(0, 579, __pyx_L1_error) + __pyx_t_11 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_11 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 579, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":544 + /* "acados_template/acados_ocp_solver_pyx.pyx":578 * self.nlp_dims, self.nlp_in, stage, field, value.data) * elif field_ in out_fields: * acados_solver_common.ocp_nlp_out_set(self.nlp_config, # <<<<<<<<<<<<<< * self.nlp_dims, self.nlp_out, stage, field, value.data) * elif field_ in mem_fields: */ - ocp_nlp_out_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_14, ((void *)__pyx_t_8)); + ocp_nlp_out_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_17, ((void *)__pyx_t_11)); - /* "acados_template/acados_ocp_solver_pyx.pyx":543 + /* "acados_template/acados_ocp_solver_pyx.pyx":577 * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, * self.nlp_dims, self.nlp_in, stage, field, value.data) * elif field_ in out_fields: # <<<<<<<<<<<<<< * acados_solver_common.ocp_nlp_out_set(self.nlp_config, * self.nlp_dims, self.nlp_out, stage, field, value.data) */ - goto __pyx_L6; + goto __pyx_L7; } - /* "acados_template/acados_ocp_solver_pyx.pyx":546 + /* "acados_template/acados_ocp_solver_pyx.pyx":580 * acados_solver_common.ocp_nlp_out_set(self.nlp_config, * self.nlp_dims, self.nlp_out, stage, field, value.data) * elif field_ in mem_fields: # <<<<<<<<<<<<<< * acados_solver_common.ocp_nlp_set(self.nlp_config, \ * self.nlp_solver, stage, field, value.data) */ - __pyx_t_7 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_mem_fields, Py_EQ)); if (unlikely((__pyx_t_7 < 0))) __PYX_ERR(0, 546, __pyx_L1_error) - if (__pyx_t_7) { + __pyx_t_4 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_mem_fields, Py_EQ)); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 580, __pyx_L1_error) + if (__pyx_t_4) { - /* "acados_template/acados_ocp_solver_pyx.pyx":548 + /* "acados_template/acados_ocp_solver_pyx.pyx":582 * elif field_ in mem_fields: * acados_solver_common.ocp_nlp_set(self.nlp_config, \ * self.nlp_solver, stage, field, value.data) # <<<<<<<<<<<<<< * - * + * if field_ == 'z': */ - __pyx_t_15 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_15) && PyErr_Occurred())) __PYX_ERR(0, 548, __pyx_L1_error) - __pyx_t_8 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_8 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 548, __pyx_L1_error) + __pyx_t_18 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_18) && PyErr_Occurred())) __PYX_ERR(0, 582, __pyx_L1_error) + __pyx_t_11 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_11 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 582, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":547 + /* "acados_template/acados_ocp_solver_pyx.pyx":581 * self.nlp_dims, self.nlp_out, stage, field, value.data) * elif field_ in mem_fields: * acados_solver_common.ocp_nlp_set(self.nlp_config, \ # <<<<<<<<<<<<<< * self.nlp_solver, stage, field, value.data) * */ - ocp_nlp_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_v_stage, __pyx_t_15, ((void *)__pyx_t_8)); + ocp_nlp_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_v_stage, __pyx_t_18, ((void *)__pyx_t_11)); - /* "acados_template/acados_ocp_solver_pyx.pyx":546 + /* "acados_template/acados_ocp_solver_pyx.pyx":580 * acados_solver_common.ocp_nlp_out_set(self.nlp_config, * self.nlp_dims, self.nlp_out, stage, field, value.data) * elif field_ in mem_fields: # <<<<<<<<<<<<<< @@ -26619,11 +27536,70 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS * self.nlp_solver, stage, field, value.data) */ } - __pyx_L6:; - } - __pyx_L3:; + __pyx_L7:; - /* "acados_template/acados_ocp_solver_pyx.pyx":492 + /* "acados_template/acados_ocp_solver_pyx.pyx":584 + * self.nlp_solver, stage, field, value.data) + * + * if field_ == 'z': # <<<<<<<<<<<<<< + * field = 'z_guess'.encode('utf-8') + * acados_solver_common.ocp_nlp_set(self.nlp_config, \ + */ + __pyx_t_4 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_z, Py_EQ)); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 584, __pyx_L1_error) + if (__pyx_t_4) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":585 + * + * if field_ == 'z': + * field = 'z_guess'.encode('utf-8') # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_set(self.nlp_config, \ + * self.nlp_solver, stage, field, value.data) + */ + __Pyx_INCREF(__pyx_n_b_z_guess); + __Pyx_DECREF_SET(__pyx_v_field, __pyx_n_b_z_guess); + + /* "acados_template/acados_ocp_solver_pyx.pyx":587 + * field = 'z_guess'.encode('utf-8') + * acados_solver_common.ocp_nlp_set(self.nlp_config, \ + * self.nlp_solver, stage, field, value.data) # <<<<<<<<<<<<<< + * return + * + */ + __pyx_t_18 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_18) && PyErr_Occurred())) __PYX_ERR(0, 587, __pyx_L1_error) + __pyx_t_11 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_11 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 587, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":586 + * if field_ == 'z': + * field = 'z_guess'.encode('utf-8') + * acados_solver_common.ocp_nlp_set(self.nlp_config, \ # <<<<<<<<<<<<<< + * self.nlp_solver, stage, field, value.data) + * return + */ + ocp_nlp_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_v_stage, __pyx_t_18, ((void *)__pyx_t_11)); + + /* "acados_template/acados_ocp_solver_pyx.pyx":584 + * self.nlp_solver, stage, field, value.data) + * + * if field_ == 'z': # <<<<<<<<<<<<<< + * field = 'z_guess'.encode('utf-8') + * acados_solver_common.ocp_nlp_set(self.nlp_config, \ + */ + } + } + __pyx_L4:; + + /* "acados_template/acados_ocp_solver_pyx.pyx":588 + * acados_solver_common.ocp_nlp_set(self.nlp_config, \ + * self.nlp_solver, stage, field, value.data) + * return # <<<<<<<<<<<<<< + * + * def cost_set(self, int stage, str field_, value_): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":524 * * # Note: this function should not be used anymore, better use cost_set, constraints_set * def set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< @@ -26632,14 +27608,12 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ /* function exit code */ - __pyx_r = Py_None; __Pyx_INCREF(Py_None); - goto __pyx_L0; __pyx_L1_error:; __Pyx_XDECREF(__pyx_t_1); __Pyx_XDECREF(__pyx_t_2); - __Pyx_XDECREF(__pyx_t_3); - __Pyx_XDECREF(__pyx_t_4); - __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_XDECREF(__pyx_t_9); { PyObject *__pyx_type, *__pyx_value, *__pyx_tb; __Pyx_PyThreadState_declare __Pyx_PyThreadState_assign @@ -26665,8 +27639,8 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":551 - * +/* "acados_template/acados_ocp_solver_pyx.pyx":590 + * return * * def cost_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< * """ @@ -26674,16 +27648,16 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ /* Python wrapper */ -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37cost_set(PyObject *__pyx_v_self, +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41cost_set(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else PyObject *__pyx_args, PyObject *__pyx_kwds #endif ); /*proto*/ -PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36cost_set, "\n Set numerical data in the cost module of the solver.\n\n :param stage: integer corresponding to shooting node\n :param field: string, e.g. 'yref', 'W', 'ext_cost_num_hess'\n :param value: of appropriate size\n "); -static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37cost_set = {"cost_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37cost_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36cost_set}; -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37cost_set(PyObject *__pyx_v_self, +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40cost_set, "\n Set numerical data in the cost module of the solver.\n\n :param stage: integer corresponding to shooting node\n :param field: string, e.g. 'yref', 'W', 'ext_cost_num_hess'\n :param value: of appropriate size\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41cost_set = {"cost_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41cost_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40cost_set}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41cost_set(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else @@ -26722,26 +27696,26 @@ PyObject *__pyx_args, PyObject *__pyx_kwds switch (__pyx_nargs) { case 0: if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_stage)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 551, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 590, __pyx_L3_error) else goto __pyx_L5_argtuple_error; CYTHON_FALLTHROUGH; case 1: if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field_2)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 551, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 590, __pyx_L3_error) else { - __Pyx_RaiseArgtupleInvalid("cost_set", 1, 3, 3, 1); __PYX_ERR(0, 551, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("cost_set", 1, 3, 3, 1); __PYX_ERR(0, 590, __pyx_L3_error) } CYTHON_FALLTHROUGH; case 2: if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_value)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 551, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 590, __pyx_L3_error) else { - __Pyx_RaiseArgtupleInvalid("cost_set", 1, 3, 3, 2); __PYX_ERR(0, 551, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("cost_set", 1, 3, 3, 2); __PYX_ERR(0, 590, __pyx_L3_error) } } if (unlikely(kw_args > 0)) { const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "cost_set") < 0)) __PYX_ERR(0, 551, __pyx_L3_error) + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "cost_set") < 0)) __PYX_ERR(0, 590, __pyx_L3_error) } } else if (unlikely(__pyx_nargs != 3)) { goto __pyx_L5_argtuple_error; @@ -26750,20 +27724,20 @@ PyObject *__pyx_args, PyObject *__pyx_kwds values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); } - __pyx_v_stage = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_stage == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 551, __pyx_L3_error) + __pyx_v_stage = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_stage == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 590, __pyx_L3_error) __pyx_v_field_ = ((PyObject*)values[1]); __pyx_v_value_ = values[2]; } goto __pyx_L4_argument_unpacking_done; __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("cost_set", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 551, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("cost_set", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 590, __pyx_L3_error) __pyx_L3_error:; __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.cost_set", __pyx_clineno, __pyx_lineno, __pyx_filename); __Pyx_RefNannyFinishContext(); return NULL; __pyx_L4_argument_unpacking_done:; - if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 551, __pyx_L1_error) - __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36cost_set(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_stage, __pyx_v_field_, __pyx_v_value_); + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 590, __pyx_L1_error) + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40cost_set(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_stage, __pyx_v_field_, __pyx_v_value_); /* function exit code */ goto __pyx_L0; @@ -26774,7 +27748,7 @@ PyObject *__pyx_args, PyObject *__pyx_kwds return __pyx_r; } -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36cost_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_) { +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40cost_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_) { PyObject *__pyx_v_field = NULL; int __pyx_v_dims[2]; __Pyx_memviewslice __pyx_v_value = { 0, 0, { 0 }, { 0 }, { 0 } }; @@ -26782,16 +27756,16 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_r = NULL; __Pyx_RefNannyDeclarations PyObject *__pyx_t_1 = NULL; - char const *__pyx_t_2; - Py_ssize_t __pyx_t_3; + PyObject *__pyx_t_2 = NULL; + int __pyx_t_3; int __pyx_t_4; - PyObject *__pyx_t_5 = NULL; - PyObject *__pyx_t_6 = NULL; - PyObject *__pyx_t_7 = NULL; - int __pyx_t_8; - __Pyx_memviewslice __pyx_t_9 = { 0, 0, { 0 }, { 0 }, { 0 } }; + Py_ssize_t __pyx_t_5; + Py_UCS4 __pyx_t_6; + char const *__pyx_t_7; + PyObject *__pyx_t_8 = NULL; + PyObject *__pyx_t_9 = NULL; int __pyx_t_10; - Py_UCS4 __pyx_t_11; + __Pyx_memviewslice __pyx_t_11 = { 0, 0, { 0 }, { 0 }, { 0 } }; char const *__pyx_t_12; Py_ssize_t __pyx_t_13; Py_ssize_t __pyx_t_14; @@ -26800,184 +27774,246 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS int __pyx_clineno = 0; __Pyx_RefNannySetupContext("cost_set", 0); - /* "acados_template/acados_ocp_solver_pyx.pyx":559 + /* "acados_template/acados_ocp_solver_pyx.pyx":598 * :param value: of appropriate size * """ + * if not isinstance(value_, np.ndarray): # <<<<<<<<<<<<<< + * raise Exception(f"cost_set: value must be numpy array, got {type(value_)}.") + * field = field_.encode('utf-8') + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 598, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_ndarray); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 598, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_3 = PyObject_IsInstance(__pyx_v_value_, __pyx_t_2); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(0, 598, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_4 = (!__pyx_t_3); + if (unlikely(__pyx_t_4)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":599 + * """ + * if not isinstance(value_, np.ndarray): + * raise Exception(f"cost_set: value must be numpy array, got {type(value_)}.") # <<<<<<<<<<<<<< + * field = field_.encode('utf-8') + * + */ + __pyx_t_2 = PyTuple_New(3); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 599, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_5 = 0; + __pyx_t_6 = 127; + __Pyx_INCREF(__pyx_kp_u_cost_set_value_must_be_numpy_arr); + __pyx_t_5 += 41; + __Pyx_GIVEREF(__pyx_kp_u_cost_set_value_must_be_numpy_arr); + PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_kp_u_cost_set_value_must_be_numpy_arr); + __pyx_t_1 = __Pyx_PyObject_FormatSimple(((PyObject *)Py_TYPE(__pyx_v_value_)), __pyx_empty_unicode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 599, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_2, 1, __pyx_t_1); + __pyx_t_1 = 0; + __Pyx_INCREF(__pyx_kp_u__2); + __pyx_t_5 += 1; + __Pyx_GIVEREF(__pyx_kp_u__2); + PyTuple_SET_ITEM(__pyx_t_2, 2, __pyx_kp_u__2); + __pyx_t_1 = __Pyx_PyUnicode_Join(__pyx_t_2, 3, __pyx_t_5, __pyx_t_6); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 599, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 599, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 599, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":598 + * :param value: of appropriate size + * """ + * if not isinstance(value_, np.ndarray): # <<<<<<<<<<<<<< + * raise Exception(f"cost_set: value must be numpy array, got {type(value_)}.") + * field = field_.encode('utf-8') + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":600 + * if not isinstance(value_, np.ndarray): + * raise Exception(f"cost_set: value must be numpy array, got {type(value_)}.") * field = field_.encode('utf-8') # <<<<<<<<<<<<<< * * cdef int dims[2] */ if (unlikely(__pyx_v_field_ == Py_None)) { PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "encode"); - __PYX_ERR(0, 559, __pyx_L1_error) + __PYX_ERR(0, 600, __pyx_L1_error) } - __pyx_t_1 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 559, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_v_field = __pyx_t_1; - __pyx_t_1 = 0; + __pyx_t_2 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 600, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_v_field = __pyx_t_2; + __pyx_t_2 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":563 + /* "acados_template/acados_ocp_solver_pyx.pyx":604 * cdef int dims[2] * acados_solver_common.ocp_nlp_cost_dims_get_from_attr(self.nlp_config, \ * self.nlp_dims, self.nlp_out, stage, field, &dims[0]) # <<<<<<<<<<<<<< * * cdef double[::1,:] value */ - __pyx_t_2 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_2) && PyErr_Occurred())) __PYX_ERR(0, 563, __pyx_L1_error) + __pyx_t_7 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 604, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":562 + /* "acados_template/acados_ocp_solver_pyx.pyx":603 * * cdef int dims[2] * acados_solver_common.ocp_nlp_cost_dims_get_from_attr(self.nlp_config, \ # <<<<<<<<<<<<<< * self.nlp_dims, self.nlp_out, stage, field, &dims[0]) * */ - ocp_nlp_cost_dims_get_from_attr(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_2, (&(__pyx_v_dims[0]))); + ocp_nlp_cost_dims_get_from_attr(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_7, (&(__pyx_v_dims[0]))); - /* "acados_template/acados_ocp_solver_pyx.pyx":567 + /* "acados_template/acados_ocp_solver_pyx.pyx":608 * cdef double[::1,:] value * * value_shape = value_.shape # <<<<<<<<<<<<<< * if len(value_shape) == 1: * value_shape = (value_shape[0], 0) */ - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_value_, __pyx_n_s_shape); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 567, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_v_value_shape = __pyx_t_1; - __pyx_t_1 = 0; + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_value_, __pyx_n_s_shape); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 608, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_v_value_shape = __pyx_t_2; + __pyx_t_2 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":568 + /* "acados_template/acados_ocp_solver_pyx.pyx":609 * * value_shape = value_.shape * if len(value_shape) == 1: # <<<<<<<<<<<<<< * value_shape = (value_shape[0], 0) * value = np.asfortranarray(value_[None,:]) */ - __pyx_t_3 = PyObject_Length(__pyx_v_value_shape); if (unlikely(__pyx_t_3 == ((Py_ssize_t)-1))) __PYX_ERR(0, 568, __pyx_L1_error) - __pyx_t_4 = (__pyx_t_3 == 1); + __pyx_t_5 = PyObject_Length(__pyx_v_value_shape); if (unlikely(__pyx_t_5 == ((Py_ssize_t)-1))) __PYX_ERR(0, 609, __pyx_L1_error) + __pyx_t_4 = (__pyx_t_5 == 1); if (__pyx_t_4) { - /* "acados_template/acados_ocp_solver_pyx.pyx":569 + /* "acados_template/acados_ocp_solver_pyx.pyx":610 * value_shape = value_.shape * if len(value_shape) == 1: * value_shape = (value_shape[0], 0) # <<<<<<<<<<<<<< * value = np.asfortranarray(value_[None,:]) * */ - __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_value_shape, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 569, __pyx_L1_error) + __pyx_t_2 = __Pyx_GetItemInt(__pyx_v_value_shape, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 610, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_1 = PyTuple_New(2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 610, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); - __pyx_t_5 = PyTuple_New(2); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 569, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_GIVEREF(__pyx_t_1); - PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_t_1); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_t_2); __Pyx_INCREF(__pyx_int_0); __Pyx_GIVEREF(__pyx_int_0); - PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_int_0); + PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_int_0); + __pyx_t_2 = 0; + __Pyx_DECREF_SET(__pyx_v_value_shape, __pyx_t_1); __pyx_t_1 = 0; - __Pyx_DECREF_SET(__pyx_v_value_shape, __pyx_t_5); - __pyx_t_5 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":570 + /* "acados_template/acados_ocp_solver_pyx.pyx":611 * if len(value_shape) == 1: * value_shape = (value_shape[0], 0) * value = np.asfortranarray(value_[None,:]) # <<<<<<<<<<<<<< * * elif len(value_shape) == 2: */ - __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 570, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_asfortranarray); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 570, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_6); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_1 = __Pyx_PyObject_GetItem(__pyx_v_value_, __pyx_tuple__26); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 570, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_7 = NULL; - __pyx_t_8 = 0; - if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_6))) { - __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_6); - if (likely(__pyx_t_7)) { - PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_6); - __Pyx_INCREF(__pyx_t_7); + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_np); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 611, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_asfortranarray); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 611, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_v_value_, __pyx_tuple__28); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 611, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_9 = NULL; + __pyx_t_10 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_8))) { + __pyx_t_9 = PyMethod_GET_SELF(__pyx_t_8); + if (likely(__pyx_t_9)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_8); + __Pyx_INCREF(__pyx_t_9); __Pyx_INCREF(function); - __Pyx_DECREF_SET(__pyx_t_6, function); - __pyx_t_8 = 1; + __Pyx_DECREF_SET(__pyx_t_8, function); + __pyx_t_10 = 1; } } { - PyObject *__pyx_callargs[2] = {__pyx_t_7, __pyx_t_1}; - __pyx_t_5 = __Pyx_PyObject_FastCall(__pyx_t_6, __pyx_callargs+1-__pyx_t_8, 1+__pyx_t_8); - __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 570, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + PyObject *__pyx_callargs[2] = {__pyx_t_9, __pyx_t_2}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_8, __pyx_callargs+1-__pyx_t_10, 1+__pyx_t_10); + __Pyx_XDECREF(__pyx_t_9); __pyx_t_9 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 611, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; } - __pyx_t_9 = __Pyx_PyObject_to_MemoryviewSlice_dcd__double(__pyx_t_5, PyBUF_WRITABLE); if (unlikely(!__pyx_t_9.memview)) __PYX_ERR(0, 570, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __pyx_v_value = __pyx_t_9; - __pyx_t_9.memview = NULL; - __pyx_t_9.data = NULL; + __pyx_t_11 = __Pyx_PyObject_to_MemoryviewSlice_dcd__double(__pyx_t_1, PyBUF_WRITABLE); if (unlikely(!__pyx_t_11.memview)) __PYX_ERR(0, 611, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_value = __pyx_t_11; + __pyx_t_11.memview = NULL; + __pyx_t_11.data = NULL; - /* "acados_template/acados_ocp_solver_pyx.pyx":568 + /* "acados_template/acados_ocp_solver_pyx.pyx":609 * * value_shape = value_.shape * if len(value_shape) == 1: # <<<<<<<<<<<<<< * value_shape = (value_shape[0], 0) * value = np.asfortranarray(value_[None,:]) */ - goto __pyx_L3; + goto __pyx_L4; } - /* "acados_template/acados_ocp_solver_pyx.pyx":572 + /* "acados_template/acados_ocp_solver_pyx.pyx":613 * value = np.asfortranarray(value_[None,:]) * * elif len(value_shape) == 2: # <<<<<<<<<<<<<< * # Get elements in column major order * value = np.asfortranarray(value_) */ - __pyx_t_3 = PyObject_Length(__pyx_v_value_shape); if (unlikely(__pyx_t_3 == ((Py_ssize_t)-1))) __PYX_ERR(0, 572, __pyx_L1_error) - __pyx_t_4 = (__pyx_t_3 == 2); + __pyx_t_5 = PyObject_Length(__pyx_v_value_shape); if (unlikely(__pyx_t_5 == ((Py_ssize_t)-1))) __PYX_ERR(0, 613, __pyx_L1_error) + __pyx_t_4 = (__pyx_t_5 == 2); if (__pyx_t_4) { - /* "acados_template/acados_ocp_solver_pyx.pyx":574 + /* "acados_template/acados_ocp_solver_pyx.pyx":615 * elif len(value_shape) == 2: * # Get elements in column major order * value = np.asfortranarray(value_) # <<<<<<<<<<<<<< * * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: */ - __Pyx_GetModuleGlobalName(__pyx_t_6, __pyx_n_s_np); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 574, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_6); - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_6, __pyx_n_s_asfortranarray); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 574, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; - __pyx_t_6 = NULL; - __pyx_t_8 = 0; - if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_1))) { - __pyx_t_6 = PyMethod_GET_SELF(__pyx_t_1); - if (likely(__pyx_t_6)) { - PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); - __Pyx_INCREF(__pyx_t_6); + __Pyx_GetModuleGlobalName(__pyx_t_8, __pyx_n_s_np); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 615, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_8, __pyx_n_s_asfortranarray); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 615, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_t_8 = NULL; + __pyx_t_10 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_8 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_8)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_8); __Pyx_INCREF(function); - __Pyx_DECREF_SET(__pyx_t_1, function); - __pyx_t_8 = 1; + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_10 = 1; } } { - PyObject *__pyx_callargs[2] = {__pyx_t_6, __pyx_v_value_}; - __pyx_t_5 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_8, 1+__pyx_t_8); - __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; - if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 574, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + PyObject *__pyx_callargs[2] = {__pyx_t_8, __pyx_v_value_}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_10, 1+__pyx_t_10); + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 615, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; } - __pyx_t_9 = __Pyx_PyObject_to_MemoryviewSlice_dcd__double(__pyx_t_5, PyBUF_WRITABLE); if (unlikely(!__pyx_t_9.memview)) __PYX_ERR(0, 574, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __pyx_v_value = __pyx_t_9; - __pyx_t_9.memview = NULL; - __pyx_t_9.data = NULL; + __pyx_t_11 = __Pyx_PyObject_to_MemoryviewSlice_dcd__double(__pyx_t_1, PyBUF_WRITABLE); if (unlikely(!__pyx_t_11.memview)) __PYX_ERR(0, 615, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_value = __pyx_t_11; + __pyx_t_11.memview = NULL; + __pyx_t_11.data = NULL; - /* "acados_template/acados_ocp_solver_pyx.pyx":572 + /* "acados_template/acados_ocp_solver_pyx.pyx":613 * value = np.asfortranarray(value_[None,:]) * * elif len(value_shape) == 2: # <<<<<<<<<<<<<< @@ -26985,128 +28021,128 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS * value = np.asfortranarray(value_) */ } - __pyx_L3:; + __pyx_L4:; - /* "acados_template/acados_ocp_solver_pyx.pyx":576 + /* "acados_template/acados_ocp_solver_pyx.pyx":617 * value = np.asfortranarray(value_) * * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: # <<<<<<<<<<<<<< * raise Exception('AcadosOcpSolverCython.cost_set(): mismatching dimension' + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') */ - __pyx_t_5 = __Pyx_GetItemInt(__pyx_v_value_shape, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 576, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __pyx_t_1 = __Pyx_PyInt_From_int((__pyx_v_dims[0])); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 576, __pyx_L1_error) + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_value_shape, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 617, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); - __pyx_t_6 = PyObject_RichCompare(__pyx_t_5, __pyx_t_1, Py_NE); __Pyx_XGOTREF(__pyx_t_6); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 576, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_2 = __Pyx_PyInt_From_int((__pyx_v_dims[0])); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_8 = PyObject_RichCompare(__pyx_t_1, __pyx_t_2, Py_NE); __Pyx_XGOTREF(__pyx_t_8); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 617, __pyx_L1_error) __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_10 = __Pyx_PyObject_IsTrue(__pyx_t_6); if (unlikely((__pyx_t_10 < 0))) __PYX_ERR(0, 576, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; - if (!__pyx_t_10) { + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_3 = __Pyx_PyObject_IsTrue(__pyx_t_8); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(0, 617, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + if (!__pyx_t_3) { } else { - __pyx_t_4 = __pyx_t_10; - goto __pyx_L5_bool_binop_done; + __pyx_t_4 = __pyx_t_3; + goto __pyx_L6_bool_binop_done; } - __pyx_t_6 = __Pyx_GetItemInt(__pyx_v_value_shape, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 576, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_6); - __pyx_t_1 = __Pyx_PyInt_From_int((__pyx_v_dims[1])); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 576, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_5 = PyObject_RichCompare(__pyx_t_6, __pyx_t_1, Py_NE); __Pyx_XGOTREF(__pyx_t_5); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 576, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __pyx_t_8 = __Pyx_GetItemInt(__pyx_v_value_shape, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_2 = __Pyx_PyInt_From_int((__pyx_v_dims[1])); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_1 = PyObject_RichCompare(__pyx_t_8, __pyx_t_2, Py_NE); __Pyx_XGOTREF(__pyx_t_1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 617, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_3 = __Pyx_PyObject_IsTrue(__pyx_t_1); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(0, 617, __pyx_L1_error) __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_10 = __Pyx_PyObject_IsTrue(__pyx_t_5); if (unlikely((__pyx_t_10 < 0))) __PYX_ERR(0, 576, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __pyx_t_4 = __pyx_t_10; - __pyx_L5_bool_binop_done:; + __pyx_t_4 = __pyx_t_3; + __pyx_L6_bool_binop_done:; if (unlikely(__pyx_t_4)) { - /* "acados_template/acados_ocp_solver_pyx.pyx":578 + /* "acados_template/acados_ocp_solver_pyx.pyx":619 * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: * raise Exception('AcadosOcpSolverCython.cost_set(): mismatching dimension' + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') # <<<<<<<<<<<<<< * * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, \ */ - __pyx_t_5 = PyTuple_New(9); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 578, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __pyx_t_3 = 0; - __pyx_t_11 = 127; + __pyx_t_1 = PyTuple_New(9); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 619, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = 0; + __pyx_t_6 = 127; __Pyx_INCREF(__pyx_kp_u_for_field); - __pyx_t_3 += 12; + __pyx_t_5 += 12; __Pyx_GIVEREF(__pyx_kp_u_for_field); - PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_kp_u_for_field); - __pyx_t_1 = __Pyx_PyUnicode_Unicode(__pyx_v_field_); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 578, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_11 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) > __pyx_t_11) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) : __pyx_t_11; - __pyx_t_3 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); - __Pyx_GIVEREF(__pyx_t_1); - PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_1); - __pyx_t_1 = 0; + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_kp_u_for_field); + __pyx_t_2 = __Pyx_PyUnicode_Unicode(__pyx_v_field_); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 619, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_t_2); + __pyx_t_2 = 0; __Pyx_INCREF(__pyx_kp_u_at_stage); - __pyx_t_3 += 11; + __pyx_t_5 += 11; __Pyx_GIVEREF(__pyx_kp_u_at_stage); - PyTuple_SET_ITEM(__pyx_t_5, 2, __pyx_kp_u_at_stage); - __pyx_t_1 = __Pyx_PyUnicode_From_int(__pyx_v_stage, 0, ' ', 'd'); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 578, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_3 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); - __Pyx_GIVEREF(__pyx_t_1); - PyTuple_SET_ITEM(__pyx_t_5, 3, __pyx_t_1); - __pyx_t_1 = 0; + PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_kp_u_at_stage); + __pyx_t_2 = __Pyx_PyUnicode_From_int(__pyx_v_stage, 0, ' ', 'd'); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 619, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_1, 3, __pyx_t_2); + __pyx_t_2 = 0; __Pyx_INCREF(__pyx_kp_u_with_dimension); - __pyx_t_3 += 16; + __pyx_t_5 += 16; __Pyx_GIVEREF(__pyx_kp_u_with_dimension); - PyTuple_SET_ITEM(__pyx_t_5, 4, __pyx_kp_u_with_dimension); - __pyx_t_1 = __Pyx_carray_to_py_int(__pyx_v_dims, 2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 578, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_6 = __Pyx_PySequence_Tuple(__pyx_t_1); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 578, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_6); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_1 = __Pyx_PyObject_FormatSimple(__pyx_t_6, __pyx_empty_unicode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 578, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; - __pyx_t_11 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) > __pyx_t_11) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) : __pyx_t_11; - __pyx_t_3 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); - __Pyx_GIVEREF(__pyx_t_1); - PyTuple_SET_ITEM(__pyx_t_5, 5, __pyx_t_1); - __pyx_t_1 = 0; + PyTuple_SET_ITEM(__pyx_t_1, 4, __pyx_kp_u_with_dimension); + __pyx_t_2 = __Pyx_carray_to_py_int(__pyx_v_dims, 2); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 619, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_8 = __Pyx_PySequence_Tuple(__pyx_t_2); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 619, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_FormatSimple(__pyx_t_8, __pyx_empty_unicode); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 619, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_1, 5, __pyx_t_2); + __pyx_t_2 = 0; __Pyx_INCREF(__pyx_kp_u_you_have); - __pyx_t_3 += 11; + __pyx_t_5 += 11; __Pyx_GIVEREF(__pyx_kp_u_you_have); - PyTuple_SET_ITEM(__pyx_t_5, 6, __pyx_kp_u_you_have); - __pyx_t_1 = __Pyx_PyObject_FormatSimple(__pyx_v_value_shape, __pyx_empty_unicode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 578, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_11 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) > __pyx_t_11) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) : __pyx_t_11; - __pyx_t_3 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); - __Pyx_GIVEREF(__pyx_t_1); - PyTuple_SET_ITEM(__pyx_t_5, 7, __pyx_t_1); - __pyx_t_1 = 0; + PyTuple_SET_ITEM(__pyx_t_1, 6, __pyx_kp_u_you_have); + __pyx_t_2 = __Pyx_PyObject_FormatSimple(__pyx_v_value_shape, __pyx_empty_unicode); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 619, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_1, 7, __pyx_t_2); + __pyx_t_2 = 0; __Pyx_INCREF(__pyx_kp_u__7); - __pyx_t_3 += 1; + __pyx_t_5 += 1; __Pyx_GIVEREF(__pyx_kp_u__7); - PyTuple_SET_ITEM(__pyx_t_5, 8, __pyx_kp_u__7); - __pyx_t_1 = __Pyx_PyUnicode_Join(__pyx_t_5, 9, __pyx_t_3, __pyx_t_11); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 578, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + PyTuple_SET_ITEM(__pyx_t_1, 8, __pyx_kp_u__7); + __pyx_t_2 = __Pyx_PyUnicode_Join(__pyx_t_1, 9, __pyx_t_5, __pyx_t_6); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 619, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":577 + /* "acados_template/acados_ocp_solver_pyx.pyx":618 * * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: * raise Exception('AcadosOcpSolverCython.cost_set(): mismatching dimension' + # <<<<<<<<<<<<<< * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') * */ - __pyx_t_5 = __Pyx_PyUnicode_Concat(__pyx_kp_u_AcadosOcpSolverCython_cost_set_m, __pyx_t_1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 577, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_1 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_5); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 577, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyUnicode_Concat(__pyx_kp_u_AcadosOcpSolverCython_cost_set_m, __pyx_t_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 618, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 618, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __PYX_ERR(0, 577, __pyx_L1_error) + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 618, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":576 + /* "acados_template/acados_ocp_solver_pyx.pyx":617 * value = np.asfortranarray(value_) * * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: # <<<<<<<<<<<<<< @@ -27115,32 +28151,32 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":581 + /* "acados_template/acados_ocp_solver_pyx.pyx":622 * * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, \ * self.nlp_dims, self.nlp_in, stage, field, &value[0][0]) # <<<<<<<<<<<<<< * * */ - __pyx_t_12 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_12) && PyErr_Occurred())) __PYX_ERR(0, 581, __pyx_L1_error) - if (unlikely(!__pyx_v_value.memview)) { __Pyx_RaiseUnboundLocalError("value"); __PYX_ERR(0, 581, __pyx_L1_error) } + __pyx_t_12 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_12) && PyErr_Occurred())) __PYX_ERR(0, 622, __pyx_L1_error) + if (unlikely(!__pyx_v_value.memview)) { __Pyx_RaiseUnboundLocalError("value"); __PYX_ERR(0, 622, __pyx_L1_error) } __pyx_t_13 = 0; __pyx_t_14 = 0; - __pyx_t_8 = -1; + __pyx_t_10 = -1; if (__pyx_t_13 < 0) { __pyx_t_13 += __pyx_v_value.shape[0]; - if (unlikely(__pyx_t_13 < 0)) __pyx_t_8 = 0; - } else if (unlikely(__pyx_t_13 >= __pyx_v_value.shape[0])) __pyx_t_8 = 0; + if (unlikely(__pyx_t_13 < 0)) __pyx_t_10 = 0; + } else if (unlikely(__pyx_t_13 >= __pyx_v_value.shape[0])) __pyx_t_10 = 0; if (__pyx_t_14 < 0) { __pyx_t_14 += __pyx_v_value.shape[1]; - if (unlikely(__pyx_t_14 < 0)) __pyx_t_8 = 1; - } else if (unlikely(__pyx_t_14 >= __pyx_v_value.shape[1])) __pyx_t_8 = 1; - if (unlikely(__pyx_t_8 != -1)) { - __Pyx_RaiseBufferIndexError(__pyx_t_8); - __PYX_ERR(0, 581, __pyx_L1_error) + if (unlikely(__pyx_t_14 < 0)) __pyx_t_10 = 1; + } else if (unlikely(__pyx_t_14 >= __pyx_v_value.shape[1])) __pyx_t_10 = 1; + if (unlikely(__pyx_t_10 != -1)) { + __Pyx_RaiseBufferIndexError(__pyx_t_10); + __PYX_ERR(0, 622, __pyx_L1_error) } - /* "acados_template/acados_ocp_solver_pyx.pyx":580 + /* "acados_template/acados_ocp_solver_pyx.pyx":621 * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') * * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, \ # <<<<<<<<<<<<<< @@ -27149,8 +28185,8 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ (void)(ocp_nlp_cost_model_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_in, __pyx_v_stage, __pyx_t_12, ((void *)(&(*((double *) ( /* dim=1 */ (( /* dim=0 */ ((char *) (((double *) __pyx_v_value.data) + __pyx_t_13)) ) + __pyx_t_14 * __pyx_v_value.strides[1]) ))))))); - /* "acados_template/acados_ocp_solver_pyx.pyx":551 - * + /* "acados_template/acados_ocp_solver_pyx.pyx":590 + * return * * def cost_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< * """ @@ -27162,10 +28198,10 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS goto __pyx_L0; __pyx_L1_error:; __Pyx_XDECREF(__pyx_t_1); - __Pyx_XDECREF(__pyx_t_5); - __Pyx_XDECREF(__pyx_t_6); - __Pyx_XDECREF(__pyx_t_7); - __PYX_XCLEAR_MEMVIEW(&__pyx_t_9, 1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_XDECREF(__pyx_t_9); + __PYX_XCLEAR_MEMVIEW(&__pyx_t_11, 1); __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.cost_set", __pyx_clineno, __pyx_lineno, __pyx_filename); __pyx_r = NULL; __pyx_L0:; @@ -27177,7 +28213,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":584 +/* "acados_template/acados_ocp_solver_pyx.pyx":625 * * * def constraints_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< @@ -27186,16 +28222,16 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ /* Python wrapper */ -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39constraints_set(PyObject *__pyx_v_self, +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43constraints_set(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else PyObject *__pyx_args, PyObject *__pyx_kwds #endif ); /*proto*/ -PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38constraints_set, "\n Set numerical data in the constraint module of the solver.\n\n :param stage: integer corresponding to shooting node\n :param field: string in ['lbx', 'ubx', 'lbu', 'ubu', 'lg', 'ug', 'lh', 'uh', 'uphi', 'C', 'D']\n :param value: of appropriate size\n "); -static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39constraints_set = {"constraints_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39constraints_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38constraints_set}; -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39constraints_set(PyObject *__pyx_v_self, +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42constraints_set, "\n Set numerical data in the constraint module of the solver.\n\n :param stage: integer corresponding to shooting node\n :param field: string in ['lbx', 'ubx', 'lbu', 'ubu', 'lg', 'ug', 'lh', 'uh', 'uphi', 'C', 'D']\n :param value: of appropriate size\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43constraints_set = {"constraints_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43constraints_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42constraints_set}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43constraints_set(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else @@ -27234,26 +28270,26 @@ PyObject *__pyx_args, PyObject *__pyx_kwds switch (__pyx_nargs) { case 0: if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_stage)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 584, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 625, __pyx_L3_error) else goto __pyx_L5_argtuple_error; CYTHON_FALLTHROUGH; case 1: if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field_2)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 584, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 625, __pyx_L3_error) else { - __Pyx_RaiseArgtupleInvalid("constraints_set", 1, 3, 3, 1); __PYX_ERR(0, 584, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("constraints_set", 1, 3, 3, 1); __PYX_ERR(0, 625, __pyx_L3_error) } CYTHON_FALLTHROUGH; case 2: if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_value)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 584, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 625, __pyx_L3_error) else { - __Pyx_RaiseArgtupleInvalid("constraints_set", 1, 3, 3, 2); __PYX_ERR(0, 584, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("constraints_set", 1, 3, 3, 2); __PYX_ERR(0, 625, __pyx_L3_error) } } if (unlikely(kw_args > 0)) { const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "constraints_set") < 0)) __PYX_ERR(0, 584, __pyx_L3_error) + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "constraints_set") < 0)) __PYX_ERR(0, 625, __pyx_L3_error) } } else if (unlikely(__pyx_nargs != 3)) { goto __pyx_L5_argtuple_error; @@ -27262,20 +28298,20 @@ PyObject *__pyx_args, PyObject *__pyx_kwds values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); } - __pyx_v_stage = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_stage == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 584, __pyx_L3_error) + __pyx_v_stage = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_stage == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 625, __pyx_L3_error) __pyx_v_field_ = ((PyObject*)values[1]); __pyx_v_value_ = values[2]; } goto __pyx_L4_argument_unpacking_done; __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("constraints_set", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 584, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("constraints_set", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 625, __pyx_L3_error) __pyx_L3_error:; __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.constraints_set", __pyx_clineno, __pyx_lineno, __pyx_filename); __Pyx_RefNannyFinishContext(); return NULL; __pyx_L4_argument_unpacking_done:; - if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 584, __pyx_L1_error) - __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38constraints_set(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_stage, __pyx_v_field_, __pyx_v_value_); + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 625, __pyx_L1_error) + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42constraints_set(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_stage, __pyx_v_field_, __pyx_v_value_); /* function exit code */ goto __pyx_L0; @@ -27286,7 +28322,7 @@ PyObject *__pyx_args, PyObject *__pyx_kwds return __pyx_r; } -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38constraints_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_) { +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42constraints_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_) { PyObject *__pyx_v_field = NULL; int __pyx_v_dims[2]; __Pyx_memviewslice __pyx_v_value = { 0, 0, { 0 }, { 0 }, { 0 } }; @@ -27294,16 +28330,16 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_r = NULL; __Pyx_RefNannyDeclarations PyObject *__pyx_t_1 = NULL; - char const *__pyx_t_2; - Py_ssize_t __pyx_t_3; + PyObject *__pyx_t_2 = NULL; + int __pyx_t_3; int __pyx_t_4; - PyObject *__pyx_t_5 = NULL; - PyObject *__pyx_t_6 = NULL; - PyObject *__pyx_t_7 = NULL; - int __pyx_t_8; - __Pyx_memviewslice __pyx_t_9 = { 0, 0, { 0 }, { 0 }, { 0 } }; + Py_ssize_t __pyx_t_5; + Py_UCS4 __pyx_t_6; + char const *__pyx_t_7; + PyObject *__pyx_t_8 = NULL; + PyObject *__pyx_t_9 = NULL; int __pyx_t_10; - Py_UCS4 __pyx_t_11; + __Pyx_memviewslice __pyx_t_11 = { 0, 0, { 0 }, { 0 }, { 0 } }; char const *__pyx_t_12; Py_ssize_t __pyx_t_13; Py_ssize_t __pyx_t_14; @@ -27312,184 +28348,246 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS int __pyx_clineno = 0; __Pyx_RefNannySetupContext("constraints_set", 0); - /* "acados_template/acados_ocp_solver_pyx.pyx":592 + /* "acados_template/acados_ocp_solver_pyx.pyx":633 * :param value: of appropriate size * """ + * if not isinstance(value_, np.ndarray): # <<<<<<<<<<<<<< + * raise Exception(f"constraints_set: value must be numpy array, got {type(value_)}.") + * + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 633, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_ndarray); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 633, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_3 = PyObject_IsInstance(__pyx_v_value_, __pyx_t_2); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(0, 633, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_4 = (!__pyx_t_3); + if (unlikely(__pyx_t_4)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":634 + * """ + * if not isinstance(value_, np.ndarray): + * raise Exception(f"constraints_set: value must be numpy array, got {type(value_)}.") # <<<<<<<<<<<<<< + * + * field = field_.encode('utf-8') + */ + __pyx_t_2 = PyTuple_New(3); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 634, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_5 = 0; + __pyx_t_6 = 127; + __Pyx_INCREF(__pyx_kp_u_constraints_set_value_must_be_nu); + __pyx_t_5 += 48; + __Pyx_GIVEREF(__pyx_kp_u_constraints_set_value_must_be_nu); + PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_kp_u_constraints_set_value_must_be_nu); + __pyx_t_1 = __Pyx_PyObject_FormatSimple(((PyObject *)Py_TYPE(__pyx_v_value_)), __pyx_empty_unicode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 634, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_2, 1, __pyx_t_1); + __pyx_t_1 = 0; + __Pyx_INCREF(__pyx_kp_u__2); + __pyx_t_5 += 1; + __Pyx_GIVEREF(__pyx_kp_u__2); + PyTuple_SET_ITEM(__pyx_t_2, 2, __pyx_kp_u__2); + __pyx_t_1 = __Pyx_PyUnicode_Join(__pyx_t_2, 3, __pyx_t_5, __pyx_t_6); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 634, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 634, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 634, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":633 + * :param value: of appropriate size + * """ + * if not isinstance(value_, np.ndarray): # <<<<<<<<<<<<<< + * raise Exception(f"constraints_set: value must be numpy array, got {type(value_)}.") + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":636 + * raise Exception(f"constraints_set: value must be numpy array, got {type(value_)}.") + * * field = field_.encode('utf-8') # <<<<<<<<<<<<<< * * cdef int dims[2] */ if (unlikely(__pyx_v_field_ == Py_None)) { PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "encode"); - __PYX_ERR(0, 592, __pyx_L1_error) + __PYX_ERR(0, 636, __pyx_L1_error) } - __pyx_t_1 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 592, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_v_field = __pyx_t_1; - __pyx_t_1 = 0; + __pyx_t_2 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 636, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_v_field = __pyx_t_2; + __pyx_t_2 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":596 + /* "acados_template/acados_ocp_solver_pyx.pyx":640 * cdef int dims[2] * acados_solver_common.ocp_nlp_constraint_dims_get_from_attr(self.nlp_config, \ * self.nlp_dims, self.nlp_out, stage, field, &dims[0]) # <<<<<<<<<<<<<< * * cdef double[::1,:] value */ - __pyx_t_2 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_2) && PyErr_Occurred())) __PYX_ERR(0, 596, __pyx_L1_error) + __pyx_t_7 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 640, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":595 + /* "acados_template/acados_ocp_solver_pyx.pyx":639 * * cdef int dims[2] * acados_solver_common.ocp_nlp_constraint_dims_get_from_attr(self.nlp_config, \ # <<<<<<<<<<<<<< * self.nlp_dims, self.nlp_out, stage, field, &dims[0]) * */ - ocp_nlp_constraint_dims_get_from_attr(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_2, (&(__pyx_v_dims[0]))); + ocp_nlp_constraint_dims_get_from_attr(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_7, (&(__pyx_v_dims[0]))); - /* "acados_template/acados_ocp_solver_pyx.pyx":600 + /* "acados_template/acados_ocp_solver_pyx.pyx":644 * cdef double[::1,:] value * * value_shape = value_.shape # <<<<<<<<<<<<<< * if len(value_shape) == 1: * value_shape = (value_shape[0], 0) */ - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_value_, __pyx_n_s_shape); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 600, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_v_value_shape = __pyx_t_1; - __pyx_t_1 = 0; + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_value_, __pyx_n_s_shape); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 644, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_v_value_shape = __pyx_t_2; + __pyx_t_2 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":601 + /* "acados_template/acados_ocp_solver_pyx.pyx":645 * * value_shape = value_.shape * if len(value_shape) == 1: # <<<<<<<<<<<<<< * value_shape = (value_shape[0], 0) * value = np.asfortranarray(value_[None,:]) */ - __pyx_t_3 = PyObject_Length(__pyx_v_value_shape); if (unlikely(__pyx_t_3 == ((Py_ssize_t)-1))) __PYX_ERR(0, 601, __pyx_L1_error) - __pyx_t_4 = (__pyx_t_3 == 1); + __pyx_t_5 = PyObject_Length(__pyx_v_value_shape); if (unlikely(__pyx_t_5 == ((Py_ssize_t)-1))) __PYX_ERR(0, 645, __pyx_L1_error) + __pyx_t_4 = (__pyx_t_5 == 1); if (__pyx_t_4) { - /* "acados_template/acados_ocp_solver_pyx.pyx":602 + /* "acados_template/acados_ocp_solver_pyx.pyx":646 * value_shape = value_.shape * if len(value_shape) == 1: * value_shape = (value_shape[0], 0) # <<<<<<<<<<<<<< * value = np.asfortranarray(value_[None,:]) * */ - __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_value_shape, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 602, __pyx_L1_error) + __pyx_t_2 = __Pyx_GetItemInt(__pyx_v_value_shape, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 646, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_1 = PyTuple_New(2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 646, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); - __pyx_t_5 = PyTuple_New(2); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 602, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_GIVEREF(__pyx_t_1); - PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_t_1); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_t_2); __Pyx_INCREF(__pyx_int_0); __Pyx_GIVEREF(__pyx_int_0); - PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_int_0); + PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_int_0); + __pyx_t_2 = 0; + __Pyx_DECREF_SET(__pyx_v_value_shape, __pyx_t_1); __pyx_t_1 = 0; - __Pyx_DECREF_SET(__pyx_v_value_shape, __pyx_t_5); - __pyx_t_5 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":603 + /* "acados_template/acados_ocp_solver_pyx.pyx":647 * if len(value_shape) == 1: * value_shape = (value_shape[0], 0) * value = np.asfortranarray(value_[None,:]) # <<<<<<<<<<<<<< * * elif len(value_shape) == 2: */ - __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 603, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_asfortranarray); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 603, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_6); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_1 = __Pyx_PyObject_GetItem(__pyx_v_value_, __pyx_tuple__26); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 603, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_7 = NULL; - __pyx_t_8 = 0; - if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_6))) { - __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_6); - if (likely(__pyx_t_7)) { - PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_6); - __Pyx_INCREF(__pyx_t_7); + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_np); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 647, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_asfortranarray); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 647, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_v_value_, __pyx_tuple__28); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 647, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_9 = NULL; + __pyx_t_10 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_8))) { + __pyx_t_9 = PyMethod_GET_SELF(__pyx_t_8); + if (likely(__pyx_t_9)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_8); + __Pyx_INCREF(__pyx_t_9); __Pyx_INCREF(function); - __Pyx_DECREF_SET(__pyx_t_6, function); - __pyx_t_8 = 1; + __Pyx_DECREF_SET(__pyx_t_8, function); + __pyx_t_10 = 1; } } { - PyObject *__pyx_callargs[2] = {__pyx_t_7, __pyx_t_1}; - __pyx_t_5 = __Pyx_PyObject_FastCall(__pyx_t_6, __pyx_callargs+1-__pyx_t_8, 1+__pyx_t_8); - __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 603, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + PyObject *__pyx_callargs[2] = {__pyx_t_9, __pyx_t_2}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_8, __pyx_callargs+1-__pyx_t_10, 1+__pyx_t_10); + __Pyx_XDECREF(__pyx_t_9); __pyx_t_9 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 647, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; } - __pyx_t_9 = __Pyx_PyObject_to_MemoryviewSlice_dcd__double(__pyx_t_5, PyBUF_WRITABLE); if (unlikely(!__pyx_t_9.memview)) __PYX_ERR(0, 603, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __pyx_v_value = __pyx_t_9; - __pyx_t_9.memview = NULL; - __pyx_t_9.data = NULL; + __pyx_t_11 = __Pyx_PyObject_to_MemoryviewSlice_dcd__double(__pyx_t_1, PyBUF_WRITABLE); if (unlikely(!__pyx_t_11.memview)) __PYX_ERR(0, 647, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_value = __pyx_t_11; + __pyx_t_11.memview = NULL; + __pyx_t_11.data = NULL; - /* "acados_template/acados_ocp_solver_pyx.pyx":601 + /* "acados_template/acados_ocp_solver_pyx.pyx":645 * * value_shape = value_.shape * if len(value_shape) == 1: # <<<<<<<<<<<<<< * value_shape = (value_shape[0], 0) * value = np.asfortranarray(value_[None,:]) */ - goto __pyx_L3; + goto __pyx_L4; } - /* "acados_template/acados_ocp_solver_pyx.pyx":605 + /* "acados_template/acados_ocp_solver_pyx.pyx":649 * value = np.asfortranarray(value_[None,:]) * * elif len(value_shape) == 2: # <<<<<<<<<<<<<< * # Get elements in column major order * value = np.asfortranarray(value_) */ - __pyx_t_3 = PyObject_Length(__pyx_v_value_shape); if (unlikely(__pyx_t_3 == ((Py_ssize_t)-1))) __PYX_ERR(0, 605, __pyx_L1_error) - __pyx_t_4 = (__pyx_t_3 == 2); + __pyx_t_5 = PyObject_Length(__pyx_v_value_shape); if (unlikely(__pyx_t_5 == ((Py_ssize_t)-1))) __PYX_ERR(0, 649, __pyx_L1_error) + __pyx_t_4 = (__pyx_t_5 == 2); if (__pyx_t_4) { - /* "acados_template/acados_ocp_solver_pyx.pyx":607 + /* "acados_template/acados_ocp_solver_pyx.pyx":651 * elif len(value_shape) == 2: * # Get elements in column major order * value = np.asfortranarray(value_) # <<<<<<<<<<<<<< * - * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: + * if value_shape != tuple(dims): */ - __Pyx_GetModuleGlobalName(__pyx_t_6, __pyx_n_s_np); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 607, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_6); - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_6, __pyx_n_s_asfortranarray); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 607, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; - __pyx_t_6 = NULL; - __pyx_t_8 = 0; - if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_1))) { - __pyx_t_6 = PyMethod_GET_SELF(__pyx_t_1); - if (likely(__pyx_t_6)) { - PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); - __Pyx_INCREF(__pyx_t_6); + __Pyx_GetModuleGlobalName(__pyx_t_8, __pyx_n_s_np); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 651, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_8, __pyx_n_s_asfortranarray); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 651, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_t_8 = NULL; + __pyx_t_10 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_8 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_8)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_8); __Pyx_INCREF(function); - __Pyx_DECREF_SET(__pyx_t_1, function); - __pyx_t_8 = 1; + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_10 = 1; } } { - PyObject *__pyx_callargs[2] = {__pyx_t_6, __pyx_v_value_}; - __pyx_t_5 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_8, 1+__pyx_t_8); - __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; - if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 607, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + PyObject *__pyx_callargs[2] = {__pyx_t_8, __pyx_v_value_}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_10, 1+__pyx_t_10); + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 651, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; } - __pyx_t_9 = __Pyx_PyObject_to_MemoryviewSlice_dcd__double(__pyx_t_5, PyBUF_WRITABLE); if (unlikely(!__pyx_t_9.memview)) __PYX_ERR(0, 607, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __pyx_v_value = __pyx_t_9; - __pyx_t_9.memview = NULL; - __pyx_t_9.data = NULL; + __pyx_t_11 = __Pyx_PyObject_to_MemoryviewSlice_dcd__double(__pyx_t_1, PyBUF_WRITABLE); if (unlikely(!__pyx_t_11.memview)) __PYX_ERR(0, 651, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_value = __pyx_t_11; + __pyx_t_11.memview = NULL; + __pyx_t_11.data = NULL; - /* "acados_template/acados_ocp_solver_pyx.pyx":605 + /* "acados_template/acados_ocp_solver_pyx.pyx":649 * value = np.asfortranarray(value_[None,:]) * * elif len(value_shape) == 2: # <<<<<<<<<<<<<< @@ -27497,162 +28595,146 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS * value = np.asfortranarray(value_) */ } - __pyx_L3:; + __pyx_L4:; - /* "acados_template/acados_ocp_solver_pyx.pyx":609 + /* "acados_template/acados_ocp_solver_pyx.pyx":653 * value = np.asfortranarray(value_) * - * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: # <<<<<<<<<<<<<< + * if value_shape != tuple(dims): # <<<<<<<<<<<<<< * raise Exception(f'AcadosOcpSolverCython.constraints_set(): mismatching dimension' + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') */ - __pyx_t_5 = __Pyx_GetItemInt(__pyx_v_value_shape, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 609, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __pyx_t_1 = __Pyx_PyInt_From_int((__pyx_v_dims[0])); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 609, __pyx_L1_error) + __pyx_t_1 = __Pyx_carray_to_py_int(__pyx_v_dims, 2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 653, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); - __pyx_t_6 = PyObject_RichCompare(__pyx_t_5, __pyx_t_1, Py_NE); __Pyx_XGOTREF(__pyx_t_6); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 609, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_2 = __Pyx_PySequence_Tuple(__pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 653, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_10 = __Pyx_PyObject_IsTrue(__pyx_t_6); if (unlikely((__pyx_t_10 < 0))) __PYX_ERR(0, 609, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; - if (!__pyx_t_10) { - } else { - __pyx_t_4 = __pyx_t_10; - goto __pyx_L5_bool_binop_done; - } - __pyx_t_6 = __Pyx_GetItemInt(__pyx_v_value_shape, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 609, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_6); - __pyx_t_1 = __Pyx_PyInt_From_int((__pyx_v_dims[1])); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 609, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_5 = PyObject_RichCompare(__pyx_t_6, __pyx_t_1, Py_NE); __Pyx_XGOTREF(__pyx_t_5); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 609, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __pyx_t_1 = PyObject_RichCompare(__pyx_v_value_shape, __pyx_t_2, Py_NE); __Pyx_XGOTREF(__pyx_t_1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 653, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_t_1); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 653, __pyx_L1_error) __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_10 = __Pyx_PyObject_IsTrue(__pyx_t_5); if (unlikely((__pyx_t_10 < 0))) __PYX_ERR(0, 609, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __pyx_t_4 = __pyx_t_10; - __pyx_L5_bool_binop_done:; if (unlikely(__pyx_t_4)) { - /* "acados_template/acados_ocp_solver_pyx.pyx":611 - * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: + /* "acados_template/acados_ocp_solver_pyx.pyx":655 + * if value_shape != tuple(dims): * raise Exception(f'AcadosOcpSolverCython.constraints_set(): mismatching dimension' + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') # <<<<<<<<<<<<<< * * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, \ */ - __pyx_t_5 = PyTuple_New(9); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 611, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __pyx_t_3 = 0; - __pyx_t_11 = 127; + __pyx_t_1 = PyTuple_New(9); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 655, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = 0; + __pyx_t_6 = 127; __Pyx_INCREF(__pyx_kp_u_for_field); - __pyx_t_3 += 12; + __pyx_t_5 += 12; __Pyx_GIVEREF(__pyx_kp_u_for_field); - PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_kp_u_for_field); - __pyx_t_1 = __Pyx_PyUnicode_Unicode(__pyx_v_field_); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 611, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_11 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) > __pyx_t_11) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) : __pyx_t_11; - __pyx_t_3 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); - __Pyx_GIVEREF(__pyx_t_1); - PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_1); - __pyx_t_1 = 0; + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_kp_u_for_field); + __pyx_t_2 = __Pyx_PyUnicode_Unicode(__pyx_v_field_); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 655, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_t_2); + __pyx_t_2 = 0; __Pyx_INCREF(__pyx_kp_u_at_stage); - __pyx_t_3 += 11; + __pyx_t_5 += 11; __Pyx_GIVEREF(__pyx_kp_u_at_stage); - PyTuple_SET_ITEM(__pyx_t_5, 2, __pyx_kp_u_at_stage); - __pyx_t_1 = __Pyx_PyUnicode_From_int(__pyx_v_stage, 0, ' ', 'd'); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 611, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_3 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); - __Pyx_GIVEREF(__pyx_t_1); - PyTuple_SET_ITEM(__pyx_t_5, 3, __pyx_t_1); - __pyx_t_1 = 0; + PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_kp_u_at_stage); + __pyx_t_2 = __Pyx_PyUnicode_From_int(__pyx_v_stage, 0, ' ', 'd'); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 655, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_1, 3, __pyx_t_2); + __pyx_t_2 = 0; __Pyx_INCREF(__pyx_kp_u_with_dimension); - __pyx_t_3 += 16; + __pyx_t_5 += 16; __Pyx_GIVEREF(__pyx_kp_u_with_dimension); - PyTuple_SET_ITEM(__pyx_t_5, 4, __pyx_kp_u_with_dimension); - __pyx_t_1 = __Pyx_carray_to_py_int(__pyx_v_dims, 2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 611, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_6 = __Pyx_PySequence_Tuple(__pyx_t_1); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 611, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_6); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_1 = __Pyx_PyObject_FormatSimple(__pyx_t_6, __pyx_empty_unicode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 611, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; - __pyx_t_11 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) > __pyx_t_11) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) : __pyx_t_11; - __pyx_t_3 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); - __Pyx_GIVEREF(__pyx_t_1); - PyTuple_SET_ITEM(__pyx_t_5, 5, __pyx_t_1); - __pyx_t_1 = 0; + PyTuple_SET_ITEM(__pyx_t_1, 4, __pyx_kp_u_with_dimension); + __pyx_t_2 = __Pyx_carray_to_py_int(__pyx_v_dims, 2); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 655, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_8 = __Pyx_PySequence_Tuple(__pyx_t_2); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 655, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_FormatSimple(__pyx_t_8, __pyx_empty_unicode); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 655, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_1, 5, __pyx_t_2); + __pyx_t_2 = 0; __Pyx_INCREF(__pyx_kp_u_you_have); - __pyx_t_3 += 11; + __pyx_t_5 += 11; __Pyx_GIVEREF(__pyx_kp_u_you_have); - PyTuple_SET_ITEM(__pyx_t_5, 6, __pyx_kp_u_you_have); - __pyx_t_1 = __Pyx_PyObject_FormatSimple(__pyx_v_value_shape, __pyx_empty_unicode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 611, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __pyx_t_11 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) > __pyx_t_11) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) : __pyx_t_11; - __pyx_t_3 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); - __Pyx_GIVEREF(__pyx_t_1); - PyTuple_SET_ITEM(__pyx_t_5, 7, __pyx_t_1); - __pyx_t_1 = 0; + PyTuple_SET_ITEM(__pyx_t_1, 6, __pyx_kp_u_you_have); + __pyx_t_2 = __Pyx_PyObject_FormatSimple(__pyx_v_value_shape, __pyx_empty_unicode); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 655, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_1, 7, __pyx_t_2); + __pyx_t_2 = 0; __Pyx_INCREF(__pyx_kp_u__7); - __pyx_t_3 += 1; + __pyx_t_5 += 1; __Pyx_GIVEREF(__pyx_kp_u__7); - PyTuple_SET_ITEM(__pyx_t_5, 8, __pyx_kp_u__7); - __pyx_t_1 = __Pyx_PyUnicode_Join(__pyx_t_5, 9, __pyx_t_3, __pyx_t_11); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 611, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_1); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + PyTuple_SET_ITEM(__pyx_t_1, 8, __pyx_kp_u__7); + __pyx_t_2 = __Pyx_PyUnicode_Join(__pyx_t_1, 9, __pyx_t_5, __pyx_t_6); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 655, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":610 + /* "acados_template/acados_ocp_solver_pyx.pyx":654 * - * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: + * if value_shape != tuple(dims): * raise Exception(f'AcadosOcpSolverCython.constraints_set(): mismatching dimension' + # <<<<<<<<<<<<<< * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') * */ - __pyx_t_5 = __Pyx_PyUnicode_Concat(__pyx_kp_u_AcadosOcpSolverCython_constraint, __pyx_t_1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 610, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_5); - __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_1 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_5); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 610, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyUnicode_Concat(__pyx_kp_u_AcadosOcpSolverCython_constraint, __pyx_t_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 654, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); - __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 654, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __PYX_ERR(0, 610, __pyx_L1_error) + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 654, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":609 + /* "acados_template/acados_ocp_solver_pyx.pyx":653 * value = np.asfortranarray(value_) * - * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: # <<<<<<<<<<<<<< + * if value_shape != tuple(dims): # <<<<<<<<<<<<<< * raise Exception(f'AcadosOcpSolverCython.constraints_set(): mismatching dimension' + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":614 + /* "acados_template/acados_ocp_solver_pyx.pyx":658 * * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, \ * self.nlp_dims, self.nlp_in, stage, field, &value[0][0]) # <<<<<<<<<<<<<< * * return */ - __pyx_t_12 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_12) && PyErr_Occurred())) __PYX_ERR(0, 614, __pyx_L1_error) - if (unlikely(!__pyx_v_value.memview)) { __Pyx_RaiseUnboundLocalError("value"); __PYX_ERR(0, 614, __pyx_L1_error) } + __pyx_t_12 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_12) && PyErr_Occurred())) __PYX_ERR(0, 658, __pyx_L1_error) + if (unlikely(!__pyx_v_value.memview)) { __Pyx_RaiseUnboundLocalError("value"); __PYX_ERR(0, 658, __pyx_L1_error) } __pyx_t_13 = 0; __pyx_t_14 = 0; - __pyx_t_8 = -1; + __pyx_t_10 = -1; if (__pyx_t_13 < 0) { __pyx_t_13 += __pyx_v_value.shape[0]; - if (unlikely(__pyx_t_13 < 0)) __pyx_t_8 = 0; - } else if (unlikely(__pyx_t_13 >= __pyx_v_value.shape[0])) __pyx_t_8 = 0; + if (unlikely(__pyx_t_13 < 0)) __pyx_t_10 = 0; + } else if (unlikely(__pyx_t_13 >= __pyx_v_value.shape[0])) __pyx_t_10 = 0; if (__pyx_t_14 < 0) { __pyx_t_14 += __pyx_v_value.shape[1]; - if (unlikely(__pyx_t_14 < 0)) __pyx_t_8 = 1; - } else if (unlikely(__pyx_t_14 >= __pyx_v_value.shape[1])) __pyx_t_8 = 1; - if (unlikely(__pyx_t_8 != -1)) { - __Pyx_RaiseBufferIndexError(__pyx_t_8); - __PYX_ERR(0, 614, __pyx_L1_error) + if (unlikely(__pyx_t_14 < 0)) __pyx_t_10 = 1; + } else if (unlikely(__pyx_t_14 >= __pyx_v_value.shape[1])) __pyx_t_10 = 1; + if (unlikely(__pyx_t_10 != -1)) { + __Pyx_RaiseBufferIndexError(__pyx_t_10); + __PYX_ERR(0, 658, __pyx_L1_error) } - /* "acados_template/acados_ocp_solver_pyx.pyx":613 + /* "acados_template/acados_ocp_solver_pyx.pyx":657 * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') * * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, \ # <<<<<<<<<<<<<< @@ -27661,7 +28743,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ (void)(ocp_nlp_constraints_model_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_in, __pyx_v_stage, __pyx_t_12, ((void *)(&(*((double *) ( /* dim=1 */ (( /* dim=0 */ ((char *) (((double *) __pyx_v_value.data) + __pyx_t_13)) ) + __pyx_t_14 * __pyx_v_value.strides[1]) ))))))); - /* "acados_template/acados_ocp_solver_pyx.pyx":616 + /* "acados_template/acados_ocp_solver_pyx.pyx":660 * self.nlp_dims, self.nlp_in, stage, field, &value[0][0]) * * return # <<<<<<<<<<<<<< @@ -27672,7 +28754,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_r = Py_None; __Pyx_INCREF(Py_None); goto __pyx_L0; - /* "acados_template/acados_ocp_solver_pyx.pyx":584 + /* "acados_template/acados_ocp_solver_pyx.pyx":625 * * * def constraints_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< @@ -27683,10 +28765,10 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS /* function exit code */ __pyx_L1_error:; __Pyx_XDECREF(__pyx_t_1); - __Pyx_XDECREF(__pyx_t_5); - __Pyx_XDECREF(__pyx_t_6); - __Pyx_XDECREF(__pyx_t_7); - __PYX_XCLEAR_MEMVIEW(&__pyx_t_9, 1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_XDECREF(__pyx_t_9); + __PYX_XCLEAR_MEMVIEW(&__pyx_t_11, 1); __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.constraints_set", __pyx_clineno, __pyx_lineno, __pyx_filename); __pyx_r = NULL; __pyx_L0:; @@ -27698,25 +28780,25 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":619 +/* "acados_template/acados_ocp_solver_pyx.pyx":663 * * - * def dynamics_get(self, int stage, str field_): # <<<<<<<<<<<<<< + * def get_from_qp_in(self, int stage, str field_): # <<<<<<<<<<<<<< * """ * Get numerical data from the dynamics module of the solver: */ /* Python wrapper */ -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41dynamics_get(PyObject *__pyx_v_self, +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_45get_from_qp_in(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else PyObject *__pyx_args, PyObject *__pyx_kwds #endif ); /*proto*/ -PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40dynamics_get, "\n Get numerical data from the dynamics module of the solver:\n\n :param stage: integer corresponding to shooting node\n :param field: string, e.g. 'A'\n "); -static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41dynamics_get = {"dynamics_get", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41dynamics_get, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40dynamics_get}; -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41dynamics_get(PyObject *__pyx_v_self, +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_44get_from_qp_in, "\n Get numerical data from the dynamics module of the solver:\n\n :param stage: integer corresponding to shooting node\n :param field: string, e.g. 'A'\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_45get_from_qp_in = {"get_from_qp_in", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_45get_from_qp_in, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_44get_from_qp_in}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_45get_from_qp_in(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else @@ -27734,7 +28816,7 @@ PyObject *__pyx_args, PyObject *__pyx_kwds int __pyx_clineno = 0; PyObject *__pyx_r = 0; __Pyx_RefNannyDeclarations - __Pyx_RefNannySetupContext("dynamics_get (wrapper)", 0); + __Pyx_RefNannySetupContext("get_from_qp_in (wrapper)", 0); { PyObject **__pyx_pyargnames[] = {&__pyx_n_s_stage,&__pyx_n_s_field_2,0}; PyObject* values[2] = {0,0}; @@ -27752,19 +28834,19 @@ PyObject *__pyx_args, PyObject *__pyx_kwds switch (__pyx_nargs) { case 0: if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_stage)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 619, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 663, __pyx_L3_error) else goto __pyx_L5_argtuple_error; CYTHON_FALLTHROUGH; case 1: if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field_2)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 619, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 663, __pyx_L3_error) else { - __Pyx_RaiseArgtupleInvalid("dynamics_get", 1, 2, 2, 1); __PYX_ERR(0, 619, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("get_from_qp_in", 1, 2, 2, 1); __PYX_ERR(0, 663, __pyx_L3_error) } } if (unlikely(kw_args > 0)) { const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "dynamics_get") < 0)) __PYX_ERR(0, 619, __pyx_L3_error) + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "get_from_qp_in") < 0)) __PYX_ERR(0, 663, __pyx_L3_error) } } else if (unlikely(__pyx_nargs != 2)) { goto __pyx_L5_argtuple_error; @@ -27772,19 +28854,19 @@ PyObject *__pyx_args, PyObject *__pyx_kwds values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); } - __pyx_v_stage = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_stage == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 619, __pyx_L3_error) + __pyx_v_stage = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_stage == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 663, __pyx_L3_error) __pyx_v_field_ = ((PyObject*)values[1]); } goto __pyx_L4_argument_unpacking_done; __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("dynamics_get", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 619, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("get_from_qp_in", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 663, __pyx_L3_error) __pyx_L3_error:; - __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.dynamics_get", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.get_from_qp_in", __pyx_clineno, __pyx_lineno, __pyx_filename); __Pyx_RefNannyFinishContext(); return NULL; __pyx_L4_argument_unpacking_done:; - if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 619, __pyx_L1_error) - __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40dynamics_get(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_stage, __pyx_v_field_); + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 663, __pyx_L1_error) + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_44get_from_qp_in(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_stage, __pyx_v_field_); /* function exit code */ goto __pyx_L0; @@ -27795,7 +28877,7 @@ PyObject *__pyx_args, PyObject *__pyx_kwds return __pyx_r; } -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40dynamics_get(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_) { +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_44get_from_qp_in(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_) { PyObject *__pyx_v_field = NULL; int __pyx_v_dims[2]; PyArrayObject *__pyx_v_out = 0; @@ -27814,13 +28896,13 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS int __pyx_lineno = 0; const char *__pyx_filename = NULL; int __pyx_clineno = 0; - __Pyx_RefNannySetupContext("dynamics_get", 0); + __Pyx_RefNannySetupContext("get_from_qp_in", 0); __pyx_pybuffer_out.pybuffer.buf = NULL; __pyx_pybuffer_out.refcount = 0; __pyx_pybuffernd_out.data = NULL; __pyx_pybuffernd_out.rcbuffer = &__pyx_pybuffer_out; - /* "acados_template/acados_ocp_solver_pyx.pyx":626 + /* "acados_template/acados_ocp_solver_pyx.pyx":670 * :param field: string, e.g. 'A' * """ * field = field_.encode('utf-8') # <<<<<<<<<<<<<< @@ -27829,40 +28911,40 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ if (unlikely(__pyx_v_field_ == Py_None)) { PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "encode"); - __PYX_ERR(0, 626, __pyx_L1_error) + __PYX_ERR(0, 670, __pyx_L1_error) } - __pyx_t_1 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 626, __pyx_L1_error) + __pyx_t_1 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 670, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __pyx_v_field = __pyx_t_1; __pyx_t_1 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":630 + /* "acados_template/acados_ocp_solver_pyx.pyx":674 * # get dims * cdef int[2] dims - * acados_solver_common.ocp_nlp_dynamics_dims_get_from_attr(self.nlp_config, self.nlp_dims, self.nlp_out, stage, field, &dims[0]) # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_qp_dims_get_from_attr(self.nlp_config, self.nlp_dims, self.nlp_out, stage, field, &dims[0]) # <<<<<<<<<<<<<< * * # create output data */ - __pyx_t_2 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_2) && PyErr_Occurred())) __PYX_ERR(0, 630, __pyx_L1_error) - ocp_nlp_dynamics_dims_get_from_attr(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_2, (&(__pyx_v_dims[0]))); + __pyx_t_2 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_2) && PyErr_Occurred())) __PYX_ERR(0, 674, __pyx_L1_error) + ocp_nlp_qp_dims_get_from_attr(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_2, (&(__pyx_v_dims[0]))); - /* "acados_template/acados_ocp_solver_pyx.pyx":633 + /* "acados_template/acados_ocp_solver_pyx.pyx":677 * * # create output data * cdef cnp.ndarray[cnp.float64_t, ndim=2] out = np.zeros((dims[0], dims[1]), order='F') # <<<<<<<<<<<<<< * * # call getter */ - __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 633, __pyx_L1_error) + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 677, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); - __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_zeros); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 633, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_zeros); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 677, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_3); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __pyx_t_1 = __Pyx_PyInt_From_int((__pyx_v_dims[0])); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 633, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyInt_From_int((__pyx_v_dims[0])); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 677, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); - __pyx_t_4 = __Pyx_PyInt_From_int((__pyx_v_dims[1])); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 633, __pyx_L1_error) + __pyx_t_4 = __Pyx_PyInt_From_int((__pyx_v_dims[1])); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 677, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); - __pyx_t_5 = PyTuple_New(2); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 633, __pyx_L1_error) + __pyx_t_5 = PyTuple_New(2); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 677, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_5); __Pyx_GIVEREF(__pyx_t_1); PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_t_1); @@ -27870,26 +28952,26 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_4); __pyx_t_1 = 0; __pyx_t_4 = 0; - __pyx_t_4 = PyTuple_New(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 633, __pyx_L1_error) + __pyx_t_4 = PyTuple_New(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 677, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); __Pyx_GIVEREF(__pyx_t_5); PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_5); __pyx_t_5 = 0; - __pyx_t_5 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 633, __pyx_L1_error) + __pyx_t_5 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 677, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_5); - if (PyDict_SetItem(__pyx_t_5, __pyx_n_s_order, __pyx_n_u_F) < 0) __PYX_ERR(0, 633, __pyx_L1_error) - __pyx_t_1 = __Pyx_PyObject_Call(__pyx_t_3, __pyx_t_4, __pyx_t_5); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 633, __pyx_L1_error) + if (PyDict_SetItem(__pyx_t_5, __pyx_n_s_order, __pyx_n_u_F) < 0) __PYX_ERR(0, 677, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_Call(__pyx_t_3, __pyx_t_4, __pyx_t_5); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 677, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - if (!(likely(((__pyx_t_1) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_1, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 633, __pyx_L1_error) + if (!(likely(((__pyx_t_1) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_1, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 677, __pyx_L1_error) __pyx_t_6 = ((PyArrayObject *)__pyx_t_1); { __Pyx_BufFmt_StackElem __pyx_stack[1]; if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_out.rcbuffer->pybuffer, (PyObject*)__pyx_t_6, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 2, 0, __pyx_stack) == -1)) { __pyx_v_out = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_out.rcbuffer->pybuffer.buf = NULL; - __PYX_ERR(0, 633, __pyx_L1_error) + __PYX_ERR(0, 677, __pyx_L1_error) } else {__pyx_pybuffernd_out.diminfo[0].strides = __pyx_pybuffernd_out.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_out.diminfo[0].shape = __pyx_pybuffernd_out.rcbuffer->pybuffer.shape[0]; __pyx_pybuffernd_out.diminfo[1].strides = __pyx_pybuffernd_out.rcbuffer->pybuffer.strides[1]; __pyx_pybuffernd_out.diminfo[1].shape = __pyx_pybuffernd_out.rcbuffer->pybuffer.shape[1]; } } @@ -27897,18 +28979,18 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_v_out = ((PyArrayObject *)__pyx_t_1); __pyx_t_1 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":636 + /* "acados_template/acados_ocp_solver_pyx.pyx":680 * * # call getter * acados_solver_common.ocp_nlp_get_at_stage(self.nlp_config, self.nlp_dims, self.nlp_solver, stage, field, out.data) # <<<<<<<<<<<<<< * * return out */ - __pyx_t_7 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 636, __pyx_L1_error) - __pyx_t_8 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_out)); if (unlikely(__pyx_t_8 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 636, __pyx_L1_error) + __pyx_t_7 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 680, __pyx_L1_error) + __pyx_t_8 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_out)); if (unlikely(__pyx_t_8 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 680, __pyx_L1_error) ocp_nlp_get_at_stage(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_solver, __pyx_v_stage, __pyx_t_7, ((void *)__pyx_t_8)); - /* "acados_template/acados_ocp_solver_pyx.pyx":638 + /* "acados_template/acados_ocp_solver_pyx.pyx":682 * acados_solver_common.ocp_nlp_get_at_stage(self.nlp_config, self.nlp_dims, self.nlp_solver, stage, field, out.data) * * return out # <<<<<<<<<<<<<< @@ -27920,10 +29002,10 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_r = ((PyObject *)__pyx_v_out); goto __pyx_L0; - /* "acados_template/acados_ocp_solver_pyx.pyx":619 + /* "acados_template/acados_ocp_solver_pyx.pyx":663 * * - * def dynamics_get(self, int stage, str field_): # <<<<<<<<<<<<<< + * def get_from_qp_in(self, int stage, str field_): # <<<<<<<<<<<<<< * """ * Get numerical data from the dynamics module of the solver: */ @@ -27940,7 +29022,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __Pyx_ErrFetch(&__pyx_type, &__pyx_value, &__pyx_tb); __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_out.rcbuffer->pybuffer); __Pyx_ErrRestore(__pyx_type, __pyx_value, __pyx_tb);} - __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.dynamics_get", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.get_from_qp_in", __pyx_clineno, __pyx_lineno, __pyx_filename); __pyx_r = NULL; goto __pyx_L2; __pyx_L0:; @@ -27953,7 +29035,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":641 +/* "acados_template/acados_ocp_solver_pyx.pyx":685 * * * def options_set(self, str field_, value_): # <<<<<<<<<<<<<< @@ -27962,16 +29044,16 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ /* Python wrapper */ -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43options_set(PyObject *__pyx_v_self, +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47options_set(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else PyObject *__pyx_args, PyObject *__pyx_kwds #endif ); /*proto*/ -PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42options_set, "\n Set options of the solver.\n\n :param field: string, e.g. 'print_level', 'rti_phase', 'initialize_t_slacks', 'step_length', 'alpha_min', 'alpha_reduction', 'qp_warm_start', 'line_search_use_sufficient_descent', 'full_step_dual', 'globalization_use_SOC', 'qp_tol_stat', 'qp_tol_eq', 'qp_tol_ineq', 'qp_tol_comp', 'qp_tau_min', 'qp_mu0'\n\n :param value: of type int, float, string\n\n - qp_tol_stat: QP solver tolerance stationarity\n - qp_tol_eq: QP solver tolerance equalities\n - qp_tol_ineq: QP solver tolerance inequalities\n - qp_tol_comp: QP solver tolerance complementarity\n - qp_tau_min: for HPIPM QP solvers: minimum value of barrier parameter in HPIPM\n - qp_mu0: for HPIPM QP solvers: initial value for complementarity slackness\n - warm_start_first_qp: indicates if first QP in SQP is warm_started\n "); -static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43options_set = {"options_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43options_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42options_set}; -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43options_set(PyObject *__pyx_v_self, +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_46options_set, "\n Set options of the solver.\n\n :param field: string, e.g. 'print_level', 'rti_phase', 'initialize_t_slacks', 'step_length', 'alpha_min', 'alpha_reduction', 'qp_warm_start', 'line_search_use_sufficient_descent', 'full_step_dual', 'globalization_use_SOC', 'qp_tol_stat', 'qp_tol_eq', 'qp_tol_ineq', 'qp_tol_comp', 'qp_tau_min', 'qp_mu0'\n\n :param value: of type int, float, string\n\n - qp_tol_stat: QP solver tolerance stationarity\n - qp_tol_eq: QP solver tolerance equalities\n - qp_tol_ineq: QP solver tolerance inequalities\n - qp_tol_comp: QP solver tolerance complementarity\n - qp_tau_min: for HPIPM QP solvers: minimum value of barrier parameter in HPIPM\n - qp_mu0: for HPIPM QP solvers: initial value for complementarity slackness\n - warm_start_first_qp: indicates if first QP in SQP is warm_started\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47options_set = {"options_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47options_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_46options_set}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47options_set(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else @@ -28007,19 +29089,19 @@ PyObject *__pyx_args, PyObject *__pyx_kwds switch (__pyx_nargs) { case 0: if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field_2)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 641, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 685, __pyx_L3_error) else goto __pyx_L5_argtuple_error; CYTHON_FALLTHROUGH; case 1: if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_value)) != 0)) kw_args--; - else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 641, __pyx_L3_error) + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 685, __pyx_L3_error) else { - __Pyx_RaiseArgtupleInvalid("options_set", 1, 2, 2, 1); __PYX_ERR(0, 641, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("options_set", 1, 2, 2, 1); __PYX_ERR(0, 685, __pyx_L3_error) } } if (unlikely(kw_args > 0)) { const Py_ssize_t kwd_pos_args = __pyx_nargs; - if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "options_set") < 0)) __PYX_ERR(0, 641, __pyx_L3_error) + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "options_set") < 0)) __PYX_ERR(0, 685, __pyx_L3_error) } } else if (unlikely(__pyx_nargs != 2)) { goto __pyx_L5_argtuple_error; @@ -28032,14 +29114,14 @@ PyObject *__pyx_args, PyObject *__pyx_kwds } goto __pyx_L4_argument_unpacking_done; __pyx_L5_argtuple_error:; - __Pyx_RaiseArgtupleInvalid("options_set", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 641, __pyx_L3_error) + __Pyx_RaiseArgtupleInvalid("options_set", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 685, __pyx_L3_error) __pyx_L3_error:; __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.options_set", __pyx_clineno, __pyx_lineno, __pyx_filename); __Pyx_RefNannyFinishContext(); return NULL; __pyx_L4_argument_unpacking_done:; - if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 641, __pyx_L1_error) - __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42options_set(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_field_, __pyx_v_value_); + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 685, __pyx_L1_error) + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_46options_set(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_field_, __pyx_v_value_); /* function exit code */ goto __pyx_L0; @@ -28050,7 +29132,7 @@ PyObject *__pyx_args, PyObject *__pyx_kwds return __pyx_r; } -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42options_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_) { +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_46options_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_) { PyObject *__pyx_v_int_fields = NULL; PyObject *__pyx_v_double_fields = NULL; PyObject *__pyx_v_string_fields = NULL; @@ -28076,14 +29158,14 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS int __pyx_clineno = 0; __Pyx_RefNannySetupContext("options_set", 0); - /* "acados_template/acados_ocp_solver_pyx.pyx":657 + /* "acados_template/acados_ocp_solver_pyx.pyx":701 * - warm_start_first_qp: indicates if first QP in SQP is warm_started * """ * int_fields = ['print_level', 'rti_phase', 'initialize_t_slacks', 'qp_warm_start', 'line_search_use_sufficient_descent', 'full_step_dual', 'globalization_use_SOC', 'warm_start_first_qp'] # <<<<<<<<<<<<<< * double_fields = ['step_length', 'tol_eq', 'tol_stat', 'tol_ineq', 'tol_comp', 'alpha_min', 'alpha_reduction', 'eps_sufficient_descent', * 'qp_tol_stat', 'qp_tol_eq', 'qp_tol_ineq', 'qp_tol_comp', 'qp_tau_min', 'qp_mu0'] */ - __pyx_t_1 = PyList_New(8); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 657, __pyx_L1_error) + __pyx_t_1 = PyList_New(8); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 701, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_INCREF(__pyx_n_u_print_level); __Pyx_GIVEREF(__pyx_n_u_print_level); @@ -28112,14 +29194,14 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_v_int_fields = ((PyObject*)__pyx_t_1); __pyx_t_1 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":658 + /* "acados_template/acados_ocp_solver_pyx.pyx":702 * """ * int_fields = ['print_level', 'rti_phase', 'initialize_t_slacks', 'qp_warm_start', 'line_search_use_sufficient_descent', 'full_step_dual', 'globalization_use_SOC', 'warm_start_first_qp'] * double_fields = ['step_length', 'tol_eq', 'tol_stat', 'tol_ineq', 'tol_comp', 'alpha_min', 'alpha_reduction', 'eps_sufficient_descent', # <<<<<<<<<<<<<< * 'qp_tol_stat', 'qp_tol_eq', 'qp_tol_ineq', 'qp_tol_comp', 'qp_tau_min', 'qp_mu0'] * string_fields = ['globalization'] */ - __pyx_t_1 = PyList_New(14); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 658, __pyx_L1_error) + __pyx_t_1 = PyList_New(14); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 702, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_INCREF(__pyx_n_u_step_length); __Pyx_GIVEREF(__pyx_n_u_step_length); @@ -28166,14 +29248,14 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_v_double_fields = ((PyObject*)__pyx_t_1); __pyx_t_1 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":660 + /* "acados_template/acados_ocp_solver_pyx.pyx":704 * double_fields = ['step_length', 'tol_eq', 'tol_stat', 'tol_ineq', 'tol_comp', 'alpha_min', 'alpha_reduction', 'eps_sufficient_descent', * 'qp_tol_stat', 'qp_tol_eq', 'qp_tol_ineq', 'qp_tol_comp', 'qp_tau_min', 'qp_mu0'] * string_fields = ['globalization'] # <<<<<<<<<<<<<< * * # encode */ - __pyx_t_1 = PyList_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 660, __pyx_L1_error) + __pyx_t_1 = PyList_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 704, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_INCREF(__pyx_n_u_globalization); __Pyx_GIVEREF(__pyx_n_u_globalization); @@ -28181,7 +29263,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_v_string_fields = ((PyObject*)__pyx_t_1); __pyx_t_1 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":663 + /* "acados_template/acados_ocp_solver_pyx.pyx":707 * * # encode * field = field_.encode('utf-8') # <<<<<<<<<<<<<< @@ -28190,24 +29272,24 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ if (unlikely(__pyx_v_field_ == Py_None)) { PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "encode"); - __PYX_ERR(0, 663, __pyx_L1_error) + __PYX_ERR(0, 707, __pyx_L1_error) } - __pyx_t_1 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 663, __pyx_L1_error) + __pyx_t_1 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 707, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __pyx_v_field = __pyx_t_1; __pyx_t_1 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":670 + /* "acados_template/acados_ocp_solver_pyx.pyx":714 * * # check field availability and type * if field_ in int_fields: # <<<<<<<<<<<<<< * if not isinstance(value_, int): * raise Exception('solver option {} must be of type int. You have {}.'.format(field_, type(value_))) */ - __pyx_t_2 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_int_fields, Py_EQ)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 670, __pyx_L1_error) + __pyx_t_2 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_int_fields, Py_EQ)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 714, __pyx_L1_error) if (__pyx_t_2) { - /* "acados_template/acados_ocp_solver_pyx.pyx":671 + /* "acados_template/acados_ocp_solver_pyx.pyx":715 * # check field availability and type * if field_ in int_fields: * if not isinstance(value_, int): # <<<<<<<<<<<<<< @@ -28218,14 +29300,14 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_t_3 = (!__pyx_t_2); if (unlikely(__pyx_t_3)) { - /* "acados_template/acados_ocp_solver_pyx.pyx":672 + /* "acados_template/acados_ocp_solver_pyx.pyx":716 * if field_ in int_fields: * if not isinstance(value_, int): * raise Exception('solver option {} must be of type int. You have {}.'.format(field_, type(value_))) # <<<<<<<<<<<<<< * * if field_ == 'rti_phase': */ - __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_solver_option_must_be_of_type_in, __pyx_n_s_format); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 672, __pyx_L1_error) + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_solver_option_must_be_of_type_in, __pyx_n_s_format); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 716, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); __pyx_t_5 = NULL; __pyx_t_6 = 0; @@ -28243,18 +29325,18 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_v_field_, ((PyObject *)Py_TYPE(__pyx_v_value_))}; __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; - if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 672, __pyx_L1_error) + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 716, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; } - __pyx_t_4 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 672, __pyx_L1_error) + __pyx_t_4 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 716, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; __Pyx_Raise(__pyx_t_4, 0, 0, 0); __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __PYX_ERR(0, 672, __pyx_L1_error) + __PYX_ERR(0, 716, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":671 + /* "acados_template/acados_ocp_solver_pyx.pyx":715 * # check field availability and type * if field_ in int_fields: * if not isinstance(value_, int): # <<<<<<<<<<<<<< @@ -28263,52 +29345,52 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":674 + /* "acados_template/acados_ocp_solver_pyx.pyx":718 * raise Exception('solver option {} must be of type int. You have {}.'.format(field_, type(value_))) * * if field_ == 'rti_phase': # <<<<<<<<<<<<<< * if value_ < 0 or value_ > 2: * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' */ - __pyx_t_3 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_rti_phase, Py_EQ)); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(0, 674, __pyx_L1_error) + __pyx_t_3 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_rti_phase, Py_EQ)); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(0, 718, __pyx_L1_error) if (__pyx_t_3) { - /* "acados_template/acados_ocp_solver_pyx.pyx":675 + /* "acados_template/acados_ocp_solver_pyx.pyx":719 * * if field_ == 'rti_phase': * if value_ < 0 or value_ > 2: # <<<<<<<<<<<<<< * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' * 'take only values 0, 1, 2 for SQP-RTI-type solvers') */ - __pyx_t_4 = PyObject_RichCompare(__pyx_v_value_, __pyx_int_0, Py_LT); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 675, __pyx_L1_error) - __pyx_t_2 = __Pyx_PyObject_IsTrue(__pyx_t_4); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 675, __pyx_L1_error) + __pyx_t_4 = PyObject_RichCompare(__pyx_v_value_, __pyx_int_0, Py_LT); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 719, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_IsTrue(__pyx_t_4); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 719, __pyx_L1_error) __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; if (!__pyx_t_2) { } else { __pyx_t_3 = __pyx_t_2; goto __pyx_L7_bool_binop_done; } - __pyx_t_4 = PyObject_RichCompare(__pyx_v_value_, __pyx_int_2, Py_GT); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 675, __pyx_L1_error) - __pyx_t_2 = __Pyx_PyObject_IsTrue(__pyx_t_4); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 675, __pyx_L1_error) + __pyx_t_4 = PyObject_RichCompare(__pyx_v_value_, __pyx_int_2, Py_GT); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 719, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_IsTrue(__pyx_t_4); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 719, __pyx_L1_error) __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; __pyx_t_3 = __pyx_t_2; __pyx_L7_bool_binop_done:; if (unlikely(__pyx_t_3)) { - /* "acados_template/acados_ocp_solver_pyx.pyx":676 + /* "acados_template/acados_ocp_solver_pyx.pyx":720 * if field_ == 'rti_phase': * if value_ < 0 or value_ > 2: * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' # <<<<<<<<<<<<<< * 'take only values 0, 1, 2 for SQP-RTI-type solvers') * if self.nlp_solver_type != 'SQP_RTI' and value_ > 0: */ - __pyx_t_4 = __Pyx_PyObject_Call(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_tuple__27, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 676, __pyx_L1_error) + __pyx_t_4 = __Pyx_PyObject_Call(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_tuple__29, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 720, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); __Pyx_Raise(__pyx_t_4, 0, 0, 0); __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __PYX_ERR(0, 676, __pyx_L1_error) + __PYX_ERR(0, 720, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":675 + /* "acados_template/acados_ocp_solver_pyx.pyx":719 * * if field_ == 'rti_phase': * if value_ < 0 or value_ > 2: # <<<<<<<<<<<<<< @@ -28317,40 +29399,40 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":678 + /* "acados_template/acados_ocp_solver_pyx.pyx":722 * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' * 'take only values 0, 1, 2 for SQP-RTI-type solvers') * if self.nlp_solver_type != 'SQP_RTI' and value_ > 0: # <<<<<<<<<<<<<< * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' * 'take only value 0 for SQP-type solvers') */ - __pyx_t_2 = (__Pyx_PyUnicode_Equals(__pyx_v_self->nlp_solver_type, __pyx_n_u_SQP_RTI, Py_NE)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 678, __pyx_L1_error) + __pyx_t_2 = (__Pyx_PyUnicode_Equals(__pyx_v_self->nlp_solver_type, __pyx_n_u_SQP_RTI, Py_NE)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 722, __pyx_L1_error) if (__pyx_t_2) { } else { __pyx_t_3 = __pyx_t_2; goto __pyx_L10_bool_binop_done; } - __pyx_t_4 = PyObject_RichCompare(__pyx_v_value_, __pyx_int_0, Py_GT); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 678, __pyx_L1_error) - __pyx_t_2 = __Pyx_PyObject_IsTrue(__pyx_t_4); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 678, __pyx_L1_error) + __pyx_t_4 = PyObject_RichCompare(__pyx_v_value_, __pyx_int_0, Py_GT); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 722, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_IsTrue(__pyx_t_4); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 722, __pyx_L1_error) __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; __pyx_t_3 = __pyx_t_2; __pyx_L10_bool_binop_done:; if (unlikely(__pyx_t_3)) { - /* "acados_template/acados_ocp_solver_pyx.pyx":679 + /* "acados_template/acados_ocp_solver_pyx.pyx":723 * 'take only values 0, 1, 2 for SQP-RTI-type solvers') * if self.nlp_solver_type != 'SQP_RTI' and value_ > 0: * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' # <<<<<<<<<<<<<< * 'take only value 0 for SQP-type solvers') * */ - __pyx_t_4 = __Pyx_PyObject_Call(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_tuple__28, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 679, __pyx_L1_error) + __pyx_t_4 = __Pyx_PyObject_Call(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_tuple__30, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 723, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); __Pyx_Raise(__pyx_t_4, 0, 0, 0); __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __PYX_ERR(0, 679, __pyx_L1_error) + __PYX_ERR(0, 723, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":678 + /* "acados_template/acados_ocp_solver_pyx.pyx":722 * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' * 'take only values 0, 1, 2 for SQP-RTI-type solvers') * if self.nlp_solver_type != 'SQP_RTI' and value_ > 0: # <<<<<<<<<<<<<< @@ -28359,7 +29441,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":674 + /* "acados_template/acados_ocp_solver_pyx.pyx":718 * raise Exception('solver option {} must be of type int. You have {}.'.format(field_, type(value_))) * * if field_ == 'rti_phase': # <<<<<<<<<<<<<< @@ -28368,27 +29450,27 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":682 + /* "acados_template/acados_ocp_solver_pyx.pyx":726 * 'take only value 0 for SQP-type solvers') * * int_value = value_ # <<<<<<<<<<<<<< * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &int_value) * */ - __pyx_t_6 = __Pyx_PyInt_As_int(__pyx_v_value_); if (unlikely((__pyx_t_6 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 682, __pyx_L1_error) + __pyx_t_6 = __Pyx_PyInt_As_int(__pyx_v_value_); if (unlikely((__pyx_t_6 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 726, __pyx_L1_error) __pyx_v_int_value = __pyx_t_6; - /* "acados_template/acados_ocp_solver_pyx.pyx":683 + /* "acados_template/acados_ocp_solver_pyx.pyx":727 * * int_value = value_ * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &int_value) # <<<<<<<<<<<<<< * * elif field_ in double_fields: */ - __pyx_t_7 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 683, __pyx_L1_error) + __pyx_t_7 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 727, __pyx_L1_error) ocp_nlp_solver_opts_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_opts, __pyx_t_7, ((void *)(&__pyx_v_int_value))); - /* "acados_template/acados_ocp_solver_pyx.pyx":670 + /* "acados_template/acados_ocp_solver_pyx.pyx":714 * * # check field availability and type * if field_ in int_fields: # <<<<<<<<<<<<<< @@ -28398,17 +29480,17 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS goto __pyx_L3; } - /* "acados_template/acados_ocp_solver_pyx.pyx":685 + /* "acados_template/acados_ocp_solver_pyx.pyx":729 * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &int_value) * * elif field_ in double_fields: # <<<<<<<<<<<<<< * if not isinstance(value_, float): * raise Exception('solver option {} must be of type float. You have {}.'.format(field_, type(value_))) */ - __pyx_t_3 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_double_fields, Py_EQ)); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(0, 685, __pyx_L1_error) + __pyx_t_3 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_double_fields, Py_EQ)); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(0, 729, __pyx_L1_error) if (__pyx_t_3) { - /* "acados_template/acados_ocp_solver_pyx.pyx":686 + /* "acados_template/acados_ocp_solver_pyx.pyx":730 * * elif field_ in double_fields: * if not isinstance(value_, float): # <<<<<<<<<<<<<< @@ -28419,14 +29501,14 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_t_2 = (!__pyx_t_3); if (unlikely(__pyx_t_2)) { - /* "acados_template/acados_ocp_solver_pyx.pyx":687 + /* "acados_template/acados_ocp_solver_pyx.pyx":731 * elif field_ in double_fields: * if not isinstance(value_, float): * raise Exception('solver option {} must be of type float. You have {}.'.format(field_, type(value_))) # <<<<<<<<<<<<<< * * double_value = value_ */ - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_solver_option_must_be_of_type_fl, __pyx_n_s_format); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 687, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_solver_option_must_be_of_type_fl, __pyx_n_s_format); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 731, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __pyx_t_5 = NULL; __pyx_t_6 = 0; @@ -28444,18 +29526,18 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_v_field_, ((PyObject *)Py_TYPE(__pyx_v_value_))}; __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; - if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 687, __pyx_L1_error) + if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 731, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; } - __pyx_t_1 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_4); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 687, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_4); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 731, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; __Pyx_Raise(__pyx_t_1, 0, 0, 0); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __PYX_ERR(0, 687, __pyx_L1_error) + __PYX_ERR(0, 731, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":686 + /* "acados_template/acados_ocp_solver_pyx.pyx":730 * * elif field_ in double_fields: * if not isinstance(value_, float): # <<<<<<<<<<<<<< @@ -28464,27 +29546,27 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":689 + /* "acados_template/acados_ocp_solver_pyx.pyx":733 * raise Exception('solver option {} must be of type float. You have {}.'.format(field_, type(value_))) * * double_value = value_ # <<<<<<<<<<<<<< * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &double_value) * */ - __pyx_t_8 = __pyx_PyFloat_AsDouble(__pyx_v_value_); if (unlikely((__pyx_t_8 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 689, __pyx_L1_error) + __pyx_t_8 = __pyx_PyFloat_AsDouble(__pyx_v_value_); if (unlikely((__pyx_t_8 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 733, __pyx_L1_error) __pyx_v_double_value = __pyx_t_8; - /* "acados_template/acados_ocp_solver_pyx.pyx":690 + /* "acados_template/acados_ocp_solver_pyx.pyx":734 * * double_value = value_ * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &double_value) # <<<<<<<<<<<<<< * * elif field_ in string_fields: */ - __pyx_t_7 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 690, __pyx_L1_error) + __pyx_t_7 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 734, __pyx_L1_error) ocp_nlp_solver_opts_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_opts, __pyx_t_7, ((void *)(&__pyx_v_double_value))); - /* "acados_template/acados_ocp_solver_pyx.pyx":685 + /* "acados_template/acados_ocp_solver_pyx.pyx":729 * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &int_value) * * elif field_ in double_fields: # <<<<<<<<<<<<<< @@ -28494,17 +29576,17 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS goto __pyx_L3; } - /* "acados_template/acados_ocp_solver_pyx.pyx":692 + /* "acados_template/acados_ocp_solver_pyx.pyx":736 * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &double_value) * * elif field_ in string_fields: # <<<<<<<<<<<<<< * if not isinstance(value_, bytes): * raise Exception('solver option {} must be of type str. You have {}.'.format(field_, type(value_))) */ - __pyx_t_2 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_string_fields, Py_EQ)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 692, __pyx_L1_error) + __pyx_t_2 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_string_fields, Py_EQ)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 736, __pyx_L1_error) if (likely(__pyx_t_2)) { - /* "acados_template/acados_ocp_solver_pyx.pyx":693 + /* "acados_template/acados_ocp_solver_pyx.pyx":737 * * elif field_ in string_fields: * if not isinstance(value_, bytes): # <<<<<<<<<<<<<< @@ -28515,14 +29597,14 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_t_3 = (!__pyx_t_2); if (unlikely(__pyx_t_3)) { - /* "acados_template/acados_ocp_solver_pyx.pyx":694 + /* "acados_template/acados_ocp_solver_pyx.pyx":738 * elif field_ in string_fields: * if not isinstance(value_, bytes): * raise Exception('solver option {} must be of type str. You have {}.'.format(field_, type(value_))) # <<<<<<<<<<<<<< * * string_value = value_.encode('utf-8') */ - __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_solver_option_must_be_of_type_st, __pyx_n_s_format); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 694, __pyx_L1_error) + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_solver_option_must_be_of_type_st, __pyx_n_s_format); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 738, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); __pyx_t_5 = NULL; __pyx_t_6 = 0; @@ -28540,18 +29622,18 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_v_field_, ((PyObject *)Py_TYPE(__pyx_v_value_))}; __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; - if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 694, __pyx_L1_error) + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 738, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; } - __pyx_t_4 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 694, __pyx_L1_error) + __pyx_t_4 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 738, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; __Pyx_Raise(__pyx_t_4, 0, 0, 0); __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __PYX_ERR(0, 694, __pyx_L1_error) + __PYX_ERR(0, 738, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":693 + /* "acados_template/acados_ocp_solver_pyx.pyx":737 * * elif field_ in string_fields: * if not isinstance(value_, bytes): # <<<<<<<<<<<<<< @@ -28560,14 +29642,14 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":696 + /* "acados_template/acados_ocp_solver_pyx.pyx":740 * raise Exception('solver option {} must be of type str. You have {}.'.format(field_, type(value_))) * * string_value = value_.encode('utf-8') # <<<<<<<<<<<<<< * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &string_value[0]) * */ - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_value_, __pyx_n_s_encode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 696, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_value_, __pyx_n_s_encode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 740, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __pyx_t_5 = NULL; __pyx_t_6 = 0; @@ -28585,24 +29667,24 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS PyObject *__pyx_callargs[2] = {__pyx_t_5, __pyx_kp_u_utf_8}; __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 1+__pyx_t_6); __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; - if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 696, __pyx_L1_error) + if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 740, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; } - __pyx_t_9 = __Pyx_PyObject_to_MemoryviewSlice_dc_unsigned_char(__pyx_t_4, PyBUF_WRITABLE); if (unlikely(!__pyx_t_9.memview)) __PYX_ERR(0, 696, __pyx_L1_error) + __pyx_t_9 = __Pyx_PyObject_to_MemoryviewSlice_dc_unsigned_char(__pyx_t_4, PyBUF_WRITABLE); if (unlikely(!__pyx_t_9.memview)) __PYX_ERR(0, 740, __pyx_L1_error) __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; __pyx_v_string_value = __pyx_t_9; __pyx_t_9.memview = NULL; __pyx_t_9.data = NULL; - /* "acados_template/acados_ocp_solver_pyx.pyx":697 + /* "acados_template/acados_ocp_solver_pyx.pyx":741 * * string_value = value_.encode('utf-8') * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &string_value[0]) # <<<<<<<<<<<<<< * * else: */ - __pyx_t_7 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 697, __pyx_L1_error) + __pyx_t_7 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 741, __pyx_L1_error) __pyx_t_10 = 0; __pyx_t_6 = -1; if (__pyx_t_10 < 0) { @@ -28611,11 +29693,11 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS } else if (unlikely(__pyx_t_10 >= __pyx_v_string_value.shape[0])) __pyx_t_6 = 0; if (unlikely(__pyx_t_6 != -1)) { __Pyx_RaiseBufferIndexError(__pyx_t_6); - __PYX_ERR(0, 697, __pyx_L1_error) + __PYX_ERR(0, 741, __pyx_L1_error) } ocp_nlp_solver_opts_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_opts, __pyx_t_7, ((void *)(&(*((unsigned char *) ( /* dim=0 */ ((char *) (((unsigned char *) __pyx_v_string_value.data) + __pyx_t_10)) )))))); - /* "acados_template/acados_ocp_solver_pyx.pyx":692 + /* "acados_template/acados_ocp_solver_pyx.pyx":736 * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &double_value) * * elif field_ in string_fields: # <<<<<<<<<<<<<< @@ -28625,7 +29707,7 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS goto __pyx_L3; } - /* "acados_template/acados_ocp_solver_pyx.pyx":700 + /* "acados_template/acados_ocp_solver_pyx.pyx":744 * * else: * raise Exception('AcadosOcpSolverCython.options_set() does not support field {}.'\ # <<<<<<<<<<<<<< @@ -28634,21 +29716,21 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ /*else*/ { - /* "acados_template/acados_ocp_solver_pyx.pyx":701 + /* "acados_template/acados_ocp_solver_pyx.pyx":745 * else: * raise Exception('AcadosOcpSolverCython.options_set() does not support field {}.'\ * '\n Possible values are {}.'.format(field_, ', '.join(int_fields + double_fields + string_fields))) # <<<<<<<<<<<<<< * * */ - __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_options_se, __pyx_n_s_format); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 701, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_options_se, __pyx_n_s_format); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 745, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); - __pyx_t_5 = PyNumber_Add(__pyx_v_int_fields, __pyx_v_double_fields); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 701, __pyx_L1_error) + __pyx_t_5 = PyNumber_Add(__pyx_v_int_fields, __pyx_v_double_fields); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 745, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_5); - __pyx_t_11 = PyNumber_Add(__pyx_t_5, __pyx_v_string_fields); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 701, __pyx_L1_error) + __pyx_t_11 = PyNumber_Add(__pyx_t_5, __pyx_v_string_fields); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 745, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_11); __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - __pyx_t_5 = PyUnicode_Join(__pyx_kp_u__29, __pyx_t_11); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 701, __pyx_L1_error) + __pyx_t_5 = PyUnicode_Join(__pyx_kp_u__31, __pyx_t_11); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 745, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_5); __Pyx_DECREF(__pyx_t_11); __pyx_t_11 = 0; __pyx_t_11 = NULL; @@ -28668,28 +29750,28 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); __Pyx_XDECREF(__pyx_t_11); __pyx_t_11 = 0; __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; - if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 701, __pyx_L1_error) + if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 745, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; } - /* "acados_template/acados_ocp_solver_pyx.pyx":700 + /* "acados_template/acados_ocp_solver_pyx.pyx":744 * * else: * raise Exception('AcadosOcpSolverCython.options_set() does not support field {}.'\ # <<<<<<<<<<<<<< * '\n Possible values are {}.'.format(field_, ', '.join(int_fields + double_fields + string_fields))) * */ - __pyx_t_1 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_4); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 700, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_4); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 744, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_1); __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; __Pyx_Raise(__pyx_t_1, 0, 0, 0); __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; - __PYX_ERR(0, 700, __pyx_L1_error) + __PYX_ERR(0, 744, __pyx_L1_error) } __pyx_L3:; - /* "acados_template/acados_ocp_solver_pyx.pyx":641 + /* "acados_template/acados_ocp_solver_pyx.pyx":685 * * * def options_set(self, str field_, value_): # <<<<<<<<<<<<<< @@ -28719,7 +29801,451 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS return __pyx_r; } -/* "acados_template/acados_ocp_solver_pyx.pyx":704 +/* "acados_template/acados_ocp_solver_pyx.pyx":748 + * + * + * def set_params_sparse(self, int stage, idx_values_, param_values_): # <<<<<<<<<<<<<< + * """ + * set parameters of the solvers external function partially: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49set_params_sparse(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_48set_params_sparse, "\n set parameters of the solvers external function partially:\n Pseudo: solver.param[idx_values_] = param_values_;\n Parameters:\n :param stage_: integer corresponding to shooting node\n :param idx_values_: 0 based integer array corresponding to parameter indices to be set\n :param param_values_: new parameter values as numpy array\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49set_params_sparse = {"set_params_sparse", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49set_params_sparse, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_48set_params_sparse}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49set_params_sparse(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + int __pyx_v_stage; + PyObject *__pyx_v_idx_values_ = 0; + PyObject *__pyx_v_param_values_ = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("set_params_sparse (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_stage,&__pyx_n_s_idx_values,&__pyx_n_s_param_values,0}; + PyObject* values[3] = {0,0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_stage)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 748, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_idx_values)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 748, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("set_params_sparse", 1, 3, 3, 1); __PYX_ERR(0, 748, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_param_values)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 748, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("set_params_sparse", 1, 3, 3, 2); __PYX_ERR(0, 748, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "set_params_sparse") < 0)) __PYX_ERR(0, 748, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + } + __pyx_v_stage = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_stage == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 748, __pyx_L3_error) + __pyx_v_idx_values_ = values[1]; + __pyx_v_param_values_ = values[2]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("set_params_sparse", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 748, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.set_params_sparse", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_48set_params_sparse(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_stage, __pyx_v_idx_values_, __pyx_v_param_values_); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_48set_params_sparse(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_idx_values_, PyObject *__pyx_v_param_values_) { + PyArrayObject *__pyx_v_value = 0; + PyArrayObject *__pyx_v_idx = 0; + int __pyx_v_n_update; + __Pyx_LocalBuf_ND __pyx_pybuffernd_idx; + __Pyx_Buffer __pyx_pybuffer_idx; + __Pyx_LocalBuf_ND __pyx_pybuffernd_value; + __Pyx_Buffer __pyx_pybuffer_value; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_t_3; + int __pyx_t_4; + Py_ssize_t __pyx_t_5; + PyObject *__pyx_t_6 = NULL; + Py_UCS4 __pyx_t_7; + Py_ssize_t __pyx_t_8; + PyObject *__pyx_t_9 = NULL; + PyObject *__pyx_t_10 = NULL; + PyArrayObject *__pyx_t_11 = NULL; + PyArrayObject *__pyx_t_12 = NULL; + npy_intp *__pyx_t_13; + char *__pyx_t_14; + char *__pyx_t_15; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("set_params_sparse", 0); + __pyx_pybuffer_value.pybuffer.buf = NULL; + __pyx_pybuffer_value.refcount = 0; + __pyx_pybuffernd_value.data = NULL; + __pyx_pybuffernd_value.rcbuffer = &__pyx_pybuffer_value; + __pyx_pybuffer_idx.pybuffer.buf = NULL; + __pyx_pybuffer_idx.refcount = 0; + __pyx_pybuffernd_idx.data = NULL; + __pyx_pybuffernd_idx.rcbuffer = &__pyx_pybuffer_idx; + + /* "acados_template/acados_ocp_solver_pyx.pyx":758 + * """ + * + * if not isinstance(param_values_, np.ndarray): # <<<<<<<<<<<<<< + * raise Exception('param_values_ must be np.array.') + * + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 758, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_ndarray); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 758, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_3 = PyObject_IsInstance(__pyx_v_param_values_, __pyx_t_2); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(0, 758, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_4 = (!__pyx_t_3); + if (unlikely(__pyx_t_4)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":759 + * + * if not isinstance(param_values_, np.ndarray): + * raise Exception('param_values_ must be np.array.') # <<<<<<<<<<<<<< + * + * if param_values_.shape[0] != len(idx_values_): + */ + __pyx_t_2 = __Pyx_PyObject_Call(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_tuple__32, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 759, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 759, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":758 + * """ + * + * if not isinstance(param_values_, np.ndarray): # <<<<<<<<<<<<<< + * raise Exception('param_values_ must be np.array.') + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":761 + * raise Exception('param_values_ must be np.array.') + * + * if param_values_.shape[0] != len(idx_values_): # <<<<<<<<<<<<<< + * raise Exception(f'param_values_ and idx_values_ must be of the same size.' + + * f' Got sizes idx {param_values_.shape[0]}, param_values {len(idx_values_)}.') + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_param_values_, __pyx_n_s_shape); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 761, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_1 = __Pyx_GetItemInt(__pyx_t_2, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 761, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_5 = PyObject_Length(__pyx_v_idx_values_); if (unlikely(__pyx_t_5 == ((Py_ssize_t)-1))) __PYX_ERR(0, 761, __pyx_L1_error) + __pyx_t_2 = PyInt_FromSsize_t(__pyx_t_5); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 761, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_6 = PyObject_RichCompare(__pyx_t_1, __pyx_t_2, Py_NE); __Pyx_XGOTREF(__pyx_t_6); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 761, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_t_6); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 761, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(__pyx_t_4)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":763 + * if param_values_.shape[0] != len(idx_values_): + * raise Exception(f'param_values_ and idx_values_ must be of the same size.' + + * f' Got sizes idx {param_values_.shape[0]}, param_values {len(idx_values_)}.') # <<<<<<<<<<<<<< + * + * # n_update = c_int(len(param_values_)) + */ + __pyx_t_6 = PyTuple_New(5); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 763, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_5 = 0; + __pyx_t_7 = 127; + __Pyx_INCREF(__pyx_kp_u_Got_sizes_idx); + __pyx_t_5 += 15; + __Pyx_GIVEREF(__pyx_kp_u_Got_sizes_idx); + PyTuple_SET_ITEM(__pyx_t_6, 0, __pyx_kp_u_Got_sizes_idx); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_param_values_, __pyx_n_s_shape); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 763, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_1 = __Pyx_GetItemInt(__pyx_t_2, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 763, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_FormatSimple(__pyx_t_1, __pyx_empty_unicode); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 763, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_7 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) > __pyx_t_7) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) : __pyx_t_7; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_6, 1, __pyx_t_2); + __pyx_t_2 = 0; + __Pyx_INCREF(__pyx_kp_u_param_values_2); + __pyx_t_5 += 15; + __Pyx_GIVEREF(__pyx_kp_u_param_values_2); + PyTuple_SET_ITEM(__pyx_t_6, 2, __pyx_kp_u_param_values_2); + __pyx_t_8 = PyObject_Length(__pyx_v_idx_values_); if (unlikely(__pyx_t_8 == ((Py_ssize_t)-1))) __PYX_ERR(0, 763, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_t_8, 0, ' ', 'd'); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 763, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_6, 3, __pyx_t_2); + __pyx_t_2 = 0; + __Pyx_INCREF(__pyx_kp_u__2); + __pyx_t_5 += 1; + __Pyx_GIVEREF(__pyx_kp_u__2); + PyTuple_SET_ITEM(__pyx_t_6, 4, __pyx_kp_u__2); + __pyx_t_2 = __Pyx_PyUnicode_Join(__pyx_t_6, 5, __pyx_t_5, __pyx_t_7); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 763, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":762 + * + * if param_values_.shape[0] != len(idx_values_): + * raise Exception(f'param_values_ and idx_values_ must be of the same size.' + # <<<<<<<<<<<<<< + * f' Got sizes idx {param_values_.shape[0]}, param_values {len(idx_values_)}.') + * + */ + __pyx_t_6 = __Pyx_PyUnicode_Concat(__pyx_kp_u_param_values__and_idx_values__mu, __pyx_t_2); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 762, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_6); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 762, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 762, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":761 + * raise Exception('param_values_ must be np.array.') + * + * if param_values_.shape[0] != len(idx_values_): # <<<<<<<<<<<<<< + * raise Exception(f'param_values_ and idx_values_ must be of the same size.' + + * f' Got sizes idx {param_values_.shape[0]}, param_values {len(idx_values_)}.') + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":777 + * # (self.capsule, stage, idx_data, param_data, n_update) + * + * cdef cnp.ndarray[cnp.float64_t, ndim=1] value = np.ascontiguousarray(param_values_, dtype=np.float64) # <<<<<<<<<<<<<< + * # cdef cnp.ndarray[cnp.intc, ndim=1] idx = np.ascontiguousarray(idx_values_, dtype=np.intc) + * + */ + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_np); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 777, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 777, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = PyTuple_New(1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 777, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_INCREF(__pyx_v_param_values_); + __Pyx_GIVEREF(__pyx_v_param_values_); + PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_v_param_values_); + __pyx_t_1 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 777, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_GetModuleGlobalName(__pyx_t_9, __pyx_n_s_np); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 777, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __pyx_t_10 = __Pyx_PyObject_GetAttrStr(__pyx_t_9, __pyx_n_s_float64); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 777, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + if (PyDict_SetItem(__pyx_t_1, __pyx_n_s_dtype, __pyx_t_10) < 0) __PYX_ERR(0, 777, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + __pyx_t_10 = __Pyx_PyObject_Call(__pyx_t_6, __pyx_t_2, __pyx_t_1); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 777, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (!(likely(((__pyx_t_10) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_10, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 777, __pyx_L1_error) + __pyx_t_11 = ((PyArrayObject *)__pyx_t_10); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_value.rcbuffer->pybuffer, (PyObject*)__pyx_t_11, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 1, 0, __pyx_stack) == -1)) { + __pyx_v_value = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_value.rcbuffer->pybuffer.buf = NULL; + __PYX_ERR(0, 777, __pyx_L1_error) + } else {__pyx_pybuffernd_value.diminfo[0].strides = __pyx_pybuffernd_value.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_value.diminfo[0].shape = __pyx_pybuffernd_value.rcbuffer->pybuffer.shape[0]; + } + } + __pyx_t_11 = 0; + __pyx_v_value = ((PyArrayObject *)__pyx_t_10); + __pyx_t_10 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":784 + * # cdef cnp.ndarray[cnp.int, ndim=1] idx = np.ascontiguousarray(idx_values_, dtype=np.intc) + * + * cdef cnp.ndarray[cnp.int32_t, ndim=1] idx = np.ascontiguousarray(idx_values_, dtype=np.int32) # <<<<<<<<<<<<<< + * cdef int n_update = value.shape[0] + * # print(f"in set_params_sparse Cython n_update {n_update}") + */ + __Pyx_GetModuleGlobalName(__pyx_t_10, __pyx_n_s_np); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 784, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_10, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 784, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + __pyx_t_10 = PyTuple_New(1); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 784, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __Pyx_INCREF(__pyx_v_idx_values_); + __Pyx_GIVEREF(__pyx_v_idx_values_); + PyTuple_SET_ITEM(__pyx_t_10, 0, __pyx_v_idx_values_); + __pyx_t_2 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 784, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_GetModuleGlobalName(__pyx_t_6, __pyx_n_s_np); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 784, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_9 = __Pyx_PyObject_GetAttrStr(__pyx_t_6, __pyx_n_s_int32); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 784, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + if (PyDict_SetItem(__pyx_t_2, __pyx_n_s_dtype, __pyx_t_9) < 0) __PYX_ERR(0, 784, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + __pyx_t_9 = __Pyx_PyObject_Call(__pyx_t_1, __pyx_t_10, __pyx_t_2); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 784, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + if (!(likely(((__pyx_t_9) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_9, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 784, __pyx_L1_error) + __pyx_t_12 = ((PyArrayObject *)__pyx_t_9); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_idx.rcbuffer->pybuffer, (PyObject*)__pyx_t_12, &__Pyx_TypeInfo_nn___pyx_t_5numpy_int32_t, PyBUF_FORMAT| PyBUF_STRIDES, 1, 0, __pyx_stack) == -1)) { + __pyx_v_idx = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_idx.rcbuffer->pybuffer.buf = NULL; + __PYX_ERR(0, 784, __pyx_L1_error) + } else {__pyx_pybuffernd_idx.diminfo[0].strides = __pyx_pybuffernd_idx.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_idx.diminfo[0].shape = __pyx_pybuffernd_idx.rcbuffer->pybuffer.shape[0]; + } + } + __pyx_t_12 = 0; + __pyx_v_idx = ((PyArrayObject *)__pyx_t_9); + __pyx_t_9 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":785 + * + * cdef cnp.ndarray[cnp.int32_t, ndim=1] idx = np.ascontiguousarray(idx_values_, dtype=np.int32) + * cdef int n_update = value.shape[0] # <<<<<<<<<<<<<< + * # print(f"in set_params_sparse Cython n_update {n_update}") + * + */ + __pyx_t_13 = __pyx_f_5numpy_7ndarray_5shape_shape(((PyArrayObject *)__pyx_v_value)); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 785, __pyx_L1_error) + __pyx_v_n_update = (__pyx_t_13[0]); + + /* "acados_template/acados_ocp_solver_pyx.pyx":788 + * # print(f"in set_params_sparse Cython n_update {n_update}") + * + * assert acados_solver.acados_update_params_sparse(self.capsule, stage, idx.data, value.data, n_update) == 0 # <<<<<<<<<<<<<< + * return + * + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_14 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_idx)); if (unlikely(__pyx_t_14 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 788, __pyx_L1_error) + __pyx_t_15 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_15 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 788, __pyx_L1_error) + __pyx_t_4 = (long_acados_update_params_sparse(__pyx_v_self->capsule, __pyx_v_stage, ((int *)__pyx_t_14), ((double *)__pyx_t_15), __pyx_v_n_update) == 0); + if (unlikely(!__pyx_t_4)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(0, 788, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(0, 788, __pyx_L1_error) + #endif + + /* "acados_template/acados_ocp_solver_pyx.pyx":789 + * + * assert acados_solver.acados_update_params_sparse(self.capsule, stage, idx.data, value.data, n_update) == 0 + * return # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":748 + * + * + * def set_params_sparse(self, int stage, idx_values_, param_values_): # <<<<<<<<<<<<<< + * """ + * set parameters of the solvers external function partially: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_9); + __Pyx_XDECREF(__pyx_t_10); + { PyObject *__pyx_type, *__pyx_value, *__pyx_tb; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&__pyx_type, &__pyx_value, &__pyx_tb); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_idx.rcbuffer->pybuffer); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_value.rcbuffer->pybuffer); + __Pyx_ErrRestore(__pyx_type, __pyx_value, __pyx_tb);} + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.set_params_sparse", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + goto __pyx_L2; + __pyx_L0:; + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_idx.rcbuffer->pybuffer); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_value.rcbuffer->pybuffer); + __pyx_L2:; + __Pyx_XDECREF((PyObject *)__pyx_v_value); + __Pyx_XDECREF((PyObject *)__pyx_v_idx); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":792 * * * def __del__(self): # <<<<<<<<<<<<<< @@ -28728,22 +30254,22 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ /* Python wrapper */ -static void __pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_45__del__(PyObject *__pyx_v_self); /*proto*/ -static void __pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_45__del__(PyObject *__pyx_v_self) { +static void __pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_51__del__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_51__del__(PyObject *__pyx_v_self) { CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); __Pyx_RefNannyDeclarations __Pyx_RefNannySetupContext("__del__ (wrapper)", 0); - __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_44__del__(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); + __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_50__del__(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); /* function exit code */ __Pyx_RefNannyFinishContext(); } -static void __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_44__del__(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { +static void __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_50__del__(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { __Pyx_RefNannyDeclarations __Pyx_RefNannySetupContext("__del__", 0); - /* "acados_template/acados_ocp_solver_pyx.pyx":705 + /* "acados_template/acados_ocp_solver_pyx.pyx":793 * * def __del__(self): * if self.solver_created: # <<<<<<<<<<<<<< @@ -28752,7 +30278,7 @@ static void __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolver */ if (__pyx_v_self->solver_created) { - /* "acados_template/acados_ocp_solver_pyx.pyx":706 + /* "acados_template/acados_ocp_solver_pyx.pyx":794 * def __del__(self): * if self.solver_created: * acados_solver.acados_free(self.capsule) # <<<<<<<<<<<<<< @@ -28760,14 +30286,14 @@ static void __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolver */ (void)(long_acados_free(__pyx_v_self->capsule)); - /* "acados_template/acados_ocp_solver_pyx.pyx":707 + /* "acados_template/acados_ocp_solver_pyx.pyx":795 * if self.solver_created: * acados_solver.acados_free(self.capsule) * acados_solver.acados_free_capsule(self.capsule) # <<<<<<<<<<<<<< */ (void)(long_acados_free_capsule(__pyx_v_self->capsule)); - /* "acados_template/acados_ocp_solver_pyx.pyx":705 + /* "acados_template/acados_ocp_solver_pyx.pyx":793 * * def __del__(self): * if self.solver_created: # <<<<<<<<<<<<<< @@ -28776,7 +30302,7 @@ static void __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolver */ } - /* "acados_template/acados_ocp_solver_pyx.pyx":704 + /* "acados_template/acados_ocp_solver_pyx.pyx":792 * * * def __del__(self): # <<<<<<<<<<<<<< @@ -28795,15 +30321,15 @@ static void __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolver */ /* Python wrapper */ -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47__reduce_cython__(PyObject *__pyx_v_self, +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_53__reduce_cython__(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else PyObject *__pyx_args, PyObject *__pyx_kwds #endif ); /*proto*/ -static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47__reduce_cython__(PyObject *__pyx_v_self, +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_53__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_53__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_53__reduce_cython__(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else @@ -28820,14 +30346,14 @@ PyObject *__pyx_args, PyObject *__pyx_kwds if (unlikely(__pyx_nargs > 0)) { __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; - __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_46__reduce_cython__(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_52__reduce_cython__(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); /* function exit code */ __Pyx_RefNannyFinishContext(); return __pyx_r; } -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_46__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_52__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { PyObject *__pyx_r = NULL; __Pyx_RefNannyDeclarations int __pyx_lineno = 0; @@ -28867,15 +30393,15 @@ static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpS */ /* Python wrapper */ -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49__setstate_cython__(PyObject *__pyx_v_self, +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_55__setstate_cython__(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else PyObject *__pyx_args, PyObject *__pyx_kwds #endif ); /*proto*/ -static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; -static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49__setstate_cython__(PyObject *__pyx_v_self, +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_55__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_55__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_55__setstate_cython__(PyObject *__pyx_v_self, #if CYTHON_METH_FASTCALL PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds #else @@ -28930,14 +30456,14 @@ PyObject *__pyx_args, PyObject *__pyx_kwds __Pyx_RefNannyFinishContext(); return NULL; __pyx_L4_argument_unpacking_done:; - __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_48__setstate_cython__(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v___pyx_state); + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_54__setstate_cython__(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v___pyx_state); /* function exit code */ __Pyx_RefNannyFinishContext(); return __pyx_r; } -static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_48__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_54__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { PyObject *__pyx_r = NULL; __Pyx_RefNannyDeclarations int __pyx_lineno = 0; @@ -28997,7 +30523,7 @@ static PyObject *__pyx_tp_new_15acados_template_21acados_ocp_solver_pyx_AcadosOc static void __pyx_tp_finalize_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython(PyObject *o) { PyObject *etype, *eval, *etb; PyErr_Fetch(&etype, &eval, &etb); - __pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_45__del__(o); + __pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_51__del__(o); PyErr_Restore(etype, eval, etb); } #endif @@ -29018,28 +30544,31 @@ static void __pyx_tp_dealloc_15acados_template_21acados_ocp_solver_pyx_AcadosOcp static PyMethodDef __pyx_methods_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython[] = { {"_AcadosOcpSolverCython__get_pointers_solver", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_3_AcadosOcpSolverCython__get_pointers_solver, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_2__get_pointers_solver}, - {"solve", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve}, - {"reset", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7reset, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6reset}, - {"set_new_time_steps", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9set_new_time_steps, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8set_new_time_steps}, - {"update_qp_solver_cond_N", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11update_qp_solver_cond_N, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10update_qp_solver_cond_N}, - {"eval_param_sens", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13eval_param_sens, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12eval_param_sens}, - {"get", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15get, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14get}, - {"print_statistics", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17print_statistics, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16print_statistics}, - {"store_iterate", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19store_iterate, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18store_iterate}, - {"load_iterate", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21load_iterate, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20load_iterate}, - {"get_stats", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23get_stats, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22get_stats}, - {"_AcadosOcpSolverCython__get_stat_int", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25_AcadosOcpSolverCython__get_stat_int, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, - {"_AcadosOcpSolverCython__get_stat_double", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27_AcadosOcpSolverCython__get_stat_double, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, - {"_AcadosOcpSolverCython__get_stat_matrix", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_matrix, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, - {"get_cost", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31get_cost, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_30get_cost}, - {"get_residuals", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33get_residuals, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_32get_residuals}, - {"set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34set}, - {"cost_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37cost_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36cost_set}, - {"constraints_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39constraints_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38constraints_set}, - {"dynamics_get", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41dynamics_get, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40dynamics_get}, - {"options_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43options_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42options_set}, - {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, - {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"solve_for_x0", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve_for_x0, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve_for_x0}, + {"solve", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7solve, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6solve}, + {"reset", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9reset, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8reset}, + {"custom_update", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11custom_update, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10custom_update}, + {"set_new_time_steps", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13set_new_time_steps, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12set_new_time_steps}, + {"update_qp_solver_cond_N", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15update_qp_solver_cond_N, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14update_qp_solver_cond_N}, + {"eval_param_sens", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17eval_param_sens, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16eval_param_sens}, + {"get", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19get, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18get}, + {"print_statistics", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21print_statistics, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20print_statistics}, + {"store_iterate", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23store_iterate, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22store_iterate}, + {"load_iterate", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25load_iterate, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_24load_iterate}, + {"get_stats", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27get_stats, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_26get_stats}, + {"_AcadosOcpSolverCython__get_stat_int", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_int, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"_AcadosOcpSolverCython__get_stat_double", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31_AcadosOcpSolverCython__get_stat_double, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"_AcadosOcpSolverCython__get_stat_matrix", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33_AcadosOcpSolverCython__get_stat_matrix, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"get_cost", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35get_cost, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34get_cost}, + {"get_residuals", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37get_residuals, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36get_residuals}, + {"set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38set}, + {"cost_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41cost_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40cost_set}, + {"constraints_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43constraints_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42constraints_set}, + {"get_from_qp_in", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_45get_from_qp_in, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_44get_from_qp_in}, + {"options_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47options_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_46options_set}, + {"set_params_sparse", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49set_params_sparse, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_48set_params_sparse}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_53__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_55__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, {0, 0, 0, 0} }; #if CYTHON_USE_TYPE_SPECS @@ -30086,6 +31615,7 @@ static PyMethodDef __pyx_methods[] = { static int __Pyx_CreateStringTabAndInitStrings(void) { __Pyx_StringTabEntry __pyx_string_tab[] = { {&__pyx_kp_u_, __pyx_k_, sizeof(__pyx_k_), 0, 1, 0, 0}, + {&__pyx_kp_u_0, __pyx_k_0, sizeof(__pyx_k_0), 0, 1, 0, 0}, {&__pyx_n_s_ASCII, __pyx_k_ASCII, sizeof(__pyx_k_ASCII), 0, 0, 1, 1}, {&__pyx_n_s_AcadosOcpSolverCython, __pyx_k_AcadosOcpSolverCython, sizeof(__pyx_k_AcadosOcpSolverCython), 0, 0, 1, 1}, {&__pyx_n_s_AcadosOcpSolverCython___get_poin, __pyx_k_AcadosOcpSolverCython___get_poin, sizeof(__pyx_k_AcadosOcpSolverCython___get_poin), 0, 0, 1, 1}, @@ -30102,15 +31632,16 @@ static int __Pyx_CreateStringTabAndInitStrings(void) { {&__pyx_n_s_AcadosOcpSolverCython_constraint_2, __pyx_k_AcadosOcpSolverCython_constraint_2, sizeof(__pyx_k_AcadosOcpSolverCython_constraint_2), 0, 0, 1, 1}, {&__pyx_n_s_AcadosOcpSolverCython_cost_set, __pyx_k_AcadosOcpSolverCython_cost_set, sizeof(__pyx_k_AcadosOcpSolverCython_cost_set), 0, 0, 1, 1}, {&__pyx_kp_u_AcadosOcpSolverCython_cost_set_m, __pyx_k_AcadosOcpSolverCython_cost_set_m, sizeof(__pyx_k_AcadosOcpSolverCython_cost_set_m), 0, 1, 0, 0}, + {&__pyx_n_s_AcadosOcpSolverCython_custom_upd, __pyx_k_AcadosOcpSolverCython_custom_upd, sizeof(__pyx_k_AcadosOcpSolverCython_custom_upd), 0, 0, 1, 1}, {&__pyx_kp_u_AcadosOcpSolverCython_does_not_s, __pyx_k_AcadosOcpSolverCython_does_not_s, sizeof(__pyx_k_AcadosOcpSolverCython_does_not_s), 0, 1, 0, 0}, {&__pyx_kp_u_AcadosOcpSolverCython_does_not_s_2, __pyx_k_AcadosOcpSolverCython_does_not_s_2, sizeof(__pyx_k_AcadosOcpSolverCython_does_not_s_2), 0, 1, 0, 0}, - {&__pyx_n_s_AcadosOcpSolverCython_dynamics_g, __pyx_k_AcadosOcpSolverCython_dynamics_g, sizeof(__pyx_k_AcadosOcpSolverCython_dynamics_g), 0, 0, 1, 1}, {&__pyx_kp_u_AcadosOcpSolverCython_eval_param, __pyx_k_AcadosOcpSolverCython_eval_param, sizeof(__pyx_k_AcadosOcpSolverCython_eval_param), 0, 1, 0, 0}, {&__pyx_kp_u_AcadosOcpSolverCython_eval_param_2, __pyx_k_AcadosOcpSolverCython_eval_param_2, sizeof(__pyx_k_AcadosOcpSolverCython_eval_param_2), 0, 1, 0, 0}, {&__pyx_n_s_AcadosOcpSolverCython_eval_param_3, __pyx_k_AcadosOcpSolverCython_eval_param_3, sizeof(__pyx_k_AcadosOcpSolverCython_eval_param_3), 0, 0, 1, 1}, {&__pyx_n_s_AcadosOcpSolverCython_get, __pyx_k_AcadosOcpSolverCython_get, sizeof(__pyx_k_AcadosOcpSolverCython_get), 0, 0, 1, 1}, {&__pyx_n_s_AcadosOcpSolverCython_get_cost, __pyx_k_AcadosOcpSolverCython_get_cost, sizeof(__pyx_k_AcadosOcpSolverCython_get_cost), 0, 0, 1, 1}, {&__pyx_kp_u_AcadosOcpSolverCython_get_field, __pyx_k_AcadosOcpSolverCython_get_field, sizeof(__pyx_k_AcadosOcpSolverCython_get_field), 0, 1, 0, 0}, + {&__pyx_n_s_AcadosOcpSolverCython_get_from_q, __pyx_k_AcadosOcpSolverCython_get_from_q, sizeof(__pyx_k_AcadosOcpSolverCython_get_from_q), 0, 0, 1, 1}, {&__pyx_kp_u_AcadosOcpSolverCython_get_is_an, __pyx_k_AcadosOcpSolverCython_get_is_an, sizeof(__pyx_k_AcadosOcpSolverCython_get_is_an), 0, 1, 0, 0}, {&__pyx_n_s_AcadosOcpSolverCython_get_residu, __pyx_k_AcadosOcpSolverCython_get_residu, sizeof(__pyx_k_AcadosOcpSolverCython_get_residu), 0, 0, 1, 1}, {&__pyx_kp_u_AcadosOcpSolverCython_get_stage, __pyx_k_AcadosOcpSolverCython_get_stage, sizeof(__pyx_k_AcadosOcpSolverCython_get_stage), 0, 1, 0, 0}, @@ -30124,9 +31655,11 @@ static int __Pyx_CreateStringTabAndInitStrings(void) { {&__pyx_kp_u_AcadosOcpSolverCython_set_is_not, __pyx_k_AcadosOcpSolverCython_set_is_not, sizeof(__pyx_k_AcadosOcpSolverCython_set_is_not), 0, 1, 0, 0}, {&__pyx_kp_u_AcadosOcpSolverCython_set_mismat, __pyx_k_AcadosOcpSolverCython_set_mismat, sizeof(__pyx_k_AcadosOcpSolverCython_set_mismat), 0, 1, 0, 0}, {&__pyx_n_s_AcadosOcpSolverCython_set_new_ti, __pyx_k_AcadosOcpSolverCython_set_new_ti, sizeof(__pyx_k_AcadosOcpSolverCython_set_new_ti), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython_set_params, __pyx_k_AcadosOcpSolverCython_set_params, sizeof(__pyx_k_AcadosOcpSolverCython_set_params), 0, 0, 1, 1}, {&__pyx_n_s_AcadosOcpSolverCython_solve, __pyx_k_AcadosOcpSolverCython_solve, sizeof(__pyx_k_AcadosOcpSolverCython_solve), 0, 0, 1, 1}, {&__pyx_kp_u_AcadosOcpSolverCython_solve_argu, __pyx_k_AcadosOcpSolverCython_solve_argu, sizeof(__pyx_k_AcadosOcpSolverCython_solve_argu), 0, 1, 0, 0}, {&__pyx_kp_u_AcadosOcpSolverCython_solve_argu_2, __pyx_k_AcadosOcpSolverCython_solve_argu_2, sizeof(__pyx_k_AcadosOcpSolverCython_solve_argu_2), 0, 1, 0, 0}, + {&__pyx_n_s_AcadosOcpSolverCython_solve_for, __pyx_k_AcadosOcpSolverCython_solve_for, sizeof(__pyx_k_AcadosOcpSolverCython_solve_for), 0, 0, 1, 1}, {&__pyx_n_s_AcadosOcpSolverCython_store_iter, __pyx_k_AcadosOcpSolverCython_store_iter, sizeof(__pyx_k_AcadosOcpSolverCython_store_iter), 0, 0, 1, 1}, {&__pyx_n_s_AcadosOcpSolverCython_update_qp, __pyx_k_AcadosOcpSolverCython_update_qp, sizeof(__pyx_k_AcadosOcpSolverCython_update_qp), 0, 0, 1, 1}, {&__pyx_kp_s_All_dimensions_preceding_dimensi, __pyx_k_All_dimensions_preceding_dimensi, sizeof(__pyx_k_All_dimensions_preceding_dimensi), 0, 0, 1, 0}, @@ -30141,6 +31674,7 @@ static int __Pyx_CreateStringTabAndInitStrings(void) { {&__pyx_n_s_Ellipsis, __pyx_k_Ellipsis, sizeof(__pyx_k_Ellipsis), 0, 0, 1, 1}, {&__pyx_kp_s_Empty_shape_tuple_for_cython_arr, __pyx_k_Empty_shape_tuple_for_cython_arr, sizeof(__pyx_k_Empty_shape_tuple_for_cython_arr), 0, 0, 1, 0}, {&__pyx_n_u_F, __pyx_k_F, sizeof(__pyx_k_F), 0, 1, 0, 1}, + {&__pyx_kp_u_Got_sizes_idx, __pyx_k_Got_sizes_idx, sizeof(__pyx_k_Got_sizes_idx), 0, 1, 0, 0}, {&__pyx_n_s_ImportError, __pyx_k_ImportError, sizeof(__pyx_k_ImportError), 0, 0, 1, 1}, {&__pyx_kp_s_Incompatible_checksums_0x_x_vs_0, __pyx_k_Incompatible_checksums_0x_x_vs_0, sizeof(__pyx_k_Incompatible_checksums_0x_x_vs_0), 0, 0, 1, 0}, {&__pyx_n_s_IndexError, __pyx_k_IndexError, sizeof(__pyx_k_IndexError), 0, 0, 1, 1}, @@ -30166,16 +31700,18 @@ static int __Pyx_CreateStringTabAndInitStrings(void) { {&__pyx_kp_s_Unable_to_convert_item_to_object, __pyx_k_Unable_to_convert_item_to_object, sizeof(__pyx_k_Unable_to_convert_item_to_object), 0, 0, 1, 0}, {&__pyx_n_s_ValueError, __pyx_k_ValueError, sizeof(__pyx_k_ValueError), 0, 0, 1, 1}, {&__pyx_n_s_View_MemoryView, __pyx_k_View_MemoryView, sizeof(__pyx_k_View_MemoryView), 0, 0, 1, 1}, + {&__pyx_kp_u_Warning_acados_ocp_solver_reache, __pyx_k_Warning_acados_ocp_solver_reache, sizeof(__pyx_k_Warning_acados_ocp_solver_reache), 0, 1, 0, 0}, {&__pyx_kp_u_Y_m_d_H_M_S_f, __pyx_k_Y_m_d_H_M_S_f, sizeof(__pyx_k_Y_m_d_H_M_S_f), 0, 1, 0, 0}, - {&__pyx_kp_u__14, __pyx_k__14, sizeof(__pyx_k__14), 0, 1, 0, 0}, - {&__pyx_n_u__15, __pyx_k__15, sizeof(__pyx_k__15), 0, 1, 0, 1}, + {&__pyx_kp_u__16, __pyx_k__16, sizeof(__pyx_k__16), 0, 1, 0, 0}, + {&__pyx_n_u__17, __pyx_k__17, sizeof(__pyx_k__17), 0, 1, 0, 1}, {&__pyx_kp_u__2, __pyx_k__2, sizeof(__pyx_k__2), 0, 1, 0, 0}, - {&__pyx_kp_u__29, __pyx_k__29, sizeof(__pyx_k__29), 0, 1, 0, 0}, {&__pyx_n_s__3, __pyx_k__3, sizeof(__pyx_k__3), 0, 0, 1, 1}, + {&__pyx_kp_u__31, __pyx_k__31, sizeof(__pyx_k__31), 0, 1, 0, 0}, {&__pyx_kp_u__6, __pyx_k__6, sizeof(__pyx_k__6), 0, 1, 0, 0}, {&__pyx_kp_u__7, __pyx_k__7, sizeof(__pyx_k__7), 0, 1, 0, 0}, - {&__pyx_n_s__84, __pyx_k__84, sizeof(__pyx_k__84), 0, 0, 1, 1}, + {&__pyx_n_s__94, __pyx_k__94, sizeof(__pyx_k__94), 0, 0, 1, 1}, {&__pyx_n_s_abc, __pyx_k_abc, sizeof(__pyx_k_abc), 0, 0, 1, 1}, + {&__pyx_kp_u_acados_acados_ocp_solver_returne, __pyx_k_acados_acados_ocp_solver_returne, sizeof(__pyx_k_acados_acados_ocp_solver_returne), 0, 1, 0, 0}, {&__pyx_n_s_acados_template_acados_ocp_solve, __pyx_k_acados_template_acados_ocp_solve, sizeof(__pyx_k_acados_template_acados_ocp_solve), 0, 0, 1, 1}, {&__pyx_n_s_allocate_buffer, __pyx_k_allocate_buffer, sizeof(__pyx_k_allocate_buffer), 0, 0, 1, 1}, {&__pyx_n_u_alpha, __pyx_k_alpha, sizeof(__pyx_k_alpha), 0, 1, 0, 1}, @@ -30198,11 +31734,18 @@ static int __Pyx_CreateStringTabAndInitStrings(void) { {&__pyx_kp_s_collections_abc, __pyx_k_collections_abc, sizeof(__pyx_k_collections_abc), 0, 0, 1, 0}, {&__pyx_n_s_constraints_fields, __pyx_k_constraints_fields, sizeof(__pyx_k_constraints_fields), 0, 0, 1, 1}, {&__pyx_n_s_constraints_set, __pyx_k_constraints_set, sizeof(__pyx_k_constraints_set), 0, 0, 1, 1}, + {&__pyx_kp_u_constraints_set_value_must_be_nu, __pyx_k_constraints_set_value_must_be_nu, sizeof(__pyx_k_constraints_set_value_must_be_nu), 0, 1, 0, 0}, {&__pyx_kp_s_contiguous_and_direct, __pyx_k_contiguous_and_direct, sizeof(__pyx_k_contiguous_and_direct), 0, 0, 1, 0}, {&__pyx_kp_s_contiguous_and_indirect, __pyx_k_contiguous_and_indirect, sizeof(__pyx_k_contiguous_and_indirect), 0, 0, 1, 0}, {&__pyx_n_s_cost_fields, __pyx_k_cost_fields, sizeof(__pyx_k_cost_fields), 0, 0, 1, 1}, {&__pyx_n_s_cost_set, __pyx_k_cost_set, sizeof(__pyx_k_cost_set), 0, 0, 1, 1}, + {&__pyx_kp_u_cost_set_value_must_be_numpy_arr, __pyx_k_cost_set_value_must_be_numpy_arr, sizeof(__pyx_k_cost_set_value_must_be_numpy_arr), 0, 1, 0, 0}, {&__pyx_n_s_count, __pyx_k_count, sizeof(__pyx_k_count), 0, 0, 1, 1}, + {&__pyx_n_s_custom_update, __pyx_k_custom_update, sizeof(__pyx_k_custom_update), 0, 0, 1, 1}, + {&__pyx_n_u_d, __pyx_k_d, sizeof(__pyx_k_d), 0, 1, 0, 1}, + {&__pyx_n_s_data, __pyx_k_data, sizeof(__pyx_k_data), 0, 0, 1, 1}, + {&__pyx_n_s_data_2, __pyx_k_data_2, sizeof(__pyx_k_data_2), 0, 0, 1, 1}, + {&__pyx_n_s_data_len, __pyx_k_data_len, sizeof(__pyx_k_data_len), 0, 0, 1, 1}, {&__pyx_n_s_datetime, __pyx_k_datetime, sizeof(__pyx_k_datetime), 0, 0, 1, 1}, {&__pyx_n_s_default, __pyx_k_default, sizeof(__pyx_k_default), 0, 0, 1, 1}, {&__pyx_n_s_dict, __pyx_k_dict, sizeof(__pyx_k_dict), 0, 0, 1, 1}, @@ -30213,7 +31756,6 @@ static int __Pyx_CreateStringTabAndInitStrings(void) { {&__pyx_n_s_dtype, __pyx_k_dtype, sizeof(__pyx_k_dtype), 0, 0, 1, 1}, {&__pyx_n_s_dtype_is_object, __pyx_k_dtype_is_object, sizeof(__pyx_k_dtype_is_object), 0, 0, 1, 1}, {&__pyx_n_s_dump, __pyx_k_dump, sizeof(__pyx_k_dump), 0, 0, 1, 1}, - {&__pyx_n_s_dynamics_get, __pyx_k_dynamics_get, sizeof(__pyx_k_dynamics_get), 0, 0, 1, 1}, {&__pyx_kp_u_enable, __pyx_k_enable, sizeof(__pyx_k_enable), 0, 1, 0, 0}, {&__pyx_n_s_encode, __pyx_k_encode, sizeof(__pyx_k_encode), 0, 0, 1, 1}, {&__pyx_n_s_enter, __pyx_k_enter, sizeof(__pyx_k_enter), 0, 0, 1, 1}, @@ -30239,6 +31781,7 @@ static int __Pyx_CreateStringTabAndInitStrings(void) { {&__pyx_kp_u_gc, __pyx_k_gc, sizeof(__pyx_k_gc), 0, 1, 0, 0}, {&__pyx_n_s_get, __pyx_k_get, sizeof(__pyx_k_get), 0, 0, 1, 1}, {&__pyx_n_s_get_cost, __pyx_k_get_cost, sizeof(__pyx_k_get_cost), 0, 0, 1, 1}, + {&__pyx_n_s_get_from_qp_in, __pyx_k_get_from_qp_in, sizeof(__pyx_k_get_from_qp_in), 0, 0, 1, 1}, {&__pyx_n_s_get_pointers_solver, __pyx_k_get_pointers_solver, sizeof(__pyx_k_get_pointers_solver), 0, 0, 1, 1}, {&__pyx_n_s_get_residuals, __pyx_k_get_residuals, sizeof(__pyx_k_get_residuals), 0, 0, 1, 1}, {&__pyx_n_s_get_stat_double, __pyx_k_get_stat_double, sizeof(__pyx_k_get_stat_double), 0, 0, 1, 1}, @@ -30252,13 +31795,17 @@ static int __Pyx_CreateStringTabAndInitStrings(void) { {&__pyx_kp_u_got, __pyx_k_got, sizeof(__pyx_k_got), 0, 1, 0, 0}, {&__pyx_kp_u_got_differing_extents_in_dimensi, __pyx_k_got_differing_extents_in_dimensi, sizeof(__pyx_k_got_differing_extents_in_dimensi), 0, 1, 0, 0}, {&__pyx_n_s_i, __pyx_k_i, sizeof(__pyx_k_i), 0, 0, 1, 1}, + {&__pyx_n_s_i_string, __pyx_k_i_string, sizeof(__pyx_k_i_string), 0, 0, 1, 1}, {&__pyx_n_s_id, __pyx_k_id, sizeof(__pyx_k_id), 0, 0, 1, 1}, + {&__pyx_n_s_idx, __pyx_k_idx, sizeof(__pyx_k_idx), 0, 0, 1, 1}, + {&__pyx_n_s_idx_values, __pyx_k_idx_values, sizeof(__pyx_k_idx_values), 0, 0, 1, 1}, {&__pyx_n_s_import, __pyx_k_import, sizeof(__pyx_k_import), 0, 0, 1, 1}, {&__pyx_n_s_indent, __pyx_k_indent, sizeof(__pyx_k_indent), 0, 0, 1, 1}, {&__pyx_n_s_index, __pyx_k_index, sizeof(__pyx_k_index), 0, 0, 1, 1}, {&__pyx_n_u_initialize_t_slacks, __pyx_k_initialize_t_slacks, sizeof(__pyx_k_initialize_t_slacks), 0, 1, 0, 1}, {&__pyx_n_s_initializing, __pyx_k_initializing, sizeof(__pyx_k_initializing), 0, 0, 1, 1}, {&__pyx_n_s_int, __pyx_k_int, sizeof(__pyx_k_int), 0, 0, 1, 1}, + {&__pyx_n_s_int32, __pyx_k_int32, sizeof(__pyx_k_int32), 0, 0, 1, 1}, {&__pyx_n_s_int_fields, __pyx_k_int_fields, sizeof(__pyx_k_int_fields), 0, 0, 1, 1}, {&__pyx_n_s_int_value, __pyx_k_int_value, sizeof(__pyx_k_int_value), 0, 0, 1, 1}, {&__pyx_n_s_is_coroutine, __pyx_k_is_coroutine, sizeof(__pyx_k_is_coroutine), 0, 0, 1, 1}, @@ -30270,8 +31817,10 @@ static int __Pyx_CreateStringTabAndInitStrings(void) { {&__pyx_n_s_join, __pyx_k_join, sizeof(__pyx_k_join), 0, 0, 1, 1}, {&__pyx_n_s_json, __pyx_k_json, sizeof(__pyx_k_json), 0, 0, 1, 1}, {&__pyx_kp_u_json_2, __pyx_k_json_2, sizeof(__pyx_k_json_2), 0, 1, 0, 0}, + {&__pyx_n_s_k, __pyx_k_k, sizeof(__pyx_k_k), 0, 0, 1, 1}, {&__pyx_n_s_key, __pyx_k_key, sizeof(__pyx_k_key), 0, 0, 1, 1}, {&__pyx_n_s_keys, __pyx_k_keys, sizeof(__pyx_k_keys), 0, 0, 1, 1}, + {&__pyx_n_s_lN, __pyx_k_lN, sizeof(__pyx_k_lN), 0, 0, 1, 1}, {&__pyx_n_u_lam, __pyx_k_lam, sizeof(__pyx_k_lam), 0, 1, 0, 1}, {&__pyx_n_u_lam_2, __pyx_k_lam_2, sizeof(__pyx_k_lam_2), 0, 1, 0, 1}, {&__pyx_n_u_lbu, __pyx_k_lbu, sizeof(__pyx_k_lbu), 0, 1, 0, 1}, @@ -30289,8 +31838,10 @@ static int __Pyx_CreateStringTabAndInitStrings(void) { {&__pyx_n_s_model_name, __pyx_k_model_name, sizeof(__pyx_k_model_name), 0, 0, 1, 1}, {&__pyx_n_s_msg, __pyx_k_msg, sizeof(__pyx_k_msg), 0, 0, 1, 1}, {&__pyx_n_s_n, __pyx_k_n, sizeof(__pyx_k_n), 0, 0, 1, 1}, + {&__pyx_n_s_n_update, __pyx_k_n_update, sizeof(__pyx_k_n_update), 0, 0, 1, 1}, {&__pyx_n_s_name, __pyx_k_name, sizeof(__pyx_k_name), 0, 0, 1, 1}, {&__pyx_n_s_name_2, __pyx_k_name_2, sizeof(__pyx_k_name_2), 0, 0, 1, 1}, + {&__pyx_n_s_ndarray, __pyx_k_ndarray, sizeof(__pyx_k_ndarray), 0, 0, 1, 1}, {&__pyx_n_s_ndim, __pyx_k_ndim, sizeof(__pyx_k_ndim), 0, 0, 1, 1}, {&__pyx_n_s_new, __pyx_k_new, sizeof(__pyx_k_new), 0, 0, 1, 1}, {&__pyx_n_s_new_time_steps, __pyx_k_new_time_steps, sizeof(__pyx_k_new_time_steps), 0, 0, 1, 1}, @@ -30312,6 +31863,10 @@ static int __Pyx_CreateStringTabAndInitStrings(void) { {&__pyx_n_s_overwrite, __pyx_k_overwrite, sizeof(__pyx_k_overwrite), 0, 0, 1, 1}, {&__pyx_n_u_p, __pyx_k_p, sizeof(__pyx_k_p), 0, 1, 0, 1}, {&__pyx_n_s_pack, __pyx_k_pack, sizeof(__pyx_k_pack), 0, 0, 1, 1}, + {&__pyx_n_s_param_values, __pyx_k_param_values, sizeof(__pyx_k_param_values), 0, 0, 1, 1}, + {&__pyx_kp_u_param_values_2, __pyx_k_param_values_2, sizeof(__pyx_k_param_values_2), 0, 1, 0, 0}, + {&__pyx_kp_u_param_values__and_idx_values__mu, __pyx_k_param_values__and_idx_values__mu, sizeof(__pyx_k_param_values__and_idx_values__mu), 0, 1, 0, 0}, + {&__pyx_kp_u_param_values__must_be_np_array, __pyx_k_param_values__must_be_np_array, sizeof(__pyx_k_param_values__must_be_np_array), 0, 1, 0, 0}, {&__pyx_n_s_path, __pyx_k_path, sizeof(__pyx_k_path), 0, 0, 1, 1}, {&__pyx_n_u_pi, __pyx_k_pi, sizeof(__pyx_k_pi), 0, 1, 0, 1}, {&__pyx_n_u_pi_2, __pyx_k_pi_2, sizeof(__pyx_k_pi_2), 0, 1, 0, 1}, @@ -30347,11 +31902,14 @@ static int __Pyx_CreateStringTabAndInitStrings(void) { {&__pyx_n_b_res_ineq, __pyx_k_res_ineq, sizeof(__pyx_k_res_ineq), 0, 0, 0, 1}, {&__pyx_n_b_res_stat, __pyx_k_res_stat, sizeof(__pyx_k_res_stat), 0, 0, 0, 1}, {&__pyx_n_s_reset, __pyx_k_reset, sizeof(__pyx_k_reset), 0, 0, 1, 1}, + {&__pyx_n_s_reset_qp_solver_mem, __pyx_k_reset_qp_solver_mem, sizeof(__pyx_k_reset_qp_solver_mem), 0, 0, 1, 1}, {&__pyx_n_u_residuals, __pyx_k_residuals, sizeof(__pyx_k_residuals), 0, 1, 0, 1}, {&__pyx_n_u_rti_phase, __pyx_k_rti_phase, sizeof(__pyx_k_rti_phase), 0, 1, 0, 1}, {&__pyx_n_s_self, __pyx_k_self, sizeof(__pyx_k_self), 0, 0, 1, 1}, {&__pyx_n_s_set, __pyx_k_set, sizeof(__pyx_k_set), 0, 0, 1, 1}, {&__pyx_n_s_set_new_time_steps, __pyx_k_set_new_time_steps, sizeof(__pyx_k_set_new_time_steps), 0, 0, 1, 1}, + {&__pyx_n_s_set_params_sparse, __pyx_k_set_params_sparse, sizeof(__pyx_k_set_params_sparse), 0, 0, 1, 1}, + {&__pyx_kp_u_set_value_must_be_numpy_array_go, __pyx_k_set_value_must_be_numpy_array_go, sizeof(__pyx_k_set_value_must_be_numpy_array_go), 0, 1, 0, 0}, {&__pyx_n_s_setstate, __pyx_k_setstate, sizeof(__pyx_k_setstate), 0, 0, 1, 1}, {&__pyx_n_s_setstate_cython, __pyx_k_setstate_cython, sizeof(__pyx_k_setstate_cython), 0, 0, 1, 1}, {&__pyx_n_s_shape, __pyx_k_shape, sizeof(__pyx_k_shape), 0, 0, 1, 1}, @@ -30360,6 +31918,7 @@ static int __Pyx_CreateStringTabAndInitStrings(void) { {&__pyx_n_u_sl_2, __pyx_k_sl_2, sizeof(__pyx_k_sl_2), 0, 1, 0, 1}, {&__pyx_n_s_solution, __pyx_k_solution, sizeof(__pyx_k_solution), 0, 0, 1, 1}, {&__pyx_n_s_solve, __pyx_k_solve, sizeof(__pyx_k_solve), 0, 0, 1, 1}, + {&__pyx_n_s_solve_for_x0, __pyx_k_solve_for_x0, sizeof(__pyx_k_solve_for_x0), 0, 0, 1, 1}, {&__pyx_kp_u_solver_option_must_be_of_type_fl, __pyx_k_solver_option_must_be_of_type_fl, sizeof(__pyx_k_solver_option_must_be_of_type_fl), 0, 1, 0, 0}, {&__pyx_kp_u_solver_option_must_be_of_type_in, __pyx_k_solver_option_must_be_of_type_in, sizeof(__pyx_k_solver_option_must_be_of_type_in), 0, 1, 0, 0}, {&__pyx_kp_u_solver_option_must_be_of_type_st, __pyx_k_solver_option_must_be_of_type_st, sizeof(__pyx_k_solver_option_must_be_of_type_st), 0, 1, 0, 0}, @@ -30375,6 +31934,7 @@ static int __Pyx_CreateStringTabAndInitStrings(void) { {&__pyx_n_s_stat_n, __pyx_k_stat_n, sizeof(__pyx_k_stat_n), 0, 0, 1, 1}, {&__pyx_n_u_stat_n, __pyx_k_stat_n, sizeof(__pyx_k_stat_n), 0, 1, 0, 1}, {&__pyx_n_u_statistics, __pyx_k_statistics, sizeof(__pyx_k_statistics), 0, 1, 0, 1}, + {&__pyx_n_s_status, __pyx_k_status, sizeof(__pyx_k_status), 0, 0, 1, 1}, {&__pyx_n_s_step, __pyx_k_step, sizeof(__pyx_k_step), 0, 0, 1, 1}, {&__pyx_n_u_step_length, __pyx_k_step_length, sizeof(__pyx_k_step_length), 0, 1, 0, 1}, {&__pyx_n_s_stop, __pyx_k_stop, sizeof(__pyx_k_stop), 0, 0, 1, 1}, @@ -30413,6 +31973,7 @@ static int __Pyx_CreateStringTabAndInitStrings(void) { {&__pyx_n_u_tol_stat, __pyx_k_tol_stat, sizeof(__pyx_k_tol_stat), 0, 1, 0, 1}, {&__pyx_n_s_tolist, __pyx_k_tolist, sizeof(__pyx_k_tolist), 0, 0, 1, 1}, {&__pyx_n_u_u, __pyx_k_u, sizeof(__pyx_k_u), 0, 1, 0, 1}, + {&__pyx_n_s_u0, __pyx_k_u0, sizeof(__pyx_k_u0), 0, 0, 1, 1}, {&__pyx_n_u_u_2, __pyx_k_u_2, sizeof(__pyx_k_u_2), 0, 1, 0, 1}, {&__pyx_n_u_ubu, __pyx_k_ubu, sizeof(__pyx_k_ubu), 0, 1, 0, 1}, {&__pyx_n_u_ubx, __pyx_k_ubx, sizeof(__pyx_k_ubx), 0, 1, 0, 1}, @@ -30434,6 +31995,7 @@ static int __Pyx_CreateStringTabAndInitStrings(void) { {&__pyx_n_b_x, __pyx_k_x, sizeof(__pyx_k_x), 0, 0, 0, 1}, {&__pyx_n_s_x, __pyx_k_x, sizeof(__pyx_k_x), 0, 0, 1, 1}, {&__pyx_n_u_x, __pyx_k_x, sizeof(__pyx_k_x), 0, 1, 0, 1}, + {&__pyx_n_s_x0_bar, __pyx_k_x0_bar, sizeof(__pyx_k_x0_bar), 0, 0, 1, 1}, {&__pyx_n_u_x_2, __pyx_k_x_2, sizeof(__pyx_k_x_2), 0, 1, 0, 1}, {&__pyx_n_u_xdot_guess, __pyx_k_xdot_guess, sizeof(__pyx_k_xdot_guess), 0, 1, 0, 1}, {&__pyx_n_u_y_ref, __pyx_k_y_ref, sizeof(__pyx_k_y_ref), 0, 1, 0, 1}, @@ -30441,6 +32003,7 @@ static int __Pyx_CreateStringTabAndInitStrings(void) { {&__pyx_n_u_yref, __pyx_k_yref, sizeof(__pyx_k_yref), 0, 1, 0, 1}, {&__pyx_n_u_z, __pyx_k_z, sizeof(__pyx_k_z), 0, 1, 0, 1}, {&__pyx_n_u_z_2, __pyx_k_z_2, sizeof(__pyx_k_z_2), 0, 1, 0, 1}, + {&__pyx_n_b_z_guess, __pyx_k_z_guess, sizeof(__pyx_k_z_guess), 0, 0, 0, 1}, {&__pyx_n_u_z_guess, __pyx_k_z_guess, sizeof(__pyx_k_z_guess), 0, 1, 0, 1}, {&__pyx_n_s_zeros, __pyx_k_zeros, sizeof(__pyx_k_zeros), 0, 0, 1, 1}, {0, 0, 0, 0, 0, 0, 0} @@ -30449,11 +32012,11 @@ static int __Pyx_CreateStringTabAndInitStrings(void) { } /* #### Code section: cached_builtins ### */ static CYTHON_SMALL_CODE int __Pyx_InitCachedBuiltins(void) { - __pyx_builtin_AssertionError = __Pyx_GetBuiltinName(__pyx_n_s_AssertionError); if (!__pyx_builtin_AssertionError) __PYX_ERR(0, 86, __pyx_L1_error) - __pyx_builtin_NotImplementedError = __Pyx_GetBuiltinName(__pyx_n_s_NotImplementedError); if (!__pyx_builtin_NotImplementedError) __PYX_ERR(0, 134, __pyx_L1_error) - __pyx_builtin_range = __Pyx_GetBuiltinName(__pyx_n_s_range); if (!__pyx_builtin_range) __PYX_ERR(0, 313, __pyx_L1_error) - __pyx_builtin_open = __Pyx_GetBuiltinName(__pyx_n_s_open); if (!__pyx_builtin_open) __PYX_ERR(0, 325, __pyx_L1_error) - __pyx_builtin_print = __Pyx_GetBuiltinName(__pyx_n_s_print); if (!__pyx_builtin_print) __PYX_ERR(0, 327, __pyx_L1_error) + __pyx_builtin_AssertionError = __Pyx_GetBuiltinName(__pyx_n_s_AssertionError); if (!__pyx_builtin_AssertionError) __PYX_ERR(0, 82, __pyx_L1_error) + __pyx_builtin_print = __Pyx_GetBuiltinName(__pyx_n_s_print); if (!__pyx_builtin_print) __PYX_ERR(0, 113, __pyx_L1_error) + __pyx_builtin_NotImplementedError = __Pyx_GetBuiltinName(__pyx_n_s_NotImplementedError); if (!__pyx_builtin_NotImplementedError) __PYX_ERR(0, 160, __pyx_L1_error) + __pyx_builtin_range = __Pyx_GetBuiltinName(__pyx_n_s_range); if (!__pyx_builtin_range) __PYX_ERR(0, 340, __pyx_L1_error) + __pyx_builtin_open = __Pyx_GetBuiltinName(__pyx_n_s_open); if (!__pyx_builtin_open) __PYX_ERR(0, 357, __pyx_L1_error) __pyx_builtin_TypeError = __Pyx_GetBuiltinName(__pyx_n_s_TypeError); if (!__pyx_builtin_TypeError) __PYX_ERR(1, 2, __pyx_L1_error) __pyx_builtin___import__ = __Pyx_GetBuiltinName(__pyx_n_s_import); if (!__pyx_builtin___import__) __PYX_ERR(1, 100, __pyx_L1_error) __pyx_builtin_ValueError = __Pyx_GetBuiltinName(__pyx_n_s_ValueError); if (!__pyx_builtin_ValueError) __PYX_ERR(1, 141, __pyx_L1_error) @@ -30531,173 +32094,206 @@ static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { __Pyx_GOTREF(__pyx_tuple__10); __Pyx_GIVEREF(__pyx_tuple__10); - /* "acados_template/acados_ocp_solver_pyx.pyx":134 + /* "acados_template/acados_ocp_solver_pyx.pyx":113 + * + * if status == 2: + * print("Warning: acados_ocp_solver reached maximum iterations.") # <<<<<<<<<<<<<< + * elif status != 0: + * raise Exception(f'acados acados_ocp_solver returned status {status}') + */ + __pyx_tuple__11 = PyTuple_Pack(1, __pyx_kp_u_Warning_acados_ocp_solver_reache); if (unlikely(!__pyx_tuple__11)) __PYX_ERR(0, 113, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__11); + __Pyx_GIVEREF(__pyx_tuple__11); + + /* "acados_template/acados_ocp_solver_pyx.pyx":117 + * raise Exception(f'acados acados_ocp_solver returned status {status}') + * + * u0 = self.get(0, "u") # <<<<<<<<<<<<<< + * return u0 + * + */ + __pyx_tuple__12 = PyTuple_Pack(2, __pyx_int_0, __pyx_n_u_u); if (unlikely(!__pyx_tuple__12)) __PYX_ERR(0, 117, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__12); + __Pyx_GIVEREF(__pyx_tuple__12); + + /* "acados_template/acados_ocp_solver_pyx.pyx":160 * """ * * raise NotImplementedError("AcadosOcpSolverCython: does not support set_new_time_steps() since it is only a prototyping feature") # <<<<<<<<<<<<<< * # # unlikely but still possible * # if not self.solver_created: */ - __pyx_tuple__11 = PyTuple_Pack(1, __pyx_kp_u_AcadosOcpSolverCython_does_not_s); if (unlikely(!__pyx_tuple__11)) __PYX_ERR(0, 134, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__11); - __Pyx_GIVEREF(__pyx_tuple__11); + __pyx_tuple__13 = PyTuple_Pack(1, __pyx_kp_u_AcadosOcpSolverCython_does_not_s); if (unlikely(!__pyx_tuple__13)) __PYX_ERR(0, 160, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__13); + __Pyx_GIVEREF(__pyx_tuple__13); - /* "acados_template/acados_ocp_solver_pyx.pyx":186 + /* "acados_template/acados_ocp_solver_pyx.pyx":212 * `qp_solver_cond_N < N`. * """ * raise NotImplementedError("AcadosOcpSolverCython: does not support update_qp_solver_cond_N() since it is only a prototyping feature") # <<<<<<<<<<<<<< * * # # unlikely but still possible */ - __pyx_tuple__12 = PyTuple_Pack(1, __pyx_kp_u_AcadosOcpSolverCython_does_not_s_2); if (unlikely(!__pyx_tuple__12)) __PYX_ERR(0, 186, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__12); - __Pyx_GIVEREF(__pyx_tuple__12); + __pyx_tuple__14 = PyTuple_Pack(1, __pyx_kp_u_AcadosOcpSolverCython_does_not_s_2); if (unlikely(!__pyx_tuple__14)) __PYX_ERR(0, 212, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__14); + __Pyx_GIVEREF(__pyx_tuple__14); - /* "acados_template/acados_ocp_solver_pyx.pyx":219 + /* "acados_template/acados_ocp_solver_pyx.pyx":245 * # checks * if not isinstance(index, int): * raise Exception('AcadosOcpSolverCython.eval_param_sens(): index must be Integer.') # <<<<<<<<<<<<<< * * cdef int nx = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, self.nlp_dims, self.nlp_out, 0, "x".encode('utf-8')) */ - __pyx_tuple__13 = PyTuple_Pack(1, __pyx_kp_u_AcadosOcpSolverCython_eval_param); if (unlikely(!__pyx_tuple__13)) __PYX_ERR(0, 219, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__13); - __Pyx_GIVEREF(__pyx_tuple__13); + __pyx_tuple__15 = PyTuple_Pack(1, __pyx_kp_u_AcadosOcpSolverCython_eval_param); if (unlikely(!__pyx_tuple__15)) __PYX_ERR(0, 245, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__15); + __Pyx_GIVEREF(__pyx_tuple__15); - /* "acados_template/acados_ocp_solver_pyx.pyx":307 + /* "acados_template/acados_ocp_solver_pyx.pyx":333 * # append timestamp * if os.path.isfile(filename): * filename = filename[:-5] # <<<<<<<<<<<<<< * filename += datetime.utcnow().strftime('%Y-%m-%d-%H:%M:%S.%f') + '.json' * */ - __pyx_slice__16 = PySlice_New(Py_None, __pyx_int_neg_5, Py_None); if (unlikely(!__pyx_slice__16)) __PYX_ERR(0, 307, __pyx_L1_error) - __Pyx_GOTREF(__pyx_slice__16); - __Pyx_GIVEREF(__pyx_slice__16); + __pyx_slice__18 = PySlice_New(Py_None, __pyx_int_neg_5, Py_None); if (unlikely(!__pyx_slice__18)) __PYX_ERR(0, 333, __pyx_L1_error) + __Pyx_GOTREF(__pyx_slice__18); + __Pyx_GIVEREF(__pyx_slice__18); - /* "acados_template/acados_ocp_solver_pyx.pyx":325 + /* "acados_template/acados_ocp_solver_pyx.pyx":357 * * # save * with open(filename, 'w') as f: # <<<<<<<<<<<<<< * json.dump(solution, f, default=lambda x: x.tolist(), indent=4, sort_keys=True) * print("stored current iterate in ", os.path.join(os.getcwd(), filename)) */ - __pyx_tuple__17 = PyTuple_Pack(3, Py_None, Py_None, Py_None); if (unlikely(!__pyx_tuple__17)) __PYX_ERR(0, 325, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__17); - __Pyx_GIVEREF(__pyx_tuple__17); + __pyx_tuple__19 = PyTuple_Pack(3, Py_None, Py_None, Py_None); if (unlikely(!__pyx_tuple__19)) __PYX_ERR(0, 357, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__19); + __Pyx_GIVEREF(__pyx_tuple__19); - /* "acados_template/acados_ocp_solver_pyx.pyx":410 + /* "acados_template/acados_ocp_solver_pyx.pyx":442 * full_stats = self.get_stats('statistics') * if self.nlp_solver_type == 'SQP': * return full_stats[6, :] # <<<<<<<<<<<<<< * elif self.nlp_solver_type == 'SQP_RTI': * return full_stats[2, :] */ - __pyx_tuple__18 = PyTuple_Pack(2, __pyx_int_6, __pyx_slice__5); if (unlikely(!__pyx_tuple__18)) __PYX_ERR(0, 410, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__18); - __Pyx_GIVEREF(__pyx_tuple__18); + __pyx_tuple__20 = PyTuple_Pack(2, __pyx_int_6, __pyx_slice__5); if (unlikely(!__pyx_tuple__20)) __PYX_ERR(0, 442, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__20); + __Pyx_GIVEREF(__pyx_tuple__20); - /* "acados_template/acados_ocp_solver_pyx.pyx":412 + /* "acados_template/acados_ocp_solver_pyx.pyx":444 * return full_stats[6, :] * elif self.nlp_solver_type == 'SQP_RTI': * return full_stats[2, :] # <<<<<<<<<<<<<< * * elif field_ == 'alpha': */ - __pyx_tuple__19 = PyTuple_Pack(2, __pyx_int_2, __pyx_slice__5); if (unlikely(!__pyx_tuple__19)) __PYX_ERR(0, 412, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__19); - __Pyx_GIVEREF(__pyx_tuple__19); + __pyx_tuple__21 = PyTuple_Pack(2, __pyx_int_2, __pyx_slice__5); if (unlikely(!__pyx_tuple__21)) __PYX_ERR(0, 444, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__21); + __Pyx_GIVEREF(__pyx_tuple__21); - /* "acados_template/acados_ocp_solver_pyx.pyx":417 + /* "acados_template/acados_ocp_solver_pyx.pyx":449 * full_stats = self.get_stats('statistics') * if self.nlp_solver_type == 'SQP': * return full_stats[7, :] # <<<<<<<<<<<<<< * else: # self.nlp_solver_type == 'SQP_RTI': * raise Exception("alpha values are not available for SQP_RTI") */ - __pyx_tuple__20 = PyTuple_Pack(2, __pyx_int_7, __pyx_slice__5); if (unlikely(!__pyx_tuple__20)) __PYX_ERR(0, 417, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__20); - __Pyx_GIVEREF(__pyx_tuple__20); + __pyx_tuple__22 = PyTuple_Pack(2, __pyx_int_7, __pyx_slice__5); if (unlikely(!__pyx_tuple__22)) __PYX_ERR(0, 449, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__22); + __Pyx_GIVEREF(__pyx_tuple__22); - /* "acados_template/acados_ocp_solver_pyx.pyx":419 + /* "acados_template/acados_ocp_solver_pyx.pyx":451 * return full_stats[7, :] * else: # self.nlp_solver_type == 'SQP_RTI': * raise Exception("alpha values are not available for SQP_RTI") # <<<<<<<<<<<<<< * * elif field_ == 'residuals': */ - __pyx_tuple__21 = PyTuple_Pack(1, __pyx_kp_u_alpha_values_are_not_available_f); if (unlikely(!__pyx_tuple__21)) __PYX_ERR(0, 419, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__21); - __Pyx_GIVEREF(__pyx_tuple__21); + __pyx_tuple__23 = PyTuple_Pack(1, __pyx_kp_u_alpha_values_are_not_available_f); if (unlikely(!__pyx_tuple__23)) __PYX_ERR(0, 451, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__23); + __Pyx_GIVEREF(__pyx_tuple__23); - /* "acados_template/acados_ocp_solver_pyx.pyx":425 + /* "acados_template/acados_ocp_solver_pyx.pyx":457 * * else: * raise NotImplementedError("TODO!") # <<<<<<<<<<<<<< * * */ - __pyx_tuple__22 = PyTuple_Pack(1, __pyx_kp_u_TODO); if (unlikely(!__pyx_tuple__22)) __PYX_ERR(0, 425, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__22); - __Pyx_GIVEREF(__pyx_tuple__22); + __pyx_tuple__24 = PyTuple_Pack(1, __pyx_kp_u_TODO); if (unlikely(!__pyx_tuple__24)) __PYX_ERR(0, 457, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__24); + __Pyx_GIVEREF(__pyx_tuple__24); - /* "acados_template/acados_ocp_solver_pyx.pyx":434 + /* "acados_template/acados_ocp_solver_pyx.pyx":466 * * def __get_stat_double(self, field): * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) # <<<<<<<<<<<<<< * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) * return out */ - __pyx_tuple__23 = PyTuple_Pack(1, __pyx_int_1); if (unlikely(!__pyx_tuple__23)) __PYX_ERR(0, 434, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__23); - __Pyx_GIVEREF(__pyx_tuple__23); + __pyx_tuple__25 = PyTuple_Pack(1, __pyx_int_1); if (unlikely(!__pyx_tuple__25)) __PYX_ERR(0, 466, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__25); + __Pyx_GIVEREF(__pyx_tuple__25); - /* "acados_template/acados_ocp_solver_pyx.pyx":469 + /* "acados_template/acados_ocp_solver_pyx.pyx":501 * * # create output array * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.ascontiguousarray(np.zeros((4,), dtype=np.float64)) # <<<<<<<<<<<<<< * cdef double double_value * */ - __pyx_tuple__24 = PyTuple_Pack(1, __pyx_int_4); if (unlikely(!__pyx_tuple__24)) __PYX_ERR(0, 469, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__24); - __Pyx_GIVEREF(__pyx_tuple__24); - __pyx_tuple__25 = PyTuple_Pack(1, __pyx_tuple__24); if (unlikely(!__pyx_tuple__25)) __PYX_ERR(0, 469, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__25); - __Pyx_GIVEREF(__pyx_tuple__25); + __pyx_tuple__26 = PyTuple_Pack(1, __pyx_int_4); if (unlikely(!__pyx_tuple__26)) __PYX_ERR(0, 501, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__26); + __Pyx_GIVEREF(__pyx_tuple__26); + __pyx_tuple__27 = PyTuple_Pack(1, __pyx_tuple__26); if (unlikely(!__pyx_tuple__27)) __PYX_ERR(0, 501, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__27); + __Pyx_GIVEREF(__pyx_tuple__27); - /* "acados_template/acados_ocp_solver_pyx.pyx":570 + /* "acados_template/acados_ocp_solver_pyx.pyx":611 * if len(value_shape) == 1: * value_shape = (value_shape[0], 0) * value = np.asfortranarray(value_[None,:]) # <<<<<<<<<<<<<< * * elif len(value_shape) == 2: */ - __pyx_tuple__26 = PyTuple_Pack(2, Py_None, __pyx_slice__5); if (unlikely(!__pyx_tuple__26)) __PYX_ERR(0, 570, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__26); - __Pyx_GIVEREF(__pyx_tuple__26); + __pyx_tuple__28 = PyTuple_Pack(2, Py_None, __pyx_slice__5); if (unlikely(!__pyx_tuple__28)) __PYX_ERR(0, 611, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__28); + __Pyx_GIVEREF(__pyx_tuple__28); - /* "acados_template/acados_ocp_solver_pyx.pyx":676 + /* "acados_template/acados_ocp_solver_pyx.pyx":720 * if field_ == 'rti_phase': * if value_ < 0 or value_ > 2: * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' # <<<<<<<<<<<<<< * 'take only values 0, 1, 2 for SQP-RTI-type solvers') * if self.nlp_solver_type != 'SQP_RTI' and value_ > 0: */ - __pyx_tuple__27 = PyTuple_Pack(1, __pyx_kp_u_AcadosOcpSolverCython_solve_argu); if (unlikely(!__pyx_tuple__27)) __PYX_ERR(0, 676, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__27); - __Pyx_GIVEREF(__pyx_tuple__27); + __pyx_tuple__29 = PyTuple_Pack(1, __pyx_kp_u_AcadosOcpSolverCython_solve_argu); if (unlikely(!__pyx_tuple__29)) __PYX_ERR(0, 720, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__29); + __Pyx_GIVEREF(__pyx_tuple__29); - /* "acados_template/acados_ocp_solver_pyx.pyx":679 + /* "acados_template/acados_ocp_solver_pyx.pyx":723 * 'take only values 0, 1, 2 for SQP-RTI-type solvers') * if self.nlp_solver_type != 'SQP_RTI' and value_ > 0: * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' # <<<<<<<<<<<<<< * 'take only value 0 for SQP-type solvers') * */ - __pyx_tuple__28 = PyTuple_Pack(1, __pyx_kp_u_AcadosOcpSolverCython_solve_argu_2); if (unlikely(!__pyx_tuple__28)) __PYX_ERR(0, 679, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__28); - __Pyx_GIVEREF(__pyx_tuple__28); + __pyx_tuple__30 = PyTuple_Pack(1, __pyx_kp_u_AcadosOcpSolverCython_solve_argu_2); if (unlikely(!__pyx_tuple__30)) __PYX_ERR(0, 723, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__30); + __Pyx_GIVEREF(__pyx_tuple__30); + + /* "acados_template/acados_ocp_solver_pyx.pyx":759 + * + * if not isinstance(param_values_, np.ndarray): + * raise Exception('param_values_ must be np.array.') # <<<<<<<<<<<<<< + * + * if param_values_.shape[0] != len(idx_values_): + */ + __pyx_tuple__32 = PyTuple_Pack(1, __pyx_kp_u_param_values__must_be_np_array); if (unlikely(!__pyx_tuple__32)) __PYX_ERR(0, 759, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__32); + __Pyx_GIVEREF(__pyx_tuple__32); /* "View.MemoryView":100 * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" @@ -30706,12 +32302,12 @@ static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence * else: */ - __pyx_tuple__30 = PyTuple_Pack(1, __pyx_n_s_sys); if (unlikely(!__pyx_tuple__30)) __PYX_ERR(1, 100, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__30); - __Pyx_GIVEREF(__pyx_tuple__30); - __pyx_tuple__31 = PyTuple_Pack(2, __pyx_int_3, __pyx_int_3); if (unlikely(!__pyx_tuple__31)) __PYX_ERR(1, 100, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__31); - __Pyx_GIVEREF(__pyx_tuple__31); + __pyx_tuple__33 = PyTuple_Pack(1, __pyx_n_s_sys); if (unlikely(!__pyx_tuple__33)) __PYX_ERR(1, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__33); + __Pyx_GIVEREF(__pyx_tuple__33); + __pyx_tuple__34 = PyTuple_Pack(2, __pyx_int_3, __pyx_int_3); if (unlikely(!__pyx_tuple__34)) __PYX_ERR(1, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__34); + __Pyx_GIVEREF(__pyx_tuple__34); /* "View.MemoryView":101 * try: @@ -30720,9 +32316,9 @@ static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { * else: * __pyx_collections_abc_Sequence = __import__("collections").Sequence */ - __pyx_tuple__32 = PyTuple_Pack(1, __pyx_kp_s_collections_abc); if (unlikely(!__pyx_tuple__32)) __PYX_ERR(1, 101, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__32); - __Pyx_GIVEREF(__pyx_tuple__32); + __pyx_tuple__35 = PyTuple_Pack(1, __pyx_kp_s_collections_abc); if (unlikely(!__pyx_tuple__35)) __PYX_ERR(1, 101, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__35); + __Pyx_GIVEREF(__pyx_tuple__35); /* "View.MemoryView":103 * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence @@ -30731,9 +32327,9 @@ static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { * except: * */ - __pyx_tuple__33 = PyTuple_Pack(1, __pyx_n_s_collections); if (unlikely(!__pyx_tuple__33)) __PYX_ERR(1, 103, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__33); - __Pyx_GIVEREF(__pyx_tuple__33); + __pyx_tuple__36 = PyTuple_Pack(1, __pyx_n_s_collections); if (unlikely(!__pyx_tuple__36)) __PYX_ERR(1, 103, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__36); + __Pyx_GIVEREF(__pyx_tuple__36); /* "View.MemoryView":309 * return self.name @@ -30742,9 +32338,9 @@ static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { * cdef strided = Enum("") # default * cdef indirect = Enum("") */ - __pyx_tuple__34 = PyTuple_Pack(1, __pyx_kp_s_strided_and_direct_or_indirect); if (unlikely(!__pyx_tuple__34)) __PYX_ERR(1, 309, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__34); - __Pyx_GIVEREF(__pyx_tuple__34); + __pyx_tuple__37 = PyTuple_Pack(1, __pyx_kp_s_strided_and_direct_or_indirect); if (unlikely(!__pyx_tuple__37)) __PYX_ERR(1, 309, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__37); + __Pyx_GIVEREF(__pyx_tuple__37); /* "View.MemoryView":310 * @@ -30753,9 +32349,9 @@ static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { * cdef indirect = Enum("") * */ - __pyx_tuple__35 = PyTuple_Pack(1, __pyx_kp_s_strided_and_direct); if (unlikely(!__pyx_tuple__35)) __PYX_ERR(1, 310, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__35); - __Pyx_GIVEREF(__pyx_tuple__35); + __pyx_tuple__38 = PyTuple_Pack(1, __pyx_kp_s_strided_and_direct); if (unlikely(!__pyx_tuple__38)) __PYX_ERR(1, 310, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__38); + __Pyx_GIVEREF(__pyx_tuple__38); /* "View.MemoryView":311 * cdef generic = Enum("") @@ -30764,9 +32360,9 @@ static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { * * */ - __pyx_tuple__36 = PyTuple_Pack(1, __pyx_kp_s_strided_and_indirect); if (unlikely(!__pyx_tuple__36)) __PYX_ERR(1, 311, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__36); - __Pyx_GIVEREF(__pyx_tuple__36); + __pyx_tuple__39 = PyTuple_Pack(1, __pyx_kp_s_strided_and_indirect); if (unlikely(!__pyx_tuple__39)) __PYX_ERR(1, 311, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__39); + __Pyx_GIVEREF(__pyx_tuple__39); /* "View.MemoryView":314 * @@ -30775,9 +32371,9 @@ static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { * cdef indirect_contiguous = Enum("") * */ - __pyx_tuple__37 = PyTuple_Pack(1, __pyx_kp_s_contiguous_and_direct); if (unlikely(!__pyx_tuple__37)) __PYX_ERR(1, 314, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__37); - __Pyx_GIVEREF(__pyx_tuple__37); + __pyx_tuple__40 = PyTuple_Pack(1, __pyx_kp_s_contiguous_and_direct); if (unlikely(!__pyx_tuple__40)) __PYX_ERR(1, 314, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__40); + __Pyx_GIVEREF(__pyx_tuple__40); /* "View.MemoryView":315 * @@ -30786,272 +32382,311 @@ static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { * * */ - __pyx_tuple__38 = PyTuple_Pack(1, __pyx_kp_s_contiguous_and_indirect); if (unlikely(!__pyx_tuple__38)) __PYX_ERR(1, 315, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__38); - __Pyx_GIVEREF(__pyx_tuple__38); + __pyx_tuple__41 = PyTuple_Pack(1, __pyx_kp_s_contiguous_and_indirect); if (unlikely(!__pyx_tuple__41)) __PYX_ERR(1, 315, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__41); + __Pyx_GIVEREF(__pyx_tuple__41); /* "(tree fragment)":1 * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< * cdef object __pyx_PickleError * cdef object __pyx_result */ - __pyx_tuple__39 = PyTuple_Pack(5, __pyx_n_s_pyx_type, __pyx_n_s_pyx_checksum, __pyx_n_s_pyx_state, __pyx_n_s_pyx_PickleError, __pyx_n_s_pyx_result); if (unlikely(!__pyx_tuple__39)) __PYX_ERR(1, 1, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__39); - __Pyx_GIVEREF(__pyx_tuple__39); - __pyx_codeobj__40 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__39, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_pyx_unpickle_Enum, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__40)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_tuple__42 = PyTuple_Pack(5, __pyx_n_s_pyx_type, __pyx_n_s_pyx_checksum, __pyx_n_s_pyx_state, __pyx_n_s_pyx_PickleError, __pyx_n_s_pyx_result); if (unlikely(!__pyx_tuple__42)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__42); + __Pyx_GIVEREF(__pyx_tuple__42); + __pyx_codeobj__43 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__42, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_pyx_unpickle_Enum, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__43)) __PYX_ERR(1, 1, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":94 + /* "acados_template/acados_ocp_solver_pyx.pyx":89 * * * def __get_pointers_solver(self): # <<<<<<<<<<<<<< * """ * Private function to get the pointers for solver */ - __pyx_tuple__41 = PyTuple_Pack(1, __pyx_n_s_self); if (unlikely(!__pyx_tuple__41)) __PYX_ERR(0, 94, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__41); - __Pyx_GIVEREF(__pyx_tuple__41); - __pyx_codeobj__42 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__41, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_pointers_solver, 94, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__42)) __PYX_ERR(0, 94, __pyx_L1_error) + __pyx_tuple__44 = PyTuple_Pack(1, __pyx_n_s_self); if (unlikely(!__pyx_tuple__44)) __PYX_ERR(0, 89, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__44); + __Pyx_GIVEREF(__pyx_tuple__44); + __pyx_codeobj__45 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__44, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_pointers_solver, 89, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__45)) __PYX_ERR(0, 89, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":108 + /* "acados_template/acados_ocp_solver_pyx.pyx":103 + * + * + * def solve_for_x0(self, x0_bar): # <<<<<<<<<<<<<< + * """ + * Wrapper around `solve()` which sets initial state constraint, solves the OCP, and returns u0. + */ + __pyx_tuple__46 = PyTuple_Pack(4, __pyx_n_s_self, __pyx_n_s_x0_bar, __pyx_n_s_status, __pyx_n_s_u0); if (unlikely(!__pyx_tuple__46)) __PYX_ERR(0, 103, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__46); + __Pyx_GIVEREF(__pyx_tuple__46); + __pyx_codeobj__47 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 4, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__46, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_solve_for_x0, 103, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__47)) __PYX_ERR(0, 103, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":121 * * * def solve(self): # <<<<<<<<<<<<<< * """ * Solve the ocp with current input. */ - __pyx_codeobj__43 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__41, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_solve, 108, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__43)) __PYX_ERR(0, 108, __pyx_L1_error) + __pyx_codeobj__48 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__44, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_solve, 121, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__48)) __PYX_ERR(0, 121, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":115 + /* "acados_template/acados_ocp_solver_pyx.pyx":128 * * - * def reset(self): # <<<<<<<<<<<<<< + * def reset(self, reset_qp_solver_mem=1): # <<<<<<<<<<<<<< * """ * Sets current iterate to all zeros. */ - __pyx_codeobj__44 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__41, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_reset, 115, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__44)) __PYX_ERR(0, 115, __pyx_L1_error) + __pyx_tuple__49 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_reset_qp_solver_mem); if (unlikely(!__pyx_tuple__49)) __PYX_ERR(0, 128, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__49); + __Pyx_GIVEREF(__pyx_tuple__49); + __pyx_codeobj__50 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__49, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_reset, 128, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__50)) __PYX_ERR(0, 128, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":122 + /* "acados_template/acados_ocp_solver_pyx.pyx":135 + * + * + * def custom_update(self, data_): # <<<<<<<<<<<<<< + * """ + * A custom function that can be implemented by a user to be called between solver calls. + */ + __pyx_tuple__51 = PyTuple_Pack(4, __pyx_n_s_self, __pyx_n_s_data, __pyx_n_s_data_len, __pyx_n_s_data_2); if (unlikely(!__pyx_tuple__51)) __PYX_ERR(0, 135, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__51); + __Pyx_GIVEREF(__pyx_tuple__51); + __pyx_codeobj__52 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 4, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__51, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_custom_update, 135, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__52)) __PYX_ERR(0, 135, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":148 * * * def set_new_time_steps(self, new_time_steps): # <<<<<<<<<<<<<< * """ * Set new time steps. */ - __pyx_tuple__45 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_new_time_steps); if (unlikely(!__pyx_tuple__45)) __PYX_ERR(0, 122, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__45); - __Pyx_GIVEREF(__pyx_tuple__45); - __pyx_codeobj__46 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__45, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_set_new_time_steps, 122, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__46)) __PYX_ERR(0, 122, __pyx_L1_error) + __pyx_tuple__53 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_new_time_steps); if (unlikely(!__pyx_tuple__53)) __PYX_ERR(0, 148, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__53); + __Pyx_GIVEREF(__pyx_tuple__53); + __pyx_codeobj__54 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__53, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_set_new_time_steps, 148, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__54)) __PYX_ERR(0, 148, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":173 + /* "acados_template/acados_ocp_solver_pyx.pyx":199 * * * def update_qp_solver_cond_N(self, qp_solver_cond_N: int): # <<<<<<<<<<<<<< * """ * Recreate solver with new value `qp_solver_cond_N` with a partial condensing QP solver. */ - __pyx_tuple__47 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_qp_solver_cond_N); if (unlikely(!__pyx_tuple__47)) __PYX_ERR(0, 173, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__47); - __Pyx_GIVEREF(__pyx_tuple__47); - __pyx_codeobj__48 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__47, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_update_qp_solver_cond_N, 173, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__48)) __PYX_ERR(0, 173, __pyx_L1_error) + __pyx_tuple__55 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_qp_solver_cond_N); if (unlikely(!__pyx_tuple__55)) __PYX_ERR(0, 199, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__55); + __Pyx_GIVEREF(__pyx_tuple__55); + __pyx_codeobj__56 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__55, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_update_qp_solver_cond_N, 199, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__56)) __PYX_ERR(0, 199, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":207 + /* "acados_template/acados_ocp_solver_pyx.pyx":233 * * * def eval_param_sens(self, index, stage=0, field="ex"): # <<<<<<<<<<<<<< * """ * Calculate the sensitivity of the curent solution with respect to the initial state component of index */ - __pyx_tuple__49 = PyTuple_Pack(6, __pyx_n_s_self, __pyx_n_s_index, __pyx_n_s_stage, __pyx_n_s_field, __pyx_n_s_field_2, __pyx_n_s_nx); if (unlikely(!__pyx_tuple__49)) __PYX_ERR(0, 207, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__49); - __Pyx_GIVEREF(__pyx_tuple__49); - __pyx_codeobj__50 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 6, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__49, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_eval_param_sens, 207, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__50)) __PYX_ERR(0, 207, __pyx_L1_error) - __pyx_tuple__51 = PyTuple_Pack(2, __pyx_int_0, __pyx_n_u_ex); if (unlikely(!__pyx_tuple__51)) __PYX_ERR(0, 207, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__51); - __Pyx_GIVEREF(__pyx_tuple__51); + __pyx_tuple__57 = PyTuple_Pack(6, __pyx_n_s_self, __pyx_n_s_index, __pyx_n_s_stage, __pyx_n_s_field, __pyx_n_s_field_2, __pyx_n_s_nx); if (unlikely(!__pyx_tuple__57)) __PYX_ERR(0, 233, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__57); + __Pyx_GIVEREF(__pyx_tuple__57); + __pyx_codeobj__58 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 6, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__57, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_eval_param_sens, 233, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__58)) __PYX_ERR(0, 233, __pyx_L1_error) + __pyx_tuple__59 = PyTuple_Pack(2, __pyx_int_0, __pyx_n_u_ex); if (unlikely(!__pyx_tuple__59)) __PYX_ERR(0, 233, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__59); + __Pyx_GIVEREF(__pyx_tuple__59); - /* "acados_template/acados_ocp_solver_pyx.pyx":232 + /* "acados_template/acados_ocp_solver_pyx.pyx":258 * * * def get(self, int stage, str field_): # <<<<<<<<<<<<<< * """ * Get the last solution of the solver: */ - __pyx_tuple__52 = PyTuple_Pack(7, __pyx_n_s_self, __pyx_n_s_stage, __pyx_n_s_field_2, __pyx_n_s_out_fields, __pyx_n_s_field, __pyx_n_s_dims, __pyx_n_s_out); if (unlikely(!__pyx_tuple__52)) __PYX_ERR(0, 232, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__52); - __Pyx_GIVEREF(__pyx_tuple__52); - __pyx_codeobj__53 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 7, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__52, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get, 232, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__53)) __PYX_ERR(0, 232, __pyx_L1_error) + __pyx_tuple__60 = PyTuple_Pack(7, __pyx_n_s_self, __pyx_n_s_stage, __pyx_n_s_field_2, __pyx_n_s_out_fields, __pyx_n_s_field, __pyx_n_s_dims, __pyx_n_s_out); if (unlikely(!__pyx_tuple__60)) __PYX_ERR(0, 258, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__60); + __Pyx_GIVEREF(__pyx_tuple__60); + __pyx_codeobj__61 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 7, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__60, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get, 258, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__61)) __PYX_ERR(0, 258, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":275 + /* "acados_template/acados_ocp_solver_pyx.pyx":301 * * * def print_statistics(self): # <<<<<<<<<<<<<< * """ * prints statistics of previous solver run as a table: */ - __pyx_codeobj__54 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__41, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_print_statistics, 275, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__54)) __PYX_ERR(0, 275, __pyx_L1_error) + __pyx_codeobj__62 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__44, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_print_statistics, 301, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__62)) __PYX_ERR(0, 301, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":293 + /* "acados_template/acados_ocp_solver_pyx.pyx":319 * * * def store_iterate(self, filename='', overwrite=False): # <<<<<<<<<<<<<< * """ * Stores the current iterate of the ocp solver in a json file. */ - __pyx_tuple__55 = PyTuple_Pack(7, __pyx_n_s_self, __pyx_n_s_filename, __pyx_n_s_overwrite, __pyx_n_s_json, __pyx_n_s_solution, __pyx_n_s_i, __pyx_n_s_f); if (unlikely(!__pyx_tuple__55)) __PYX_ERR(0, 293, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__55); - __Pyx_GIVEREF(__pyx_tuple__55); - __pyx_codeobj__56 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 7, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__55, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_store_iterate, 293, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__56)) __PYX_ERR(0, 293, __pyx_L1_error) - __pyx_tuple__57 = PyTuple_Pack(2, __pyx_kp_u__14, Py_False); if (unlikely(!__pyx_tuple__57)) __PYX_ERR(0, 293, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__57); - __Pyx_GIVEREF(__pyx_tuple__57); + __pyx_tuple__63 = PyTuple_Pack(10, __pyx_n_s_self, __pyx_n_s_filename, __pyx_n_s_overwrite, __pyx_n_s_json, __pyx_n_s_solution, __pyx_n_s_lN, __pyx_n_s_i, __pyx_n_s_i_string, __pyx_n_s_k, __pyx_n_s_f); if (unlikely(!__pyx_tuple__63)) __PYX_ERR(0, 319, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__63); + __Pyx_GIVEREF(__pyx_tuple__63); + __pyx_codeobj__64 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 10, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__63, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_store_iterate, 319, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__64)) __PYX_ERR(0, 319, __pyx_L1_error) + __pyx_tuple__65 = PyTuple_Pack(2, __pyx_kp_u__16, Py_False); if (unlikely(!__pyx_tuple__65)) __PYX_ERR(0, 319, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__65); + __Pyx_GIVEREF(__pyx_tuple__65); - /* "acados_template/acados_ocp_solver_pyx.pyx":330 + /* "acados_template/acados_ocp_solver_pyx.pyx":362 * * * def load_iterate(self, filename): # <<<<<<<<<<<<<< * """ * Loads the iterate stored in json file with filename into the ocp solver. */ - __pyx_tuple__58 = PyTuple_Pack(8, __pyx_n_s_self, __pyx_n_s_filename, __pyx_n_s_json, __pyx_n_s_f, __pyx_n_s_solution, __pyx_n_s_key, __pyx_n_s_field, __pyx_n_s_stage); if (unlikely(!__pyx_tuple__58)) __PYX_ERR(0, 330, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__58); - __Pyx_GIVEREF(__pyx_tuple__58); - __pyx_codeobj__59 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 8, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__58, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_load_iterate, 330, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__59)) __PYX_ERR(0, 330, __pyx_L1_error) + __pyx_tuple__66 = PyTuple_Pack(8, __pyx_n_s_self, __pyx_n_s_filename, __pyx_n_s_json, __pyx_n_s_f, __pyx_n_s_solution, __pyx_n_s_key, __pyx_n_s_field, __pyx_n_s_stage); if (unlikely(!__pyx_tuple__66)) __PYX_ERR(0, 362, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__66); + __Pyx_GIVEREF(__pyx_tuple__66); + __pyx_codeobj__67 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 8, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__66, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_load_iterate, 362, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__67)) __PYX_ERR(0, 362, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":346 + /* "acados_template/acados_ocp_solver_pyx.pyx":378 * * * def get_stats(self, field_): # <<<<<<<<<<<<<< * """ * Get the information of the last solver call. */ - __pyx_tuple__60 = PyTuple_Pack(10, __pyx_n_s_self, __pyx_n_s_field_2, __pyx_n_s_double_fields, __pyx_n_s_fields, __pyx_n_s_field, __pyx_n_s_sqp_iter, __pyx_n_s_stat_m, __pyx_n_s_stat_n, __pyx_n_s_min_size, __pyx_n_s_full_stats); if (unlikely(!__pyx_tuple__60)) __PYX_ERR(0, 346, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__60); - __Pyx_GIVEREF(__pyx_tuple__60); - __pyx_codeobj__61 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 10, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__60, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_stats, 346, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__61)) __PYX_ERR(0, 346, __pyx_L1_error) + __pyx_tuple__68 = PyTuple_Pack(10, __pyx_n_s_self, __pyx_n_s_field_2, __pyx_n_s_double_fields, __pyx_n_s_fields, __pyx_n_s_field, __pyx_n_s_sqp_iter, __pyx_n_s_stat_m, __pyx_n_s_stat_n, __pyx_n_s_min_size, __pyx_n_s_full_stats); if (unlikely(!__pyx_tuple__68)) __PYX_ERR(0, 378, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__68); + __Pyx_GIVEREF(__pyx_tuple__68); + __pyx_codeobj__69 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 10, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__68, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_stats, 378, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__69)) __PYX_ERR(0, 378, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":428 + /* "acados_template/acados_ocp_solver_pyx.pyx":460 * * * def __get_stat_int(self, field): # <<<<<<<<<<<<<< * cdef int out * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &out) */ - __pyx_tuple__62 = PyTuple_Pack(3, __pyx_n_s_self, __pyx_n_s_field, __pyx_n_s_out); if (unlikely(!__pyx_tuple__62)) __PYX_ERR(0, 428, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__62); - __Pyx_GIVEREF(__pyx_tuple__62); - __pyx_codeobj__63 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__62, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_stat_int, 428, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__63)) __PYX_ERR(0, 428, __pyx_L1_error) + __pyx_tuple__70 = PyTuple_Pack(3, __pyx_n_s_self, __pyx_n_s_field, __pyx_n_s_out); if (unlikely(!__pyx_tuple__70)) __PYX_ERR(0, 460, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__70); + __Pyx_GIVEREF(__pyx_tuple__70); + __pyx_codeobj__71 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__70, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_stat_int, 460, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__71)) __PYX_ERR(0, 460, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":433 + /* "acados_template/acados_ocp_solver_pyx.pyx":465 * return out * * def __get_stat_double(self, field): # <<<<<<<<<<<<<< * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) */ - __pyx_codeobj__64 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__62, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_stat_double, 433, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__64)) __PYX_ERR(0, 433, __pyx_L1_error) + __pyx_codeobj__72 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__70, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_stat_double, 465, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__72)) __PYX_ERR(0, 465, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":438 + /* "acados_template/acados_ocp_solver_pyx.pyx":470 * return out * * def __get_stat_matrix(self, field, n, m): # <<<<<<<<<<<<<< * cdef cnp.ndarray[cnp.float64_t, ndim=2] out_mat = np.ascontiguousarray(np.zeros((n, m)), dtype=np.float64) * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_mat.data) */ - __pyx_tuple__65 = PyTuple_Pack(5, __pyx_n_s_self, __pyx_n_s_field, __pyx_n_s_n, __pyx_n_s_m, __pyx_n_s_out_mat); if (unlikely(!__pyx_tuple__65)) __PYX_ERR(0, 438, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__65); - __Pyx_GIVEREF(__pyx_tuple__65); - __pyx_codeobj__66 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__65, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_stat_matrix, 438, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__66)) __PYX_ERR(0, 438, __pyx_L1_error) + __pyx_tuple__73 = PyTuple_Pack(5, __pyx_n_s_self, __pyx_n_s_field, __pyx_n_s_n, __pyx_n_s_m, __pyx_n_s_out_mat); if (unlikely(!__pyx_tuple__73)) __PYX_ERR(0, 470, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__73); + __Pyx_GIVEREF(__pyx_tuple__73); + __pyx_codeobj__74 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__73, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_stat_matrix, 470, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__74)) __PYX_ERR(0, 470, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":444 + /* "acados_template/acados_ocp_solver_pyx.pyx":476 * * * def get_cost(self): # <<<<<<<<<<<<<< * """ * Returns the cost value of the current solution. */ - __pyx_tuple__67 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_out); if (unlikely(!__pyx_tuple__67)) __PYX_ERR(0, 444, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__67); - __Pyx_GIVEREF(__pyx_tuple__67); - __pyx_codeobj__68 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__67, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_cost, 444, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__68)) __PYX_ERR(0, 444, __pyx_L1_error) + __pyx_tuple__75 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_out); if (unlikely(!__pyx_tuple__75)) __PYX_ERR(0, 476, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__75); + __Pyx_GIVEREF(__pyx_tuple__75); + __pyx_codeobj__76 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__75, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_cost, 476, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__76)) __PYX_ERR(0, 476, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":460 + /* "acados_template/acados_ocp_solver_pyx.pyx":492 * * * def get_residuals(self, recompute=False): # <<<<<<<<<<<<<< * """ * Returns an array of the form [res_stat, res_eq, res_ineq, res_comp]. */ - __pyx_tuple__69 = PyTuple_Pack(5, __pyx_n_s_self, __pyx_n_s_recompute, __pyx_n_s_out, __pyx_n_s_double_value, __pyx_n_s_field); if (unlikely(!__pyx_tuple__69)) __PYX_ERR(0, 460, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__69); - __Pyx_GIVEREF(__pyx_tuple__69); - __pyx_codeobj__70 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__69, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_residuals, 460, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__70)) __PYX_ERR(0, 460, __pyx_L1_error) - __pyx_tuple__71 = PyTuple_Pack(1, Py_False); if (unlikely(!__pyx_tuple__71)) __PYX_ERR(0, 460, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__71); - __Pyx_GIVEREF(__pyx_tuple__71); + __pyx_tuple__77 = PyTuple_Pack(5, __pyx_n_s_self, __pyx_n_s_recompute, __pyx_n_s_out, __pyx_n_s_double_value, __pyx_n_s_field); if (unlikely(!__pyx_tuple__77)) __PYX_ERR(0, 492, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__77); + __Pyx_GIVEREF(__pyx_tuple__77); + __pyx_codeobj__78 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__77, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_residuals, 492, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__78)) __PYX_ERR(0, 492, __pyx_L1_error) + __pyx_tuple__79 = PyTuple_Pack(1, Py_False); if (unlikely(!__pyx_tuple__79)) __PYX_ERR(0, 492, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__79); + __Pyx_GIVEREF(__pyx_tuple__79); - /* "acados_template/acados_ocp_solver_pyx.pyx":492 + /* "acados_template/acados_ocp_solver_pyx.pyx":524 * * # Note: this function should not be used anymore, better use cost_set, constraints_set * def set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< * * """ */ - __pyx_tuple__72 = PyTuple_Pack(12, __pyx_n_s_self, __pyx_n_s_stage, __pyx_n_s_field_2, __pyx_n_s_value, __pyx_n_s_cost_fields, __pyx_n_s_constraints_fields, __pyx_n_s_out_fields, __pyx_n_s_mem_fields, __pyx_n_s_field, __pyx_n_s_value_2, __pyx_n_s_dims, __pyx_n_s_msg); if (unlikely(!__pyx_tuple__72)) __PYX_ERR(0, 492, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__72); - __Pyx_GIVEREF(__pyx_tuple__72); - __pyx_codeobj__73 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 12, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__72, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_set, 492, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__73)) __PYX_ERR(0, 492, __pyx_L1_error) + __pyx_tuple__80 = PyTuple_Pack(12, __pyx_n_s_self, __pyx_n_s_stage, __pyx_n_s_field_2, __pyx_n_s_value, __pyx_n_s_cost_fields, __pyx_n_s_constraints_fields, __pyx_n_s_out_fields, __pyx_n_s_mem_fields, __pyx_n_s_field, __pyx_n_s_value_2, __pyx_n_s_dims, __pyx_n_s_msg); if (unlikely(!__pyx_tuple__80)) __PYX_ERR(0, 524, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__80); + __Pyx_GIVEREF(__pyx_tuple__80); + __pyx_codeobj__81 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 12, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__80, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_set, 524, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__81)) __PYX_ERR(0, 524, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":551 - * + /* "acados_template/acados_ocp_solver_pyx.pyx":590 + * return * * def cost_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< * """ * Set numerical data in the cost module of the solver. */ - __pyx_tuple__74 = PyTuple_Pack(8, __pyx_n_s_self, __pyx_n_s_stage, __pyx_n_s_field_2, __pyx_n_s_value, __pyx_n_s_field, __pyx_n_s_dims, __pyx_n_s_value_2, __pyx_n_s_value_shape); if (unlikely(!__pyx_tuple__74)) __PYX_ERR(0, 551, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__74); - __Pyx_GIVEREF(__pyx_tuple__74); - __pyx_codeobj__75 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 8, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__74, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_cost_set, 551, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__75)) __PYX_ERR(0, 551, __pyx_L1_error) + __pyx_tuple__82 = PyTuple_Pack(8, __pyx_n_s_self, __pyx_n_s_stage, __pyx_n_s_field_2, __pyx_n_s_value, __pyx_n_s_field, __pyx_n_s_dims, __pyx_n_s_value_2, __pyx_n_s_value_shape); if (unlikely(!__pyx_tuple__82)) __PYX_ERR(0, 590, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__82); + __Pyx_GIVEREF(__pyx_tuple__82); + __pyx_codeobj__83 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 8, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__82, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_cost_set, 590, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__83)) __PYX_ERR(0, 590, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":584 + /* "acados_template/acados_ocp_solver_pyx.pyx":625 * * * def constraints_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< * """ * Set numerical data in the constraint module of the solver. */ - __pyx_codeobj__76 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 8, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__74, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_constraints_set, 584, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__76)) __PYX_ERR(0, 584, __pyx_L1_error) + __pyx_codeobj__84 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 8, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__82, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_constraints_set, 625, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__84)) __PYX_ERR(0, 625, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":619 + /* "acados_template/acados_ocp_solver_pyx.pyx":663 * * - * def dynamics_get(self, int stage, str field_): # <<<<<<<<<<<<<< + * def get_from_qp_in(self, int stage, str field_): # <<<<<<<<<<<<<< * """ * Get numerical data from the dynamics module of the solver: */ - __pyx_tuple__77 = PyTuple_Pack(6, __pyx_n_s_self, __pyx_n_s_stage, __pyx_n_s_field_2, __pyx_n_s_field, __pyx_n_s_dims, __pyx_n_s_out); if (unlikely(!__pyx_tuple__77)) __PYX_ERR(0, 619, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__77); - __Pyx_GIVEREF(__pyx_tuple__77); - __pyx_codeobj__78 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 6, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__77, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_dynamics_get, 619, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__78)) __PYX_ERR(0, 619, __pyx_L1_error) + __pyx_tuple__85 = PyTuple_Pack(6, __pyx_n_s_self, __pyx_n_s_stage, __pyx_n_s_field_2, __pyx_n_s_field, __pyx_n_s_dims, __pyx_n_s_out); if (unlikely(!__pyx_tuple__85)) __PYX_ERR(0, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__85); + __Pyx_GIVEREF(__pyx_tuple__85); + __pyx_codeobj__86 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 6, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__85, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_from_qp_in, 663, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__86)) __PYX_ERR(0, 663, __pyx_L1_error) - /* "acados_template/acados_ocp_solver_pyx.pyx":641 + /* "acados_template/acados_ocp_solver_pyx.pyx":685 * * * def options_set(self, str field_, value_): # <<<<<<<<<<<<<< * """ * Set options of the solver. */ - __pyx_tuple__79 = PyTuple_Pack(10, __pyx_n_s_self, __pyx_n_s_field_2, __pyx_n_s_value, __pyx_n_s_int_fields, __pyx_n_s_double_fields, __pyx_n_s_string_fields, __pyx_n_s_field, __pyx_n_s_int_value, __pyx_n_s_double_value, __pyx_n_s_string_value); if (unlikely(!__pyx_tuple__79)) __PYX_ERR(0, 641, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__79); - __Pyx_GIVEREF(__pyx_tuple__79); - __pyx_codeobj__80 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 10, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__79, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_options_set, 641, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__80)) __PYX_ERR(0, 641, __pyx_L1_error) + __pyx_tuple__87 = PyTuple_Pack(10, __pyx_n_s_self, __pyx_n_s_field_2, __pyx_n_s_value, __pyx_n_s_int_fields, __pyx_n_s_double_fields, __pyx_n_s_string_fields, __pyx_n_s_field, __pyx_n_s_int_value, __pyx_n_s_double_value, __pyx_n_s_string_value); if (unlikely(!__pyx_tuple__87)) __PYX_ERR(0, 685, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__87); + __Pyx_GIVEREF(__pyx_tuple__87); + __pyx_codeobj__88 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 10, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__87, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_options_set, 685, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__88)) __PYX_ERR(0, 685, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":748 + * + * + * def set_params_sparse(self, int stage, idx_values_, param_values_): # <<<<<<<<<<<<<< + * """ + * set parameters of the solvers external function partially: + */ + __pyx_tuple__89 = PyTuple_Pack(7, __pyx_n_s_self, __pyx_n_s_stage, __pyx_n_s_idx_values, __pyx_n_s_param_values, __pyx_n_s_value_2, __pyx_n_s_idx, __pyx_n_s_n_update); if (unlikely(!__pyx_tuple__89)) __PYX_ERR(0, 748, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__89); + __Pyx_GIVEREF(__pyx_tuple__89); + __pyx_codeobj__90 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 7, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__89, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_set_params_sparse, 748, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__90)) __PYX_ERR(0, 748, __pyx_L1_error) /* "(tree fragment)":1 * def __reduce_cython__(self): # <<<<<<<<<<<<<< * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" * def __setstate_cython__(self, __pyx_state): */ - __pyx_codeobj__81 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__41, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__81)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_codeobj__91 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__44, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__91)) __PYX_ERR(1, 1, __pyx_L1_error) /* "(tree fragment)":3 * def __reduce_cython__(self): @@ -31059,10 +32694,10 @@ static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" */ - __pyx_tuple__82 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_pyx_state); if (unlikely(!__pyx_tuple__82)) __PYX_ERR(1, 3, __pyx_L1_error) - __Pyx_GOTREF(__pyx_tuple__82); - __Pyx_GIVEREF(__pyx_tuple__82); - __pyx_codeobj__83 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__82, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__83)) __PYX_ERR(1, 3, __pyx_L1_error) + __pyx_tuple__92 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_pyx_state); if (unlikely(!__pyx_tuple__92)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__92); + __Pyx_GIVEREF(__pyx_tuple__92); + __pyx_codeobj__93 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__92, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__93)) __PYX_ERR(1, 3, __pyx_L1_error) __Pyx_RefNannyFinishContext(); return 0; __pyx_L1_error:; @@ -31072,6 +32707,8 @@ static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { /* #### Code section: init_constants ### */ static CYTHON_SMALL_CODE int __Pyx_InitConstants(void) { + __pyx_umethod_PyDict_Type_keys.type = (PyObject*)&PyDict_Type; + __pyx_umethod_PyDict_Type_keys.method_name = &__pyx_n_s_keys; if (__Pyx_CreateStringTabAndInitStrings() < 0) __PYX_ERR(0, 1, __pyx_L1_error); __pyx_int_0 = PyInt_FromLong(0); if (unlikely(!__pyx_int_0)) __PYX_ERR(0, 1, __pyx_L1_error) __pyx_int_1 = PyInt_FromLong(1); if (unlikely(!__pyx_int_1)) __PYX_ERR(0, 1, __pyx_L1_error) @@ -31169,15 +32806,15 @@ static int __Pyx_modinit_type_init_code(void) { __Pyx_RefNannySetupContext("__Pyx_modinit_type_init_code", 0); /*--- Type init code ---*/ #if CYTHON_USE_TYPE_SPECS - __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython_spec, NULL); if (unlikely(!__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython)) __PYX_ERR(0, 52, __pyx_L1_error) - if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython_spec, __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython) < 0) __PYX_ERR(0, 52, __pyx_L1_error) + __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython_spec, NULL); if (unlikely(!__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython)) __PYX_ERR(0, 49, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython_spec, __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython) < 0) __PYX_ERR(0, 49, __pyx_L1_error) #else __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython = &__pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython; #endif #if !CYTHON_COMPILING_IN_LIMITED_API #endif #if !CYTHON_USE_TYPE_SPECS - if (__Pyx_PyType_Ready(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython) < 0) __PYX_ERR(0, 52, __pyx_L1_error) + if (__Pyx_PyType_Ready(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython) < 0) __PYX_ERR(0, 49, __pyx_L1_error) #endif #if PY_MAJOR_VERSION < 3 __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_print = 0; @@ -31187,9 +32824,9 @@ static int __Pyx_modinit_type_init_code(void) { __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_getattro = __Pyx_PyObject_GenericGetAttr; } #endif - if (PyObject_SetAttr(__pyx_m, __pyx_n_s_AcadosOcpSolverCython, (PyObject *) __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython) < 0) __PYX_ERR(0, 52, __pyx_L1_error) + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_AcadosOcpSolverCython, (PyObject *) __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython) < 0) __PYX_ERR(0, 49, __pyx_L1_error) #if !CYTHON_COMPILING_IN_LIMITED_API - if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython) < 0) __PYX_ERR(0, 52, __pyx_L1_error) + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython) < 0) __PYX_ERR(0, 49, __pyx_L1_error) #endif __pyx_vtabptr_array = &__pyx_vtable_array; __pyx_vtable_array.get_memview = (PyObject *(*)(struct __pyx_array_obj *))__pyx_array_get_memview; @@ -31710,12 +33347,12 @@ if (!__Pyx_RefNanny) { * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence * else: */ - __pyx_t_4 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__30, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 100, __pyx_L2_error) + __pyx_t_4 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__33, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 100, __pyx_L2_error) __Pyx_GOTREF(__pyx_t_4); __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_version_info); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 100, __pyx_L2_error) __Pyx_GOTREF(__pyx_t_5); __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - __pyx_t_4 = PyObject_RichCompare(__pyx_t_5, __pyx_tuple__31, Py_GE); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 100, __pyx_L2_error) + __pyx_t_4 = PyObject_RichCompare(__pyx_t_5, __pyx_tuple__34, Py_GE); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 100, __pyx_L2_error) __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; __pyx_t_6 = __Pyx_PyObject_IsTrue(__pyx_t_4); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(1, 100, __pyx_L2_error) __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; @@ -31728,7 +33365,7 @@ if (!__Pyx_RefNanny) { * else: * __pyx_collections_abc_Sequence = __import__("collections").Sequence */ - __pyx_t_4 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__32, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 101, __pyx_L2_error) + __pyx_t_4 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__35, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 101, __pyx_L2_error) __Pyx_GOTREF(__pyx_t_4); __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_abc); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 101, __pyx_L2_error) __Pyx_GOTREF(__pyx_t_5); @@ -31759,7 +33396,7 @@ if (!__Pyx_RefNanny) { * */ /*else*/ { - __pyx_t_4 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__33, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 103, __pyx_L2_error) + __pyx_t_4 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__36, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 103, __pyx_L2_error) __Pyx_GOTREF(__pyx_t_4); __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_Sequence); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 103, __pyx_L2_error) __Pyx_GOTREF(__pyx_t_5); @@ -31924,7 +33561,7 @@ if (!__Pyx_RefNanny) { * cdef strided = Enum("") # default * cdef indirect = Enum("") */ - __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__34, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 309, __pyx_L1_error) + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__37, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 309, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); __Pyx_XGOTREF(generic); __Pyx_DECREF_SET(generic, __pyx_t_7); @@ -31938,7 +33575,7 @@ if (!__Pyx_RefNanny) { * cdef indirect = Enum("") * */ - __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__35, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 310, __pyx_L1_error) + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__38, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 310, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); __Pyx_XGOTREF(strided); __Pyx_DECREF_SET(strided, __pyx_t_7); @@ -31952,7 +33589,7 @@ if (!__Pyx_RefNanny) { * * */ - __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__36, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 311, __pyx_L1_error) + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__39, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 311, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); __Pyx_XGOTREF(indirect); __Pyx_DECREF_SET(indirect, __pyx_t_7); @@ -31966,7 +33603,7 @@ if (!__Pyx_RefNanny) { * cdef indirect_contiguous = Enum("") * */ - __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__37, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 314, __pyx_L1_error) + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__40, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 314, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); __Pyx_XGOTREF(contiguous); __Pyx_DECREF_SET(contiguous, __pyx_t_7); @@ -31980,7 +33617,7 @@ if (!__Pyx_RefNanny) { * * */ - __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__38, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 315, __pyx_L1_error) + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__41, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 315, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); __Pyx_XGOTREF(indirect_contiguous); __Pyx_DECREF_SET(indirect_contiguous, __pyx_t_7); @@ -32200,329 +33837,369 @@ if (!__Pyx_RefNanny) { if (PyDict_SetItem(__pyx_d, __pyx_n_s_pyx_unpickle_Enum, __pyx_t_7) < 0) __PYX_ERR(1, 1, __pyx_L1_error) __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":47 + /* "acados_template/acados_ocp_solver_pyx.pyx":44 * cimport numpy as cnp * * import os # <<<<<<<<<<<<<< * from datetime import datetime * import numpy as np */ - __pyx_t_7 = __Pyx_ImportDottedModule(__pyx_n_s_os, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 47, __pyx_L1_error) + __pyx_t_7 = __Pyx_ImportDottedModule(__pyx_n_s_os, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 44, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); - if (PyDict_SetItem(__pyx_d, __pyx_n_s_os, __pyx_t_7) < 0) __PYX_ERR(0, 47, __pyx_L1_error) + if (PyDict_SetItem(__pyx_d, __pyx_n_s_os, __pyx_t_7) < 0) __PYX_ERR(0, 44, __pyx_L1_error) __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":48 + /* "acados_template/acados_ocp_solver_pyx.pyx":45 * * import os * from datetime import datetime # <<<<<<<<<<<<<< * import numpy as np * */ - __pyx_t_7 = PyList_New(1); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 48, __pyx_L1_error) + __pyx_t_7 = PyList_New(1); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 45, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); __Pyx_INCREF(__pyx_n_s_datetime); __Pyx_GIVEREF(__pyx_n_s_datetime); PyList_SET_ITEM(__pyx_t_7, 0, __pyx_n_s_datetime); - __pyx_t_4 = __Pyx_Import(__pyx_n_s_datetime, __pyx_t_7, 0); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 48, __pyx_L1_error) + __pyx_t_4 = __Pyx_Import(__pyx_n_s_datetime, __pyx_t_7, 0); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 45, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - __pyx_t_7 = __Pyx_ImportFrom(__pyx_t_4, __pyx_n_s_datetime); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 48, __pyx_L1_error) + __pyx_t_7 = __Pyx_ImportFrom(__pyx_t_4, __pyx_n_s_datetime); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 45, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); - if (PyDict_SetItem(__pyx_d, __pyx_n_s_datetime, __pyx_t_7) < 0) __PYX_ERR(0, 48, __pyx_L1_error) + if (PyDict_SetItem(__pyx_d, __pyx_n_s_datetime, __pyx_t_7) < 0) __PYX_ERR(0, 45, __pyx_L1_error) __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":49 + /* "acados_template/acados_ocp_solver_pyx.pyx":46 * import os * from datetime import datetime * import numpy as np # <<<<<<<<<<<<<< * * */ - __pyx_t_4 = __Pyx_ImportDottedModule(__pyx_n_s_numpy, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 49, __pyx_L1_error) + __pyx_t_4 = __Pyx_ImportDottedModule(__pyx_n_s_numpy, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 46, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); - if (PyDict_SetItem(__pyx_d, __pyx_n_s_np, __pyx_t_4) < 0) __PYX_ERR(0, 49, __pyx_L1_error) + if (PyDict_SetItem(__pyx_d, __pyx_n_s_np, __pyx_t_4) < 0) __PYX_ERR(0, 46, __pyx_L1_error) __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - /* "acados_template/acados_ocp_solver_pyx.pyx":94 + /* "acados_template/acados_ocp_solver_pyx.pyx":89 * * * def __get_pointers_solver(self): # <<<<<<<<<<<<<< * """ * Private function to get the pointers for solver */ - __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_3_AcadosOcpSolverCython__get_pointers_solver, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___get_poin, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__42)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 94, __pyx_L1_error) + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_3_AcadosOcpSolverCython__get_pointers_solver, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___get_poin, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__45)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 89, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); - if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_AcadosOcpSolverCython__get_poin, __pyx_t_4) < 0) __PYX_ERR(0, 94, __pyx_L1_error) + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_AcadosOcpSolverCython__get_poin, __pyx_t_4) < 0) __PYX_ERR(0, 89, __pyx_L1_error) __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); - /* "acados_template/acados_ocp_solver_pyx.pyx":108 + /* "acados_template/acados_ocp_solver_pyx.pyx":103 + * + * + * def solve_for_x0(self, x0_bar): # <<<<<<<<<<<<<< + * """ + * Wrapper around `solve()` which sets initial state constraint, solves the OCP, and returns u0. + */ + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve_for_x0, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_solve_for, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__47)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 103, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_solve_for_x0, __pyx_t_4) < 0) __PYX_ERR(0, 103, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":121 * * * def solve(self): # <<<<<<<<<<<<<< * """ * Solve the ocp with current input. */ - __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_solve, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__43)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 108, __pyx_L1_error) + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7solve, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_solve, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__48)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 121, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); - if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_solve, __pyx_t_4) < 0) __PYX_ERR(0, 108, __pyx_L1_error) + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_solve, __pyx_t_4) < 0) __PYX_ERR(0, 121, __pyx_L1_error) __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); - /* "acados_template/acados_ocp_solver_pyx.pyx":115 + /* "acados_template/acados_ocp_solver_pyx.pyx":128 * * - * def reset(self): # <<<<<<<<<<<<<< + * def reset(self, reset_qp_solver_mem=1): # <<<<<<<<<<<<<< * """ * Sets current iterate to all zeros. */ - __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7reset, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_reset, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__44)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 115, __pyx_L1_error) + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9reset, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_reset, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__50)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 128, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); - if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_reset, __pyx_t_4) < 0) __PYX_ERR(0, 115, __pyx_L1_error) + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_4, __pyx_tuple__25); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_reset, __pyx_t_4) < 0) __PYX_ERR(0, 128, __pyx_L1_error) __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); - /* "acados_template/acados_ocp_solver_pyx.pyx":122 + /* "acados_template/acados_ocp_solver_pyx.pyx":135 + * + * + * def custom_update(self, data_): # <<<<<<<<<<<<<< + * """ + * A custom function that can be implemented by a user to be called between solver calls. + */ + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11custom_update, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_custom_upd, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__52)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 135, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_custom_update, __pyx_t_4) < 0) __PYX_ERR(0, 135, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":148 * * * def set_new_time_steps(self, new_time_steps): # <<<<<<<<<<<<<< * """ * Set new time steps. */ - __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9set_new_time_steps, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_set_new_ti, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__46)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 122, __pyx_L1_error) + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13set_new_time_steps, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_set_new_ti, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__54)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 148, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); - if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_set_new_time_steps, __pyx_t_4) < 0) __PYX_ERR(0, 122, __pyx_L1_error) + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_set_new_time_steps, __pyx_t_4) < 0) __PYX_ERR(0, 148, __pyx_L1_error) __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); - /* "acados_template/acados_ocp_solver_pyx.pyx":173 + /* "acados_template/acados_ocp_solver_pyx.pyx":199 * * * def update_qp_solver_cond_N(self, qp_solver_cond_N: int): # <<<<<<<<<<<<<< * """ * Recreate solver with new value `qp_solver_cond_N` with a partial condensing QP solver. */ - __pyx_t_4 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 173, __pyx_L1_error) + __pyx_t_4 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 199, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_4); - if (PyDict_SetItem(__pyx_t_4, __pyx_n_s_qp_solver_cond_N, __pyx_n_s_int) < 0) __PYX_ERR(0, 173, __pyx_L1_error) - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11update_qp_solver_cond_N, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_update_qp, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__48)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 173, __pyx_L1_error) + if (PyDict_SetItem(__pyx_t_4, __pyx_n_s_qp_solver_cond_N, __pyx_n_s_int) < 0) __PYX_ERR(0, 199, __pyx_L1_error) + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15update_qp_solver_cond_N, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_update_qp, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__56)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 199, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); __Pyx_CyFunction_SetAnnotationsDict(__pyx_t_7, __pyx_t_4); __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; - if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_update_qp_solver_cond_N, __pyx_t_7) < 0) __PYX_ERR(0, 173, __pyx_L1_error) + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_update_qp_solver_cond_N, __pyx_t_7) < 0) __PYX_ERR(0, 199, __pyx_L1_error) __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); - /* "acados_template/acados_ocp_solver_pyx.pyx":207 + /* "acados_template/acados_ocp_solver_pyx.pyx":233 * * * def eval_param_sens(self, index, stage=0, field="ex"): # <<<<<<<<<<<<<< * """ * Calculate the sensitivity of the curent solution with respect to the initial state component of index */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13eval_param_sens, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_eval_param_3, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__50)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 207, __pyx_L1_error) + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17eval_param_sens, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_eval_param_3, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__58)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 233, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); - __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_7, __pyx_tuple__51); - if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_eval_param_sens, __pyx_t_7) < 0) __PYX_ERR(0, 207, __pyx_L1_error) + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_7, __pyx_tuple__59); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_eval_param_sens, __pyx_t_7) < 0) __PYX_ERR(0, 233, __pyx_L1_error) __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); - /* "acados_template/acados_ocp_solver_pyx.pyx":232 + /* "acados_template/acados_ocp_solver_pyx.pyx":258 * * * def get(self, int stage, str field_): # <<<<<<<<<<<<<< * """ * Get the last solution of the solver: */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15get, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_get, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__53)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 232, __pyx_L1_error) + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19get, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_get, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__61)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 258, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); - if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_get, __pyx_t_7) < 0) __PYX_ERR(0, 232, __pyx_L1_error) + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_get, __pyx_t_7) < 0) __PYX_ERR(0, 258, __pyx_L1_error) __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); - /* "acados_template/acados_ocp_solver_pyx.pyx":275 + /* "acados_template/acados_ocp_solver_pyx.pyx":301 * * * def print_statistics(self): # <<<<<<<<<<<<<< * """ * prints statistics of previous solver run as a table: */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17print_statistics, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_print_stat, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__54)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 275, __pyx_L1_error) + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21print_statistics, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_print_stat, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__62)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 301, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); - if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_print_statistics, __pyx_t_7) < 0) __PYX_ERR(0, 275, __pyx_L1_error) + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_print_statistics, __pyx_t_7) < 0) __PYX_ERR(0, 301, __pyx_L1_error) __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); - /* "acados_template/acados_ocp_solver_pyx.pyx":293 + /* "acados_template/acados_ocp_solver_pyx.pyx":319 * * * def store_iterate(self, filename='', overwrite=False): # <<<<<<<<<<<<<< * """ * Stores the current iterate of the ocp solver in a json file. */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19store_iterate, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_store_iter, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__56)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 293, __pyx_L1_error) + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23store_iterate, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_store_iter, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__64)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 319, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); - __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_7, __pyx_tuple__57); - if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_store_iterate, __pyx_t_7) < 0) __PYX_ERR(0, 293, __pyx_L1_error) + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_7, __pyx_tuple__65); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_store_iterate, __pyx_t_7) < 0) __PYX_ERR(0, 319, __pyx_L1_error) __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); - /* "acados_template/acados_ocp_solver_pyx.pyx":330 + /* "acados_template/acados_ocp_solver_pyx.pyx":362 * * * def load_iterate(self, filename): # <<<<<<<<<<<<<< * """ * Loads the iterate stored in json file with filename into the ocp solver. */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21load_iterate, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_load_itera, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__59)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 330, __pyx_L1_error) + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25load_iterate, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_load_itera, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__67)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 362, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); - if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_load_iterate, __pyx_t_7) < 0) __PYX_ERR(0, 330, __pyx_L1_error) + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_load_iterate, __pyx_t_7) < 0) __PYX_ERR(0, 362, __pyx_L1_error) __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); - /* "acados_template/acados_ocp_solver_pyx.pyx":346 + /* "acados_template/acados_ocp_solver_pyx.pyx":378 * * * def get_stats(self, field_): # <<<<<<<<<<<<<< * """ * Get the information of the last solver call. */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23get_stats, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_get_stats, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__61)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 346, __pyx_L1_error) + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27get_stats, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_get_stats, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__69)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 378, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); - if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_get_stats, __pyx_t_7) < 0) __PYX_ERR(0, 346, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); - - /* "acados_template/acados_ocp_solver_pyx.pyx":428 - * - * - * def __get_stat_int(self, field): # <<<<<<<<<<<<<< - * cdef int out - * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &out) - */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25_AcadosOcpSolverCython__get_stat_int, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___get_stat, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__63)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 428, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_AcadosOcpSolverCython__get_stat, __pyx_t_7) < 0) __PYX_ERR(0, 428, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); - - /* "acados_template/acados_ocp_solver_pyx.pyx":433 - * return out - * - * def __get_stat_double(self, field): # <<<<<<<<<<<<<< - * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) - * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) - */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27_AcadosOcpSolverCython__get_stat_double, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___get_stat_2, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__64)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 433, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_AcadosOcpSolverCython__get_stat_2, __pyx_t_7) < 0) __PYX_ERR(0, 433, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); - - /* "acados_template/acados_ocp_solver_pyx.pyx":438 - * return out - * - * def __get_stat_matrix(self, field, n, m): # <<<<<<<<<<<<<< - * cdef cnp.ndarray[cnp.float64_t, ndim=2] out_mat = np.ascontiguousarray(np.zeros((n, m)), dtype=np.float64) - * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_mat.data) - */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_matrix, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___get_stat_3, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__66)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 438, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_AcadosOcpSolverCython__get_stat_3, __pyx_t_7) < 0) __PYX_ERR(0, 438, __pyx_L1_error) - __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; - PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); - - /* "acados_template/acados_ocp_solver_pyx.pyx":444 - * - * - * def get_cost(self): # <<<<<<<<<<<<<< - * """ - * Returns the cost value of the current solution. - */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31get_cost, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_get_cost, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__68)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 444, __pyx_L1_error) - __Pyx_GOTREF(__pyx_t_7); - if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_get_cost, __pyx_t_7) < 0) __PYX_ERR(0, 444, __pyx_L1_error) + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_get_stats, __pyx_t_7) < 0) __PYX_ERR(0, 378, __pyx_L1_error) __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); /* "acados_template/acados_ocp_solver_pyx.pyx":460 * * - * def get_residuals(self, recompute=False): # <<<<<<<<<<<<<< - * """ - * Returns an array of the form [res_stat, res_eq, res_ineq, res_comp]. + * def __get_stat_int(self, field): # <<<<<<<<<<<<<< + * cdef int out + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &out) */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33get_residuals, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_get_residu, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__70)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 460, __pyx_L1_error) + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_int, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___get_stat, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__71)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 460, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); - __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_7, __pyx_tuple__71); - if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_get_residuals, __pyx_t_7) < 0) __PYX_ERR(0, 460, __pyx_L1_error) + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_AcadosOcpSolverCython__get_stat, __pyx_t_7) < 0) __PYX_ERR(0, 460, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":465 + * return out + * + * def __get_stat_double(self, field): # <<<<<<<<<<<<<< + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31_AcadosOcpSolverCython__get_stat_double, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___get_stat_2, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__72)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 465, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_AcadosOcpSolverCython__get_stat_2, __pyx_t_7) < 0) __PYX_ERR(0, 465, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":470 + * return out + * + * def __get_stat_matrix(self, field, n, m): # <<<<<<<<<<<<<< + * cdef cnp.ndarray[cnp.float64_t, ndim=2] out_mat = np.ascontiguousarray(np.zeros((n, m)), dtype=np.float64) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_mat.data) + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33_AcadosOcpSolverCython__get_stat_matrix, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___get_stat_3, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__74)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 470, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_AcadosOcpSolverCython__get_stat_3, __pyx_t_7) < 0) __PYX_ERR(0, 470, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":476 + * + * + * def get_cost(self): # <<<<<<<<<<<<<< + * """ + * Returns the cost value of the current solution. + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35get_cost, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_get_cost, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__76)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 476, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_get_cost, __pyx_t_7) < 0) __PYX_ERR(0, 476, __pyx_L1_error) __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); /* "acados_template/acados_ocp_solver_pyx.pyx":492 * + * + * def get_residuals(self, recompute=False): # <<<<<<<<<<<<<< + * """ + * Returns an array of the form [res_stat, res_eq, res_ineq, res_comp]. + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37get_residuals, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_get_residu, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__78)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 492, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_7, __pyx_tuple__79); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_get_residuals, __pyx_t_7) < 0) __PYX_ERR(0, 492, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":524 + * * # Note: this function should not be used anymore, better use cost_set, constraints_set * def set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< * * """ */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35set, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_set, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__73)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 492, __pyx_L1_error) + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39set, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_set, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__81)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 524, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); - if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_set, __pyx_t_7) < 0) __PYX_ERR(0, 492, __pyx_L1_error) + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_set, __pyx_t_7) < 0) __PYX_ERR(0, 524, __pyx_L1_error) __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); - /* "acados_template/acados_ocp_solver_pyx.pyx":551 - * + /* "acados_template/acados_ocp_solver_pyx.pyx":590 + * return * * def cost_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< * """ * Set numerical data in the cost module of the solver. */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37cost_set, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_cost_set, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__75)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 551, __pyx_L1_error) + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41cost_set, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_cost_set, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__83)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 590, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); - if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_cost_set, __pyx_t_7) < 0) __PYX_ERR(0, 551, __pyx_L1_error) + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_cost_set, __pyx_t_7) < 0) __PYX_ERR(0, 590, __pyx_L1_error) __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); - /* "acados_template/acados_ocp_solver_pyx.pyx":584 + /* "acados_template/acados_ocp_solver_pyx.pyx":625 * * * def constraints_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< * """ * Set numerical data in the constraint module of the solver. */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39constraints_set, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_constraint_2, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__76)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 584, __pyx_L1_error) + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43constraints_set, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_constraint_2, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__84)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 625, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); - if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_constraints_set, __pyx_t_7) < 0) __PYX_ERR(0, 584, __pyx_L1_error) + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_constraints_set, __pyx_t_7) < 0) __PYX_ERR(0, 625, __pyx_L1_error) __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); - /* "acados_template/acados_ocp_solver_pyx.pyx":619 + /* "acados_template/acados_ocp_solver_pyx.pyx":663 * * - * def dynamics_get(self, int stage, str field_): # <<<<<<<<<<<<<< + * def get_from_qp_in(self, int stage, str field_): # <<<<<<<<<<<<<< * """ * Get numerical data from the dynamics module of the solver: */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41dynamics_get, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_dynamics_g, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__78)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 619, __pyx_L1_error) + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_45get_from_qp_in, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_get_from_q, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__86)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 663, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); - if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_dynamics_get, __pyx_t_7) < 0) __PYX_ERR(0, 619, __pyx_L1_error) + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_get_from_qp_in, __pyx_t_7) < 0) __PYX_ERR(0, 663, __pyx_L1_error) __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); - /* "acados_template/acados_ocp_solver_pyx.pyx":641 + /* "acados_template/acados_ocp_solver_pyx.pyx":685 * * * def options_set(self, str field_, value_): # <<<<<<<<<<<<<< * """ * Set options of the solver. */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43options_set, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_options_se_2, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__80)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 641, __pyx_L1_error) + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47options_set, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_options_se_2, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__88)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 685, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); - if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_options_set, __pyx_t_7) < 0) __PYX_ERR(0, 641, __pyx_L1_error) + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_options_set, __pyx_t_7) < 0) __PYX_ERR(0, 685, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":748 + * + * + * def set_params_sparse(self, int stage, idx_values_, param_values_): # <<<<<<<<<<<<<< + * """ + * set parameters of the solvers external function partially: + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49set_params_sparse, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_set_params, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__90)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 748, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_set_params_sparse, __pyx_t_7) < 0) __PYX_ERR(0, 748, __pyx_L1_error) __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); @@ -32531,7 +34208,7 @@ if (!__Pyx_RefNanny) { * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" * def __setstate_cython__(self, __pyx_state): */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___reduce_c, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__81)); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_53__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___reduce_c, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__91)); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 1, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); if (PyDict_SetItem(__pyx_d, __pyx_n_s_reduce_cython, __pyx_t_7) < 0) __PYX_ERR(1, 1, __pyx_L1_error) __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; @@ -32542,7 +34219,7 @@ if (!__Pyx_RefNanny) { * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" */ - __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___setstate, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__83)); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 3, __pyx_L1_error) + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_55__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___setstate, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__93)); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 3, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); if (PyDict_SetItem(__pyx_d, __pyx_n_s_setstate_cython, __pyx_t_7) < 0) __PYX_ERR(1, 3, __pyx_L1_error) __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; @@ -32550,7 +34227,7 @@ if (!__Pyx_RefNanny) { /* "acados_template/acados_ocp_solver_pyx.pyx":1 * # -*- coding: future_fstrings -*- # <<<<<<<<<<<<<< * # - * # Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, + * # Copyright (c) The acados authors. */ __pyx_t_7 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 1, __pyx_L1_error) __Pyx_GOTREF(__pyx_t_7); @@ -34953,6 +36630,150 @@ static CYTHON_INLINE int __Pyx_HasAttr(PyObject *o, PyObject *n) { } } +/* PyIntCompare */ +static CYTHON_INLINE int __Pyx_PyInt_BoolEqObjC(PyObject *op1, PyObject *op2, long intval, long inplace) { + CYTHON_MAYBE_UNUSED_VAR(intval); + CYTHON_UNUSED_VAR(inplace); + if (op1 == op2) { + return 1; + } + #if PY_MAJOR_VERSION < 3 + if (likely(PyInt_CheckExact(op1))) { + const long b = intval; + long a = PyInt_AS_LONG(op1); + return (a == b); + } + #endif + #if CYTHON_USE_PYLONG_INTERNALS + if (likely(PyLong_CheckExact(op1))) { + int unequal; + unsigned long uintval; + Py_ssize_t size = __Pyx_PyLong_DigitCount(op1); + const digit* digits = __Pyx_PyLong_Digits(op1); + if (intval == 0) { + return (__Pyx_PyLong_IsZero(op1) == 1); + } else if (intval < 0) { + if (__Pyx_PyLong_IsNonNeg(op1)) + return 0; + intval = -intval; + } else { + if (__Pyx_PyLong_IsNeg(op1)) + return 0; + } + uintval = (unsigned long) intval; +#if PyLong_SHIFT * 4 < SIZEOF_LONG*8 + if (uintval >> (PyLong_SHIFT * 4)) { + unequal = (size != 5) || (digits[0] != (uintval & (unsigned long) PyLong_MASK)) + | (digits[1] != ((uintval >> (1 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[2] != ((uintval >> (2 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[3] != ((uintval >> (3 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[4] != ((uintval >> (4 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)); + } else +#endif +#if PyLong_SHIFT * 3 < SIZEOF_LONG*8 + if (uintval >> (PyLong_SHIFT * 3)) { + unequal = (size != 4) || (digits[0] != (uintval & (unsigned long) PyLong_MASK)) + | (digits[1] != ((uintval >> (1 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[2] != ((uintval >> (2 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[3] != ((uintval >> (3 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)); + } else +#endif +#if PyLong_SHIFT * 2 < SIZEOF_LONG*8 + if (uintval >> (PyLong_SHIFT * 2)) { + unequal = (size != 3) || (digits[0] != (uintval & (unsigned long) PyLong_MASK)) + | (digits[1] != ((uintval >> (1 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[2] != ((uintval >> (2 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)); + } else +#endif +#if PyLong_SHIFT * 1 < SIZEOF_LONG*8 + if (uintval >> (PyLong_SHIFT * 1)) { + unequal = (size != 2) || (digits[0] != (uintval & (unsigned long) PyLong_MASK)) + | (digits[1] != ((uintval >> (1 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)); + } else +#endif + unequal = (size != 1) || (((unsigned long) digits[0]) != (uintval & (unsigned long) PyLong_MASK)); + return (unequal == 0); + } + #endif + if (PyFloat_CheckExact(op1)) { + const long b = intval; +#if CYTHON_COMPILING_IN_LIMITED_API + double a = __pyx_PyFloat_AsDouble(op1); +#else + double a = PyFloat_AS_DOUBLE(op1); +#endif + return ((double)a == (double)b); + } + return __Pyx_PyObject_IsTrueAndDecref( + PyObject_RichCompare(op1, op2, Py_EQ)); +} + +/* PyIntCompare */ +static CYTHON_INLINE int __Pyx_PyInt_BoolNeObjC(PyObject *op1, PyObject *op2, long intval, long inplace) { + CYTHON_MAYBE_UNUSED_VAR(intval); + CYTHON_UNUSED_VAR(inplace); + if (op1 == op2) { + return 0; + } + #if PY_MAJOR_VERSION < 3 + if (likely(PyInt_CheckExact(op1))) { + const long b = intval; + long a = PyInt_AS_LONG(op1); + return (a != b); + } + #endif + #if CYTHON_USE_PYLONG_INTERNALS + if (likely(PyLong_CheckExact(op1))) { + int unequal; + unsigned long uintval; + Py_ssize_t size = __Pyx_PyLong_DigitCount(op1); + const digit* digits = __Pyx_PyLong_Digits(op1); + if (intval == 0) { + return (__Pyx_PyLong_IsZero(op1) != 1); + } else if (intval < 0) { + if (__Pyx_PyLong_IsNonNeg(op1)) + return 1; + intval = -intval; + } else { + if (__Pyx_PyLong_IsNeg(op1)) + return 1; + } + uintval = (unsigned long) intval; +#if PyLong_SHIFT * 4 < SIZEOF_LONG*8 + if (uintval >> (PyLong_SHIFT * 4)) { + unequal = (size != 5) || (digits[0] != (uintval & (unsigned long) PyLong_MASK)) + | (digits[1] != ((uintval >> (1 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[2] != ((uintval >> (2 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[3] != ((uintval >> (3 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[4] != ((uintval >> (4 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)); + } else +#endif +#if PyLong_SHIFT * 3 < SIZEOF_LONG*8 + if (uintval >> (PyLong_SHIFT * 3)) { + unequal = (size != 4) || (digits[0] != (uintval & (unsigned long) PyLong_MASK)) + | (digits[1] != ((uintval >> (1 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[2] != ((uintval >> (2 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[3] != ((uintval >> (3 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)); + } else +#endif +#if PyLong_SHIFT * 2 < SIZEOF_LONG*8 + if (uintval >> (PyLong_SHIFT * 2)) { + unequal = (size != 3) || (digits[0] != (uintval & (unsigned long) PyLong_MASK)) + | (digits[1] != ((uintval >> (1 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[2] != ((uintval >> (2 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)); + } else +#endif +#if PyLong_SHIFT * 1 < SIZEOF_LONG*8 + if (uintval >> (PyLong_SHIFT * 1)) { + unequal = (size != 2) || (digits[0] != (uintval & (unsigned long) PyLong_MASK)) + | (digits[1] != ((uintval >> (1 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)); + } else +#endif + unequal = (size != 1) || (((unsigned long) digits[0]) != (uintval & (unsigned long) PyLong_MASK)); + return (unequal != 0); + } + #endif + if (PyFloat_CheckExact(op1)) { + const long b = intval; +#if CYTHON_COMPILING_IN_LIMITED_API + double a = __pyx_PyFloat_AsDouble(op1); +#else + double a = PyFloat_AS_DOUBLE(op1); +#endif + return ((double)a != (double)b); + } + return __Pyx_PyObject_IsTrueAndDecref( + PyObject_RichCompare(op1, op2, Py_NE)); +} + /* IsLittleEndian */ static CYTHON_INLINE int __Pyx_Is_Little_Endian(void) { @@ -35677,6 +37498,156 @@ bad: return NULL; } +/* PyObjectFormat */ + #if CYTHON_USE_UNICODE_WRITER +static PyObject* __Pyx_PyObject_Format(PyObject* obj, PyObject* format_spec) { + int ret; + _PyUnicodeWriter writer; + if (likely(PyFloat_CheckExact(obj))) { +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x03040000 + _PyUnicodeWriter_Init(&writer, 0); +#else + _PyUnicodeWriter_Init(&writer); +#endif + ret = _PyFloat_FormatAdvancedWriter( + &writer, + obj, + format_spec, 0, PyUnicode_GET_LENGTH(format_spec)); + } else if (likely(PyLong_CheckExact(obj))) { +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x03040000 + _PyUnicodeWriter_Init(&writer, 0); +#else + _PyUnicodeWriter_Init(&writer); +#endif + ret = _PyLong_FormatAdvancedWriter( + &writer, + obj, + format_spec, 0, PyUnicode_GET_LENGTH(format_spec)); + } else { + return PyObject_Format(obj, format_spec); + } + if (unlikely(ret == -1)) { + _PyUnicodeWriter_Dealloc(&writer); + return NULL; + } + return _PyUnicodeWriter_Finish(&writer); +} +#endif + +/* UnpackUnboundCMethod */ + static PyObject *__Pyx_SelflessCall(PyObject *method, PyObject *args, PyObject *kwargs) { + PyObject *selfless_args = PyTuple_GetSlice(args, 1, PyTuple_Size(args)); + if (unlikely(!selfless_args)) return NULL; + PyObject *result = PyObject_Call(method, selfless_args, kwargs); + Py_DECREF(selfless_args); + return result; +} +static PyMethodDef __Pyx_UnboundCMethod_Def = { + "CythonUnboundCMethod", + __PYX_REINTERPRET_FUNCION(PyCFunction, __Pyx_SelflessCall), + METH_VARARGS | METH_KEYWORDS, + NULL +}; +static int __Pyx_TryUnpackUnboundCMethod(__Pyx_CachedCFunction* target) { + PyObject *method; + method = __Pyx_PyObject_GetAttrStr(target->type, *target->method_name); + if (unlikely(!method)) + return -1; + target->method = method; +#if CYTHON_COMPILING_IN_CPYTHON + #if PY_MAJOR_VERSION >= 3 + if (likely(__Pyx_TypeCheck(method, &PyMethodDescr_Type))) + #else + if (likely(!PyCFunction_Check(method))) + #endif + { + PyMethodDescrObject *descr = (PyMethodDescrObject*) method; + target->func = descr->d_method->ml_meth; + target->flag = descr->d_method->ml_flags & ~(METH_CLASS | METH_STATIC | METH_COEXIST | METH_STACKLESS); + } else +#endif +#if defined(CYTHON_COMPILING_IN_PYPY) +#elif PY_VERSION_HEX >= 0x03090000 + if (PyCFunction_CheckExact(method)) +#else + if (PyCFunction_Check(method)) +#endif + { + PyObject *self; + int self_found; +#if CYTHON_COMPILING_IN_LIMITED_API || CYTHON_COMPILING_IN_PYPY + self = PyObject_GetAttrString(method, "__self__"); + if (!self) { + PyErr_Clear(); + } +#else + self = PyCFunction_GET_SELF(method); +#endif + self_found = (self && self != Py_None); +#if CYTHON_COMPILING_IN_LIMITED_API || CYTHON_COMPILING_IN_PYPY + Py_XDECREF(self); +#endif + if (self_found) { + PyObject *unbound_method = PyCFunction_New(&__Pyx_UnboundCMethod_Def, method); + if (unlikely(!unbound_method)) return -1; + Py_DECREF(method); + target->method = unbound_method; + } + } + return 0; +} + +/* CallUnboundCMethod0 */ + static PyObject* __Pyx__CallUnboundCMethod0(__Pyx_CachedCFunction* cfunc, PyObject* self) { + PyObject *args, *result = NULL; + if (unlikely(!cfunc->method) && unlikely(__Pyx_TryUnpackUnboundCMethod(cfunc) < 0)) return NULL; +#if CYTHON_ASSUME_SAFE_MACROS + args = PyTuple_New(1); + if (unlikely(!args)) goto bad; + Py_INCREF(self); + PyTuple_SET_ITEM(args, 0, self); +#else + args = PyTuple_Pack(1, self); + if (unlikely(!args)) goto bad; +#endif + result = __Pyx_PyObject_Call(cfunc->method, args, NULL); + Py_DECREF(args); +bad: + return result; +} + +/* py_dict_keys */ + static CYTHON_INLINE PyObject* __Pyx_PyDict_Keys(PyObject* d) { + if (PY_MAJOR_VERSION >= 3) + return __Pyx_CallUnboundCMethod0(&__pyx_umethod_PyDict_Type_keys, d); + else + return PyDict_Keys(d); +} + +/* DictGetItem */ + #if PY_MAJOR_VERSION >= 3 && !CYTHON_COMPILING_IN_PYPY +static PyObject *__Pyx_PyDict_GetItem(PyObject *d, PyObject* key) { + PyObject *value; + value = PyDict_GetItemWithError(d, key); + if (unlikely(!value)) { + if (!PyErr_Occurred()) { + if (unlikely(PyTuple_Check(key))) { + PyObject* args = PyTuple_Pack(1, key); + if (likely(args)) { + PyErr_SetObject(PyExc_KeyError, args); + Py_DECREF(args); + } + } else { + PyErr_SetObject(PyExc_KeyError, key); + } + } + return NULL; + } + Py_INCREF(value); + return value; +} +#endif + /* PyObjectLookupSpecial */ #if CYTHON_USE_PYTYPE_LOOKUP && CYTHON_USE_TYPE_SLOTS static CYTHON_INLINE PyObject* __Pyx__PyObject_LookupSpecial(PyObject* obj, PyObject* attr_name, int with_error) { @@ -39191,6 +41162,279 @@ raise_neg_overflow: } } +/* CIntFromPy */ + static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(long) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(long, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (long) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 2 * PyLong_SHIFT)) { + return (long) (((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 3 * PyLong_SHIFT)) { + return (long) (((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 4 * PyLong_SHIFT)) { + return (long) (((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(long) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(long) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) ((((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) ((((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) ((((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(long) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + long val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (long) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (long) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (long) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (long) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(long) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(long) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((long) 1) << (sizeof(long) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (long) -1; + } + } else { + long val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (long) -1; + val = __Pyx_PyInt_As_long(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to long"); + return (long) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to long"); + return (long) -1; +} + /* CIntToPy */ static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value) { #ifdef __Pyx_HAS_GCC_DIAGNOSTIC @@ -39502,279 +41746,6 @@ raise_neg_overflow: return (size_t) -1; } -/* CIntFromPy */ - static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *x) { -#ifdef __Pyx_HAS_GCC_DIAGNOSTIC -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wconversion" -#endif - const long neg_one = (long) -1, const_zero = (long) 0; -#ifdef __Pyx_HAS_GCC_DIAGNOSTIC -#pragma GCC diagnostic pop -#endif - const int is_unsigned = neg_one > const_zero; -#if PY_MAJOR_VERSION < 3 - if (likely(PyInt_Check(x))) { - if ((sizeof(long) < sizeof(long))) { - __PYX_VERIFY_RETURN_INT(long, long, PyInt_AS_LONG(x)) - } else { - long val = PyInt_AS_LONG(x); - if (is_unsigned && unlikely(val < 0)) { - goto raise_neg_overflow; - } - return (long) val; - } - } else -#endif - if (likely(PyLong_Check(x))) { - if (is_unsigned) { -#if CYTHON_USE_PYLONG_INTERNALS - if (unlikely(__Pyx_PyLong_IsNeg(x))) { - goto raise_neg_overflow; - } else if (__Pyx_PyLong_IsCompact(x)) { - __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) - } else { - const digit* digits = __Pyx_PyLong_Digits(x); - assert(__Pyx_PyLong_DigitCount(x) > 1); - switch (__Pyx_PyLong_DigitCount(x)) { - case 2: - if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { - if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { - __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) - } else if ((8 * sizeof(long) >= 2 * PyLong_SHIFT)) { - return (long) (((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); - } - } - break; - case 3: - if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { - if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { - __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) - } else if ((8 * sizeof(long) >= 3 * PyLong_SHIFT)) { - return (long) (((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); - } - } - break; - case 4: - if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { - if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { - __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) - } else if ((8 * sizeof(long) >= 4 * PyLong_SHIFT)) { - return (long) (((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); - } - } - break; - } - } -#endif -#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 - if (unlikely(Py_SIZE(x) < 0)) { - goto raise_neg_overflow; - } -#else - { - int result = PyObject_RichCompareBool(x, Py_False, Py_LT); - if (unlikely(result < 0)) - return (long) -1; - if (unlikely(result == 1)) - goto raise_neg_overflow; - } -#endif - if ((sizeof(long) <= sizeof(unsigned long))) { - __PYX_VERIFY_RETURN_INT_EXC(long, unsigned long, PyLong_AsUnsignedLong(x)) -#ifdef HAVE_LONG_LONG - } else if ((sizeof(long) <= sizeof(unsigned PY_LONG_LONG))) { - __PYX_VERIFY_RETURN_INT_EXC(long, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) -#endif - } - } else { -#if CYTHON_USE_PYLONG_INTERNALS - if (__Pyx_PyLong_IsCompact(x)) { - __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) - } else { - const digit* digits = __Pyx_PyLong_Digits(x); - assert(__Pyx_PyLong_DigitCount(x) > 1); - switch (__Pyx_PyLong_SignedDigitCount(x)) { - case -2: - if ((8 * sizeof(long) - 1 > 1 * PyLong_SHIFT)) { - if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { - __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) - } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { - return (long) (((long)-1)*(((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); - } - } - break; - case 2: - if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { - if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { - __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) - } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { - return (long) ((((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); - } - } - break; - case -3: - if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { - if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { - __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) - } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { - return (long) (((long)-1)*(((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); - } - } - break; - case 3: - if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { - if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { - __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) - } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { - return (long) ((((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); - } - } - break; - case -4: - if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { - if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { - __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) - } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { - return (long) (((long)-1)*(((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); - } - } - break; - case 4: - if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { - if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { - __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) - } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { - return (long) ((((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); - } - } - break; - } - } -#endif - if ((sizeof(long) <= sizeof(long))) { - __PYX_VERIFY_RETURN_INT_EXC(long, long, PyLong_AsLong(x)) -#ifdef HAVE_LONG_LONG - } else if ((sizeof(long) <= sizeof(PY_LONG_LONG))) { - __PYX_VERIFY_RETURN_INT_EXC(long, PY_LONG_LONG, PyLong_AsLongLong(x)) -#endif - } - } - { - long val; - PyObject *v = __Pyx_PyNumber_IntOrLong(x); -#if PY_MAJOR_VERSION < 3 - if (likely(v) && !PyLong_Check(v)) { - PyObject *tmp = v; - v = PyNumber_Long(tmp); - Py_DECREF(tmp); - } -#endif - if (likely(v)) { - int ret = -1; -#if !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) - int one = 1; int is_little = (int)*(unsigned char *)&one; - unsigned char *bytes = (unsigned char *)&val; - ret = _PyLong_AsByteArray((PyLongObject *)v, - bytes, sizeof(val), - is_little, !is_unsigned); -#else - PyObject *stepval = NULL, *mask = NULL, *shift = NULL; - int bits, remaining_bits, is_negative = 0; - long idigit; - int chunk_size = (sizeof(long) < 8) ? 30 : 62; - if (unlikely(!PyLong_CheckExact(v))) { - PyObject *tmp = v; - v = PyNumber_Long(v); - assert(PyLong_CheckExact(v)); - Py_DECREF(tmp); - if (unlikely(!v)) return (long) -1; - } -#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 - if (Py_SIZE(x) == 0) - return (long) 0; - is_negative = Py_SIZE(x) < 0; -#else - { - int result = PyObject_RichCompareBool(x, Py_False, Py_LT); - if (unlikely(result < 0)) - return (long) -1; - is_negative = result == 1; - } -#endif - if (is_unsigned && unlikely(is_negative)) { - goto raise_neg_overflow; - } else if (is_negative) { - stepval = PyNumber_Invert(v); - if (unlikely(!stepval)) - return (long) -1; - } else { - stepval = __Pyx_NewRef(v); - } - val = (long) 0; - mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; - shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; - for (bits = 0; bits < (int) sizeof(long) * 8 - chunk_size; bits += chunk_size) { - PyObject *tmp, *digit; - digit = PyNumber_And(stepval, mask); - if (unlikely(!digit)) goto done; - idigit = PyLong_AsLong(digit); - Py_DECREF(digit); - if (unlikely(idigit < 0)) goto done; - tmp = PyNumber_Rshift(stepval, shift); - if (unlikely(!tmp)) goto done; - Py_DECREF(stepval); stepval = tmp; - val |= ((long) idigit) << bits; - #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 - if (Py_SIZE(stepval) == 0) - goto unpacking_done; - #endif - } - idigit = PyLong_AsLong(stepval); - if (unlikely(idigit < 0)) goto done; - remaining_bits = ((int) sizeof(long) * 8) - bits - (is_unsigned ? 0 : 1); - if (unlikely(idigit >= (1L << remaining_bits))) - goto raise_overflow; - val |= ((long) idigit) << bits; - #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 - unpacking_done: - #endif - if (!is_unsigned) { - if (unlikely(val & (((long) 1) << (sizeof(long) * 8 - 1)))) - goto raise_overflow; - if (is_negative) - val = ~val; - } - ret = 0; - done: - Py_XDECREF(shift); - Py_XDECREF(mask); - Py_XDECREF(stepval); -#endif - Py_DECREF(v); - if (likely(!ret)) - return val; - } - return (long) -1; - } - } else { - long val; - PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); - if (!tmp) return (long) -1; - val = __Pyx_PyInt_As_long(tmp); - Py_DECREF(tmp); - return val; - } -raise_overflow: - PyErr_SetString(PyExc_OverflowError, - "value too large to convert to long"); - return (long) -1; -raise_neg_overflow: - PyErr_SetString(PyExc_OverflowError, - "can't convert negative value to long"); - return (long) -1; -} - /* CIntFromPy */ static CYTHON_INLINE char __Pyx_PyInt_As_char(PyObject *x) { #ifdef __Pyx_HAS_GCC_DIAGNOSTIC @@ -40057,7 +42028,7 @@ __Pyx_PyType_GetName(PyTypeObject* tp) __pyx_n_s_name_2); if (unlikely(name == NULL) || unlikely(!PyUnicode_Check(name))) { PyErr_Clear(); - Py_XSETREF(name, __Pyx_NewRef(__pyx_n_s__84)); + Py_XSETREF(name, __Pyx_NewRef(__pyx_n_s__94)); } return name; } diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_ocp_solver_pyx.so b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_ocp_solver_pyx.so index 9977669de..374d0742d 100755 Binary files a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_ocp_solver_pyx.so and b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_ocp_solver_pyx.so differ diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_sim_solver_long.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_sim_solver_long.c index 20f8890fc..d451c5609 100644 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_sim_solver_long.c +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_sim_solver_long.c @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * @@ -82,6 +79,7 @@ int long_acados_sim_create(sim_solver_capsule * capsule) // explicit ode capsule->sim_forw_vde_casadi = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)); + capsule->sim_vde_adj_casadi = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)); capsule->sim_expl_ode_fun_casadi = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)); capsule->sim_forw_vde_casadi->casadi_fun = &long_expl_vde_forw; @@ -92,6 +90,14 @@ int long_acados_sim_create(sim_solver_capsule * capsule) capsule->sim_forw_vde_casadi->casadi_work = &long_expl_vde_forw_work; external_function_param_casadi_create(capsule->sim_forw_vde_casadi, np); + capsule->sim_vde_adj_casadi->casadi_fun = &long_expl_vde_adj; + capsule->sim_vde_adj_casadi->casadi_n_in = &long_expl_vde_adj_n_in; + capsule->sim_vde_adj_casadi->casadi_n_out = &long_expl_vde_adj_n_out; + capsule->sim_vde_adj_casadi->casadi_sparsity_in = &long_expl_vde_adj_sparsity_in; + capsule->sim_vde_adj_casadi->casadi_sparsity_out = &long_expl_vde_adj_sparsity_out; + capsule->sim_vde_adj_casadi->casadi_work = &long_expl_vde_adj_work; + external_function_param_casadi_create(capsule->sim_vde_adj_casadi, np); + capsule->sim_expl_ode_fun_casadi->casadi_fun = &long_expl_ode_fun; capsule->sim_expl_ode_fun_casadi->casadi_n_in = &long_expl_ode_fun_n_in; capsule->sim_expl_ode_fun_casadi->casadi_n_out = &long_expl_ode_fun_n_out; @@ -123,6 +129,8 @@ int long_acados_sim_create(sim_solver_capsule * capsule) capsule->acados_sim_opts = long_sim_opts; int tmp_int = 3; sim_opts_set(long_sim_config, long_sim_opts, "newton_iter", &tmp_int); + double tmp_double = 0.0; + sim_opts_set(long_sim_config, long_sim_opts, "newton_tol", &tmp_double); sim_collocation_type collocation_type = GAUSS_LEGENDRE; sim_opts_set(long_sim_config, long_sim_opts, "collocation_type", &collocation_type); @@ -146,7 +154,9 @@ int long_acados_sim_create(sim_solver_capsule * capsule) // model functions long_sim_config->model_set(long_sim_in->model, - "expl_vde_for", capsule->sim_forw_vde_casadi); + "expl_vde_forw", capsule->sim_forw_vde_casadi); + long_sim_config->model_set(long_sim_in->model, + "expl_vde_adj", capsule->sim_vde_adj_casadi); long_sim_config->model_set(long_sim_in->model, "expl_ode_fun", capsule->sim_expl_ode_fun_casadi); @@ -227,6 +237,7 @@ int long_acados_sim_free(sim_solver_capsule *capsule) // free external function external_function_param_casadi_free(capsule->sim_forw_vde_casadi); + external_function_param_casadi_free(capsule->sim_vde_adj_casadi); external_function_param_casadi_free(capsule->sim_expl_ode_fun_casadi); return 0; @@ -244,6 +255,7 @@ int long_acados_sim_update_params(sim_solver_capsule *capsule, double *p, int np exit(1); } capsule->sim_forw_vde_casadi[0].set_param(capsule->sim_forw_vde_casadi, p); + capsule->sim_vde_adj_casadi[0].set_param(capsule->sim_vde_adj_casadi, p); capsule->sim_expl_ode_fun_casadi[0].set_param(capsule->sim_expl_ode_fun_casadi, p); return status; diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_sim_solver_long.h b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_sim_solver_long.h index ea0e04c49..36326b999 100644 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_sim_solver_long.h +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_sim_solver_long.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * @@ -61,6 +58,7 @@ typedef struct sim_solver_capsule /* external functions */ // ERK external_function_param_casadi * sim_forw_vde_casadi; + external_function_param_casadi * sim_vde_adj_casadi; external_function_param_casadi * sim_expl_ode_fun_casadi; external_function_param_casadi * sim_expl_ode_hess; diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_solver.pxd b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_solver.pxd index b00b36583..c04a1b20b 100644 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_solver.pxd +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_solver.pxd @@ -1,8 +1,5 @@ # -# Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, -# Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, -# Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, -# Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl +# Copyright (c) The acados authors. # # This file is part of acados. # @@ -47,11 +44,14 @@ cdef extern from "acados_solver_long.h": int acados_update_qp_solver_cond_N "long_acados_update_qp_solver_cond_N"(nlp_solver_capsule * capsule, int qp_solver_cond_N) int acados_update_params "long_acados_update_params"(nlp_solver_capsule * capsule, int stage, double *value, int np_) + int acados_update_params_sparse "long_acados_update_params_sparse"(nlp_solver_capsule * capsule, int stage, int *idx, double *p, int n_update) int acados_solve "long_acados_solve"(nlp_solver_capsule * capsule) - int acados_reset "long_acados_reset"(nlp_solver_capsule * capsule) + int acados_reset "long_acados_reset"(nlp_solver_capsule * capsule, int reset_qp_solver_mem) int acados_free "long_acados_free"(nlp_solver_capsule * capsule) void acados_print_stats "long_acados_print_stats"(nlp_solver_capsule * capsule) + int acados_custom_update "long_acados_custom_update"(nlp_solver_capsule* capsule, double * data, int data_len) + acados_solver_common.ocp_nlp_in *acados_get_nlp_in "long_acados_get_nlp_in"(nlp_solver_capsule * capsule) acados_solver_common.ocp_nlp_out *acados_get_nlp_out "long_acados_get_nlp_out"(nlp_solver_capsule * capsule) acados_solver_common.ocp_nlp_out *acados_get_sens_out "long_acados_get_sens_out"(nlp_solver_capsule * capsule) diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_solver_long.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_solver_long.c index 7b28e0206..bdeec91e9 100644 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_solver_long.c +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_solver_long.c @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * @@ -42,15 +39,11 @@ // example specific #include "long_model/long_model.h" +#include "long_constraints/long_constraints.h" +#include "long_cost/long_cost.h" -#include "long_constraints/long_h_constraint.h" - - -#include "long_cost/long_cost_y_fun.h" -#include "long_cost/long_cost_y_0_fun.h" -#include "long_cost/long_cost_y_e_fun.h" #include "acados_solver_long.h" @@ -293,7 +286,6 @@ return nlp_dims; void long_acados_create_3_create_and_set_functions(long_solver_capsule* capsule) { const int N = capsule->nlp_solver_plan->N; - ocp_nlp_config* nlp_config = capsule->nlp_config; /************************************************ * external functions @@ -433,28 +425,38 @@ void long_acados_create_5_set_nlp_in(long_solver_capsule* capsule, const int N, } /**** Cost ****/ - double* W_0 = calloc(NY0*NY0, sizeof(double)); - // change only the non-zero elements: - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "W", W_0); - free(W_0); - double* yref_0 = calloc(NY0, sizeof(double)); // change only the non-zero elements: ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "yref", yref_0); free(yref_0); - double* W = calloc(NY*NY, sizeof(double)); - // change only the non-zero elements: - double* yref = calloc(NY, sizeof(double)); // change only the non-zero elements: for (int i = 1; i < N; i++) { - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "W", W); ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "yref", yref); } - free(W); free(yref); + double* yref_e = calloc(NYN, sizeof(double)); + // change only the non-zero elements: + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "yref", yref_e); + free(yref_e); + double* W_0 = calloc(NY0*NY0, sizeof(double)); + // change only the non-zero elements: + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "W", W_0); + free(W_0); + double* W = calloc(NY*NY, sizeof(double)); + // change only the non-zero elements: + + for (int i = 1; i < N; i++) + { + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "W", W); + } + free(W); + double* W_e = calloc(NYN*NYN, sizeof(double)); + // change only the non-zero elements: + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "W", W_e); + free(W_e); ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "nls_y_fun", &capsule->cost_y_0_fun); ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "nls_y_fun_jac", &capsule->cost_y_0_fun_jac_ut_xt); ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "nls_y_hess", &capsule->cost_y_0_hess); @@ -464,6 +466,10 @@ void long_acados_create_5_set_nlp_in(long_solver_capsule* capsule, const int N, ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "nls_y_fun_jac", &capsule->cost_y_fun_jac_ut_xt[i-1]); ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "nls_y_hess", &capsule->cost_y_hess[i-1]); } + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "nls_y_fun", &capsule->cost_y_e_fun); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "nls_y_fun_jac", &capsule->cost_y_e_fun_jac_ut_xt); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "nls_y_hess", &capsule->cost_y_e_hess); + // slacks double* zlumem = calloc(4*NS, sizeof(double)); double* Zl = zlumem+NS*0; double* Zu = zlumem+NS*1; @@ -480,20 +486,6 @@ void long_acados_create_5_set_nlp_in(long_solver_capsule* capsule, const int N, } free(zlumem); - // terminal cost - double* yref_e = calloc(NYN, sizeof(double)); - // change only the non-zero elements: - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "yref", yref_e); - free(yref_e); - - double* W_e = calloc(NYN*NYN, sizeof(double)); - // change only the non-zero elements: - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "W", W_e); - free(W_e); - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "nls_y_fun", &capsule->cost_y_e_fun); - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "nls_y_fun_jac", &capsule->cost_y_e_fun_jac_ut_xt); - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "nls_y_hess", &capsule->cost_y_e_hess); - /**** Constraints ****/ @@ -565,11 +557,11 @@ void long_acados_create_5_set_nlp_in(long_solver_capsule* capsule, const int N, - uh[0] = 10000; - uh[1] = 10000; - uh[2] = 10000; - uh[3] = 10000; - + uh[0] = 10000.0; + uh[1] = 10000.0; + uh[2] = 10000.0; + uh[3] = 10000.0; + for (int i = 0; i < N; i++) { // nonlinear constraints for stages 0 to N-1 @@ -611,7 +603,6 @@ void long_acados_create_6_set_opts(long_solver_capsule* capsule) { const int N = capsule->nlp_solver_plan->N; ocp_nlp_config* nlp_config = capsule->nlp_config; - ocp_nlp_dims* nlp_dims = capsule->nlp_dims; void *nlp_opts = capsule->nlp_opts; /************************************************ @@ -649,10 +640,10 @@ void long_acados_create_6_set_opts(long_solver_capsule* capsule) for (int i = 0; i < N; i++) ocp_nlp_solver_opts_set_at_stage(nlp_config, nlp_opts, i, "dynamics_jac_reuse", &tmp_bool); - double nlp_solver_step_length = 1; + double nlp_solver_step_length = 1.0; ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "step_length", &nlp_solver_step_length); - double levenberg_marquardt = 0; + double levenberg_marquardt = 0.0; ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "levenberg_marquardt", &levenberg_marquardt); /* options QP solver */ @@ -661,6 +652,9 @@ void long_acados_create_6_set_opts(long_solver_capsule* capsule) const int qp_solver_cond_N_ori = 1; qp_solver_cond_N = N < qp_solver_cond_N_ori ? N : qp_solver_cond_N_ori; // use the minimum value here ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "qp_cond_N", &qp_solver_cond_N); + + int nlp_solver_ext_qp_res = 0; + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "ext_qp_res", &nlp_solver_ext_qp_res); // set HPIPM mode: should be done before setting other QP solver options ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "qp_hpipm_mode", "BALANCE"); @@ -679,6 +673,11 @@ void long_acados_create_6_set_opts(long_solver_capsule* capsule) double qp_solver_tol_comp = 0.001; ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "qp_tol_comp", &qp_solver_tol_comp);int print_level = 0; ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "print_level", &print_level); + int qp_solver_cond_ric_alg = 1; + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "qp_cond_ric_alg", &qp_solver_cond_ric_alg); + + int qp_solver_ric_alg = 1; + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "qp_ric_alg", &qp_solver_ric_alg); int ext_cost_num_hess = 0; @@ -787,6 +786,7 @@ int long_acados_create_with_discretization(long_solver_capsule* capsule, int N, // 9) do precomputations int status = long_acados_create_9_precompute(capsule); + return status; } @@ -814,7 +814,7 @@ int long_acados_update_qp_solver_cond_N(long_solver_capsule* capsule, int qp_sol } -int long_acados_reset(long_solver_capsule* capsule) +int long_acados_reset(long_solver_capsule* capsule, int reset_qp_solver_mem) { // set initialization to all zeros @@ -826,8 +826,6 @@ int long_acados_reset(long_solver_capsule* capsule) ocp_nlp_in* nlp_in = capsule->nlp_in; ocp_nlp_solver* nlp_solver = capsule->nlp_solver; - int nx, nu, nv, ns, nz, ni, dim; - double* buffer = calloc(NX+NU+NZ+2*NS+2*NSN+NBX+NBU+NG+NH+NPHI+NBX0+NBXN+NHN+NPHIN+NGN, sizeof(double)); for(int i=0; i reset memory int qp_status; ocp_nlp_get(capsule->nlp_config, capsule->nlp_solver, "qp_status", &qp_status); - if (qp_status == 3) + if (reset_qp_solver_mem || (qp_status == 3)) { // printf("\nin reset qp_status %d -> resetting QP memory\n", qp_status); ocp_nlp_solver_reset_qp_memory(nlp_solver, nlp_in, nlp_out); @@ -870,6 +868,7 @@ int long_acados_update_params(long_solver_capsule* capsule, int stage, double *p " External function has %i parameters. Exiting.\n", np, casadi_np); exit(1); } + const int N = capsule->nlp_solver_plan->N; if (stage < N && stage >= 0) { @@ -908,15 +907,74 @@ int long_acados_update_params(long_solver_capsule* capsule, int stage, double *p } - return solver_status; } +int long_acados_update_params_sparse(long_solver_capsule * capsule, int stage, int *idx, double *p, int n_update) +{ + int solver_status = 0; + + int casadi_np = 6; + if (casadi_np < n_update) { + printf("long_acados_update_params_sparse: trying to set %d parameters for external functions." + " External function has %d parameters. Exiting.\n", n_update, casadi_np); + exit(1); + } + // for (int i = 0; i < n_update; i++) + // { + // if (idx[i] > casadi_np) { + // printf("long_acados_update_params_sparse: attempt to set parameters with index %d, while" + // " external functions only has %d parameters. Exiting.\n", idx[i], casadi_np); + // exit(1); + // } + // printf("param %d value %e\n", idx[i], p[i]); + // } + const int N = capsule->nlp_solver_plan->N; + if (stage < N && stage >= 0) + { + capsule->forw_vde_casadi[stage].set_param_sparse(capsule->forw_vde_casadi+stage, n_update, idx, p); + capsule->expl_ode_fun[stage].set_param_sparse(capsule->expl_ode_fun+stage, n_update, idx, p); + + + // constraints + + capsule->nl_constr_h_fun_jac[stage].set_param_sparse(capsule->nl_constr_h_fun_jac+stage, n_update, idx, p); + capsule->nl_constr_h_fun[stage].set_param_sparse(capsule->nl_constr_h_fun+stage, n_update, idx, p); + + // cost + if (stage == 0) + { + capsule->cost_y_0_fun.set_param_sparse(&capsule->cost_y_0_fun, n_update, idx, p); + capsule->cost_y_0_fun_jac_ut_xt.set_param_sparse(&capsule->cost_y_0_fun_jac_ut_xt, n_update, idx, p); + capsule->cost_y_0_hess.set_param_sparse(&capsule->cost_y_0_hess, n_update, idx, p); + } + else // 0 < stage < N + { + capsule->cost_y_fun[stage-1].set_param_sparse(capsule->cost_y_fun+stage-1, n_update, idx, p); + capsule->cost_y_fun_jac_ut_xt[stage-1].set_param_sparse(capsule->cost_y_fun_jac_ut_xt+stage-1, n_update, idx, p); + capsule->cost_y_hess[stage-1].set_param_sparse(capsule->cost_y_hess+stage-1, n_update, idx, p); + } + } + + else // stage == N + { + // terminal shooting node has no dynamics + // cost + capsule->cost_y_e_fun.set_param_sparse(&capsule->cost_y_e_fun, n_update, idx, p); + capsule->cost_y_e_fun_jac_ut_xt.set_param_sparse(&capsule->cost_y_e_fun_jac_ut_xt, n_update, idx, p); + capsule->cost_y_e_hess.set_param_sparse(&capsule->cost_y_e_hess, n_update, idx, p); + // constraints + + } + + + return solver_status; +} int long_acados_solve(long_solver_capsule* capsule) { - // solve NLP + // solve NLP int solver_status = ocp_nlp_solve(capsule->nlp_solver, capsule->nlp_in, capsule->nlp_out); return solver_status; @@ -976,15 +1034,6 @@ int long_acados_free(long_solver_capsule* capsule) return 0; } -ocp_nlp_in *long_acados_get_nlp_in(long_solver_capsule* capsule) { return capsule->nlp_in; } -ocp_nlp_out *long_acados_get_nlp_out(long_solver_capsule* capsule) { return capsule->nlp_out; } -ocp_nlp_out *long_acados_get_sens_out(long_solver_capsule* capsule) { return capsule->sens_out; } -ocp_nlp_solver *long_acados_get_nlp_solver(long_solver_capsule* capsule) { return capsule->nlp_solver; } -ocp_nlp_config *long_acados_get_nlp_config(long_solver_capsule* capsule) { return capsule->nlp_config; } -void *long_acados_get_nlp_opts(long_solver_capsule* capsule) { return capsule->nlp_opts; } -ocp_nlp_dims *long_acados_get_nlp_dims(long_solver_capsule* capsule) { return capsule->nlp_dims; } -ocp_nlp_plan_t *long_acados_get_nlp_plan(long_solver_capsule* capsule) { return capsule->nlp_solver_plan; } - void long_acados_print_stats(long_solver_capsule* capsule) { @@ -998,6 +1047,11 @@ void long_acados_print_stats(long_solver_capsule* capsule) ocp_nlp_get(capsule->nlp_config, capsule->nlp_solver, "statistics", stat); int nrow = sqp_iter+1 < stat_m ? sqp_iter+1 : stat_m; + + printf("iter\tres_stat\tres_eq\t\tres_ineq\tres_comp\tqp_stat\tqp_iter\talpha"); + if (stat_n > 8) + printf("\t\tqp_res_stat\tqp_res_eq\tqp_res_ineq\tqp_res_comp"); + printf("\n"); printf("iter\tqp_stat\tqp_iter\n"); for (int i = 0; i < nrow; i++) { @@ -1010,3 +1064,24 @@ void long_acados_print_stats(long_solver_capsule* capsule) } } +int long_acados_custom_update(long_solver_capsule* capsule, double* data, int data_len) +{ + (void)capsule; + (void)data; + (void)data_len; + printf("\ndummy function that can be called in between solver calls to update parameters or numerical data efficiently in C.\n"); + printf("nothing set yet..\n"); + return 1; + +} + + + +ocp_nlp_in *long_acados_get_nlp_in(long_solver_capsule* capsule) { return capsule->nlp_in; } +ocp_nlp_out *long_acados_get_nlp_out(long_solver_capsule* capsule) { return capsule->nlp_out; } +ocp_nlp_out *long_acados_get_sens_out(long_solver_capsule* capsule) { return capsule->sens_out; } +ocp_nlp_solver *long_acados_get_nlp_solver(long_solver_capsule* capsule) { return capsule->nlp_solver; } +ocp_nlp_config *long_acados_get_nlp_config(long_solver_capsule* capsule) { return capsule->nlp_config; } +void *long_acados_get_nlp_opts(long_solver_capsule* capsule) { return capsule->nlp_opts; } +ocp_nlp_dims *long_acados_get_nlp_dims(long_solver_capsule* capsule) { return capsule->nlp_dims; } +ocp_nlp_plan_t *long_acados_get_nlp_plan(long_solver_capsule* capsule) { return capsule->nlp_solver_plan; } diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_solver_long.h b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_solver_long.h index afc630825..351d6ac8c 100644 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_solver_long.h +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_solver_long.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * @@ -74,6 +71,7 @@ extern "C" { #endif + // ** capsule for solver data ** typedef struct long_solver_capsule { @@ -106,6 +104,7 @@ typedef struct long_solver_capsule external_function_param_casadi *cost_y_hess; + external_function_param_casadi cost_y_0_fun; external_function_param_casadi cost_y_0_fun_jac_ut_xt; external_function_param_casadi cost_y_0_hess; @@ -120,7 +119,6 @@ typedef struct long_solver_capsule // constraints external_function_param_casadi *nl_constr_h_fun_jac; external_function_param_casadi *nl_constr_h_fun; - external_function_param_casadi *nl_constr_h_fun_jac_hess; @@ -132,7 +130,7 @@ ACADOS_SYMBOL_EXPORT int long_acados_free_capsule(long_solver_capsule *capsule); ACADOS_SYMBOL_EXPORT int long_acados_create(long_solver_capsule * capsule); -ACADOS_SYMBOL_EXPORT int long_acados_reset(long_solver_capsule* capsule); +ACADOS_SYMBOL_EXPORT int long_acados_reset(long_solver_capsule* capsule, int reset_qp_solver_mem); /** * Generic version of long_acados_create which allows to use a different number of shooting intervals than @@ -150,10 +148,14 @@ ACADOS_SYMBOL_EXPORT int long_acados_update_time_steps(long_solver_capsule * cap */ ACADOS_SYMBOL_EXPORT int long_acados_update_qp_solver_cond_N(long_solver_capsule * capsule, int qp_solver_cond_N); ACADOS_SYMBOL_EXPORT int long_acados_update_params(long_solver_capsule * capsule, int stage, double *value, int np); +ACADOS_SYMBOL_EXPORT int long_acados_update_params_sparse(long_solver_capsule * capsule, int stage, int *idx, double *p, int n_update); + ACADOS_SYMBOL_EXPORT int long_acados_solve(long_solver_capsule * capsule); ACADOS_SYMBOL_EXPORT int long_acados_free(long_solver_capsule * capsule); ACADOS_SYMBOL_EXPORT void long_acados_print_stats(long_solver_capsule * capsule); - +ACADOS_SYMBOL_EXPORT int long_acados_custom_update(long_solver_capsule* capsule, double* data, int data_len); + + ACADOS_SYMBOL_EXPORT ocp_nlp_in *long_acados_get_nlp_in(long_solver_capsule * capsule); ACADOS_SYMBOL_EXPORT ocp_nlp_out *long_acados_get_nlp_out(long_solver_capsule * capsule); ACADOS_SYMBOL_EXPORT ocp_nlp_out *long_acados_get_sens_out(long_solver_capsule * capsule); diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_solver_sfunction_long.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_solver_sfunction_long.c deleted file mode 100644 index 41b6d4431..000000000 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_solver_sfunction_long.c +++ /dev/null @@ -1,264 +0,0 @@ -/* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl - * - * This file is part of acados. - * - * 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 HOLDER 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.; - */ - -#define S_FUNCTION_NAME acados_solver_sfunction_long -#define S_FUNCTION_LEVEL 2 - -#define MDL_START - -// acados -// #include "acados/utils/print.h" -#include "acados_c/sim_interface.h" -#include "acados_c/external_function_interface.h" - -// example specific -#include "long_model/long_model.h" -#include "acados_solver_long.h" - -#include "simstruc.h" - -#define SAMPLINGTIME 0.06944444444444445 - -static void mdlInitializeSizes (SimStruct *S) -{ - // specify the number of continuous and discrete states - ssSetNumContStates(S, 0); - ssSetNumDiscStates(S, 0);// specify the number of input ports - if ( !ssSetNumInputPorts(S, 8) ) - return; - - // specify the number of output ports - if ( !ssSetNumOutputPorts(S, 6) ) - return; - - // specify dimension information for the input ports - // lbx_0 - ssSetInputPortVectorDimension(S, 0, 3); - // ubx_0 - ssSetInputPortVectorDimension(S, 1, 3); - // parameters - ssSetInputPortVectorDimension(S, 2, (12+1) * 6); - // y_ref_0 - ssSetInputPortVectorDimension(S, 3, 6); - // y_ref - ssSetInputPortVectorDimension(S, 4, 66); - // y_ref_e - ssSetInputPortVectorDimension(S, 5, 5); - // lh - ssSetInputPortVectorDimension(S, 6, 4); - // uh - ssSetInputPortVectorDimension(S, 7, 4);/* specify dimension information for the OUTPUT ports */ - ssSetOutputPortVectorDimension(S, 0, 1 ); - ssSetOutputPortVectorDimension(S, 1, 1 ); - ssSetOutputPortVectorDimension(S, 2, 1 ); - ssSetOutputPortVectorDimension(S, 3, 3 ); // state at shooting node 1 - ssSetOutputPortVectorDimension(S, 4, 1); - ssSetOutputPortVectorDimension(S, 5, 1 ); - - // specify the direct feedthrough status - // should be set to 1 for all inputs used in mdlOutputs - ssSetInputPortDirectFeedThrough(S, 0, 1); - ssSetInputPortDirectFeedThrough(S, 1, 1); - ssSetInputPortDirectFeedThrough(S, 2, 1); - ssSetInputPortDirectFeedThrough(S, 3, 1); - ssSetInputPortDirectFeedThrough(S, 4, 1); - ssSetInputPortDirectFeedThrough(S, 5, 1); - ssSetInputPortDirectFeedThrough(S, 6, 1); - ssSetInputPortDirectFeedThrough(S, 7, 1); - - // one sample time - ssSetNumSampleTimes(S, 1); -} - - -#if defined(MATLAB_MEX_FILE) - -#define MDL_SET_INPUT_PORT_DIMENSION_INFO -#define MDL_SET_OUTPUT_PORT_DIMENSION_INFO - -static void mdlSetInputPortDimensionInfo(SimStruct *S, int_T port, const DimsInfo_T *dimsInfo) -{ - if ( !ssSetInputPortDimensionInfo(S, port, dimsInfo) ) - return; -} - -static void mdlSetOutputPortDimensionInfo(SimStruct *S, int_T port, const DimsInfo_T *dimsInfo) -{ - if ( !ssSetOutputPortDimensionInfo(S, port, dimsInfo) ) - return; -} - -#endif /* MATLAB_MEX_FILE */ - - -static void mdlInitializeSampleTimes(SimStruct *S) -{ - ssSetSampleTime(S, 0, SAMPLINGTIME); - ssSetOffsetTime(S, 0, 0.0); -} - - -static void mdlStart(SimStruct *S) -{ - long_solver_capsule *capsule = long_acados_create_capsule(); - long_acados_create(capsule); - - ssSetUserData(S, (void*)capsule); -} - - -static void mdlOutputs(SimStruct *S, int_T tid) -{ - long_solver_capsule *capsule = ssGetUserData(S); - ocp_nlp_config *nlp_config = long_acados_get_nlp_config(capsule); - ocp_nlp_dims *nlp_dims = long_acados_get_nlp_dims(capsule); - ocp_nlp_in *nlp_in = long_acados_get_nlp_in(capsule); - ocp_nlp_out *nlp_out = long_acados_get_nlp_out(capsule); - - InputRealPtrsType in_sign; - - // local buffer - real_t buffer[6]; - - /* go through inputs */ - // lbx_0 - in_sign = ssGetInputPortRealSignalPtrs(S, 0); - for (int i = 0; i < 3; i++) - buffer[i] = (double)(*in_sign[i]); - - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "lbx", buffer); - // ubx_0 - in_sign = ssGetInputPortRealSignalPtrs(S, 1); - for (int i = 0; i < 3; i++) - buffer[i] = (double)(*in_sign[i]); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "ubx", buffer); - // parameters - stage-variant !!! - in_sign = ssGetInputPortRealSignalPtrs(S, 2); - - // update value of parameters - for (int ii = 0; ii <= 12; ii++) - { - for (int jj = 0; jj < 6; jj++) - buffer[jj] = (double)(*in_sign[ii*6+jj]); - long_acados_update_params(capsule, ii, buffer, 6); - } - - - // y_ref_0 - in_sign = ssGetInputPortRealSignalPtrs(S, 3); - - for (int i = 0; i < 6; i++) - buffer[i] = (double)(*in_sign[i]); - - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "yref", (void *) buffer); - - - // y_ref - for stages 1 to N-1 - in_sign = ssGetInputPortRealSignalPtrs(S, 4); - - for (int ii = 1; ii < 12; ii++) - { - for (int jj = 0; jj < 6; jj++) - buffer[jj] = (double)(*in_sign[(ii-1)*6+jj]); - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, ii, "yref", (void *) buffer); - } - - - // y_ref_e - in_sign = ssGetInputPortRealSignalPtrs(S, 5); - - for (int i = 0; i < 5; i++) - buffer[i] = (double)(*in_sign[i]); - - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 12, "yref", (void *) buffer); - // lh - in_sign = ssGetInputPortRealSignalPtrs(S, 6); - - for (int i = 0; i < 4; i++) - buffer[i] = (double)(*in_sign[i]); - - for (int ii = 0; ii < 12; ii++) - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, ii, "lh", buffer); - // uh - in_sign = ssGetInputPortRealSignalPtrs(S, 7); - - for (int i = 0; i < 4; i++) - buffer[i] = (double)(*in_sign[i]); - - for (int ii = 0; ii < 12; ii++) - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, ii, "uh", buffer); - - /* call solver */ - int rti_phase = 0; - ocp_nlp_solver_opts_set(nlp_config, capsule->nlp_opts, "rti_phase", &rti_phase); - int acados_status = long_acados_solve(capsule); - - - /* set outputs */ - // assign pointers to output signals - real_t *out_u0, *out_utraj, *out_xtraj, *out_status, *out_sqp_iter, *out_KKT_res, *out_x1, *out_cpu_time, *out_cpu_time_sim, *out_cpu_time_qp, *out_cpu_time_lin; - int tmp_int; - out_u0 = ssGetOutputPortRealSignal(S, 0); - ocp_nlp_out_get(nlp_config, nlp_dims, nlp_out, 0, "u", (void *) out_u0); - - - out_status = ssGetOutputPortRealSignal(S, 1); - *out_status = (real_t) acados_status; - out_KKT_res = ssGetOutputPortRealSignal(S, 2); - *out_KKT_res = (real_t) nlp_out->inf_norm_res; - out_x1 = ssGetOutputPortRealSignal(S, 3); - ocp_nlp_out_get(nlp_config, nlp_dims, nlp_out, 1, "x", (void *) out_x1); - out_cpu_time = ssGetOutputPortRealSignal(S, 4); - // get solution time - ocp_nlp_get(nlp_config, capsule->nlp_solver, "time_tot", (void *) out_cpu_time); - out_sqp_iter = ssGetOutputPortRealSignal(S, 5); - // get sqp iter - ocp_nlp_get(nlp_config, capsule->nlp_solver, "sqp_iter", (void *) &tmp_int); - *out_sqp_iter = (real_t) tmp_int; - -} - -static void mdlTerminate(SimStruct *S) -{ - long_solver_capsule *capsule = ssGetUserData(S); - - long_acados_free(capsule); - long_acados_free_capsule(capsule); -} - - -#ifdef MATLAB_MEX_FILE -#include "simulink.c" -#else -#include "cg_sfun.h" -#endif diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/libacados_ocp_solver_long.so b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/libacados_ocp_solver_long.so index da3a2c889..b9ab33a02 100755 Binary files a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/libacados_ocp_solver_long.so and b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/libacados_ocp_solver_long.so differ diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_constraints/long_h_constraint.h b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_constraints/long_constraints.h similarity index 85% rename from selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_constraints/long_h_constraint.h rename to selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_constraints/long_constraints.h index eab2d0d9b..d0abd78bd 100644 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_constraints/long_h_constraint.h +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_constraints/long_constraints.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * @@ -31,14 +28,18 @@ * POSSIBILITY OF SUCH DAMAGE.; */ -#ifndef long_H_CONSTRAINT -#define long_H_CONSTRAINT +#ifndef long_CONSTRAINTS +#define long_CONSTRAINTS #ifdef __cplusplus extern "C" { #endif + + + + int long_constr_h_fun_jac_uxt_zt(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); int long_constr_h_fun_jac_uxt_zt_work(int *, int *, int *, int *); const int *long_constr_h_fun_jac_uxt_zt_sparsity_in(int); @@ -56,8 +57,10 @@ int long_constr_h_fun_n_out(void); + + #ifdef __cplusplus } /* extern "C" */ #endif -#endif // long_H_CONSTRAINT +#endif // long_CONSTRAINTS diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_0_fun.h b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost.h similarity index 53% rename from selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_0_fun.h rename to selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost.h index 928ef7a8c..03878fd75 100644 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_0_fun.h +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * @@ -32,14 +29,16 @@ */ -#ifndef long_Y_0_COST -#define long_Y_0_COST +#ifndef long_COST +#define long_COST #ifdef __cplusplus extern "C" { #endif +// Cost at initial shooting node + int long_cost_y_0_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); int long_cost_y_0_fun_work(int *, int *, int *, int *); const int *long_cost_y_0_fun_sparsity_in(int); @@ -62,8 +61,59 @@ int long_cost_y_0_hess_n_in(void); int long_cost_y_0_hess_n_out(void); + +// Cost at path shooting node + +int long_cost_y_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); +int long_cost_y_fun_work(int *, int *, int *, int *); +const int *long_cost_y_fun_sparsity_in(int); +const int *long_cost_y_fun_sparsity_out(int); +int long_cost_y_fun_n_in(void); +int long_cost_y_fun_n_out(void); + +int long_cost_y_fun_jac_ut_xt(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); +int long_cost_y_fun_jac_ut_xt_work(int *, int *, int *, int *); +const int *long_cost_y_fun_jac_ut_xt_sparsity_in(int); +const int *long_cost_y_fun_jac_ut_xt_sparsity_out(int); +int long_cost_y_fun_jac_ut_xt_n_in(void); +int long_cost_y_fun_jac_ut_xt_n_out(void); + +int long_cost_y_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); +int long_cost_y_hess_work(int *, int *, int *, int *); +const int *long_cost_y_hess_sparsity_in(int); +const int *long_cost_y_hess_sparsity_out(int); +int long_cost_y_hess_n_in(void); +int long_cost_y_hess_n_out(void); + + + +// Cost at terminal shooting node + +int long_cost_y_e_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); +int long_cost_y_e_fun_work(int *, int *, int *, int *); +const int *long_cost_y_e_fun_sparsity_in(int); +const int *long_cost_y_e_fun_sparsity_out(int); +int long_cost_y_e_fun_n_in(void); +int long_cost_y_e_fun_n_out(void); + +int long_cost_y_e_fun_jac_ut_xt(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); +int long_cost_y_e_fun_jac_ut_xt_work(int *, int *, int *, int *); +const int *long_cost_y_e_fun_jac_ut_xt_sparsity_in(int); +const int *long_cost_y_e_fun_jac_ut_xt_sparsity_out(int); +int long_cost_y_e_fun_jac_ut_xt_n_in(void); +int long_cost_y_e_fun_jac_ut_xt_n_out(void); + +int long_cost_y_e_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); +int long_cost_y_e_hess_work(int *, int *, int *, int *); +const int *long_cost_y_e_hess_sparsity_in(int); +const int *long_cost_y_e_hess_sparsity_out(int); +int long_cost_y_e_hess_n_in(void); +int long_cost_y_e_hess_n_out(void); + + + #ifdef __cplusplus } /* extern "C" */ #endif -#endif // long_Y_0_COST +#endif // long_COST diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_0_fun.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_0_fun.c index 09f838e55..f5edb8820 100644 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_0_fun.c +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_0_fun.c @@ -33,6 +33,7 @@ extern "C" { #define casadi_s0 CASADI_PREFIX(s0) #define casadi_s1 CASADI_PREFIX(s1) #define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) #define casadi_sq CASADI_PREFIX(sq) /* Symbol visibility in DLLs */ @@ -54,19 +55,20 @@ casadi_real casadi_sq(casadi_real x) { return x*x;} static const casadi_int casadi_s0[7] = {3, 1, 0, 3, 0, 1, 2}; static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; -static const casadi_int casadi_s2[10] = {6, 1, 0, 6, 0, 1, 2, 3, 4, 5}; +static const casadi_int casadi_s2[3] = {0, 0, 0}; +static const casadi_int casadi_s3[10] = {6, 1, 0, 6, 0, 1, 2, 3, 4, 5}; -/* long_cost_y_0_fun:(i0[3],i1,i2[6])->(o0[6]) */ +/* long_cost_y_0_fun:(i0[3],i1,i2[],i3[6])->(o0[6]) */ static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { casadi_real a0, a1, a2, a3, a4; - a0=arg[2]? arg[2][2] : 0; + a0=arg[3]? arg[3][2] : 0; a1=arg[0]? arg[0][0] : 0; a0=(a0-a1); a2=arg[0]? arg[0][1] : 0; a3=casadi_sq(a2); a4=5.; a3=(a3/a4); - a4=arg[2]? arg[2][4] : 0; + a4=arg[3]? arg[3][4] : 0; a4=(a4*a2); a3=(a3+a4); a4=6.; @@ -80,7 +82,7 @@ static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, if (res[0]!=0) res[0][2]=a2; a2=arg[0]? arg[0][2] : 0; if (res[0]!=0) res[0][3]=a2; - a1=arg[2]? arg[2][3] : 0; + a1=arg[3]? arg[3][3] : 0; a2=(a2-a1); if (res[0]!=0) res[0][4]=a2; a2=arg[1]? arg[1][0] : 0; @@ -116,7 +118,7 @@ CASADI_SYMBOL_EXPORT void long_cost_y_0_fun_incref(void) { CASADI_SYMBOL_EXPORT void long_cost_y_0_fun_decref(void) { } -CASADI_SYMBOL_EXPORT casadi_int long_cost_y_0_fun_n_in(void) { return 3;} +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_0_fun_n_in(void) { return 4;} CASADI_SYMBOL_EXPORT casadi_int long_cost_y_0_fun_n_out(void) { return 1;} @@ -131,6 +133,7 @@ CASADI_SYMBOL_EXPORT const char* long_cost_y_0_fun_name_in(casadi_int i) { case 0: return "i0"; case 1: return "i1"; case 2: return "i2"; + case 3: return "i3"; default: return 0; } } @@ -147,19 +150,20 @@ CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_0_fun_sparsity_in(casadi_int case 0: return casadi_s0; case 1: return casadi_s1; case 2: return casadi_s2; + case 3: return casadi_s3; default: return 0; } } CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_0_fun_sparsity_out(casadi_int i) { switch (i) { - case 0: return casadi_s2; + case 0: return casadi_s3; default: return 0; } } CASADI_SYMBOL_EXPORT int long_cost_y_0_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { - if (sz_arg) *sz_arg = 3; + if (sz_arg) *sz_arg = 4; if (sz_res) *sz_res = 1; if (sz_iw) *sz_iw = 0; if (sz_w) *sz_w = 0; diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_0_fun_jac_ut_xt.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_0_fun_jac_ut_xt.c index 1347703e5..94f206d6f 100644 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_0_fun_jac_ut_xt.c +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_0_fun_jac_ut_xt.c @@ -34,6 +34,8 @@ extern "C" { #define casadi_s1 CASADI_PREFIX(s1) #define casadi_s2 CASADI_PREFIX(s2) #define casadi_s3 CASADI_PREFIX(s3) +#define casadi_s4 CASADI_PREFIX(s4) +#define casadi_s5 CASADI_PREFIX(s5) #define casadi_sq CASADI_PREFIX(sq) /* Symbol visibility in DLLs */ @@ -55,20 +57,22 @@ casadi_real casadi_sq(casadi_real x) { return x*x;} static const casadi_int casadi_s0[7] = {3, 1, 0, 3, 0, 1, 2}; static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; -static const casadi_int casadi_s2[10] = {6, 1, 0, 6, 0, 1, 2, 3, 4, 5}; -static const casadi_int casadi_s3[16] = {4, 6, 0, 2, 3, 4, 5, 6, 7, 1, 2, 1, 2, 3, 3, 0}; +static const casadi_int casadi_s2[3] = {0, 0, 0}; +static const casadi_int casadi_s3[10] = {6, 1, 0, 6, 0, 1, 2, 3, 4, 5}; +static const casadi_int casadi_s4[16] = {4, 6, 0, 2, 3, 4, 5, 6, 7, 1, 2, 1, 2, 3, 3, 0}; +static const casadi_int casadi_s5[3] = {6, 0, 0}; -/* long_cost_y_0_fun_jac_ut_xt:(i0[3],i1,i2[6])->(o0[6],o1[4x6,7nz]) */ +/* long_cost_y_0_fun_jac_ut_xt:(i0[3],i1,i2[],i3[6])->(o0[6],o1[4x6,7nz],o2[6x0]) */ static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { casadi_real a0, a1, a2, a3, a4, a5; - a0=arg[2]? arg[2][2] : 0; + a0=arg[3]? arg[3][2] : 0; a1=arg[0]? arg[0][0] : 0; a0=(a0-a1); a2=arg[0]? arg[0][1] : 0; a3=casadi_sq(a2); a4=5.; a3=(a3/a4); - a4=arg[2]? arg[2][4] : 0; + a4=arg[3]? arg[3][4] : 0; a5=(a4*a2); a3=(a3+a5); a5=6.; @@ -82,7 +86,7 @@ static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, if (res[0]!=0) res[0][2]=a2; a1=arg[0]? arg[0][2] : 0; if (res[0]!=0) res[0][3]=a1; - a5=arg[2]? arg[2][3] : 0; + a5=arg[3]? arg[3][3] : 0; a1=(a1-a5); if (res[0]!=0) res[0][4]=a1; a1=arg[1]? arg[1][0] : 0; @@ -136,9 +140,9 @@ CASADI_SYMBOL_EXPORT void long_cost_y_0_fun_jac_ut_xt_incref(void) { CASADI_SYMBOL_EXPORT void long_cost_y_0_fun_jac_ut_xt_decref(void) { } -CASADI_SYMBOL_EXPORT casadi_int long_cost_y_0_fun_jac_ut_xt_n_in(void) { return 3;} +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_0_fun_jac_ut_xt_n_in(void) { return 4;} -CASADI_SYMBOL_EXPORT casadi_int long_cost_y_0_fun_jac_ut_xt_n_out(void) { return 2;} +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_0_fun_jac_ut_xt_n_out(void) { return 3;} CASADI_SYMBOL_EXPORT casadi_real long_cost_y_0_fun_jac_ut_xt_default_in(casadi_int i) { switch (i) { @@ -151,6 +155,7 @@ CASADI_SYMBOL_EXPORT const char* long_cost_y_0_fun_jac_ut_xt_name_in(casadi_int case 0: return "i0"; case 1: return "i1"; case 2: return "i2"; + case 3: return "i3"; default: return 0; } } @@ -159,6 +164,7 @@ CASADI_SYMBOL_EXPORT const char* long_cost_y_0_fun_jac_ut_xt_name_out(casadi_int switch (i) { case 0: return "o0"; case 1: return "o1"; + case 2: return "o2"; default: return 0; } } @@ -168,21 +174,23 @@ CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_0_fun_jac_ut_xt_sparsity_in(c case 0: return casadi_s0; case 1: return casadi_s1; case 2: return casadi_s2; + case 3: return casadi_s3; default: return 0; } } CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_0_fun_jac_ut_xt_sparsity_out(casadi_int i) { switch (i) { - case 0: return casadi_s2; - case 1: return casadi_s3; + case 0: return casadi_s3; + case 1: return casadi_s4; + case 2: return casadi_s5; default: return 0; } } CASADI_SYMBOL_EXPORT int long_cost_y_0_fun_jac_ut_xt_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { - if (sz_arg) *sz_arg = 3; - if (sz_res) *sz_res = 2; + if (sz_arg) *sz_arg = 4; + if (sz_res) *sz_res = 3; if (sz_iw) *sz_iw = 0; if (sz_w) *sz_w = 0; return 0; diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_0_hess.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_0_hess.c index 5a0b4a82b..29ba74626 100644 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_0_hess.c +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_0_hess.c @@ -34,6 +34,7 @@ extern "C" { #define casadi_s1 CASADI_PREFIX(s1) #define casadi_s2 CASADI_PREFIX(s2) #define casadi_s3 CASADI_PREFIX(s3) +#define casadi_s4 CASADI_PREFIX(s4) #define casadi_sq CASADI_PREFIX(sq) /* Symbol visibility in DLLs */ @@ -55,13 +56,14 @@ casadi_real casadi_sq(casadi_real x) { return x*x;} static const casadi_int casadi_s0[7] = {3, 1, 0, 3, 0, 1, 2}; static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; -static const casadi_int casadi_s2[10] = {6, 1, 0, 6, 0, 1, 2, 3, 4, 5}; -static const casadi_int casadi_s3[10] = {4, 4, 0, 0, 1, 3, 3, 2, 1, 2}; +static const casadi_int casadi_s2[3] = {0, 0, 0}; +static const casadi_int casadi_s3[10] = {6, 1, 0, 6, 0, 1, 2, 3, 4, 5}; +static const casadi_int casadi_s4[10] = {4, 4, 0, 0, 1, 3, 3, 2, 1, 2}; -/* long_cost_y_0_hess:(i0[3],i1,i2[6],i3[6])->(o0[4x4,3nz]) */ +/* long_cost_y_0_hess:(i0[3],i1,i2[],i3[6],i4[6])->(o0[4x4,3nz]) */ static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { casadi_real a0, a1, a10, a2, a3, a4, a5, a6, a7, a8, a9; - a0=arg[2]? arg[2][0] : 0; + a0=arg[3]? arg[3][0] : 0; a1=arg[0]? arg[0][1] : 0; a2=10.; a2=(a1+a2); @@ -75,10 +77,10 @@ static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, a5=2.0000000000000001e-01; a6=(a1+a1); a6=(a5*a6); - a7=arg[3]? arg[3][4] : 0; + a7=arg[4]? arg[4][4] : 0; a6=(a6+a7); a6=(a6/a2); - a8=arg[3]? arg[3][2] : 0; + a8=arg[4]? arg[4][2] : 0; a9=arg[0]? arg[0][0] : 0; a8=(a8-a9); a9=casadi_sq(a1); @@ -139,7 +141,7 @@ CASADI_SYMBOL_EXPORT void long_cost_y_0_hess_incref(void) { CASADI_SYMBOL_EXPORT void long_cost_y_0_hess_decref(void) { } -CASADI_SYMBOL_EXPORT casadi_int long_cost_y_0_hess_n_in(void) { return 4;} +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_0_hess_n_in(void) { return 5;} CASADI_SYMBOL_EXPORT casadi_int long_cost_y_0_hess_n_out(void) { return 1;} @@ -155,6 +157,7 @@ CASADI_SYMBOL_EXPORT const char* long_cost_y_0_hess_name_in(casadi_int i) { case 1: return "i1"; case 2: return "i2"; case 3: return "i3"; + case 4: return "i4"; default: return 0; } } @@ -171,20 +174,21 @@ CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_0_hess_sparsity_in(casadi_int case 0: return casadi_s0; case 1: return casadi_s1; case 2: return casadi_s2; - case 3: return casadi_s2; + case 3: return casadi_s3; + case 4: return casadi_s3; default: return 0; } } CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_0_hess_sparsity_out(casadi_int i) { switch (i) { - case 0: return casadi_s3; + case 0: return casadi_s4; default: return 0; } } CASADI_SYMBOL_EXPORT int long_cost_y_0_hess_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { - if (sz_arg) *sz_arg = 4; + if (sz_arg) *sz_arg = 5; if (sz_res) *sz_res = 1; if (sz_iw) *sz_iw = 0; if (sz_w) *sz_w = 0; diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_e_fun.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_e_fun.c index f17893993..50d42e08b 100644 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_e_fun.c +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_e_fun.c @@ -58,17 +58,17 @@ static const casadi_int casadi_s1[3] = {0, 0, 0}; static const casadi_int casadi_s2[10] = {6, 1, 0, 6, 0, 1, 2, 3, 4, 5}; static const casadi_int casadi_s3[9] = {5, 1, 0, 5, 0, 1, 2, 3, 4}; -/* long_cost_y_e_fun:(i0[3],i1[],i2[6])->(o0[5]) */ +/* long_cost_y_e_fun:(i0[3],i1[],i2[],i3[6])->(o0[5]) */ static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { casadi_real a0, a1, a2, a3, a4; - a0=arg[2]? arg[2][2] : 0; + a0=arg[3]? arg[3][2] : 0; a1=arg[0]? arg[0][0] : 0; a0=(a0-a1); a2=arg[0]? arg[0][1] : 0; a3=casadi_sq(a2); a4=5.; a3=(a3/a4); - a4=arg[2]? arg[2][4] : 0; + a4=arg[3]? arg[3][4] : 0; a4=(a4*a2); a3=(a3+a4); a4=6.; @@ -82,7 +82,7 @@ static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, if (res[0]!=0) res[0][2]=a2; a2=arg[0]? arg[0][2] : 0; if (res[0]!=0) res[0][3]=a2; - a1=arg[2]? arg[2][3] : 0; + a1=arg[3]? arg[3][3] : 0; a2=(a2-a1); if (res[0]!=0) res[0][4]=a2; return 0; @@ -116,7 +116,7 @@ CASADI_SYMBOL_EXPORT void long_cost_y_e_fun_incref(void) { CASADI_SYMBOL_EXPORT void long_cost_y_e_fun_decref(void) { } -CASADI_SYMBOL_EXPORT casadi_int long_cost_y_e_fun_n_in(void) { return 3;} +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_e_fun_n_in(void) { return 4;} CASADI_SYMBOL_EXPORT casadi_int long_cost_y_e_fun_n_out(void) { return 1;} @@ -131,6 +131,7 @@ CASADI_SYMBOL_EXPORT const char* long_cost_y_e_fun_name_in(casadi_int i) { case 0: return "i0"; case 1: return "i1"; case 2: return "i2"; + case 3: return "i3"; default: return 0; } } @@ -146,7 +147,8 @@ CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_e_fun_sparsity_in(casadi_int switch (i) { case 0: return casadi_s0; case 1: return casadi_s1; - case 2: return casadi_s2; + case 2: return casadi_s1; + case 3: return casadi_s2; default: return 0; } } @@ -159,7 +161,7 @@ CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_e_fun_sparsity_out(casadi_int } CASADI_SYMBOL_EXPORT int long_cost_y_e_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { - if (sz_arg) *sz_arg = 3; + if (sz_arg) *sz_arg = 4; if (sz_res) *sz_res = 1; if (sz_iw) *sz_iw = 0; if (sz_w) *sz_w = 0; diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_e_fun.h b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_e_fun.h deleted file mode 100644 index 41db4d27a..000000000 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_e_fun.h +++ /dev/null @@ -1,69 +0,0 @@ -/* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl - * - * This file is part of acados. - * - * 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 HOLDER 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.; - */ - - -#ifndef long_Y_E_COST -#define long_Y_E_COST - -#ifdef __cplusplus -extern "C" { -#endif - - -int long_cost_y_e_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int long_cost_y_e_fun_work(int *, int *, int *, int *); -const int *long_cost_y_e_fun_sparsity_in(int); -const int *long_cost_y_e_fun_sparsity_out(int); -int long_cost_y_e_fun_n_in(void); -int long_cost_y_e_fun_n_out(void); - -int long_cost_y_e_fun_jac_ut_xt(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int long_cost_y_e_fun_jac_ut_xt_work(int *, int *, int *, int *); -const int *long_cost_y_e_fun_jac_ut_xt_sparsity_in(int); -const int *long_cost_y_e_fun_jac_ut_xt_sparsity_out(int); -int long_cost_y_e_fun_jac_ut_xt_n_in(void); -int long_cost_y_e_fun_jac_ut_xt_n_out(void); - -int long_cost_y_e_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int long_cost_y_e_hess_work(int *, int *, int *, int *); -const int *long_cost_y_e_hess_sparsity_in(int); -const int *long_cost_y_e_hess_sparsity_out(int); -int long_cost_y_e_hess_n_in(void); -int long_cost_y_e_hess_n_out(void); - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // long_Y_E_COST diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_e_fun_jac_ut_xt.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_e_fun_jac_ut_xt.c index 402181b8c..46958d19a 100644 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_e_fun_jac_ut_xt.c +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_e_fun_jac_ut_xt.c @@ -35,6 +35,7 @@ extern "C" { #define casadi_s2 CASADI_PREFIX(s2) #define casadi_s3 CASADI_PREFIX(s3) #define casadi_s4 CASADI_PREFIX(s4) +#define casadi_s5 CASADI_PREFIX(s5) #define casadi_sq CASADI_PREFIX(sq) /* Symbol visibility in DLLs */ @@ -59,18 +60,19 @@ static const casadi_int casadi_s1[3] = {0, 0, 0}; static const casadi_int casadi_s2[10] = {6, 1, 0, 6, 0, 1, 2, 3, 4, 5}; static const casadi_int casadi_s3[9] = {5, 1, 0, 5, 0, 1, 2, 3, 4}; static const casadi_int casadi_s4[14] = {3, 5, 0, 2, 3, 4, 5, 6, 0, 1, 0, 1, 2, 2}; +static const casadi_int casadi_s5[3] = {5, 0, 0}; -/* long_cost_y_e_fun_jac_ut_xt:(i0[3],i1[],i2[6])->(o0[5],o1[3x5,6nz]) */ +/* long_cost_y_e_fun_jac_ut_xt:(i0[3],i1[],i2[],i3[6])->(o0[5],o1[3x5,6nz],o2[5x0]) */ static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { casadi_real a0, a1, a2, a3, a4, a5; - a0=arg[2]? arg[2][2] : 0; + a0=arg[3]? arg[3][2] : 0; a1=arg[0]? arg[0][0] : 0; a0=(a0-a1); a2=arg[0]? arg[0][1] : 0; a3=casadi_sq(a2); a4=5.; a3=(a3/a4); - a4=arg[2]? arg[2][4] : 0; + a4=arg[3]? arg[3][4] : 0; a5=(a4*a2); a3=(a3+a5); a5=6.; @@ -84,7 +86,7 @@ static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, if (res[0]!=0) res[0][2]=a2; a1=arg[0]? arg[0][2] : 0; if (res[0]!=0) res[0][3]=a1; - a5=arg[2]? arg[2][3] : 0; + a5=arg[3]? arg[3][3] : 0; a1=(a1-a5); if (res[0]!=0) res[0][4]=a1; a1=(1./a3); @@ -135,9 +137,9 @@ CASADI_SYMBOL_EXPORT void long_cost_y_e_fun_jac_ut_xt_incref(void) { CASADI_SYMBOL_EXPORT void long_cost_y_e_fun_jac_ut_xt_decref(void) { } -CASADI_SYMBOL_EXPORT casadi_int long_cost_y_e_fun_jac_ut_xt_n_in(void) { return 3;} +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_e_fun_jac_ut_xt_n_in(void) { return 4;} -CASADI_SYMBOL_EXPORT casadi_int long_cost_y_e_fun_jac_ut_xt_n_out(void) { return 2;} +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_e_fun_jac_ut_xt_n_out(void) { return 3;} CASADI_SYMBOL_EXPORT casadi_real long_cost_y_e_fun_jac_ut_xt_default_in(casadi_int i) { switch (i) { @@ -150,6 +152,7 @@ CASADI_SYMBOL_EXPORT const char* long_cost_y_e_fun_jac_ut_xt_name_in(casadi_int case 0: return "i0"; case 1: return "i1"; case 2: return "i2"; + case 3: return "i3"; default: return 0; } } @@ -158,6 +161,7 @@ CASADI_SYMBOL_EXPORT const char* long_cost_y_e_fun_jac_ut_xt_name_out(casadi_int switch (i) { case 0: return "o0"; case 1: return "o1"; + case 2: return "o2"; default: return 0; } } @@ -166,7 +170,8 @@ CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_e_fun_jac_ut_xt_sparsity_in(c switch (i) { case 0: return casadi_s0; case 1: return casadi_s1; - case 2: return casadi_s2; + case 2: return casadi_s1; + case 3: return casadi_s2; default: return 0; } } @@ -175,13 +180,14 @@ CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_e_fun_jac_ut_xt_sparsity_out( switch (i) { case 0: return casadi_s3; case 1: return casadi_s4; + case 2: return casadi_s5; default: return 0; } } CASADI_SYMBOL_EXPORT int long_cost_y_e_fun_jac_ut_xt_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { - if (sz_arg) *sz_arg = 3; - if (sz_res) *sz_res = 2; + if (sz_arg) *sz_arg = 4; + if (sz_res) *sz_res = 3; if (sz_iw) *sz_iw = 0; if (sz_w) *sz_w = 0; return 0; diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_e_hess.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_e_hess.c index e5ceea6d9..d1f1e2319 100644 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_e_hess.c +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_e_hess.c @@ -60,10 +60,10 @@ static const casadi_int casadi_s2[9] = {5, 1, 0, 5, 0, 1, 2, 3, 4}; static const casadi_int casadi_s3[10] = {6, 1, 0, 6, 0, 1, 2, 3, 4, 5}; static const casadi_int casadi_s4[9] = {3, 3, 0, 1, 3, 3, 1, 0, 1}; -/* long_cost_y_e_hess:(i0[3],i1[],i2[5],i3[6])->(o0[3x3,3nz]) */ +/* long_cost_y_e_hess:(i0[3],i1[],i2[],i3[5],i4[6])->(o0[3x3,3nz]) */ static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { casadi_real a0, a1, a10, a2, a3, a4, a5, a6, a7, a8, a9; - a0=arg[2]? arg[2][0] : 0; + a0=arg[3]? arg[3][0] : 0; a1=arg[0]? arg[0][1] : 0; a2=10.; a2=(a1+a2); @@ -77,10 +77,10 @@ static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, a5=2.0000000000000001e-01; a6=(a1+a1); a6=(a5*a6); - a7=arg[3]? arg[3][4] : 0; + a7=arg[4]? arg[4][4] : 0; a6=(a6+a7); a6=(a6/a2); - a8=arg[3]? arg[3][2] : 0; + a8=arg[4]? arg[4][2] : 0; a9=arg[0]? arg[0][0] : 0; a8=(a8-a9); a9=casadi_sq(a1); @@ -141,7 +141,7 @@ CASADI_SYMBOL_EXPORT void long_cost_y_e_hess_incref(void) { CASADI_SYMBOL_EXPORT void long_cost_y_e_hess_decref(void) { } -CASADI_SYMBOL_EXPORT casadi_int long_cost_y_e_hess_n_in(void) { return 4;} +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_e_hess_n_in(void) { return 5;} CASADI_SYMBOL_EXPORT casadi_int long_cost_y_e_hess_n_out(void) { return 1;} @@ -157,6 +157,7 @@ CASADI_SYMBOL_EXPORT const char* long_cost_y_e_hess_name_in(casadi_int i) { case 1: return "i1"; case 2: return "i2"; case 3: return "i3"; + case 4: return "i4"; default: return 0; } } @@ -172,8 +173,9 @@ CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_e_hess_sparsity_in(casadi_int switch (i) { case 0: return casadi_s0; case 1: return casadi_s1; - case 2: return casadi_s2; - case 3: return casadi_s3; + case 2: return casadi_s1; + case 3: return casadi_s2; + case 4: return casadi_s3; default: return 0; } } @@ -186,7 +188,7 @@ CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_e_hess_sparsity_out(casadi_in } CASADI_SYMBOL_EXPORT int long_cost_y_e_hess_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { - if (sz_arg) *sz_arg = 4; + if (sz_arg) *sz_arg = 5; if (sz_res) *sz_res = 1; if (sz_iw) *sz_iw = 0; if (sz_w) *sz_w = 0; diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_fun.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_fun.c index 7d8ac7eda..45f9ef128 100644 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_fun.c +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_fun.c @@ -33,6 +33,7 @@ extern "C" { #define casadi_s0 CASADI_PREFIX(s0) #define casadi_s1 CASADI_PREFIX(s1) #define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) #define casadi_sq CASADI_PREFIX(sq) /* Symbol visibility in DLLs */ @@ -54,19 +55,20 @@ casadi_real casadi_sq(casadi_real x) { return x*x;} static const casadi_int casadi_s0[7] = {3, 1, 0, 3, 0, 1, 2}; static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; -static const casadi_int casadi_s2[10] = {6, 1, 0, 6, 0, 1, 2, 3, 4, 5}; +static const casadi_int casadi_s2[3] = {0, 0, 0}; +static const casadi_int casadi_s3[10] = {6, 1, 0, 6, 0, 1, 2, 3, 4, 5}; -/* long_cost_y_fun:(i0[3],i1,i2[6])->(o0[6]) */ +/* long_cost_y_fun:(i0[3],i1,i2[],i3[6])->(o0[6]) */ static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { casadi_real a0, a1, a2, a3, a4; - a0=arg[2]? arg[2][2] : 0; + a0=arg[3]? arg[3][2] : 0; a1=arg[0]? arg[0][0] : 0; a0=(a0-a1); a2=arg[0]? arg[0][1] : 0; a3=casadi_sq(a2); a4=5.; a3=(a3/a4); - a4=arg[2]? arg[2][4] : 0; + a4=arg[3]? arg[3][4] : 0; a4=(a4*a2); a3=(a3+a4); a4=6.; @@ -80,7 +82,7 @@ static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, if (res[0]!=0) res[0][2]=a2; a2=arg[0]? arg[0][2] : 0; if (res[0]!=0) res[0][3]=a2; - a1=arg[2]? arg[2][3] : 0; + a1=arg[3]? arg[3][3] : 0; a2=(a2-a1); if (res[0]!=0) res[0][4]=a2; a2=arg[1]? arg[1][0] : 0; @@ -116,7 +118,7 @@ CASADI_SYMBOL_EXPORT void long_cost_y_fun_incref(void) { CASADI_SYMBOL_EXPORT void long_cost_y_fun_decref(void) { } -CASADI_SYMBOL_EXPORT casadi_int long_cost_y_fun_n_in(void) { return 3;} +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_fun_n_in(void) { return 4;} CASADI_SYMBOL_EXPORT casadi_int long_cost_y_fun_n_out(void) { return 1;} @@ -131,6 +133,7 @@ CASADI_SYMBOL_EXPORT const char* long_cost_y_fun_name_in(casadi_int i) { case 0: return "i0"; case 1: return "i1"; case 2: return "i2"; + case 3: return "i3"; default: return 0; } } @@ -147,19 +150,20 @@ CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_fun_sparsity_in(casadi_int i) case 0: return casadi_s0; case 1: return casadi_s1; case 2: return casadi_s2; + case 3: return casadi_s3; default: return 0; } } CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_fun_sparsity_out(casadi_int i) { switch (i) { - case 0: return casadi_s2; + case 0: return casadi_s3; default: return 0; } } CASADI_SYMBOL_EXPORT int long_cost_y_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { - if (sz_arg) *sz_arg = 3; + if (sz_arg) *sz_arg = 4; if (sz_res) *sz_res = 1; if (sz_iw) *sz_iw = 0; if (sz_w) *sz_w = 0; diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_fun.h b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_fun.h deleted file mode 100644 index 63e9d84c0..000000000 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_fun.h +++ /dev/null @@ -1,69 +0,0 @@ -/* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl - * - * This file is part of acados. - * - * 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 HOLDER 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.; - */ - - -#ifndef long_Y_COST -#define long_Y_COST - -#ifdef __cplusplus -extern "C" { -#endif - - -int long_cost_y_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int long_cost_y_fun_work(int *, int *, int *, int *); -const int *long_cost_y_fun_sparsity_in(int); -const int *long_cost_y_fun_sparsity_out(int); -int long_cost_y_fun_n_in(void); -int long_cost_y_fun_n_out(void); - -int long_cost_y_fun_jac_ut_xt(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int long_cost_y_fun_jac_ut_xt_work(int *, int *, int *, int *); -const int *long_cost_y_fun_jac_ut_xt_sparsity_in(int); -const int *long_cost_y_fun_jac_ut_xt_sparsity_out(int); -int long_cost_y_fun_jac_ut_xt_n_in(void); -int long_cost_y_fun_jac_ut_xt_n_out(void); - -int long_cost_y_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int long_cost_y_hess_work(int *, int *, int *, int *); -const int *long_cost_y_hess_sparsity_in(int); -const int *long_cost_y_hess_sparsity_out(int); -int long_cost_y_hess_n_in(void); -int long_cost_y_hess_n_out(void); - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // long_Y_COST diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_fun_jac_ut_xt.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_fun_jac_ut_xt.c index 228abb242..a02ffbc73 100644 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_fun_jac_ut_xt.c +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_fun_jac_ut_xt.c @@ -34,6 +34,8 @@ extern "C" { #define casadi_s1 CASADI_PREFIX(s1) #define casadi_s2 CASADI_PREFIX(s2) #define casadi_s3 CASADI_PREFIX(s3) +#define casadi_s4 CASADI_PREFIX(s4) +#define casadi_s5 CASADI_PREFIX(s5) #define casadi_sq CASADI_PREFIX(sq) /* Symbol visibility in DLLs */ @@ -55,20 +57,22 @@ casadi_real casadi_sq(casadi_real x) { return x*x;} static const casadi_int casadi_s0[7] = {3, 1, 0, 3, 0, 1, 2}; static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; -static const casadi_int casadi_s2[10] = {6, 1, 0, 6, 0, 1, 2, 3, 4, 5}; -static const casadi_int casadi_s3[16] = {4, 6, 0, 2, 3, 4, 5, 6, 7, 1, 2, 1, 2, 3, 3, 0}; +static const casadi_int casadi_s2[3] = {0, 0, 0}; +static const casadi_int casadi_s3[10] = {6, 1, 0, 6, 0, 1, 2, 3, 4, 5}; +static const casadi_int casadi_s4[16] = {4, 6, 0, 2, 3, 4, 5, 6, 7, 1, 2, 1, 2, 3, 3, 0}; +static const casadi_int casadi_s5[3] = {6, 0, 0}; -/* long_cost_y_fun_jac_ut_xt:(i0[3],i1,i2[6])->(o0[6],o1[4x6,7nz]) */ +/* long_cost_y_fun_jac_ut_xt:(i0[3],i1,i2[],i3[6])->(o0[6],o1[4x6,7nz],o2[6x0]) */ static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { casadi_real a0, a1, a2, a3, a4, a5; - a0=arg[2]? arg[2][2] : 0; + a0=arg[3]? arg[3][2] : 0; a1=arg[0]? arg[0][0] : 0; a0=(a0-a1); a2=arg[0]? arg[0][1] : 0; a3=casadi_sq(a2); a4=5.; a3=(a3/a4); - a4=arg[2]? arg[2][4] : 0; + a4=arg[3]? arg[3][4] : 0; a5=(a4*a2); a3=(a3+a5); a5=6.; @@ -82,7 +86,7 @@ static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, if (res[0]!=0) res[0][2]=a2; a1=arg[0]? arg[0][2] : 0; if (res[0]!=0) res[0][3]=a1; - a5=arg[2]? arg[2][3] : 0; + a5=arg[3]? arg[3][3] : 0; a1=(a1-a5); if (res[0]!=0) res[0][4]=a1; a1=arg[1]? arg[1][0] : 0; @@ -136,9 +140,9 @@ CASADI_SYMBOL_EXPORT void long_cost_y_fun_jac_ut_xt_incref(void) { CASADI_SYMBOL_EXPORT void long_cost_y_fun_jac_ut_xt_decref(void) { } -CASADI_SYMBOL_EXPORT casadi_int long_cost_y_fun_jac_ut_xt_n_in(void) { return 3;} +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_fun_jac_ut_xt_n_in(void) { return 4;} -CASADI_SYMBOL_EXPORT casadi_int long_cost_y_fun_jac_ut_xt_n_out(void) { return 2;} +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_fun_jac_ut_xt_n_out(void) { return 3;} CASADI_SYMBOL_EXPORT casadi_real long_cost_y_fun_jac_ut_xt_default_in(casadi_int i) { switch (i) { @@ -151,6 +155,7 @@ CASADI_SYMBOL_EXPORT const char* long_cost_y_fun_jac_ut_xt_name_in(casadi_int i) case 0: return "i0"; case 1: return "i1"; case 2: return "i2"; + case 3: return "i3"; default: return 0; } } @@ -159,6 +164,7 @@ CASADI_SYMBOL_EXPORT const char* long_cost_y_fun_jac_ut_xt_name_out(casadi_int i switch (i) { case 0: return "o0"; case 1: return "o1"; + case 2: return "o2"; default: return 0; } } @@ -168,21 +174,23 @@ CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_fun_jac_ut_xt_sparsity_in(cas case 0: return casadi_s0; case 1: return casadi_s1; case 2: return casadi_s2; + case 3: return casadi_s3; default: return 0; } } CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_fun_jac_ut_xt_sparsity_out(casadi_int i) { switch (i) { - case 0: return casadi_s2; - case 1: return casadi_s3; + case 0: return casadi_s3; + case 1: return casadi_s4; + case 2: return casadi_s5; default: return 0; } } CASADI_SYMBOL_EXPORT int long_cost_y_fun_jac_ut_xt_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { - if (sz_arg) *sz_arg = 3; - if (sz_res) *sz_res = 2; + if (sz_arg) *sz_arg = 4; + if (sz_res) *sz_res = 3; if (sz_iw) *sz_iw = 0; if (sz_w) *sz_w = 0; return 0; diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_hess.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_hess.c index b9bb530b2..5bd879f86 100644 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_hess.c +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_hess.c @@ -34,6 +34,7 @@ extern "C" { #define casadi_s1 CASADI_PREFIX(s1) #define casadi_s2 CASADI_PREFIX(s2) #define casadi_s3 CASADI_PREFIX(s3) +#define casadi_s4 CASADI_PREFIX(s4) #define casadi_sq CASADI_PREFIX(sq) /* Symbol visibility in DLLs */ @@ -55,13 +56,14 @@ casadi_real casadi_sq(casadi_real x) { return x*x;} static const casadi_int casadi_s0[7] = {3, 1, 0, 3, 0, 1, 2}; static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; -static const casadi_int casadi_s2[10] = {6, 1, 0, 6, 0, 1, 2, 3, 4, 5}; -static const casadi_int casadi_s3[10] = {4, 4, 0, 0, 1, 3, 3, 2, 1, 2}; +static const casadi_int casadi_s2[3] = {0, 0, 0}; +static const casadi_int casadi_s3[10] = {6, 1, 0, 6, 0, 1, 2, 3, 4, 5}; +static const casadi_int casadi_s4[10] = {4, 4, 0, 0, 1, 3, 3, 2, 1, 2}; -/* long_cost_y_hess:(i0[3],i1,i2[6],i3[6])->(o0[4x4,3nz]) */ +/* long_cost_y_hess:(i0[3],i1,i2[],i3[6],i4[6])->(o0[4x4,3nz]) */ static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { casadi_real a0, a1, a10, a2, a3, a4, a5, a6, a7, a8, a9; - a0=arg[2]? arg[2][0] : 0; + a0=arg[3]? arg[3][0] : 0; a1=arg[0]? arg[0][1] : 0; a2=10.; a2=(a1+a2); @@ -75,10 +77,10 @@ static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, a5=2.0000000000000001e-01; a6=(a1+a1); a6=(a5*a6); - a7=arg[3]? arg[3][4] : 0; + a7=arg[4]? arg[4][4] : 0; a6=(a6+a7); a6=(a6/a2); - a8=arg[3]? arg[3][2] : 0; + a8=arg[4]? arg[4][2] : 0; a9=arg[0]? arg[0][0] : 0; a8=(a8-a9); a9=casadi_sq(a1); @@ -139,7 +141,7 @@ CASADI_SYMBOL_EXPORT void long_cost_y_hess_incref(void) { CASADI_SYMBOL_EXPORT void long_cost_y_hess_decref(void) { } -CASADI_SYMBOL_EXPORT casadi_int long_cost_y_hess_n_in(void) { return 4;} +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_hess_n_in(void) { return 5;} CASADI_SYMBOL_EXPORT casadi_int long_cost_y_hess_n_out(void) { return 1;} @@ -155,6 +157,7 @@ CASADI_SYMBOL_EXPORT const char* long_cost_y_hess_name_in(casadi_int i) { case 1: return "i1"; case 2: return "i2"; case 3: return "i3"; + case 4: return "i4"; default: return 0; } } @@ -171,20 +174,21 @@ CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_hess_sparsity_in(casadi_int i case 0: return casadi_s0; case 1: return casadi_s1; case 2: return casadi_s2; - case 3: return casadi_s2; + case 3: return casadi_s3; + case 4: return casadi_s3; default: return 0; } } CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_hess_sparsity_out(casadi_int i) { switch (i) { - case 0: return casadi_s3; + case 0: return casadi_s4; default: return 0; } } CASADI_SYMBOL_EXPORT int long_cost_y_hess_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { - if (sz_arg) *sz_arg = 4; + if (sz_arg) *sz_arg = 5; if (sz_res) *sz_res = 1; if (sz_iw) *sz_iw = 0; if (sz_w) *sz_w = 0; diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_model/long_model.h b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_model/long_model.h index 723316848..cfe3a885e 100644 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_model/long_model.h +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_model/long_model.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/main_long.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/main_long.c index a52250226..94ff7c1f7 100644 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/main_long.c +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/main_long.c @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * @@ -42,6 +39,9 @@ #include "acados_c/external_function_interface.h" #include "acados_solver_long.h" +// blasfeo +#include "blasfeo/include/blasfeo_d_aux_ext_dep.h" + #define NX LONG_NX #define NZ LONG_NZ #define NU LONG_NU @@ -104,12 +104,12 @@ int main() double lbx0[NBX0]; double ubx0[NBX0]; - lbx0[0] = 0; - ubx0[0] = 0; - lbx0[1] = 0; - ubx0[1] = 0; - lbx0[2] = 0; - ubx0[2] = 0; + lbx0[0] = 0.0; + ubx0[0] = 0.0; + lbx0[1] = 0.0; + ubx0[1] = 0.0; + lbx0[2] = 0.0; + ubx0[2] = 0.0; ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "idxbx", idxbx0); ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "lbx", lbx0); @@ -128,8 +128,8 @@ int main() double p[NP]; p[0] = -1.2; p[1] = 1.2; - p[2] = 0; - p[3] = 0; + p[2] = 0.0; + p[3] = 0.0; p[4] = 1.45; p[5] = 0.75; diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/main_sim_long.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/main_sim_long.c index 21165e164..67fa56069 100644 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/main_sim_long.c +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/main_sim_long.c @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * @@ -71,9 +68,9 @@ int main() x_current[2] = 0.0; - x_current[0] = 0; - x_current[1] = 0; - x_current[2] = 0; + x_current[0] = 0.0; + x_current[1] = 0.0; + x_current[2] = 0.0; @@ -85,8 +82,8 @@ int main() double p[NP]; p[0] = -1.2; p[1] = 1.2; - p[2] = 0; - p[3] = 0; + p[2] = 0.0; + p[3] = 0.0; p[4] = 1.45; p[5] = 0.75; diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/make_sfun_long.m b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/make_sfun_long.m deleted file mode 100644 index d5a8463cc..000000000 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/make_sfun_long.m +++ /dev/null @@ -1,128 +0,0 @@ -% -% Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, -% Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, -% Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, -% Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl -% -% This file is part of acados. -% -% 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 HOLDER 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.; -% - -SOURCES = { ... - 'long_model/long_expl_ode_fun.c', ... - 'long_model/long_expl_vde_forw.c',... - 'long_cost/long_cost_y_0_fun.c',... - 'long_cost/long_cost_y_0_fun_jac_ut_xt.c',... - 'long_cost/long_cost_y_0_hess.c',... - 'long_cost/long_cost_y_fun.c',... - 'long_cost/long_cost_y_fun_jac_ut_xt.c',... - 'long_cost/long_cost_y_hess.c',... - 'long_cost/long_cost_y_e_fun.c',... - 'long_cost/long_cost_y_e_fun_jac_ut_xt.c',... - 'long_cost/long_cost_y_e_hess.c',... - 'long_constraints/long_constr_h_fun.c', ... - 'long_constraints/long_constr_h_fun_jac_uxt_zt_hess.c', ... - 'long_constraints/long_constr_h_fun_jac_uxt_zt.c', ... - 'acados_solver_sfunction_long.c', ... - 'acados_solver_long.c' - }; - -INC_PATH = '/data/openpilot/third_party/acados/include'; - -INCS = {['-I', fullfile(INC_PATH, 'blasfeo', 'include')], ... - ['-I', fullfile(INC_PATH, 'hpipm', 'include')], ... - ['-I', fullfile(INC_PATH, 'acados')], ... - ['-I', fullfile(INC_PATH)]}; - - - -CFLAGS = 'CFLAGS=$CFLAGS'; -LDFLAGS = 'LDFLAGS=$LDFLAGS'; -COMPFLAGS = 'COMPFLAGS=$COMPFLAGS'; -COMPDEFINES = 'COMPDEFINES=$COMPDEFINES'; - - - -LIB_PATH = ['-L', fullfile('/data/openpilot/third_party/acados/lib')]; - -LIBS = {'-lacados', '-lhpipm', '-lblasfeo'}; - -% acados linking libraries and flags - - -mex('-v', '-O', CFLAGS, LDFLAGS, COMPFLAGS, COMPDEFINES, INCS{:}, ... - LIB_PATH, LIBS{:}, SOURCES{:}, ... - '-output', 'acados_solver_sfunction_long' ); - -fprintf( [ '\n\nSuccessfully created sfunction:\nacados_solver_sfunction_long', '.', ... - eval('mexext')] ); - - -%% print note on usage of s-function -fprintf('\n\nNote: Usage of Sfunction is as follows:\n') -input_note = 'Inputs are:\n'; -i_in = 1; -input_note = strcat(input_note, num2str(i_in), ') lbx_0 - lower bound on x for stage 0,',... - ' size [3]\n '); -i_in = i_in + 1; -input_note = strcat(input_note, num2str(i_in), ') ubx_0 - upper bound on x for stage 0,',... - ' size [3]\n '); -i_in = i_in + 1; -input_note = strcat(input_note, num2str(i_in), ') parameters - concatenated for all shooting nodes 0 to N+1,',... - ' size [78]\n '); -i_in = i_in + 1; -input_note = strcat(input_note, num2str(i_in), ') y_ref_0, size [6]\n '); -i_in = i_in + 1; -input_note = strcat(input_note, num2str(i_in), ') y_ref - concatenated for shooting nodes 1 to N-1,',... - ' size [66]\n '); -i_in = i_in + 1; -input_note = strcat(input_note, num2str(i_in), ') y_ref_e, size [5]\n '); -i_in = i_in + 1; -input_note = strcat(input_note, num2str(i_in), ') lh, size [4]\n '); -i_in = i_in + 1; -input_note = strcat(input_note, num2str(i_in), ') uh, size [4]\n '); -i_in = i_in + 1; - -fprintf(input_note) - -disp(' ') - -output_note = 'Outputs are:\n'; -i_out = 0; -i_out = i_out + 1; -output_note = strcat(output_note, num2str(i_out), ') u0, control input at node 0, size [1]\n '); -i_out = i_out + 1; -output_note = strcat(output_note, num2str(i_out), ') acados solver status (0 = SUCCESS)\n '); -i_out = i_out + 1; -output_note = strcat(output_note, num2str(i_out), ') KKT residual\n '); -i_out = i_out + 1; -output_note = strcat(output_note, num2str(i_out), ') x1, state at node 1\n '); -i_out = i_out + 1; -output_note = strcat(output_note, num2str(i_out), ') CPU time\n '); -i_out = i_out + 1; -output_note = strcat(output_note, num2str(i_out), ') SQP iterations\n '); - -fprintf(output_note) diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py b/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py index afbb2a4b8..ac540b9a8 100644 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py @@ -97,7 +97,9 @@ def get_stopped_equivalence_factor(v_lead): def get_safe_obstacle_distance(v_ego, t_follow): return (v_ego**2) / (2 * COMFORT_BRAKE) + t_follow * v_ego + STOP_DISTANCE -def desired_follow_distance(v_ego, v_lead, t_follow=get_T_FOLLOW()): +def desired_follow_distance(v_ego, v_lead, t_follow=None): + if t_follow is None: + t_follow = get_T_FOLLOW() return get_safe_obstacle_distance(v_ego, t_follow) - get_stopped_equivalence_factor(v_lead) diff --git a/selfdrive/controls/radard.py b/selfdrive/controls/radard.py index cce866a09..303bbaaaf 100755 --- a/selfdrive/controls/radard.py +++ b/selfdrive/controls/radard.py @@ -8,7 +8,7 @@ import capnp from cereal import messaging, log, car from common.numpy_fast import interp from common.params import Params -from common.realtime import Ratekeeper, Priority, config_realtime_process +from common.realtime import Ratekeeper, Priority, config_realtime_process, DT_MDL from system.swaglog import cloudlog from common.kalman.simple_kalman import KF1D @@ -50,7 +50,8 @@ class KalmanParams: class Track: - def __init__(self, v_lead: float, kalman_params: KalmanParams): + def __init__(self, identifier: int, v_lead: float, kalman_params: KalmanParams): + self.identifier = identifier self.cnt = 0 self.aLeadTau = _LEAD_ACCEL_TAU self.K_A = kalman_params.A @@ -63,9 +64,13 @@ class Track: self.dRel = d_rel # LONG_DIST self.yRel = y_rel # -LAT_DIST self.vRel = v_rel # REL_SPEED - self.vLead = v_lead self.measured = measured # measured or estimate + self.update_vlead(v_lead) + + def update_vlead(self, v_lead: float): + self.vLead = v_lead + # computed velocity and accelerations if self.cnt > 0: self.kf.update(self.vLead) @@ -98,11 +103,12 @@ class Track: "vLead": float(self.vLead), "vLeadK": float(self.vLeadK), "aLeadK": float(self.aLeadK), + "aLeadTau": float(self.aLeadTau), "status": True, "fcw": self.is_potential_fcw(model_prob), "modelProb": model_prob, "radar": True, - "aLeadTau": float(self.aLeadTau) + "radarTrackId": self.identifier, } def potential_low_speed_lead(self, v_ego: float): @@ -158,15 +164,17 @@ def get_RadarState_from_vision(lead_msg: capnp._DynamicStructReader, v_ego: floa "aLeadTau": 0.3, "fcw": False, "modelProb": float(lead_msg.prob), + "status": True, "radar": False, - "status": True + "radarTrackId": -1, } def get_lead(v_ego: float, ready: bool, tracks: Dict[int, Track], lead_msg: capnp._DynamicStructReader, model_v_ego: float, low_speed_override: bool = True) -> Dict[str, Any]: # Determine leads, this is where the essential logic happens - if len(tracks) > 0 and ready and lead_msg.prob > .5: + lead_msg_empty = any(len(c) == 0 for c in [lead_msg.x, lead_msg.y, lead_msg.v]) + if len(tracks) > 0 and ready and not lead_msg_empty and lead_msg.prob > .5: track = match_vision_to_track(v_ego, lead_msg, tracks) else: track = None @@ -174,7 +182,7 @@ def get_lead(v_ego: float, ready: bool, tracks: Dict[int, Track], lead_msg: capn lead_dict = {'status': False} if track is not None: lead_dict = track.get_RadarState(lead_msg.prob) - elif (track is None) and ready and (lead_msg.prob > .5): + elif track is None and ready and not lead_msg_empty and lead_msg.prob > .5: lead_dict = get_RadarState_from_vision(lead_msg, v_ego, model_v_ego) if low_speed_override: @@ -204,14 +212,14 @@ class RadarD: self.ready = False - def update(self, sm: messaging.SubMaster, rr: Optional[car.RadarData]): + def update(self, sm: messaging.SubMaster, radar_data: Optional[car.RadarData]): self.current_time = 1e-9*max(sm.logMonoTime.values()) radar_points = [] radar_errors = [] - if rr is not None: - radar_points = rr.points - radar_errors = rr.errors + if radar_data is not None: + radar_points = radar_data.points + radar_errors = radar_data.errors if sm.updated['carState']: self.v_ego = sm['carState'].vEgo @@ -219,26 +227,32 @@ class RadarD: if sm.updated['modelV2']: self.ready = True - ar_pts = {} - for pt in radar_points: - ar_pts[pt.trackId] = [pt.dRel, pt.yRel, pt.vRel, pt.measured] + if radar_data is not None: + ar_pts = {} + for pt in radar_points: + ar_pts[pt.trackId] = [pt.dRel, pt.yRel, pt.vRel, pt.measured] - # *** remove missing points from meta data *** - for ids in list(self.tracks.keys()): - if ids not in ar_pts: - self.tracks.pop(ids, None) + # *** remove missing points from meta data *** + for ids in list(self.tracks.keys()): + if ids not in ar_pts: + self.tracks.pop(ids, None) - # *** compute the tracks *** - for ids in ar_pts: - rpt = ar_pts[ids] + # *** compute the tracks *** + for ids in ar_pts: + rpt = ar_pts[ids] - # align v_ego by a fixed time to align it with the radar measurement - v_lead = rpt[2] + self.v_ego_hist[0] + # align v_ego by a fixed time to align it with the radar measurement + v_lead = rpt[2] + self.v_ego_hist[0] - # create the track if it doesn't exist or it's a new track - if ids not in self.tracks: - self.tracks[ids] = Track(v_lead, self.kalman_params) - self.tracks[ids].update(rpt[0], rpt[1], rpt[2], v_lead, rpt[3]) + # create the track if it doesn't exist or it's a new track + if ids not in self.tracks: + self.tracks[ids] = Track(ids, v_lead, self.kalman_params) + self.tracks[ids].update(rpt[0], rpt[1], rpt[2], v_lead, rpt[3]) + else: + # *** no radar points, keep existing tracks, update v_lead + for track in self.tracks.values(): + v_lead = track.vRel + self.v_ego_hist[0] + track.update_vlead(v_lead) # *** publish radarState *** self.radar_state_valid = sm.all_checks() and len(radar_errors) == 0 @@ -291,32 +305,33 @@ def radard_thread(sm: Optional[messaging.SubMaster] = None, pm: Optional[messagi cloudlog.info("radard is importing %s", CP.carName) RadarInterface = importlib.import_module(f'selfdrive.car.{CP.carName}.radar_interface').RadarInterface - # *** setup messaging + # setup messaging if can_sock is None: can_sock = messaging.sub_sock('can') if sm is None: - sm = messaging.SubMaster(['modelV2', 'carState'], ignore_avg_freq=['modelV2', 'carState']) # Can't check average frequency, since radar determines timing + sm = messaging.SubMaster(['modelV2', 'carState'], poll=["modelV2"]) if pm is None: pm = messaging.PubMaster(['radarState', 'liveTracks']) - RI = RadarInterface(CP) + interface = RadarInterface(CP) - rk = Ratekeeper(1.0 / CP.radarTimeStep, print_delay_threshold=None) - RD = RadarD(CP.radarTimeStep, RI.delay) + rk = Ratekeeper(1 / DT_MDL, print_delay_threshold=None) + radar = RadarD(DT_MDL, interface.delay) - while 1: - can_strings = messaging.drain_sock_raw(can_sock, wait_for_one=True) - rr = RI.update(can_strings) + while True: + sm.update() - if rr is None: - continue + if sm.updated['modelV2']: + can_strings = messaging.drain_sock_raw(can_sock) + if len(can_strings) == 0: + radar_data = None + else: + radar_data = interface.update(can_strings) - sm.update(0) + radar.update(sm, radar_data) + radar.publish(pm, -rk.remaining*1000.0) - RD.update(sm, rr) - RD.publish(pm, -rk.remaining*1000.0) - - rk.monitor_time() + rk.monitor_time() def main(sm: Optional[messaging.SubMaster] = None, pm: Optional[messaging.PubMaster] = None, can_sock: messaging.SubSocket = None): diff --git a/selfdrive/debug/filter_log_message.py b/selfdrive/debug/filter_log_message.py index af5295393..8d9ce8e6a 100755 --- a/selfdrive/debug/filter_log_message.py +++ b/selfdrive/debug/filter_log_message.py @@ -59,7 +59,7 @@ if __name__ == "__main__": logs = [args.route[0]] else: r = Route(args.route[0]) - logs = [q_log if r_log is None else r_log for (q_log, r_log) in zip(r.qlog_paths(), r.log_paths())] + logs = [q_log if r_log is None else r_log for (q_log, r_log) in zip(r.qlog_paths(), r.log_paths(), strict=True)] if len(args.route) == 2 and logs: n = int(args.route[1]) diff --git a/selfdrive/dragonpilot/dpdmonitoringd.py b/selfdrive/dragonpilot/dpdmonitoringd.py new file mode 100755 index 000000000..e9f3fc777 --- /dev/null +++ b/selfdrive/dragonpilot/dpdmonitoringd.py @@ -0,0 +1,41 @@ +#!/usr/bin/env python3 +import gc +import time + +import cereal.messaging as messaging +from common.realtime import set_realtime_priority, DT_DMON +from common.params import Params + + +def dmonitoringd_thread(sm=None, pm=None): + Params().put_bool("DmModelInitialized", True); + gc.disable() + set_realtime_priority(2) + + if pm is None: + pm = messaging.PubMaster(['driverStateV2', 'driverMonitoringState']) + + # 10Hz <- dmonitoringmodeld + while True: + dat = messaging.new_message('driverStateV2') + dat.driverStateV2.leftDriverData.faceOrientation = [0., 0., 0.] + dat.driverStateV2.leftDriverData.faceProb = 1.0 + dat.driverStateV2.rightDriverData.faceOrientation = [0., 0., 0.] + dat.driverStateV2.rightDriverData.faceProb = 1.0 + pm.send('driverStateV2', dat) + + dat = messaging.new_message('driverMonitoringState') + dat.driverMonitoringState = { + "faceDetected": True, + "isDistracted": False, + "awarenessStatus": 1., + } + pm.send('driverMonitoringState', dat) + time.sleep(DT_DMON) + +def main(sm=None, pm=None): + dmonitoringd_thread(sm, pm) + + +if __name__ == '__main__': + main() diff --git a/selfdrive/locationd/laikad.py b/selfdrive/locationd/laikad.py index cbc1822e5..e4a408d13 100755 --- a/selfdrive/locationd/laikad.py +++ b/selfdrive/locationd/laikad.py @@ -137,8 +137,8 @@ class Laikad: #TODO this only saves currently valid ephems, when we download future ephems we should save them too valid_navs = [e for e in nav_list if e.valid(self.last_report_time)] if len(valid_navs) > 0: - ephem_cache = ephemeris_structs.EphemerisCache(**{'glonassEphemerides': [e.data for e in valid_navs if e.prn[0]=='R'], - 'gpsEphemerides': [e.data for e in valid_navs if e.prn[0]=='G']}) + ephem_cache = ephemeris_structs.EphemerisCache(glonassEphemerides=[e.data for e in valid_navs if e.prn[0]=='R'], + gpsEphemerides=[e.data for e in valid_navs if e.prn[0]=='G']) put_nonblocking(EPHEMERIS_CACHE, ephem_cache.to_bytes()) cloudlog.debug("Cache saved") self.last_cached_t = self.last_report_time diff --git a/selfdrive/locationd/locationd b/selfdrive/locationd/locationd index 6d9e64cf5..f38d2badd 100755 Binary files a/selfdrive/locationd/locationd and b/selfdrive/locationd/locationd differ diff --git a/selfdrive/locationd/models/generated/car.cpp b/selfdrive/locationd/models/generated/car.cpp index 617433932..367a13ec2 100644 --- a/selfdrive/locationd/models/generated/car.cpp +++ b/selfdrive/locationd/models/generated/car.cpp @@ -45,326 +45,326 @@ const static double MAHA_THRESH_31 = 3.8414588206941227; * * * This file is part of 'ekf' * ******************************************************************************/ -void err_fun(double *nom_x, double *delta_x, double *out_1282327502940326821) { - out_1282327502940326821[0] = delta_x[0] + nom_x[0]; - out_1282327502940326821[1] = delta_x[1] + nom_x[1]; - out_1282327502940326821[2] = delta_x[2] + nom_x[2]; - out_1282327502940326821[3] = delta_x[3] + nom_x[3]; - out_1282327502940326821[4] = delta_x[4] + nom_x[4]; - out_1282327502940326821[5] = delta_x[5] + nom_x[5]; - out_1282327502940326821[6] = delta_x[6] + nom_x[6]; - out_1282327502940326821[7] = delta_x[7] + nom_x[7]; - out_1282327502940326821[8] = delta_x[8] + nom_x[8]; +void err_fun(double *nom_x, double *delta_x, double *out_3511157536608921668) { + out_3511157536608921668[0] = delta_x[0] + nom_x[0]; + out_3511157536608921668[1] = delta_x[1] + nom_x[1]; + out_3511157536608921668[2] = delta_x[2] + nom_x[2]; + out_3511157536608921668[3] = delta_x[3] + nom_x[3]; + out_3511157536608921668[4] = delta_x[4] + nom_x[4]; + out_3511157536608921668[5] = delta_x[5] + nom_x[5]; + out_3511157536608921668[6] = delta_x[6] + nom_x[6]; + out_3511157536608921668[7] = delta_x[7] + nom_x[7]; + out_3511157536608921668[8] = delta_x[8] + nom_x[8]; } -void inv_err_fun(double *nom_x, double *true_x, double *out_4590721196226970281) { - out_4590721196226970281[0] = -nom_x[0] + true_x[0]; - out_4590721196226970281[1] = -nom_x[1] + true_x[1]; - out_4590721196226970281[2] = -nom_x[2] + true_x[2]; - out_4590721196226970281[3] = -nom_x[3] + true_x[3]; - out_4590721196226970281[4] = -nom_x[4] + true_x[4]; - out_4590721196226970281[5] = -nom_x[5] + true_x[5]; - out_4590721196226970281[6] = -nom_x[6] + true_x[6]; - out_4590721196226970281[7] = -nom_x[7] + true_x[7]; - out_4590721196226970281[8] = -nom_x[8] + true_x[8]; +void inv_err_fun(double *nom_x, double *true_x, double *out_6431969432730020252) { + out_6431969432730020252[0] = -nom_x[0] + true_x[0]; + out_6431969432730020252[1] = -nom_x[1] + true_x[1]; + out_6431969432730020252[2] = -nom_x[2] + true_x[2]; + out_6431969432730020252[3] = -nom_x[3] + true_x[3]; + out_6431969432730020252[4] = -nom_x[4] + true_x[4]; + out_6431969432730020252[5] = -nom_x[5] + true_x[5]; + out_6431969432730020252[6] = -nom_x[6] + true_x[6]; + out_6431969432730020252[7] = -nom_x[7] + true_x[7]; + out_6431969432730020252[8] = -nom_x[8] + true_x[8]; } -void H_mod_fun(double *state, double *out_2163953626510216661) { - out_2163953626510216661[0] = 1.0; - out_2163953626510216661[1] = 0; - out_2163953626510216661[2] = 0; - out_2163953626510216661[3] = 0; - out_2163953626510216661[4] = 0; - out_2163953626510216661[5] = 0; - out_2163953626510216661[6] = 0; - out_2163953626510216661[7] = 0; - out_2163953626510216661[8] = 0; - out_2163953626510216661[9] = 0; - out_2163953626510216661[10] = 1.0; - out_2163953626510216661[11] = 0; - out_2163953626510216661[12] = 0; - out_2163953626510216661[13] = 0; - out_2163953626510216661[14] = 0; - out_2163953626510216661[15] = 0; - out_2163953626510216661[16] = 0; - out_2163953626510216661[17] = 0; - out_2163953626510216661[18] = 0; - out_2163953626510216661[19] = 0; - out_2163953626510216661[20] = 1.0; - out_2163953626510216661[21] = 0; - out_2163953626510216661[22] = 0; - out_2163953626510216661[23] = 0; - out_2163953626510216661[24] = 0; - out_2163953626510216661[25] = 0; - out_2163953626510216661[26] = 0; - out_2163953626510216661[27] = 0; - out_2163953626510216661[28] = 0; - out_2163953626510216661[29] = 0; - out_2163953626510216661[30] = 1.0; - out_2163953626510216661[31] = 0; - out_2163953626510216661[32] = 0; - out_2163953626510216661[33] = 0; - out_2163953626510216661[34] = 0; - out_2163953626510216661[35] = 0; - out_2163953626510216661[36] = 0; - out_2163953626510216661[37] = 0; - out_2163953626510216661[38] = 0; - out_2163953626510216661[39] = 0; - out_2163953626510216661[40] = 1.0; - out_2163953626510216661[41] = 0; - out_2163953626510216661[42] = 0; - out_2163953626510216661[43] = 0; - out_2163953626510216661[44] = 0; - out_2163953626510216661[45] = 0; - out_2163953626510216661[46] = 0; - out_2163953626510216661[47] = 0; - out_2163953626510216661[48] = 0; - out_2163953626510216661[49] = 0; - out_2163953626510216661[50] = 1.0; - out_2163953626510216661[51] = 0; - out_2163953626510216661[52] = 0; - out_2163953626510216661[53] = 0; - out_2163953626510216661[54] = 0; - out_2163953626510216661[55] = 0; - out_2163953626510216661[56] = 0; - out_2163953626510216661[57] = 0; - out_2163953626510216661[58] = 0; - out_2163953626510216661[59] = 0; - out_2163953626510216661[60] = 1.0; - out_2163953626510216661[61] = 0; - out_2163953626510216661[62] = 0; - out_2163953626510216661[63] = 0; - out_2163953626510216661[64] = 0; - out_2163953626510216661[65] = 0; - out_2163953626510216661[66] = 0; - out_2163953626510216661[67] = 0; - out_2163953626510216661[68] = 0; - out_2163953626510216661[69] = 0; - out_2163953626510216661[70] = 1.0; - out_2163953626510216661[71] = 0; - out_2163953626510216661[72] = 0; - out_2163953626510216661[73] = 0; - out_2163953626510216661[74] = 0; - out_2163953626510216661[75] = 0; - out_2163953626510216661[76] = 0; - out_2163953626510216661[77] = 0; - out_2163953626510216661[78] = 0; - out_2163953626510216661[79] = 0; - out_2163953626510216661[80] = 1.0; +void H_mod_fun(double *state, double *out_7948008639250905645) { + out_7948008639250905645[0] = 1.0; + out_7948008639250905645[1] = 0; + out_7948008639250905645[2] = 0; + out_7948008639250905645[3] = 0; + out_7948008639250905645[4] = 0; + out_7948008639250905645[5] = 0; + out_7948008639250905645[6] = 0; + out_7948008639250905645[7] = 0; + out_7948008639250905645[8] = 0; + out_7948008639250905645[9] = 0; + out_7948008639250905645[10] = 1.0; + out_7948008639250905645[11] = 0; + out_7948008639250905645[12] = 0; + out_7948008639250905645[13] = 0; + out_7948008639250905645[14] = 0; + out_7948008639250905645[15] = 0; + out_7948008639250905645[16] = 0; + out_7948008639250905645[17] = 0; + out_7948008639250905645[18] = 0; + out_7948008639250905645[19] = 0; + out_7948008639250905645[20] = 1.0; + out_7948008639250905645[21] = 0; + out_7948008639250905645[22] = 0; + out_7948008639250905645[23] = 0; + out_7948008639250905645[24] = 0; + out_7948008639250905645[25] = 0; + out_7948008639250905645[26] = 0; + out_7948008639250905645[27] = 0; + out_7948008639250905645[28] = 0; + out_7948008639250905645[29] = 0; + out_7948008639250905645[30] = 1.0; + out_7948008639250905645[31] = 0; + out_7948008639250905645[32] = 0; + out_7948008639250905645[33] = 0; + out_7948008639250905645[34] = 0; + out_7948008639250905645[35] = 0; + out_7948008639250905645[36] = 0; + out_7948008639250905645[37] = 0; + out_7948008639250905645[38] = 0; + out_7948008639250905645[39] = 0; + out_7948008639250905645[40] = 1.0; + out_7948008639250905645[41] = 0; + out_7948008639250905645[42] = 0; + out_7948008639250905645[43] = 0; + out_7948008639250905645[44] = 0; + out_7948008639250905645[45] = 0; + out_7948008639250905645[46] = 0; + out_7948008639250905645[47] = 0; + out_7948008639250905645[48] = 0; + out_7948008639250905645[49] = 0; + out_7948008639250905645[50] = 1.0; + out_7948008639250905645[51] = 0; + out_7948008639250905645[52] = 0; + out_7948008639250905645[53] = 0; + out_7948008639250905645[54] = 0; + out_7948008639250905645[55] = 0; + out_7948008639250905645[56] = 0; + out_7948008639250905645[57] = 0; + out_7948008639250905645[58] = 0; + out_7948008639250905645[59] = 0; + out_7948008639250905645[60] = 1.0; + out_7948008639250905645[61] = 0; + out_7948008639250905645[62] = 0; + out_7948008639250905645[63] = 0; + out_7948008639250905645[64] = 0; + out_7948008639250905645[65] = 0; + out_7948008639250905645[66] = 0; + out_7948008639250905645[67] = 0; + out_7948008639250905645[68] = 0; + out_7948008639250905645[69] = 0; + out_7948008639250905645[70] = 1.0; + out_7948008639250905645[71] = 0; + out_7948008639250905645[72] = 0; + out_7948008639250905645[73] = 0; + out_7948008639250905645[74] = 0; + out_7948008639250905645[75] = 0; + out_7948008639250905645[76] = 0; + out_7948008639250905645[77] = 0; + out_7948008639250905645[78] = 0; + out_7948008639250905645[79] = 0; + out_7948008639250905645[80] = 1.0; } -void f_fun(double *state, double dt, double *out_405606070335708994) { - out_405606070335708994[0] = state[0]; - out_405606070335708994[1] = state[1]; - out_405606070335708994[2] = state[2]; - out_405606070335708994[3] = state[3]; - out_405606070335708994[4] = state[4]; - out_405606070335708994[5] = dt*((-state[4] + (-center_to_front*stiffness_front*state[0] + center_to_rear*stiffness_rear*state[0])/(mass*state[4]))*state[6] - 9.8000000000000007*state[8] + stiffness_front*(-state[2] - state[3] + state[7])*state[0]/(mass*state[1]) + (-stiffness_front*state[0] - stiffness_rear*state[0])*state[5]/(mass*state[4])) + state[5]; - out_405606070335708994[6] = dt*(center_to_front*stiffness_front*(-state[2] - state[3] + state[7])*state[0]/(rotational_inertia*state[1]) + (-center_to_front*stiffness_front*state[0] + center_to_rear*stiffness_rear*state[0])*state[5]/(rotational_inertia*state[4]) + (-pow(center_to_front, 2)*stiffness_front*state[0] - pow(center_to_rear, 2)*stiffness_rear*state[0])*state[6]/(rotational_inertia*state[4])) + state[6]; - out_405606070335708994[7] = state[7]; - out_405606070335708994[8] = state[8]; +void f_fun(double *state, double dt, double *out_2086994761209225774) { + out_2086994761209225774[0] = state[0]; + out_2086994761209225774[1] = state[1]; + out_2086994761209225774[2] = state[2]; + out_2086994761209225774[3] = state[3]; + out_2086994761209225774[4] = state[4]; + out_2086994761209225774[5] = dt*((-state[4] + (-center_to_front*stiffness_front*state[0] + center_to_rear*stiffness_rear*state[0])/(mass*state[4]))*state[6] - 9.8000000000000007*state[8] + stiffness_front*(-state[2] - state[3] + state[7])*state[0]/(mass*state[1]) + (-stiffness_front*state[0] - stiffness_rear*state[0])*state[5]/(mass*state[4])) + state[5]; + out_2086994761209225774[6] = dt*(center_to_front*stiffness_front*(-state[2] - state[3] + state[7])*state[0]/(rotational_inertia*state[1]) + (-center_to_front*stiffness_front*state[0] + center_to_rear*stiffness_rear*state[0])*state[5]/(rotational_inertia*state[4]) + (-pow(center_to_front, 2)*stiffness_front*state[0] - pow(center_to_rear, 2)*stiffness_rear*state[0])*state[6]/(rotational_inertia*state[4])) + state[6]; + out_2086994761209225774[7] = state[7]; + out_2086994761209225774[8] = state[8]; } -void F_fun(double *state, double dt, double *out_7303340041697938188) { - out_7303340041697938188[0] = 1; - out_7303340041697938188[1] = 0; - out_7303340041697938188[2] = 0; - out_7303340041697938188[3] = 0; - out_7303340041697938188[4] = 0; - out_7303340041697938188[5] = 0; - out_7303340041697938188[6] = 0; - out_7303340041697938188[7] = 0; - out_7303340041697938188[8] = 0; - out_7303340041697938188[9] = 0; - out_7303340041697938188[10] = 1; - out_7303340041697938188[11] = 0; - out_7303340041697938188[12] = 0; - out_7303340041697938188[13] = 0; - out_7303340041697938188[14] = 0; - out_7303340041697938188[15] = 0; - out_7303340041697938188[16] = 0; - out_7303340041697938188[17] = 0; - out_7303340041697938188[18] = 0; - out_7303340041697938188[19] = 0; - out_7303340041697938188[20] = 1; - out_7303340041697938188[21] = 0; - out_7303340041697938188[22] = 0; - out_7303340041697938188[23] = 0; - out_7303340041697938188[24] = 0; - out_7303340041697938188[25] = 0; - out_7303340041697938188[26] = 0; - out_7303340041697938188[27] = 0; - out_7303340041697938188[28] = 0; - out_7303340041697938188[29] = 0; - out_7303340041697938188[30] = 1; - out_7303340041697938188[31] = 0; - out_7303340041697938188[32] = 0; - out_7303340041697938188[33] = 0; - out_7303340041697938188[34] = 0; - out_7303340041697938188[35] = 0; - out_7303340041697938188[36] = 0; - out_7303340041697938188[37] = 0; - out_7303340041697938188[38] = 0; - out_7303340041697938188[39] = 0; - out_7303340041697938188[40] = 1; - out_7303340041697938188[41] = 0; - out_7303340041697938188[42] = 0; - out_7303340041697938188[43] = 0; - out_7303340041697938188[44] = 0; - out_7303340041697938188[45] = dt*(stiffness_front*(-state[2] - state[3] + state[7])/(mass*state[1]) + (-stiffness_front - stiffness_rear)*state[5]/(mass*state[4]) + (-center_to_front*stiffness_front + center_to_rear*stiffness_rear)*state[6]/(mass*state[4])); - out_7303340041697938188[46] = -dt*stiffness_front*(-state[2] - state[3] + state[7])*state[0]/(mass*pow(state[1], 2)); - out_7303340041697938188[47] = -dt*stiffness_front*state[0]/(mass*state[1]); - out_7303340041697938188[48] = -dt*stiffness_front*state[0]/(mass*state[1]); - out_7303340041697938188[49] = dt*((-1 - (-center_to_front*stiffness_front*state[0] + center_to_rear*stiffness_rear*state[0])/(mass*pow(state[4], 2)))*state[6] - (-stiffness_front*state[0] - stiffness_rear*state[0])*state[5]/(mass*pow(state[4], 2))); - out_7303340041697938188[50] = dt*(-stiffness_front*state[0] - stiffness_rear*state[0])/(mass*state[4]) + 1; - out_7303340041697938188[51] = dt*(-state[4] + (-center_to_front*stiffness_front*state[0] + center_to_rear*stiffness_rear*state[0])/(mass*state[4])); - out_7303340041697938188[52] = dt*stiffness_front*state[0]/(mass*state[1]); - out_7303340041697938188[53] = -9.8000000000000007*dt; - out_7303340041697938188[54] = dt*(center_to_front*stiffness_front*(-state[2] - state[3] + state[7])/(rotational_inertia*state[1]) + (-center_to_front*stiffness_front + center_to_rear*stiffness_rear)*state[5]/(rotational_inertia*state[4]) + (-pow(center_to_front, 2)*stiffness_front - pow(center_to_rear, 2)*stiffness_rear)*state[6]/(rotational_inertia*state[4])); - out_7303340041697938188[55] = -center_to_front*dt*stiffness_front*(-state[2] - state[3] + state[7])*state[0]/(rotational_inertia*pow(state[1], 2)); - out_7303340041697938188[56] = -center_to_front*dt*stiffness_front*state[0]/(rotational_inertia*state[1]); - out_7303340041697938188[57] = -center_to_front*dt*stiffness_front*state[0]/(rotational_inertia*state[1]); - out_7303340041697938188[58] = dt*(-(-center_to_front*stiffness_front*state[0] + center_to_rear*stiffness_rear*state[0])*state[5]/(rotational_inertia*pow(state[4], 2)) - (-pow(center_to_front, 2)*stiffness_front*state[0] - pow(center_to_rear, 2)*stiffness_rear*state[0])*state[6]/(rotational_inertia*pow(state[4], 2))); - out_7303340041697938188[59] = dt*(-center_to_front*stiffness_front*state[0] + center_to_rear*stiffness_rear*state[0])/(rotational_inertia*state[4]); - out_7303340041697938188[60] = dt*(-pow(center_to_front, 2)*stiffness_front*state[0] - pow(center_to_rear, 2)*stiffness_rear*state[0])/(rotational_inertia*state[4]) + 1; - out_7303340041697938188[61] = center_to_front*dt*stiffness_front*state[0]/(rotational_inertia*state[1]); - out_7303340041697938188[62] = 0; - out_7303340041697938188[63] = 0; - out_7303340041697938188[64] = 0; - out_7303340041697938188[65] = 0; - out_7303340041697938188[66] = 0; - out_7303340041697938188[67] = 0; - out_7303340041697938188[68] = 0; - out_7303340041697938188[69] = 0; - out_7303340041697938188[70] = 1; - out_7303340041697938188[71] = 0; - out_7303340041697938188[72] = 0; - out_7303340041697938188[73] = 0; - out_7303340041697938188[74] = 0; - out_7303340041697938188[75] = 0; - out_7303340041697938188[76] = 0; - out_7303340041697938188[77] = 0; - out_7303340041697938188[78] = 0; - out_7303340041697938188[79] = 0; - out_7303340041697938188[80] = 1; +void F_fun(double *state, double dt, double *out_8139310027990993197) { + out_8139310027990993197[0] = 1; + out_8139310027990993197[1] = 0; + out_8139310027990993197[2] = 0; + out_8139310027990993197[3] = 0; + out_8139310027990993197[4] = 0; + out_8139310027990993197[5] = 0; + out_8139310027990993197[6] = 0; + out_8139310027990993197[7] = 0; + out_8139310027990993197[8] = 0; + out_8139310027990993197[9] = 0; + out_8139310027990993197[10] = 1; + out_8139310027990993197[11] = 0; + out_8139310027990993197[12] = 0; + out_8139310027990993197[13] = 0; + out_8139310027990993197[14] = 0; + out_8139310027990993197[15] = 0; + out_8139310027990993197[16] = 0; + out_8139310027990993197[17] = 0; + out_8139310027990993197[18] = 0; + out_8139310027990993197[19] = 0; + out_8139310027990993197[20] = 1; + out_8139310027990993197[21] = 0; + out_8139310027990993197[22] = 0; + out_8139310027990993197[23] = 0; + out_8139310027990993197[24] = 0; + out_8139310027990993197[25] = 0; + out_8139310027990993197[26] = 0; + out_8139310027990993197[27] = 0; + out_8139310027990993197[28] = 0; + out_8139310027990993197[29] = 0; + out_8139310027990993197[30] = 1; + out_8139310027990993197[31] = 0; + out_8139310027990993197[32] = 0; + out_8139310027990993197[33] = 0; + out_8139310027990993197[34] = 0; + out_8139310027990993197[35] = 0; + out_8139310027990993197[36] = 0; + out_8139310027990993197[37] = 0; + out_8139310027990993197[38] = 0; + out_8139310027990993197[39] = 0; + out_8139310027990993197[40] = 1; + out_8139310027990993197[41] = 0; + out_8139310027990993197[42] = 0; + out_8139310027990993197[43] = 0; + out_8139310027990993197[44] = 0; + out_8139310027990993197[45] = dt*(stiffness_front*(-state[2] - state[3] + state[7])/(mass*state[1]) + (-stiffness_front - stiffness_rear)*state[5]/(mass*state[4]) + (-center_to_front*stiffness_front + center_to_rear*stiffness_rear)*state[6]/(mass*state[4])); + out_8139310027990993197[46] = -dt*stiffness_front*(-state[2] - state[3] + state[7])*state[0]/(mass*pow(state[1], 2)); + out_8139310027990993197[47] = -dt*stiffness_front*state[0]/(mass*state[1]); + out_8139310027990993197[48] = -dt*stiffness_front*state[0]/(mass*state[1]); + out_8139310027990993197[49] = dt*((-1 - (-center_to_front*stiffness_front*state[0] + center_to_rear*stiffness_rear*state[0])/(mass*pow(state[4], 2)))*state[6] - (-stiffness_front*state[0] - stiffness_rear*state[0])*state[5]/(mass*pow(state[4], 2))); + out_8139310027990993197[50] = dt*(-stiffness_front*state[0] - stiffness_rear*state[0])/(mass*state[4]) + 1; + out_8139310027990993197[51] = dt*(-state[4] + (-center_to_front*stiffness_front*state[0] + center_to_rear*stiffness_rear*state[0])/(mass*state[4])); + out_8139310027990993197[52] = dt*stiffness_front*state[0]/(mass*state[1]); + out_8139310027990993197[53] = -9.8000000000000007*dt; + out_8139310027990993197[54] = dt*(center_to_front*stiffness_front*(-state[2] - state[3] + state[7])/(rotational_inertia*state[1]) + (-center_to_front*stiffness_front + center_to_rear*stiffness_rear)*state[5]/(rotational_inertia*state[4]) + (-pow(center_to_front, 2)*stiffness_front - pow(center_to_rear, 2)*stiffness_rear)*state[6]/(rotational_inertia*state[4])); + out_8139310027990993197[55] = -center_to_front*dt*stiffness_front*(-state[2] - state[3] + state[7])*state[0]/(rotational_inertia*pow(state[1], 2)); + out_8139310027990993197[56] = -center_to_front*dt*stiffness_front*state[0]/(rotational_inertia*state[1]); + out_8139310027990993197[57] = -center_to_front*dt*stiffness_front*state[0]/(rotational_inertia*state[1]); + out_8139310027990993197[58] = dt*(-(-center_to_front*stiffness_front*state[0] + center_to_rear*stiffness_rear*state[0])*state[5]/(rotational_inertia*pow(state[4], 2)) - (-pow(center_to_front, 2)*stiffness_front*state[0] - pow(center_to_rear, 2)*stiffness_rear*state[0])*state[6]/(rotational_inertia*pow(state[4], 2))); + out_8139310027990993197[59] = dt*(-center_to_front*stiffness_front*state[0] + center_to_rear*stiffness_rear*state[0])/(rotational_inertia*state[4]); + out_8139310027990993197[60] = dt*(-pow(center_to_front, 2)*stiffness_front*state[0] - pow(center_to_rear, 2)*stiffness_rear*state[0])/(rotational_inertia*state[4]) + 1; + out_8139310027990993197[61] = center_to_front*dt*stiffness_front*state[0]/(rotational_inertia*state[1]); + out_8139310027990993197[62] = 0; + out_8139310027990993197[63] = 0; + out_8139310027990993197[64] = 0; + out_8139310027990993197[65] = 0; + out_8139310027990993197[66] = 0; + out_8139310027990993197[67] = 0; + out_8139310027990993197[68] = 0; + out_8139310027990993197[69] = 0; + out_8139310027990993197[70] = 1; + out_8139310027990993197[71] = 0; + out_8139310027990993197[72] = 0; + out_8139310027990993197[73] = 0; + out_8139310027990993197[74] = 0; + out_8139310027990993197[75] = 0; + out_8139310027990993197[76] = 0; + out_8139310027990993197[77] = 0; + out_8139310027990993197[78] = 0; + out_8139310027990993197[79] = 0; + out_8139310027990993197[80] = 1; } -void h_25(double *state, double *unused, double *out_5588110016210508170) { - out_5588110016210508170[0] = state[6]; +void h_25(double *state, double *unused, double *out_4906131110836938043) { + out_4906131110836938043[0] = state[6]; } -void H_25(double *state, double *unused, double *out_6037113083971364302) { - out_6037113083971364302[0] = 0; - out_6037113083971364302[1] = 0; - out_6037113083971364302[2] = 0; - out_6037113083971364302[3] = 0; - out_6037113083971364302[4] = 0; - out_6037113083971364302[5] = 0; - out_6037113083971364302[6] = 1; - out_6037113083971364302[7] = 0; - out_6037113083971364302[8] = 0; +void H_25(double *state, double *unused, double *out_8920612812001856359) { + out_8920612812001856359[0] = 0; + out_8920612812001856359[1] = 0; + out_8920612812001856359[2] = 0; + out_8920612812001856359[3] = 0; + out_8920612812001856359[4] = 0; + out_8920612812001856359[5] = 0; + out_8920612812001856359[6] = 1; + out_8920612812001856359[7] = 0; + out_8920612812001856359[8] = 0; } -void h_24(double *state, double *unused, double *out_4380624216713203670) { - out_4380624216713203670[0] = state[4]; - out_4380624216713203670[1] = state[5]; +void h_24(double *state, double *unused, double *out_3427550057756876624) { + out_3427550057756876624[0] = state[4]; + out_3427550057756876624[1] = state[5]; } -void H_24(double *state, double *unused, double *out_8209762682976863868) { - out_8209762682976863868[0] = 0; - out_8209762682976863868[1] = 0; - out_8209762682976863868[2] = 0; - out_8209762682976863868[3] = 0; - out_8209762682976863868[4] = 1; - out_8209762682976863868[5] = 0; - out_8209762682976863868[6] = 0; - out_8209762682976863868[7] = 0; - out_8209762682976863868[8] = 0; - out_8209762682976863868[9] = 0; - out_8209762682976863868[10] = 0; - out_8209762682976863868[11] = 0; - out_8209762682976863868[12] = 0; - out_8209762682976863868[13] = 0; - out_8209762682976863868[14] = 1; - out_8209762682976863868[15] = 0; - out_8209762682976863868[16] = 0; - out_8209762682976863868[17] = 0; +void H_24(double *state, double *unused, double *out_5543808110309927359) { + out_5543808110309927359[0] = 0; + out_5543808110309927359[1] = 0; + out_5543808110309927359[2] = 0; + out_5543808110309927359[3] = 0; + out_5543808110309927359[4] = 1; + out_5543808110309927359[5] = 0; + out_5543808110309927359[6] = 0; + out_5543808110309927359[7] = 0; + out_5543808110309927359[8] = 0; + out_5543808110309927359[9] = 0; + out_5543808110309927359[10] = 0; + out_5543808110309927359[11] = 0; + out_5543808110309927359[12] = 0; + out_5543808110309927359[13] = 0; + out_5543808110309927359[14] = 1; + out_5543808110309927359[15] = 0; + out_5543808110309927359[16] = 0; + out_5543808110309927359[17] = 0; } -void h_30(double *state, double *unused, double *out_4965694562614520087) { - out_4965694562614520087[0] = state[4]; +void h_30(double *state, double *unused, double *out_5063317779188067188) { + out_5063317779188067188[0] = state[4]; } -void H_30(double *state, double *unused, double *out_879577257520252453) { - out_879577257520252453[0] = 0; - out_879577257520252453[1] = 0; - out_879577257520252453[2] = 0; - out_879577257520252453[3] = 0; - out_879577257520252453[4] = 1; - out_879577257520252453[5] = 0; - out_879577257520252453[6] = 0; - out_879577257520252453[7] = 0; - out_879577257520252453[8] = 0; +void H_30(double *state, double *unused, double *out_2003922470510239604) { + out_2003922470510239604[0] = 0; + out_2003922470510239604[1] = 0; + out_2003922470510239604[2] = 0; + out_2003922470510239604[3] = 0; + out_2003922470510239604[4] = 1; + out_2003922470510239604[5] = 0; + out_2003922470510239604[6] = 0; + out_2003922470510239604[7] = 0; + out_2003922470510239604[8] = 0; } -void h_26(double *state, double *unused, double *out_4499080339088190764) { - out_4499080339088190764[0] = state[7]; +void h_26(double *state, double *unused, double *out_8958065379223252895) { + out_8958065379223252895[0] = state[7]; } -void H_26(double *state, double *unused, double *out_8668127670864131090) { - out_8668127670864131090[0] = 0; - out_8668127670864131090[1] = 0; - out_8668127670864131090[2] = 0; - out_8668127670864131090[3] = 0; - out_8668127670864131090[4] = 0; - out_8668127670864131090[5] = 0; - out_8668127670864131090[6] = 0; - out_8668127670864131090[7] = 1; - out_8668127670864131090[8] = 0; +void H_26(double *state, double *unused, double *out_5784627942833639033) { + out_5784627942833639033[0] = 0; + out_5784627942833639033[1] = 0; + out_5784627942833639033[2] = 0; + out_5784627942833639033[3] = 0; + out_5784627942833639033[4] = 0; + out_5784627942833639033[5] = 0; + out_5784627942833639033[6] = 0; + out_5784627942833639033[7] = 1; + out_5784627942833639033[8] = 0; } -void h_27(double *state, double *unused, double *out_586436748549662525) { - out_586436748549662525[0] = state[3]; +void h_27(double *state, double *unused, double *out_7942917162281270728) { + out_7942917162281270728[0] = state[3]; } -void H_27(double *state, double *unused, double *out_1295186054280172458) { - out_1295186054280172458[0] = 0; - out_1295186054280172458[1] = 0; - out_1295186054280172458[2] = 0; - out_1295186054280172458[3] = 1; - out_1295186054280172458[4] = 0; - out_1295186054280172458[5] = 0; - out_1295186054280172458[6] = 0; - out_1295186054280172458[7] = 0; - out_1295186054280172458[8] = 0; +void H_27(double *state, double *unused, double *out_4178685782310664515) { + out_4178685782310664515[0] = 0; + out_4178685782310664515[1] = 0; + out_4178685782310664515[2] = 0; + out_4178685782310664515[3] = 1; + out_4178685782310664515[4] = 0; + out_4178685782310664515[5] = 0; + out_4178685782310664515[6] = 0; + out_4178685782310664515[7] = 0; + out_4178685782310664515[8] = 0; } -void h_29(double *state, double *unused, double *out_5569010447290997604) { - out_5569010447290997604[0] = state[1]; +void h_29(double *state, double *unused, double *out_3732991685077929952) { + out_3732991685077929952[0] = state[1]; } -void H_29(double *state, double *unused, double *out_3008548781149723491) { - out_3008548781149723491[0] = 0; - out_3008548781149723491[1] = 1; - out_3008548781149723491[2] = 0; - out_3008548781149723491[3] = 0; - out_3008548781149723491[4] = 0; - out_3008548781149723491[5] = 0; - out_3008548781149723491[6] = 0; - out_3008548781149723491[7] = 0; - out_3008548781149723491[8] = 0; +void H_29(double *state, double *unused, double *out_1493691126195847420) { + out_1493691126195847420[0] = 0; + out_1493691126195847420[1] = 1; + out_1493691126195847420[2] = 0; + out_1493691126195847420[3] = 0; + out_1493691126195847420[4] = 0; + out_1493691126195847420[5] = 0; + out_1493691126195847420[6] = 0; + out_1493691126195847420[7] = 0; + out_1493691126195847420[8] = 0; } -void h_28(double *state, double *unused, double *out_2689411064197794064) { - out_2689411064197794064[0] = state[0]; +void h_28(double *state, double *unused, double *out_2300187291200313893) { + out_2300187291200313893[0] = state[0]; } -void H_28(double *state, double *unused, double *out_8090947798219254065) { - out_8090947798219254065[0] = 1; - out_8090947798219254065[1] = 0; - out_8090947798219254065[2] = 0; - out_8090947798219254065[3] = 0; - out_8090947798219254065[4] = 0; - out_8090947798219254065[5] = 0; - out_8090947798219254065[6] = 0; - out_8090947798219254065[7] = 0; - out_8090947798219254065[8] = 0; +void H_28(double *state, double *unused, double *out_6576090143265377994) { + out_6576090143265377994[0] = 1; + out_6576090143265377994[1] = 0; + out_6576090143265377994[2] = 0; + out_6576090143265377994[3] = 0; + out_6576090143265377994[4] = 0; + out_6576090143265377994[5] = 0; + out_6576090143265377994[6] = 0; + out_6576090143265377994[7] = 0; + out_6576090143265377994[8] = 0; } -void h_31(double *state, double *unused, double *out_5863304078495014059) { - out_5863304078495014059[0] = state[8]; +void h_31(double *state, double *unused, double *out_5181325173121443932) { + out_5181325173121443932[0] = state[8]; } -void H_31(double *state, double *unused, double *out_6006467122094403874) { - out_6006467122094403874[0] = 0; - out_6006467122094403874[1] = 0; - out_6006467122094403874[2] = 0; - out_6006467122094403874[3] = 0; - out_6006467122094403874[4] = 0; - out_6006467122094403874[5] = 0; - out_6006467122094403874[6] = 0; - out_6006467122094403874[7] = 0; - out_6006467122094403874[8] = 1; +void H_31(double *state, double *unused, double *out_8889966850124895931) { + out_8889966850124895931[0] = 0; + out_8889966850124895931[1] = 0; + out_8889966850124895931[2] = 0; + out_8889966850124895931[3] = 0; + out_8889966850124895931[4] = 0; + out_8889966850124895931[5] = 0; + out_8889966850124895931[6] = 0; + out_8889966850124895931[7] = 0; + out_8889966850124895931[8] = 1; } #include #include @@ -518,68 +518,68 @@ void car_update_28(double *in_x, double *in_P, double *in_z, double *in_R, doubl void car_update_31(double *in_x, double *in_P, double *in_z, double *in_R, double *in_ea) { update<1, 3, 0>(in_x, in_P, h_31, H_31, NULL, in_z, in_R, in_ea, MAHA_THRESH_31); } -void car_err_fun(double *nom_x, double *delta_x, double *out_1282327502940326821) { - err_fun(nom_x, delta_x, out_1282327502940326821); +void car_err_fun(double *nom_x, double *delta_x, double *out_3511157536608921668) { + err_fun(nom_x, delta_x, out_3511157536608921668); } -void car_inv_err_fun(double *nom_x, double *true_x, double *out_4590721196226970281) { - inv_err_fun(nom_x, true_x, out_4590721196226970281); +void car_inv_err_fun(double *nom_x, double *true_x, double *out_6431969432730020252) { + inv_err_fun(nom_x, true_x, out_6431969432730020252); } -void car_H_mod_fun(double *state, double *out_2163953626510216661) { - H_mod_fun(state, out_2163953626510216661); +void car_H_mod_fun(double *state, double *out_7948008639250905645) { + H_mod_fun(state, out_7948008639250905645); } -void car_f_fun(double *state, double dt, double *out_405606070335708994) { - f_fun(state, dt, out_405606070335708994); +void car_f_fun(double *state, double dt, double *out_2086994761209225774) { + f_fun(state, dt, out_2086994761209225774); } -void car_F_fun(double *state, double dt, double *out_7303340041697938188) { - F_fun(state, dt, out_7303340041697938188); +void car_F_fun(double *state, double dt, double *out_8139310027990993197) { + F_fun(state, dt, out_8139310027990993197); } -void car_h_25(double *state, double *unused, double *out_5588110016210508170) { - h_25(state, unused, out_5588110016210508170); +void car_h_25(double *state, double *unused, double *out_4906131110836938043) { + h_25(state, unused, out_4906131110836938043); } -void car_H_25(double *state, double *unused, double *out_6037113083971364302) { - H_25(state, unused, out_6037113083971364302); +void car_H_25(double *state, double *unused, double *out_8920612812001856359) { + H_25(state, unused, out_8920612812001856359); } -void car_h_24(double *state, double *unused, double *out_4380624216713203670) { - h_24(state, unused, out_4380624216713203670); +void car_h_24(double *state, double *unused, double *out_3427550057756876624) { + h_24(state, unused, out_3427550057756876624); } -void car_H_24(double *state, double *unused, double *out_8209762682976863868) { - H_24(state, unused, out_8209762682976863868); +void car_H_24(double *state, double *unused, double *out_5543808110309927359) { + H_24(state, unused, out_5543808110309927359); } -void car_h_30(double *state, double *unused, double *out_4965694562614520087) { - h_30(state, unused, out_4965694562614520087); +void car_h_30(double *state, double *unused, double *out_5063317779188067188) { + h_30(state, unused, out_5063317779188067188); } -void car_H_30(double *state, double *unused, double *out_879577257520252453) { - H_30(state, unused, out_879577257520252453); +void car_H_30(double *state, double *unused, double *out_2003922470510239604) { + H_30(state, unused, out_2003922470510239604); } -void car_h_26(double *state, double *unused, double *out_4499080339088190764) { - h_26(state, unused, out_4499080339088190764); +void car_h_26(double *state, double *unused, double *out_8958065379223252895) { + h_26(state, unused, out_8958065379223252895); } -void car_H_26(double *state, double *unused, double *out_8668127670864131090) { - H_26(state, unused, out_8668127670864131090); +void car_H_26(double *state, double *unused, double *out_5784627942833639033) { + H_26(state, unused, out_5784627942833639033); } -void car_h_27(double *state, double *unused, double *out_586436748549662525) { - h_27(state, unused, out_586436748549662525); +void car_h_27(double *state, double *unused, double *out_7942917162281270728) { + h_27(state, unused, out_7942917162281270728); } -void car_H_27(double *state, double *unused, double *out_1295186054280172458) { - H_27(state, unused, out_1295186054280172458); +void car_H_27(double *state, double *unused, double *out_4178685782310664515) { + H_27(state, unused, out_4178685782310664515); } -void car_h_29(double *state, double *unused, double *out_5569010447290997604) { - h_29(state, unused, out_5569010447290997604); +void car_h_29(double *state, double *unused, double *out_3732991685077929952) { + h_29(state, unused, out_3732991685077929952); } -void car_H_29(double *state, double *unused, double *out_3008548781149723491) { - H_29(state, unused, out_3008548781149723491); +void car_H_29(double *state, double *unused, double *out_1493691126195847420) { + H_29(state, unused, out_1493691126195847420); } -void car_h_28(double *state, double *unused, double *out_2689411064197794064) { - h_28(state, unused, out_2689411064197794064); +void car_h_28(double *state, double *unused, double *out_2300187291200313893) { + h_28(state, unused, out_2300187291200313893); } -void car_H_28(double *state, double *unused, double *out_8090947798219254065) { - H_28(state, unused, out_8090947798219254065); +void car_H_28(double *state, double *unused, double *out_6576090143265377994) { + H_28(state, unused, out_6576090143265377994); } -void car_h_31(double *state, double *unused, double *out_5863304078495014059) { - h_31(state, unused, out_5863304078495014059); +void car_h_31(double *state, double *unused, double *out_5181325173121443932) { + h_31(state, unused, out_5181325173121443932); } -void car_H_31(double *state, double *unused, double *out_6006467122094403874) { - H_31(state, unused, out_6006467122094403874); +void car_H_31(double *state, double *unused, double *out_8889966850124895931) { + H_31(state, unused, out_8889966850124895931); } void car_predict(double *in_x, double *in_P, double *in_Q, double dt) { predict(in_x, in_P, in_Q, dt); diff --git a/selfdrive/locationd/models/generated/car.h b/selfdrive/locationd/models/generated/car.h index 544df47c4..a420d5d3b 100644 --- a/selfdrive/locationd/models/generated/car.h +++ b/selfdrive/locationd/models/generated/car.h @@ -9,27 +9,27 @@ void car_update_27(double *in_x, double *in_P, double *in_z, double *in_R, doubl void car_update_29(double *in_x, double *in_P, double *in_z, double *in_R, double *in_ea); void car_update_28(double *in_x, double *in_P, double *in_z, double *in_R, double *in_ea); void car_update_31(double *in_x, double *in_P, double *in_z, double *in_R, double *in_ea); -void car_err_fun(double *nom_x, double *delta_x, double *out_1282327502940326821); -void car_inv_err_fun(double *nom_x, double *true_x, double *out_4590721196226970281); -void car_H_mod_fun(double *state, double *out_2163953626510216661); -void car_f_fun(double *state, double dt, double *out_405606070335708994); -void car_F_fun(double *state, double dt, double *out_7303340041697938188); -void car_h_25(double *state, double *unused, double *out_5588110016210508170); -void car_H_25(double *state, double *unused, double *out_6037113083971364302); -void car_h_24(double *state, double *unused, double *out_4380624216713203670); -void car_H_24(double *state, double *unused, double *out_8209762682976863868); -void car_h_30(double *state, double *unused, double *out_4965694562614520087); -void car_H_30(double *state, double *unused, double *out_879577257520252453); -void car_h_26(double *state, double *unused, double *out_4499080339088190764); -void car_H_26(double *state, double *unused, double *out_8668127670864131090); -void car_h_27(double *state, double *unused, double *out_586436748549662525); -void car_H_27(double *state, double *unused, double *out_1295186054280172458); -void car_h_29(double *state, double *unused, double *out_5569010447290997604); -void car_H_29(double *state, double *unused, double *out_3008548781149723491); -void car_h_28(double *state, double *unused, double *out_2689411064197794064); -void car_H_28(double *state, double *unused, double *out_8090947798219254065); -void car_h_31(double *state, double *unused, double *out_5863304078495014059); -void car_H_31(double *state, double *unused, double *out_6006467122094403874); +void car_err_fun(double *nom_x, double *delta_x, double *out_3511157536608921668); +void car_inv_err_fun(double *nom_x, double *true_x, double *out_6431969432730020252); +void car_H_mod_fun(double *state, double *out_7948008639250905645); +void car_f_fun(double *state, double dt, double *out_2086994761209225774); +void car_F_fun(double *state, double dt, double *out_8139310027990993197); +void car_h_25(double *state, double *unused, double *out_4906131110836938043); +void car_H_25(double *state, double *unused, double *out_8920612812001856359); +void car_h_24(double *state, double *unused, double *out_3427550057756876624); +void car_H_24(double *state, double *unused, double *out_5543808110309927359); +void car_h_30(double *state, double *unused, double *out_5063317779188067188); +void car_H_30(double *state, double *unused, double *out_2003922470510239604); +void car_h_26(double *state, double *unused, double *out_8958065379223252895); +void car_H_26(double *state, double *unused, double *out_5784627942833639033); +void car_h_27(double *state, double *unused, double *out_7942917162281270728); +void car_H_27(double *state, double *unused, double *out_4178685782310664515); +void car_h_29(double *state, double *unused, double *out_3732991685077929952); +void car_H_29(double *state, double *unused, double *out_1493691126195847420); +void car_h_28(double *state, double *unused, double *out_2300187291200313893); +void car_H_28(double *state, double *unused, double *out_6576090143265377994); +void car_h_31(double *state, double *unused, double *out_5181325173121443932); +void car_H_31(double *state, double *unused, double *out_8889966850124895931); void car_predict(double *in_x, double *in_P, double *in_Q, double dt); void car_set_mass(double x); void car_set_rotational_inertia(double x); diff --git a/selfdrive/locationd/models/generated/gnss.cpp b/selfdrive/locationd/models/generated/gnss.cpp index e3df158d1..f778b0150 100644 --- a/selfdrive/locationd/models/generated/gnss.cpp +++ b/selfdrive/locationd/models/generated/gnss.cpp @@ -17,354 +17,354 @@ const static double MAHA_THRESH_21 = 3.8414588206941227; * * * This file is part of 'ekf' * ******************************************************************************/ -void err_fun(double *nom_x, double *delta_x, double *out_5270397344340919402) { - out_5270397344340919402[0] = delta_x[0] + nom_x[0]; - out_5270397344340919402[1] = delta_x[1] + nom_x[1]; - out_5270397344340919402[2] = delta_x[2] + nom_x[2]; - out_5270397344340919402[3] = delta_x[3] + nom_x[3]; - out_5270397344340919402[4] = delta_x[4] + nom_x[4]; - out_5270397344340919402[5] = delta_x[5] + nom_x[5]; - out_5270397344340919402[6] = delta_x[6] + nom_x[6]; - out_5270397344340919402[7] = delta_x[7] + nom_x[7]; - out_5270397344340919402[8] = delta_x[8] + nom_x[8]; - out_5270397344340919402[9] = delta_x[9] + nom_x[9]; - out_5270397344340919402[10] = delta_x[10] + nom_x[10]; +void err_fun(double *nom_x, double *delta_x, double *out_2155524759348881706) { + out_2155524759348881706[0] = delta_x[0] + nom_x[0]; + out_2155524759348881706[1] = delta_x[1] + nom_x[1]; + out_2155524759348881706[2] = delta_x[2] + nom_x[2]; + out_2155524759348881706[3] = delta_x[3] + nom_x[3]; + out_2155524759348881706[4] = delta_x[4] + nom_x[4]; + out_2155524759348881706[5] = delta_x[5] + nom_x[5]; + out_2155524759348881706[6] = delta_x[6] + nom_x[6]; + out_2155524759348881706[7] = delta_x[7] + nom_x[7]; + out_2155524759348881706[8] = delta_x[8] + nom_x[8]; + out_2155524759348881706[9] = delta_x[9] + nom_x[9]; + out_2155524759348881706[10] = delta_x[10] + nom_x[10]; } -void inv_err_fun(double *nom_x, double *true_x, double *out_1512259161409062554) { - out_1512259161409062554[0] = -nom_x[0] + true_x[0]; - out_1512259161409062554[1] = -nom_x[1] + true_x[1]; - out_1512259161409062554[2] = -nom_x[2] + true_x[2]; - out_1512259161409062554[3] = -nom_x[3] + true_x[3]; - out_1512259161409062554[4] = -nom_x[4] + true_x[4]; - out_1512259161409062554[5] = -nom_x[5] + true_x[5]; - out_1512259161409062554[6] = -nom_x[6] + true_x[6]; - out_1512259161409062554[7] = -nom_x[7] + true_x[7]; - out_1512259161409062554[8] = -nom_x[8] + true_x[8]; - out_1512259161409062554[9] = -nom_x[9] + true_x[9]; - out_1512259161409062554[10] = -nom_x[10] + true_x[10]; +void inv_err_fun(double *nom_x, double *true_x, double *out_3000442515133824169) { + out_3000442515133824169[0] = -nom_x[0] + true_x[0]; + out_3000442515133824169[1] = -nom_x[1] + true_x[1]; + out_3000442515133824169[2] = -nom_x[2] + true_x[2]; + out_3000442515133824169[3] = -nom_x[3] + true_x[3]; + out_3000442515133824169[4] = -nom_x[4] + true_x[4]; + out_3000442515133824169[5] = -nom_x[5] + true_x[5]; + out_3000442515133824169[6] = -nom_x[6] + true_x[6]; + out_3000442515133824169[7] = -nom_x[7] + true_x[7]; + out_3000442515133824169[8] = -nom_x[8] + true_x[8]; + out_3000442515133824169[9] = -nom_x[9] + true_x[9]; + out_3000442515133824169[10] = -nom_x[10] + true_x[10]; } -void H_mod_fun(double *state, double *out_8413937430488034064) { - out_8413937430488034064[0] = 1.0; - out_8413937430488034064[1] = 0; - out_8413937430488034064[2] = 0; - out_8413937430488034064[3] = 0; - out_8413937430488034064[4] = 0; - out_8413937430488034064[5] = 0; - out_8413937430488034064[6] = 0; - out_8413937430488034064[7] = 0; - out_8413937430488034064[8] = 0; - out_8413937430488034064[9] = 0; - out_8413937430488034064[10] = 0; - out_8413937430488034064[11] = 0; - out_8413937430488034064[12] = 1.0; - out_8413937430488034064[13] = 0; - out_8413937430488034064[14] = 0; - out_8413937430488034064[15] = 0; - out_8413937430488034064[16] = 0; - out_8413937430488034064[17] = 0; - out_8413937430488034064[18] = 0; - out_8413937430488034064[19] = 0; - out_8413937430488034064[20] = 0; - out_8413937430488034064[21] = 0; - out_8413937430488034064[22] = 0; - out_8413937430488034064[23] = 0; - out_8413937430488034064[24] = 1.0; - out_8413937430488034064[25] = 0; - out_8413937430488034064[26] = 0; - out_8413937430488034064[27] = 0; - out_8413937430488034064[28] = 0; - out_8413937430488034064[29] = 0; - out_8413937430488034064[30] = 0; - out_8413937430488034064[31] = 0; - out_8413937430488034064[32] = 0; - out_8413937430488034064[33] = 0; - out_8413937430488034064[34] = 0; - out_8413937430488034064[35] = 0; - out_8413937430488034064[36] = 1.0; - out_8413937430488034064[37] = 0; - out_8413937430488034064[38] = 0; - out_8413937430488034064[39] = 0; - out_8413937430488034064[40] = 0; - out_8413937430488034064[41] = 0; - out_8413937430488034064[42] = 0; - out_8413937430488034064[43] = 0; - out_8413937430488034064[44] = 0; - out_8413937430488034064[45] = 0; - out_8413937430488034064[46] = 0; - out_8413937430488034064[47] = 0; - out_8413937430488034064[48] = 1.0; - out_8413937430488034064[49] = 0; - out_8413937430488034064[50] = 0; - out_8413937430488034064[51] = 0; - out_8413937430488034064[52] = 0; - out_8413937430488034064[53] = 0; - out_8413937430488034064[54] = 0; - out_8413937430488034064[55] = 0; - out_8413937430488034064[56] = 0; - out_8413937430488034064[57] = 0; - out_8413937430488034064[58] = 0; - out_8413937430488034064[59] = 0; - out_8413937430488034064[60] = 1.0; - out_8413937430488034064[61] = 0; - out_8413937430488034064[62] = 0; - out_8413937430488034064[63] = 0; - out_8413937430488034064[64] = 0; - out_8413937430488034064[65] = 0; - out_8413937430488034064[66] = 0; - out_8413937430488034064[67] = 0; - out_8413937430488034064[68] = 0; - out_8413937430488034064[69] = 0; - out_8413937430488034064[70] = 0; - out_8413937430488034064[71] = 0; - out_8413937430488034064[72] = 1.0; - out_8413937430488034064[73] = 0; - out_8413937430488034064[74] = 0; - out_8413937430488034064[75] = 0; - out_8413937430488034064[76] = 0; - out_8413937430488034064[77] = 0; - out_8413937430488034064[78] = 0; - out_8413937430488034064[79] = 0; - out_8413937430488034064[80] = 0; - out_8413937430488034064[81] = 0; - out_8413937430488034064[82] = 0; - out_8413937430488034064[83] = 0; - out_8413937430488034064[84] = 1.0; - out_8413937430488034064[85] = 0; - out_8413937430488034064[86] = 0; - out_8413937430488034064[87] = 0; - out_8413937430488034064[88] = 0; - out_8413937430488034064[89] = 0; - out_8413937430488034064[90] = 0; - out_8413937430488034064[91] = 0; - out_8413937430488034064[92] = 0; - out_8413937430488034064[93] = 0; - out_8413937430488034064[94] = 0; - out_8413937430488034064[95] = 0; - out_8413937430488034064[96] = 1.0; - out_8413937430488034064[97] = 0; - out_8413937430488034064[98] = 0; - out_8413937430488034064[99] = 0; - out_8413937430488034064[100] = 0; - out_8413937430488034064[101] = 0; - out_8413937430488034064[102] = 0; - out_8413937430488034064[103] = 0; - out_8413937430488034064[104] = 0; - out_8413937430488034064[105] = 0; - out_8413937430488034064[106] = 0; - out_8413937430488034064[107] = 0; - out_8413937430488034064[108] = 1.0; - out_8413937430488034064[109] = 0; - out_8413937430488034064[110] = 0; - out_8413937430488034064[111] = 0; - out_8413937430488034064[112] = 0; - out_8413937430488034064[113] = 0; - out_8413937430488034064[114] = 0; - out_8413937430488034064[115] = 0; - out_8413937430488034064[116] = 0; - out_8413937430488034064[117] = 0; - out_8413937430488034064[118] = 0; - out_8413937430488034064[119] = 0; - out_8413937430488034064[120] = 1.0; +void H_mod_fun(double *state, double *out_6886810493919790975) { + out_6886810493919790975[0] = 1.0; + out_6886810493919790975[1] = 0; + out_6886810493919790975[2] = 0; + out_6886810493919790975[3] = 0; + out_6886810493919790975[4] = 0; + out_6886810493919790975[5] = 0; + out_6886810493919790975[6] = 0; + out_6886810493919790975[7] = 0; + out_6886810493919790975[8] = 0; + out_6886810493919790975[9] = 0; + out_6886810493919790975[10] = 0; + out_6886810493919790975[11] = 0; + out_6886810493919790975[12] = 1.0; + out_6886810493919790975[13] = 0; + out_6886810493919790975[14] = 0; + out_6886810493919790975[15] = 0; + out_6886810493919790975[16] = 0; + out_6886810493919790975[17] = 0; + out_6886810493919790975[18] = 0; + out_6886810493919790975[19] = 0; + out_6886810493919790975[20] = 0; + out_6886810493919790975[21] = 0; + out_6886810493919790975[22] = 0; + out_6886810493919790975[23] = 0; + out_6886810493919790975[24] = 1.0; + out_6886810493919790975[25] = 0; + out_6886810493919790975[26] = 0; + out_6886810493919790975[27] = 0; + out_6886810493919790975[28] = 0; + out_6886810493919790975[29] = 0; + out_6886810493919790975[30] = 0; + out_6886810493919790975[31] = 0; + out_6886810493919790975[32] = 0; + out_6886810493919790975[33] = 0; + out_6886810493919790975[34] = 0; + out_6886810493919790975[35] = 0; + out_6886810493919790975[36] = 1.0; + out_6886810493919790975[37] = 0; + out_6886810493919790975[38] = 0; + out_6886810493919790975[39] = 0; + out_6886810493919790975[40] = 0; + out_6886810493919790975[41] = 0; + out_6886810493919790975[42] = 0; + out_6886810493919790975[43] = 0; + out_6886810493919790975[44] = 0; + out_6886810493919790975[45] = 0; + out_6886810493919790975[46] = 0; + out_6886810493919790975[47] = 0; + out_6886810493919790975[48] = 1.0; + out_6886810493919790975[49] = 0; + out_6886810493919790975[50] = 0; + out_6886810493919790975[51] = 0; + out_6886810493919790975[52] = 0; + out_6886810493919790975[53] = 0; + out_6886810493919790975[54] = 0; + out_6886810493919790975[55] = 0; + out_6886810493919790975[56] = 0; + out_6886810493919790975[57] = 0; + out_6886810493919790975[58] = 0; + out_6886810493919790975[59] = 0; + out_6886810493919790975[60] = 1.0; + out_6886810493919790975[61] = 0; + out_6886810493919790975[62] = 0; + out_6886810493919790975[63] = 0; + out_6886810493919790975[64] = 0; + out_6886810493919790975[65] = 0; + out_6886810493919790975[66] = 0; + out_6886810493919790975[67] = 0; + out_6886810493919790975[68] = 0; + out_6886810493919790975[69] = 0; + out_6886810493919790975[70] = 0; + out_6886810493919790975[71] = 0; + out_6886810493919790975[72] = 1.0; + out_6886810493919790975[73] = 0; + out_6886810493919790975[74] = 0; + out_6886810493919790975[75] = 0; + out_6886810493919790975[76] = 0; + out_6886810493919790975[77] = 0; + out_6886810493919790975[78] = 0; + out_6886810493919790975[79] = 0; + out_6886810493919790975[80] = 0; + out_6886810493919790975[81] = 0; + out_6886810493919790975[82] = 0; + out_6886810493919790975[83] = 0; + out_6886810493919790975[84] = 1.0; + out_6886810493919790975[85] = 0; + out_6886810493919790975[86] = 0; + out_6886810493919790975[87] = 0; + out_6886810493919790975[88] = 0; + out_6886810493919790975[89] = 0; + out_6886810493919790975[90] = 0; + out_6886810493919790975[91] = 0; + out_6886810493919790975[92] = 0; + out_6886810493919790975[93] = 0; + out_6886810493919790975[94] = 0; + out_6886810493919790975[95] = 0; + out_6886810493919790975[96] = 1.0; + out_6886810493919790975[97] = 0; + out_6886810493919790975[98] = 0; + out_6886810493919790975[99] = 0; + out_6886810493919790975[100] = 0; + out_6886810493919790975[101] = 0; + out_6886810493919790975[102] = 0; + out_6886810493919790975[103] = 0; + out_6886810493919790975[104] = 0; + out_6886810493919790975[105] = 0; + out_6886810493919790975[106] = 0; + out_6886810493919790975[107] = 0; + out_6886810493919790975[108] = 1.0; + out_6886810493919790975[109] = 0; + out_6886810493919790975[110] = 0; + out_6886810493919790975[111] = 0; + out_6886810493919790975[112] = 0; + out_6886810493919790975[113] = 0; + out_6886810493919790975[114] = 0; + out_6886810493919790975[115] = 0; + out_6886810493919790975[116] = 0; + out_6886810493919790975[117] = 0; + out_6886810493919790975[118] = 0; + out_6886810493919790975[119] = 0; + out_6886810493919790975[120] = 1.0; } -void f_fun(double *state, double dt, double *out_8044790491496694058) { - out_8044790491496694058[0] = dt*state[3] + state[0]; - out_8044790491496694058[1] = dt*state[4] + state[1]; - out_8044790491496694058[2] = dt*state[5] + state[2]; - out_8044790491496694058[3] = state[3]; - out_8044790491496694058[4] = state[4]; - out_8044790491496694058[5] = state[5]; - out_8044790491496694058[6] = dt*state[7] + state[6]; - out_8044790491496694058[7] = dt*state[8] + state[7]; - out_8044790491496694058[8] = state[8]; - out_8044790491496694058[9] = state[9]; - out_8044790491496694058[10] = state[10]; +void f_fun(double *state, double dt, double *out_8724257366443597251) { + out_8724257366443597251[0] = dt*state[3] + state[0]; + out_8724257366443597251[1] = dt*state[4] + state[1]; + out_8724257366443597251[2] = dt*state[5] + state[2]; + out_8724257366443597251[3] = state[3]; + out_8724257366443597251[4] = state[4]; + out_8724257366443597251[5] = state[5]; + out_8724257366443597251[6] = dt*state[7] + state[6]; + out_8724257366443597251[7] = dt*state[8] + state[7]; + out_8724257366443597251[8] = state[8]; + out_8724257366443597251[9] = state[9]; + out_8724257366443597251[10] = state[10]; } -void F_fun(double *state, double dt, double *out_7107643139068643538) { - out_7107643139068643538[0] = 1; - out_7107643139068643538[1] = 0; - out_7107643139068643538[2] = 0; - out_7107643139068643538[3] = dt; - out_7107643139068643538[4] = 0; - out_7107643139068643538[5] = 0; - out_7107643139068643538[6] = 0; - out_7107643139068643538[7] = 0; - out_7107643139068643538[8] = 0; - out_7107643139068643538[9] = 0; - out_7107643139068643538[10] = 0; - out_7107643139068643538[11] = 0; - out_7107643139068643538[12] = 1; - out_7107643139068643538[13] = 0; - out_7107643139068643538[14] = 0; - out_7107643139068643538[15] = dt; - out_7107643139068643538[16] = 0; - out_7107643139068643538[17] = 0; - out_7107643139068643538[18] = 0; - out_7107643139068643538[19] = 0; - out_7107643139068643538[20] = 0; - out_7107643139068643538[21] = 0; - out_7107643139068643538[22] = 0; - out_7107643139068643538[23] = 0; - out_7107643139068643538[24] = 1; - out_7107643139068643538[25] = 0; - out_7107643139068643538[26] = 0; - out_7107643139068643538[27] = dt; - out_7107643139068643538[28] = 0; - out_7107643139068643538[29] = 0; - out_7107643139068643538[30] = 0; - out_7107643139068643538[31] = 0; - out_7107643139068643538[32] = 0; - out_7107643139068643538[33] = 0; - out_7107643139068643538[34] = 0; - out_7107643139068643538[35] = 0; - out_7107643139068643538[36] = 1; - out_7107643139068643538[37] = 0; - out_7107643139068643538[38] = 0; - out_7107643139068643538[39] = 0; - out_7107643139068643538[40] = 0; - out_7107643139068643538[41] = 0; - out_7107643139068643538[42] = 0; - out_7107643139068643538[43] = 0; - out_7107643139068643538[44] = 0; - out_7107643139068643538[45] = 0; - out_7107643139068643538[46] = 0; - out_7107643139068643538[47] = 0; - out_7107643139068643538[48] = 1; - out_7107643139068643538[49] = 0; - out_7107643139068643538[50] = 0; - out_7107643139068643538[51] = 0; - out_7107643139068643538[52] = 0; - out_7107643139068643538[53] = 0; - out_7107643139068643538[54] = 0; - out_7107643139068643538[55] = 0; - out_7107643139068643538[56] = 0; - out_7107643139068643538[57] = 0; - out_7107643139068643538[58] = 0; - out_7107643139068643538[59] = 0; - out_7107643139068643538[60] = 1; - out_7107643139068643538[61] = 0; - out_7107643139068643538[62] = 0; - out_7107643139068643538[63] = 0; - out_7107643139068643538[64] = 0; - out_7107643139068643538[65] = 0; - out_7107643139068643538[66] = 0; - out_7107643139068643538[67] = 0; - out_7107643139068643538[68] = 0; - out_7107643139068643538[69] = 0; - out_7107643139068643538[70] = 0; - out_7107643139068643538[71] = 0; - out_7107643139068643538[72] = 1; - out_7107643139068643538[73] = dt; - out_7107643139068643538[74] = 0; - out_7107643139068643538[75] = 0; - out_7107643139068643538[76] = 0; - out_7107643139068643538[77] = 0; - out_7107643139068643538[78] = 0; - out_7107643139068643538[79] = 0; - out_7107643139068643538[80] = 0; - out_7107643139068643538[81] = 0; - out_7107643139068643538[82] = 0; - out_7107643139068643538[83] = 0; - out_7107643139068643538[84] = 1; - out_7107643139068643538[85] = dt; - out_7107643139068643538[86] = 0; - out_7107643139068643538[87] = 0; - out_7107643139068643538[88] = 0; - out_7107643139068643538[89] = 0; - out_7107643139068643538[90] = 0; - out_7107643139068643538[91] = 0; - out_7107643139068643538[92] = 0; - out_7107643139068643538[93] = 0; - out_7107643139068643538[94] = 0; - out_7107643139068643538[95] = 0; - out_7107643139068643538[96] = 1; - out_7107643139068643538[97] = 0; - out_7107643139068643538[98] = 0; - out_7107643139068643538[99] = 0; - out_7107643139068643538[100] = 0; - out_7107643139068643538[101] = 0; - out_7107643139068643538[102] = 0; - out_7107643139068643538[103] = 0; - out_7107643139068643538[104] = 0; - out_7107643139068643538[105] = 0; - out_7107643139068643538[106] = 0; - out_7107643139068643538[107] = 0; - out_7107643139068643538[108] = 1; - out_7107643139068643538[109] = 0; - out_7107643139068643538[110] = 0; - out_7107643139068643538[111] = 0; - out_7107643139068643538[112] = 0; - out_7107643139068643538[113] = 0; - out_7107643139068643538[114] = 0; - out_7107643139068643538[115] = 0; - out_7107643139068643538[116] = 0; - out_7107643139068643538[117] = 0; - out_7107643139068643538[118] = 0; - out_7107643139068643538[119] = 0; - out_7107643139068643538[120] = 1; +void F_fun(double *state, double dt, double *out_2206723714956142118) { + out_2206723714956142118[0] = 1; + out_2206723714956142118[1] = 0; + out_2206723714956142118[2] = 0; + out_2206723714956142118[3] = dt; + out_2206723714956142118[4] = 0; + out_2206723714956142118[5] = 0; + out_2206723714956142118[6] = 0; + out_2206723714956142118[7] = 0; + out_2206723714956142118[8] = 0; + out_2206723714956142118[9] = 0; + out_2206723714956142118[10] = 0; + out_2206723714956142118[11] = 0; + out_2206723714956142118[12] = 1; + out_2206723714956142118[13] = 0; + out_2206723714956142118[14] = 0; + out_2206723714956142118[15] = dt; + out_2206723714956142118[16] = 0; + out_2206723714956142118[17] = 0; + out_2206723714956142118[18] = 0; + out_2206723714956142118[19] = 0; + out_2206723714956142118[20] = 0; + out_2206723714956142118[21] = 0; + out_2206723714956142118[22] = 0; + out_2206723714956142118[23] = 0; + out_2206723714956142118[24] = 1; + out_2206723714956142118[25] = 0; + out_2206723714956142118[26] = 0; + out_2206723714956142118[27] = dt; + out_2206723714956142118[28] = 0; + out_2206723714956142118[29] = 0; + out_2206723714956142118[30] = 0; + out_2206723714956142118[31] = 0; + out_2206723714956142118[32] = 0; + out_2206723714956142118[33] = 0; + out_2206723714956142118[34] = 0; + out_2206723714956142118[35] = 0; + out_2206723714956142118[36] = 1; + out_2206723714956142118[37] = 0; + out_2206723714956142118[38] = 0; + out_2206723714956142118[39] = 0; + out_2206723714956142118[40] = 0; + out_2206723714956142118[41] = 0; + out_2206723714956142118[42] = 0; + out_2206723714956142118[43] = 0; + out_2206723714956142118[44] = 0; + out_2206723714956142118[45] = 0; + out_2206723714956142118[46] = 0; + out_2206723714956142118[47] = 0; + out_2206723714956142118[48] = 1; + out_2206723714956142118[49] = 0; + out_2206723714956142118[50] = 0; + out_2206723714956142118[51] = 0; + out_2206723714956142118[52] = 0; + out_2206723714956142118[53] = 0; + out_2206723714956142118[54] = 0; + out_2206723714956142118[55] = 0; + out_2206723714956142118[56] = 0; + out_2206723714956142118[57] = 0; + out_2206723714956142118[58] = 0; + out_2206723714956142118[59] = 0; + out_2206723714956142118[60] = 1; + out_2206723714956142118[61] = 0; + out_2206723714956142118[62] = 0; + out_2206723714956142118[63] = 0; + out_2206723714956142118[64] = 0; + out_2206723714956142118[65] = 0; + out_2206723714956142118[66] = 0; + out_2206723714956142118[67] = 0; + out_2206723714956142118[68] = 0; + out_2206723714956142118[69] = 0; + out_2206723714956142118[70] = 0; + out_2206723714956142118[71] = 0; + out_2206723714956142118[72] = 1; + out_2206723714956142118[73] = dt; + out_2206723714956142118[74] = 0; + out_2206723714956142118[75] = 0; + out_2206723714956142118[76] = 0; + out_2206723714956142118[77] = 0; + out_2206723714956142118[78] = 0; + out_2206723714956142118[79] = 0; + out_2206723714956142118[80] = 0; + out_2206723714956142118[81] = 0; + out_2206723714956142118[82] = 0; + out_2206723714956142118[83] = 0; + out_2206723714956142118[84] = 1; + out_2206723714956142118[85] = dt; + out_2206723714956142118[86] = 0; + out_2206723714956142118[87] = 0; + out_2206723714956142118[88] = 0; + out_2206723714956142118[89] = 0; + out_2206723714956142118[90] = 0; + out_2206723714956142118[91] = 0; + out_2206723714956142118[92] = 0; + out_2206723714956142118[93] = 0; + out_2206723714956142118[94] = 0; + out_2206723714956142118[95] = 0; + out_2206723714956142118[96] = 1; + out_2206723714956142118[97] = 0; + out_2206723714956142118[98] = 0; + out_2206723714956142118[99] = 0; + out_2206723714956142118[100] = 0; + out_2206723714956142118[101] = 0; + out_2206723714956142118[102] = 0; + out_2206723714956142118[103] = 0; + out_2206723714956142118[104] = 0; + out_2206723714956142118[105] = 0; + out_2206723714956142118[106] = 0; + out_2206723714956142118[107] = 0; + out_2206723714956142118[108] = 1; + out_2206723714956142118[109] = 0; + out_2206723714956142118[110] = 0; + out_2206723714956142118[111] = 0; + out_2206723714956142118[112] = 0; + out_2206723714956142118[113] = 0; + out_2206723714956142118[114] = 0; + out_2206723714956142118[115] = 0; + out_2206723714956142118[116] = 0; + out_2206723714956142118[117] = 0; + out_2206723714956142118[118] = 0; + out_2206723714956142118[119] = 0; + out_2206723714956142118[120] = 1; } -void h_6(double *state, double *sat_pos, double *out_1014783744438669605) { - out_1014783744438669605[0] = sqrt(pow(-sat_pos[0] + state[0], 2) + pow(-sat_pos[1] + state[1], 2) + pow(-sat_pos[2] + state[2], 2)) + state[6]; +void h_6(double *state, double *sat_pos, double *out_9215791719434072081) { + out_9215791719434072081[0] = sqrt(pow(-sat_pos[0] + state[0], 2) + pow(-sat_pos[1] + state[1], 2) + pow(-sat_pos[2] + state[2], 2)) + state[6]; } -void H_6(double *state, double *sat_pos, double *out_2647892629803094557) { - out_2647892629803094557[0] = (-sat_pos[0] + state[0])/sqrt(pow(-sat_pos[0] + state[0], 2) + pow(-sat_pos[1] + state[1], 2) + pow(-sat_pos[2] + state[2], 2)); - out_2647892629803094557[1] = (-sat_pos[1] + state[1])/sqrt(pow(-sat_pos[0] + state[0], 2) + pow(-sat_pos[1] + state[1], 2) + pow(-sat_pos[2] + state[2], 2)); - out_2647892629803094557[2] = (-sat_pos[2] + state[2])/sqrt(pow(-sat_pos[0] + state[0], 2) + pow(-sat_pos[1] + state[1], 2) + pow(-sat_pos[2] + state[2], 2)); - out_2647892629803094557[3] = 0; - out_2647892629803094557[4] = 0; - out_2647892629803094557[5] = 0; - out_2647892629803094557[6] = 1; - out_2647892629803094557[7] = 0; - out_2647892629803094557[8] = 0; - out_2647892629803094557[9] = 0; - out_2647892629803094557[10] = 0; +void H_6(double *state, double *sat_pos, double *out_6079281560797038039) { + out_6079281560797038039[0] = (-sat_pos[0] + state[0])/sqrt(pow(-sat_pos[0] + state[0], 2) + pow(-sat_pos[1] + state[1], 2) + pow(-sat_pos[2] + state[2], 2)); + out_6079281560797038039[1] = (-sat_pos[1] + state[1])/sqrt(pow(-sat_pos[0] + state[0], 2) + pow(-sat_pos[1] + state[1], 2) + pow(-sat_pos[2] + state[2], 2)); + out_6079281560797038039[2] = (-sat_pos[2] + state[2])/sqrt(pow(-sat_pos[0] + state[0], 2) + pow(-sat_pos[1] + state[1], 2) + pow(-sat_pos[2] + state[2], 2)); + out_6079281560797038039[3] = 0; + out_6079281560797038039[4] = 0; + out_6079281560797038039[5] = 0; + out_6079281560797038039[6] = 1; + out_6079281560797038039[7] = 0; + out_6079281560797038039[8] = 0; + out_6079281560797038039[9] = 0; + out_6079281560797038039[10] = 0; } -void h_20(double *state, double *sat_pos, double *out_4446463785726682298) { - out_4446463785726682298[0] = sqrt(pow(-sat_pos[0] + state[0], 2) + pow(-sat_pos[1] + state[1], 2) + pow(-sat_pos[2] + state[2], 2)) + sat_pos[3]*state[10] + state[6] + state[9]; +void h_20(double *state, double *sat_pos, double *out_707679285162606847) { + out_707679285162606847[0] = sqrt(pow(-sat_pos[0] + state[0], 2) + pow(-sat_pos[1] + state[1], 2) + pow(-sat_pos[2] + state[2], 2)) + sat_pos[3]*state[10] + state[6] + state[9]; } -void H_20(double *state, double *sat_pos, double *out_2058835805956563056) { - out_2058835805956563056[0] = (-sat_pos[0] + state[0])/sqrt(pow(-sat_pos[0] + state[0], 2) + pow(-sat_pos[1] + state[1], 2) + pow(-sat_pos[2] + state[2], 2)); - out_2058835805956563056[1] = (-sat_pos[1] + state[1])/sqrt(pow(-sat_pos[0] + state[0], 2) + pow(-sat_pos[1] + state[1], 2) + pow(-sat_pos[2] + state[2], 2)); - out_2058835805956563056[2] = (-sat_pos[2] + state[2])/sqrt(pow(-sat_pos[0] + state[0], 2) + pow(-sat_pos[1] + state[1], 2) + pow(-sat_pos[2] + state[2], 2)); - out_2058835805956563056[3] = 0; - out_2058835805956563056[4] = 0; - out_2058835805956563056[5] = 0; - out_2058835805956563056[6] = 1; - out_2058835805956563056[7] = 0; - out_2058835805956563056[8] = 0; - out_2058835805956563056[9] = 1; - out_2058835805956563056[10] = sat_pos[3]; +void H_20(double *state, double *sat_pos, double *out_6425650286104756584) { + out_6425650286104756584[0] = (-sat_pos[0] + state[0])/sqrt(pow(-sat_pos[0] + state[0], 2) + pow(-sat_pos[1] + state[1], 2) + pow(-sat_pos[2] + state[2], 2)); + out_6425650286104756584[1] = (-sat_pos[1] + state[1])/sqrt(pow(-sat_pos[0] + state[0], 2) + pow(-sat_pos[1] + state[1], 2) + pow(-sat_pos[2] + state[2], 2)); + out_6425650286104756584[2] = (-sat_pos[2] + state[2])/sqrt(pow(-sat_pos[0] + state[0], 2) + pow(-sat_pos[1] + state[1], 2) + pow(-sat_pos[2] + state[2], 2)); + out_6425650286104756584[3] = 0; + out_6425650286104756584[4] = 0; + out_6425650286104756584[5] = 0; + out_6425650286104756584[6] = 1; + out_6425650286104756584[7] = 0; + out_6425650286104756584[8] = 0; + out_6425650286104756584[9] = 1; + out_6425650286104756584[10] = sat_pos[3]; } -void h_7(double *state, double *sat_pos_vel, double *out_6977013047509885177) { - out_6977013047509885177[0] = (sat_pos_vel[0] - state[0])*(sat_pos_vel[3] - state[3])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)) + (sat_pos_vel[1] - state[1])*(sat_pos_vel[4] - state[4])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)) + (sat_pos_vel[2] - state[2])*(sat_pos_vel[5] - state[5])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)) + state[7]; +void h_7(double *state, double *sat_pos_vel, double *out_8648640613651272087) { + out_8648640613651272087[0] = (sat_pos_vel[0] - state[0])*(sat_pos_vel[3] - state[3])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)) + (sat_pos_vel[1] - state[1])*(sat_pos_vel[4] - state[4])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)) + (sat_pos_vel[2] - state[2])*(sat_pos_vel[5] - state[5])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)) + state[7]; } -void H_7(double *state, double *sat_pos_vel, double *out_3396370189700754510) { - out_3396370189700754510[0] = pow(sat_pos_vel[0] - state[0], 2)*(sat_pos_vel[3] - state[3])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + (sat_pos_vel[0] - state[0])*(sat_pos_vel[1] - state[1])*(sat_pos_vel[4] - state[4])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + (sat_pos_vel[0] - state[0])*(sat_pos_vel[2] - state[2])*(sat_pos_vel[5] - state[5])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) - (sat_pos_vel[3] - state[3])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); - out_3396370189700754510[1] = (sat_pos_vel[0] - state[0])*(sat_pos_vel[1] - state[1])*(sat_pos_vel[3] - state[3])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + pow(sat_pos_vel[1] - state[1], 2)*(sat_pos_vel[4] - state[4])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + (sat_pos_vel[1] - state[1])*(sat_pos_vel[2] - state[2])*(sat_pos_vel[5] - state[5])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) - (sat_pos_vel[4] - state[4])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); - out_3396370189700754510[2] = (sat_pos_vel[0] - state[0])*(sat_pos_vel[2] - state[2])*(sat_pos_vel[3] - state[3])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + (sat_pos_vel[1] - state[1])*(sat_pos_vel[2] - state[2])*(sat_pos_vel[4] - state[4])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + pow(sat_pos_vel[2] - state[2], 2)*(sat_pos_vel[5] - state[5])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) - (sat_pos_vel[5] - state[5])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); - out_3396370189700754510[3] = -(sat_pos_vel[0] - state[0])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); - out_3396370189700754510[4] = -(sat_pos_vel[1] - state[1])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); - out_3396370189700754510[5] = -(sat_pos_vel[2] - state[2])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); - out_3396370189700754510[6] = 0; - out_3396370189700754510[7] = 1; - out_3396370189700754510[8] = 0; - out_3396370189700754510[9] = 0; - out_3396370189700754510[10] = 0; +void H_7(double *state, double *sat_pos_vel, double *out_236788228116502184) { + out_236788228116502184[0] = pow(sat_pos_vel[0] - state[0], 2)*(sat_pos_vel[3] - state[3])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + (sat_pos_vel[0] - state[0])*(sat_pos_vel[1] - state[1])*(sat_pos_vel[4] - state[4])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + (sat_pos_vel[0] - state[0])*(sat_pos_vel[2] - state[2])*(sat_pos_vel[5] - state[5])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) - (sat_pos_vel[3] - state[3])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); + out_236788228116502184[1] = (sat_pos_vel[0] - state[0])*(sat_pos_vel[1] - state[1])*(sat_pos_vel[3] - state[3])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + pow(sat_pos_vel[1] - state[1], 2)*(sat_pos_vel[4] - state[4])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + (sat_pos_vel[1] - state[1])*(sat_pos_vel[2] - state[2])*(sat_pos_vel[5] - state[5])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) - (sat_pos_vel[4] - state[4])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); + out_236788228116502184[2] = (sat_pos_vel[0] - state[0])*(sat_pos_vel[2] - state[2])*(sat_pos_vel[3] - state[3])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + (sat_pos_vel[1] - state[1])*(sat_pos_vel[2] - state[2])*(sat_pos_vel[4] - state[4])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + pow(sat_pos_vel[2] - state[2], 2)*(sat_pos_vel[5] - state[5])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) - (sat_pos_vel[5] - state[5])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); + out_236788228116502184[3] = -(sat_pos_vel[0] - state[0])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); + out_236788228116502184[4] = -(sat_pos_vel[1] - state[1])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); + out_236788228116502184[5] = -(sat_pos_vel[2] - state[2])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); + out_236788228116502184[6] = 0; + out_236788228116502184[7] = 1; + out_236788228116502184[8] = 0; + out_236788228116502184[9] = 0; + out_236788228116502184[10] = 0; } -void h_21(double *state, double *sat_pos_vel, double *out_6977013047509885177) { - out_6977013047509885177[0] = (sat_pos_vel[0] - state[0])*(sat_pos_vel[3] - state[3])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)) + (sat_pos_vel[1] - state[1])*(sat_pos_vel[4] - state[4])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)) + (sat_pos_vel[2] - state[2])*(sat_pos_vel[5] - state[5])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)) + state[7]; +void h_21(double *state, double *sat_pos_vel, double *out_8648640613651272087) { + out_8648640613651272087[0] = (sat_pos_vel[0] - state[0])*(sat_pos_vel[3] - state[3])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)) + (sat_pos_vel[1] - state[1])*(sat_pos_vel[4] - state[4])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)) + (sat_pos_vel[2] - state[2])*(sat_pos_vel[5] - state[5])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)) + state[7]; } -void H_21(double *state, double *sat_pos_vel, double *out_3396370189700754510) { - out_3396370189700754510[0] = pow(sat_pos_vel[0] - state[0], 2)*(sat_pos_vel[3] - state[3])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + (sat_pos_vel[0] - state[0])*(sat_pos_vel[1] - state[1])*(sat_pos_vel[4] - state[4])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + (sat_pos_vel[0] - state[0])*(sat_pos_vel[2] - state[2])*(sat_pos_vel[5] - state[5])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) - (sat_pos_vel[3] - state[3])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); - out_3396370189700754510[1] = (sat_pos_vel[0] - state[0])*(sat_pos_vel[1] - state[1])*(sat_pos_vel[3] - state[3])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + pow(sat_pos_vel[1] - state[1], 2)*(sat_pos_vel[4] - state[4])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + (sat_pos_vel[1] - state[1])*(sat_pos_vel[2] - state[2])*(sat_pos_vel[5] - state[5])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) - (sat_pos_vel[4] - state[4])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); - out_3396370189700754510[2] = (sat_pos_vel[0] - state[0])*(sat_pos_vel[2] - state[2])*(sat_pos_vel[3] - state[3])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + (sat_pos_vel[1] - state[1])*(sat_pos_vel[2] - state[2])*(sat_pos_vel[4] - state[4])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + pow(sat_pos_vel[2] - state[2], 2)*(sat_pos_vel[5] - state[5])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) - (sat_pos_vel[5] - state[5])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); - out_3396370189700754510[3] = -(sat_pos_vel[0] - state[0])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); - out_3396370189700754510[4] = -(sat_pos_vel[1] - state[1])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); - out_3396370189700754510[5] = -(sat_pos_vel[2] - state[2])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); - out_3396370189700754510[6] = 0; - out_3396370189700754510[7] = 1; - out_3396370189700754510[8] = 0; - out_3396370189700754510[9] = 0; - out_3396370189700754510[10] = 0; +void H_21(double *state, double *sat_pos_vel, double *out_236788228116502184) { + out_236788228116502184[0] = pow(sat_pos_vel[0] - state[0], 2)*(sat_pos_vel[3] - state[3])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + (sat_pos_vel[0] - state[0])*(sat_pos_vel[1] - state[1])*(sat_pos_vel[4] - state[4])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + (sat_pos_vel[0] - state[0])*(sat_pos_vel[2] - state[2])*(sat_pos_vel[5] - state[5])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) - (sat_pos_vel[3] - state[3])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); + out_236788228116502184[1] = (sat_pos_vel[0] - state[0])*(sat_pos_vel[1] - state[1])*(sat_pos_vel[3] - state[3])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + pow(sat_pos_vel[1] - state[1], 2)*(sat_pos_vel[4] - state[4])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + (sat_pos_vel[1] - state[1])*(sat_pos_vel[2] - state[2])*(sat_pos_vel[5] - state[5])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) - (sat_pos_vel[4] - state[4])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); + out_236788228116502184[2] = (sat_pos_vel[0] - state[0])*(sat_pos_vel[2] - state[2])*(sat_pos_vel[3] - state[3])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + (sat_pos_vel[1] - state[1])*(sat_pos_vel[2] - state[2])*(sat_pos_vel[4] - state[4])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) + pow(sat_pos_vel[2] - state[2], 2)*(sat_pos_vel[5] - state[5])/pow(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2), 3.0/2.0) - (sat_pos_vel[5] - state[5])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); + out_236788228116502184[3] = -(sat_pos_vel[0] - state[0])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); + out_236788228116502184[4] = -(sat_pos_vel[1] - state[1])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); + out_236788228116502184[5] = -(sat_pos_vel[2] - state[2])/sqrt(pow(sat_pos_vel[0] - state[0], 2) + pow(sat_pos_vel[1] - state[1], 2) + pow(sat_pos_vel[2] - state[2], 2)); + out_236788228116502184[6] = 0; + out_236788228116502184[7] = 1; + out_236788228116502184[8] = 0; + out_236788228116502184[9] = 0; + out_236788228116502184[10] = 0; } #include #include @@ -506,44 +506,44 @@ void gnss_update_7(double *in_x, double *in_P, double *in_z, double *in_R, doubl void gnss_update_21(double *in_x, double *in_P, double *in_z, double *in_R, double *in_ea) { update<1, 3, 0>(in_x, in_P, h_21, H_21, NULL, in_z, in_R, in_ea, MAHA_THRESH_21); } -void gnss_err_fun(double *nom_x, double *delta_x, double *out_5270397344340919402) { - err_fun(nom_x, delta_x, out_5270397344340919402); +void gnss_err_fun(double *nom_x, double *delta_x, double *out_2155524759348881706) { + err_fun(nom_x, delta_x, out_2155524759348881706); } -void gnss_inv_err_fun(double *nom_x, double *true_x, double *out_1512259161409062554) { - inv_err_fun(nom_x, true_x, out_1512259161409062554); +void gnss_inv_err_fun(double *nom_x, double *true_x, double *out_3000442515133824169) { + inv_err_fun(nom_x, true_x, out_3000442515133824169); } -void gnss_H_mod_fun(double *state, double *out_8413937430488034064) { - H_mod_fun(state, out_8413937430488034064); +void gnss_H_mod_fun(double *state, double *out_6886810493919790975) { + H_mod_fun(state, out_6886810493919790975); } -void gnss_f_fun(double *state, double dt, double *out_8044790491496694058) { - f_fun(state, dt, out_8044790491496694058); +void gnss_f_fun(double *state, double dt, double *out_8724257366443597251) { + f_fun(state, dt, out_8724257366443597251); } -void gnss_F_fun(double *state, double dt, double *out_7107643139068643538) { - F_fun(state, dt, out_7107643139068643538); +void gnss_F_fun(double *state, double dt, double *out_2206723714956142118) { + F_fun(state, dt, out_2206723714956142118); } -void gnss_h_6(double *state, double *sat_pos, double *out_1014783744438669605) { - h_6(state, sat_pos, out_1014783744438669605); +void gnss_h_6(double *state, double *sat_pos, double *out_9215791719434072081) { + h_6(state, sat_pos, out_9215791719434072081); } -void gnss_H_6(double *state, double *sat_pos, double *out_2647892629803094557) { - H_6(state, sat_pos, out_2647892629803094557); +void gnss_H_6(double *state, double *sat_pos, double *out_6079281560797038039) { + H_6(state, sat_pos, out_6079281560797038039); } -void gnss_h_20(double *state, double *sat_pos, double *out_4446463785726682298) { - h_20(state, sat_pos, out_4446463785726682298); +void gnss_h_20(double *state, double *sat_pos, double *out_707679285162606847) { + h_20(state, sat_pos, out_707679285162606847); } -void gnss_H_20(double *state, double *sat_pos, double *out_2058835805956563056) { - H_20(state, sat_pos, out_2058835805956563056); +void gnss_H_20(double *state, double *sat_pos, double *out_6425650286104756584) { + H_20(state, sat_pos, out_6425650286104756584); } -void gnss_h_7(double *state, double *sat_pos_vel, double *out_6977013047509885177) { - h_7(state, sat_pos_vel, out_6977013047509885177); +void gnss_h_7(double *state, double *sat_pos_vel, double *out_8648640613651272087) { + h_7(state, sat_pos_vel, out_8648640613651272087); } -void gnss_H_7(double *state, double *sat_pos_vel, double *out_3396370189700754510) { - H_7(state, sat_pos_vel, out_3396370189700754510); +void gnss_H_7(double *state, double *sat_pos_vel, double *out_236788228116502184) { + H_7(state, sat_pos_vel, out_236788228116502184); } -void gnss_h_21(double *state, double *sat_pos_vel, double *out_6977013047509885177) { - h_21(state, sat_pos_vel, out_6977013047509885177); +void gnss_h_21(double *state, double *sat_pos_vel, double *out_8648640613651272087) { + h_21(state, sat_pos_vel, out_8648640613651272087); } -void gnss_H_21(double *state, double *sat_pos_vel, double *out_3396370189700754510) { - H_21(state, sat_pos_vel, out_3396370189700754510); +void gnss_H_21(double *state, double *sat_pos_vel, double *out_236788228116502184) { + H_21(state, sat_pos_vel, out_236788228116502184); } void gnss_predict(double *in_x, double *in_P, double *in_Q, double dt) { predict(in_x, in_P, in_Q, dt); diff --git a/selfdrive/locationd/models/generated/gnss.h b/selfdrive/locationd/models/generated/gnss.h index d55128308..7c7a5ff01 100644 --- a/selfdrive/locationd/models/generated/gnss.h +++ b/selfdrive/locationd/models/generated/gnss.h @@ -5,18 +5,18 @@ void gnss_update_6(double *in_x, double *in_P, double *in_z, double *in_R, doubl void gnss_update_20(double *in_x, double *in_P, double *in_z, double *in_R, double *in_ea); void gnss_update_7(double *in_x, double *in_P, double *in_z, double *in_R, double *in_ea); void gnss_update_21(double *in_x, double *in_P, double *in_z, double *in_R, double *in_ea); -void gnss_err_fun(double *nom_x, double *delta_x, double *out_5270397344340919402); -void gnss_inv_err_fun(double *nom_x, double *true_x, double *out_1512259161409062554); -void gnss_H_mod_fun(double *state, double *out_8413937430488034064); -void gnss_f_fun(double *state, double dt, double *out_8044790491496694058); -void gnss_F_fun(double *state, double dt, double *out_7107643139068643538); -void gnss_h_6(double *state, double *sat_pos, double *out_1014783744438669605); -void gnss_H_6(double *state, double *sat_pos, double *out_2647892629803094557); -void gnss_h_20(double *state, double *sat_pos, double *out_4446463785726682298); -void gnss_H_20(double *state, double *sat_pos, double *out_2058835805956563056); -void gnss_h_7(double *state, double *sat_pos_vel, double *out_6977013047509885177); -void gnss_H_7(double *state, double *sat_pos_vel, double *out_3396370189700754510); -void gnss_h_21(double *state, double *sat_pos_vel, double *out_6977013047509885177); -void gnss_H_21(double *state, double *sat_pos_vel, double *out_3396370189700754510); +void gnss_err_fun(double *nom_x, double *delta_x, double *out_2155524759348881706); +void gnss_inv_err_fun(double *nom_x, double *true_x, double *out_3000442515133824169); +void gnss_H_mod_fun(double *state, double *out_6886810493919790975); +void gnss_f_fun(double *state, double dt, double *out_8724257366443597251); +void gnss_F_fun(double *state, double dt, double *out_2206723714956142118); +void gnss_h_6(double *state, double *sat_pos, double *out_9215791719434072081); +void gnss_H_6(double *state, double *sat_pos, double *out_6079281560797038039); +void gnss_h_20(double *state, double *sat_pos, double *out_707679285162606847); +void gnss_H_20(double *state, double *sat_pos, double *out_6425650286104756584); +void gnss_h_7(double *state, double *sat_pos_vel, double *out_8648640613651272087); +void gnss_H_7(double *state, double *sat_pos_vel, double *out_236788228116502184); +void gnss_h_21(double *state, double *sat_pos_vel, double *out_8648640613651272087); +void gnss_H_21(double *state, double *sat_pos_vel, double *out_236788228116502184); void gnss_predict(double *in_x, double *in_P, double *in_Q, double dt); } \ No newline at end of file diff --git a/selfdrive/locationd/models/generated/libkf.so b/selfdrive/locationd/models/generated/libkf.so index 39270f700..8c3c00154 100755 Binary files a/selfdrive/locationd/models/generated/libkf.so and b/selfdrive/locationd/models/generated/libkf.so differ diff --git a/selfdrive/locationd/models/generated/live.cpp b/selfdrive/locationd/models/generated/live.cpp index 36d1574d6..9c76225d5 100644 --- a/selfdrive/locationd/models/generated/live.cpp +++ b/selfdrive/locationd/models/generated/live.cpp @@ -22,1683 +22,1683 @@ const static double MAHA_THRESH_33 = 7.814727903251177; * * * This file is part of 'ekf' * ******************************************************************************/ -void H(double *in_vec, double *out_2107061543090158966) { - out_2107061543090158966[0] = 0; - out_2107061543090158966[1] = -sin(in_vec[1])*sin(in_vec[2])*in_vec[4] - sin(in_vec[1])*cos(in_vec[2])*in_vec[3] - cos(in_vec[1])*in_vec[5]; - out_2107061543090158966[2] = -sin(in_vec[2])*cos(in_vec[1])*in_vec[3] + cos(in_vec[1])*cos(in_vec[2])*in_vec[4]; - out_2107061543090158966[3] = cos(in_vec[1])*cos(in_vec[2]); - out_2107061543090158966[4] = sin(in_vec[2])*cos(in_vec[1]); - out_2107061543090158966[5] = -sin(in_vec[1]); - out_2107061543090158966[6] = (sin(in_vec[0])*sin(in_vec[2]) + sin(in_vec[1])*cos(in_vec[0])*cos(in_vec[2]))*in_vec[3] + (-sin(in_vec[0])*cos(in_vec[2]) + sin(in_vec[1])*sin(in_vec[2])*cos(in_vec[0]))*in_vec[4] + cos(in_vec[0])*cos(in_vec[1])*in_vec[5]; - out_2107061543090158966[7] = -sin(in_vec[0])*sin(in_vec[1])*in_vec[5] + sin(in_vec[0])*sin(in_vec[2])*cos(in_vec[1])*in_vec[4] + sin(in_vec[0])*cos(in_vec[1])*cos(in_vec[2])*in_vec[3]; - out_2107061543090158966[8] = (-sin(in_vec[0])*sin(in_vec[1])*sin(in_vec[2]) - cos(in_vec[0])*cos(in_vec[2]))*in_vec[3] + (sin(in_vec[0])*sin(in_vec[1])*cos(in_vec[2]) - sin(in_vec[2])*cos(in_vec[0]))*in_vec[4]; - out_2107061543090158966[9] = sin(in_vec[0])*sin(in_vec[1])*cos(in_vec[2]) - sin(in_vec[2])*cos(in_vec[0]); - out_2107061543090158966[10] = sin(in_vec[0])*sin(in_vec[1])*sin(in_vec[2]) + cos(in_vec[0])*cos(in_vec[2]); - out_2107061543090158966[11] = sin(in_vec[0])*cos(in_vec[1]); - out_2107061543090158966[12] = (-sin(in_vec[0])*sin(in_vec[1])*sin(in_vec[2]) - cos(in_vec[0])*cos(in_vec[2]))*in_vec[4] + (-sin(in_vec[0])*sin(in_vec[1])*cos(in_vec[2]) + sin(in_vec[2])*cos(in_vec[0]))*in_vec[3] - sin(in_vec[0])*cos(in_vec[1])*in_vec[5]; - out_2107061543090158966[13] = -sin(in_vec[1])*cos(in_vec[0])*in_vec[5] + sin(in_vec[2])*cos(in_vec[0])*cos(in_vec[1])*in_vec[4] + cos(in_vec[0])*cos(in_vec[1])*cos(in_vec[2])*in_vec[3]; - out_2107061543090158966[14] = (sin(in_vec[0])*sin(in_vec[2]) + sin(in_vec[1])*cos(in_vec[0])*cos(in_vec[2]))*in_vec[4] + (sin(in_vec[0])*cos(in_vec[2]) - sin(in_vec[1])*sin(in_vec[2])*cos(in_vec[0]))*in_vec[3]; - out_2107061543090158966[15] = sin(in_vec[0])*sin(in_vec[2]) + sin(in_vec[1])*cos(in_vec[0])*cos(in_vec[2]); - out_2107061543090158966[16] = -sin(in_vec[0])*cos(in_vec[2]) + sin(in_vec[1])*sin(in_vec[2])*cos(in_vec[0]); - out_2107061543090158966[17] = cos(in_vec[0])*cos(in_vec[1]); +void H(double *in_vec, double *out_5027207160750161004) { + out_5027207160750161004[0] = 0; + out_5027207160750161004[1] = -sin(in_vec[1])*sin(in_vec[2])*in_vec[4] - sin(in_vec[1])*cos(in_vec[2])*in_vec[3] - cos(in_vec[1])*in_vec[5]; + out_5027207160750161004[2] = -sin(in_vec[2])*cos(in_vec[1])*in_vec[3] + cos(in_vec[1])*cos(in_vec[2])*in_vec[4]; + out_5027207160750161004[3] = cos(in_vec[1])*cos(in_vec[2]); + out_5027207160750161004[4] = sin(in_vec[2])*cos(in_vec[1]); + out_5027207160750161004[5] = -sin(in_vec[1]); + out_5027207160750161004[6] = (sin(in_vec[0])*sin(in_vec[2]) + sin(in_vec[1])*cos(in_vec[0])*cos(in_vec[2]))*in_vec[3] + (-sin(in_vec[0])*cos(in_vec[2]) + sin(in_vec[1])*sin(in_vec[2])*cos(in_vec[0]))*in_vec[4] + cos(in_vec[0])*cos(in_vec[1])*in_vec[5]; + out_5027207160750161004[7] = -sin(in_vec[0])*sin(in_vec[1])*in_vec[5] + sin(in_vec[0])*sin(in_vec[2])*cos(in_vec[1])*in_vec[4] + sin(in_vec[0])*cos(in_vec[1])*cos(in_vec[2])*in_vec[3]; + out_5027207160750161004[8] = (-sin(in_vec[0])*sin(in_vec[1])*sin(in_vec[2]) - cos(in_vec[0])*cos(in_vec[2]))*in_vec[3] + (sin(in_vec[0])*sin(in_vec[1])*cos(in_vec[2]) - sin(in_vec[2])*cos(in_vec[0]))*in_vec[4]; + out_5027207160750161004[9] = sin(in_vec[0])*sin(in_vec[1])*cos(in_vec[2]) - sin(in_vec[2])*cos(in_vec[0]); + out_5027207160750161004[10] = sin(in_vec[0])*sin(in_vec[1])*sin(in_vec[2]) + cos(in_vec[0])*cos(in_vec[2]); + out_5027207160750161004[11] = sin(in_vec[0])*cos(in_vec[1]); + out_5027207160750161004[12] = (-sin(in_vec[0])*sin(in_vec[1])*sin(in_vec[2]) - cos(in_vec[0])*cos(in_vec[2]))*in_vec[4] + (-sin(in_vec[0])*sin(in_vec[1])*cos(in_vec[2]) + sin(in_vec[2])*cos(in_vec[0]))*in_vec[3] - sin(in_vec[0])*cos(in_vec[1])*in_vec[5]; + out_5027207160750161004[13] = -sin(in_vec[1])*cos(in_vec[0])*in_vec[5] + sin(in_vec[2])*cos(in_vec[0])*cos(in_vec[1])*in_vec[4] + cos(in_vec[0])*cos(in_vec[1])*cos(in_vec[2])*in_vec[3]; + out_5027207160750161004[14] = (sin(in_vec[0])*sin(in_vec[2]) + sin(in_vec[1])*cos(in_vec[0])*cos(in_vec[2]))*in_vec[4] + (sin(in_vec[0])*cos(in_vec[2]) - sin(in_vec[1])*sin(in_vec[2])*cos(in_vec[0]))*in_vec[3]; + out_5027207160750161004[15] = sin(in_vec[0])*sin(in_vec[2]) + sin(in_vec[1])*cos(in_vec[0])*cos(in_vec[2]); + out_5027207160750161004[16] = -sin(in_vec[0])*cos(in_vec[2]) + sin(in_vec[1])*sin(in_vec[2])*cos(in_vec[0]); + out_5027207160750161004[17] = cos(in_vec[0])*cos(in_vec[1]); } -void err_fun(double *nom_x, double *delta_x, double *out_1090842864546838841) { - out_1090842864546838841[0] = delta_x[0] + nom_x[0]; - out_1090842864546838841[1] = delta_x[1] + nom_x[1]; - out_1090842864546838841[2] = delta_x[2] + nom_x[2]; - out_1090842864546838841[3] = -0.5*delta_x[3]*nom_x[4] - 0.5*delta_x[4]*nom_x[5] - 0.5*delta_x[5]*nom_x[6] + 1.0*nom_x[3]; - out_1090842864546838841[4] = 0.5*delta_x[3]*nom_x[3] + 0.5*delta_x[4]*nom_x[6] - 0.5*delta_x[5]*nom_x[5] + 1.0*nom_x[4]; - out_1090842864546838841[5] = -0.5*delta_x[3]*nom_x[6] + 0.5*delta_x[4]*nom_x[3] + 0.5*delta_x[5]*nom_x[4] + 1.0*nom_x[5]; - out_1090842864546838841[6] = 0.5*delta_x[3]*nom_x[5] - 0.5*delta_x[4]*nom_x[4] + 0.5*delta_x[5]*nom_x[3] + 1.0*nom_x[6]; - out_1090842864546838841[7] = delta_x[6] + nom_x[7]; - out_1090842864546838841[8] = delta_x[7] + nom_x[8]; - out_1090842864546838841[9] = delta_x[8] + nom_x[9]; - out_1090842864546838841[10] = delta_x[9] + nom_x[10]; - out_1090842864546838841[11] = delta_x[10] + nom_x[11]; - out_1090842864546838841[12] = delta_x[11] + nom_x[12]; - out_1090842864546838841[13] = delta_x[12] + nom_x[13]; - out_1090842864546838841[14] = delta_x[13] + nom_x[14]; - out_1090842864546838841[15] = delta_x[14] + nom_x[15]; - out_1090842864546838841[16] = delta_x[15] + nom_x[16]; - out_1090842864546838841[17] = delta_x[16] + nom_x[17]; - out_1090842864546838841[18] = delta_x[17] + nom_x[18]; - out_1090842864546838841[19] = delta_x[18] + nom_x[19]; - out_1090842864546838841[20] = delta_x[19] + nom_x[20]; - out_1090842864546838841[21] = delta_x[20] + nom_x[21]; +void err_fun(double *nom_x, double *delta_x, double *out_812293829444590878) { + out_812293829444590878[0] = delta_x[0] + nom_x[0]; + out_812293829444590878[1] = delta_x[1] + nom_x[1]; + out_812293829444590878[2] = delta_x[2] + nom_x[2]; + out_812293829444590878[3] = -0.5*delta_x[3]*nom_x[4] - 0.5*delta_x[4]*nom_x[5] - 0.5*delta_x[5]*nom_x[6] + 1.0*nom_x[3]; + out_812293829444590878[4] = 0.5*delta_x[3]*nom_x[3] + 0.5*delta_x[4]*nom_x[6] - 0.5*delta_x[5]*nom_x[5] + 1.0*nom_x[4]; + out_812293829444590878[5] = -0.5*delta_x[3]*nom_x[6] + 0.5*delta_x[4]*nom_x[3] + 0.5*delta_x[5]*nom_x[4] + 1.0*nom_x[5]; + out_812293829444590878[6] = 0.5*delta_x[3]*nom_x[5] - 0.5*delta_x[4]*nom_x[4] + 0.5*delta_x[5]*nom_x[3] + 1.0*nom_x[6]; + out_812293829444590878[7] = delta_x[6] + nom_x[7]; + out_812293829444590878[8] = delta_x[7] + nom_x[8]; + out_812293829444590878[9] = delta_x[8] + nom_x[9]; + out_812293829444590878[10] = delta_x[9] + nom_x[10]; + out_812293829444590878[11] = delta_x[10] + nom_x[11]; + out_812293829444590878[12] = delta_x[11] + nom_x[12]; + out_812293829444590878[13] = delta_x[12] + nom_x[13]; + out_812293829444590878[14] = delta_x[13] + nom_x[14]; + out_812293829444590878[15] = delta_x[14] + nom_x[15]; + out_812293829444590878[16] = delta_x[15] + nom_x[16]; + out_812293829444590878[17] = delta_x[16] + nom_x[17]; + out_812293829444590878[18] = delta_x[17] + nom_x[18]; + out_812293829444590878[19] = delta_x[18] + nom_x[19]; + out_812293829444590878[20] = delta_x[19] + nom_x[20]; + out_812293829444590878[21] = delta_x[20] + nom_x[21]; } -void inv_err_fun(double *nom_x, double *true_x, double *out_1751534880763809428) { - out_1751534880763809428[0] = -nom_x[0] + true_x[0]; - out_1751534880763809428[1] = -nom_x[1] + true_x[1]; - out_1751534880763809428[2] = -nom_x[2] + true_x[2]; - out_1751534880763809428[3] = 2*nom_x[3]*true_x[4] - 2*nom_x[4]*true_x[3] + 2*nom_x[5]*true_x[6] - 2*nom_x[6]*true_x[5]; - out_1751534880763809428[4] = 2*nom_x[3]*true_x[5] - 2*nom_x[4]*true_x[6] - 2*nom_x[5]*true_x[3] + 2*nom_x[6]*true_x[4]; - out_1751534880763809428[5] = 2*nom_x[3]*true_x[6] + 2*nom_x[4]*true_x[5] - 2*nom_x[5]*true_x[4] - 2*nom_x[6]*true_x[3]; - out_1751534880763809428[6] = -nom_x[7] + true_x[7]; - out_1751534880763809428[7] = -nom_x[8] + true_x[8]; - out_1751534880763809428[8] = -nom_x[9] + true_x[9]; - out_1751534880763809428[9] = -nom_x[10] + true_x[10]; - out_1751534880763809428[10] = -nom_x[11] + true_x[11]; - out_1751534880763809428[11] = -nom_x[12] + true_x[12]; - out_1751534880763809428[12] = -nom_x[13] + true_x[13]; - out_1751534880763809428[13] = -nom_x[14] + true_x[14]; - out_1751534880763809428[14] = -nom_x[15] + true_x[15]; - out_1751534880763809428[15] = -nom_x[16] + true_x[16]; - out_1751534880763809428[16] = -nom_x[17] + true_x[17]; - out_1751534880763809428[17] = -nom_x[18] + true_x[18]; - out_1751534880763809428[18] = -nom_x[19] + true_x[19]; - out_1751534880763809428[19] = -nom_x[20] + true_x[20]; - out_1751534880763809428[20] = -nom_x[21] + true_x[21]; +void inv_err_fun(double *nom_x, double *true_x, double *out_2331899367078236024) { + out_2331899367078236024[0] = -nom_x[0] + true_x[0]; + out_2331899367078236024[1] = -nom_x[1] + true_x[1]; + out_2331899367078236024[2] = -nom_x[2] + true_x[2]; + out_2331899367078236024[3] = 2*nom_x[3]*true_x[4] - 2*nom_x[4]*true_x[3] + 2*nom_x[5]*true_x[6] - 2*nom_x[6]*true_x[5]; + out_2331899367078236024[4] = 2*nom_x[3]*true_x[5] - 2*nom_x[4]*true_x[6] - 2*nom_x[5]*true_x[3] + 2*nom_x[6]*true_x[4]; + out_2331899367078236024[5] = 2*nom_x[3]*true_x[6] + 2*nom_x[4]*true_x[5] - 2*nom_x[5]*true_x[4] - 2*nom_x[6]*true_x[3]; + out_2331899367078236024[6] = -nom_x[7] + true_x[7]; + out_2331899367078236024[7] = -nom_x[8] + true_x[8]; + out_2331899367078236024[8] = -nom_x[9] + true_x[9]; + out_2331899367078236024[9] = -nom_x[10] + true_x[10]; + out_2331899367078236024[10] = -nom_x[11] + true_x[11]; + out_2331899367078236024[11] = -nom_x[12] + true_x[12]; + out_2331899367078236024[12] = -nom_x[13] + true_x[13]; + out_2331899367078236024[13] = -nom_x[14] + true_x[14]; + out_2331899367078236024[14] = -nom_x[15] + true_x[15]; + out_2331899367078236024[15] = -nom_x[16] + true_x[16]; + out_2331899367078236024[16] = -nom_x[17] + true_x[17]; + out_2331899367078236024[17] = -nom_x[18] + true_x[18]; + out_2331899367078236024[18] = -nom_x[19] + true_x[19]; + out_2331899367078236024[19] = -nom_x[20] + true_x[20]; + out_2331899367078236024[20] = -nom_x[21] + true_x[21]; } -void H_mod_fun(double *state, double *out_2270168032272230264) { - out_2270168032272230264[0] = 1.0; - out_2270168032272230264[1] = 0; - out_2270168032272230264[2] = 0; - out_2270168032272230264[3] = 0; - out_2270168032272230264[4] = 0; - out_2270168032272230264[5] = 0; - out_2270168032272230264[6] = 0; - out_2270168032272230264[7] = 0; - out_2270168032272230264[8] = 0; - out_2270168032272230264[9] = 0; - out_2270168032272230264[10] = 0; - out_2270168032272230264[11] = 0; - out_2270168032272230264[12] = 0; - out_2270168032272230264[13] = 0; - out_2270168032272230264[14] = 0; - out_2270168032272230264[15] = 0; - out_2270168032272230264[16] = 0; - out_2270168032272230264[17] = 0; - out_2270168032272230264[18] = 0; - out_2270168032272230264[19] = 0; - out_2270168032272230264[20] = 0; - out_2270168032272230264[21] = 0; - out_2270168032272230264[22] = 1.0; - out_2270168032272230264[23] = 0; - out_2270168032272230264[24] = 0; - out_2270168032272230264[25] = 0; - out_2270168032272230264[26] = 0; - out_2270168032272230264[27] = 0; - out_2270168032272230264[28] = 0; - out_2270168032272230264[29] = 0; - out_2270168032272230264[30] = 0; - out_2270168032272230264[31] = 0; - out_2270168032272230264[32] = 0; - out_2270168032272230264[33] = 0; - out_2270168032272230264[34] = 0; - out_2270168032272230264[35] = 0; - out_2270168032272230264[36] = 0; - out_2270168032272230264[37] = 0; - out_2270168032272230264[38] = 0; - out_2270168032272230264[39] = 0; - out_2270168032272230264[40] = 0; - out_2270168032272230264[41] = 0; - out_2270168032272230264[42] = 0; - out_2270168032272230264[43] = 0; - out_2270168032272230264[44] = 1.0; - out_2270168032272230264[45] = 0; - out_2270168032272230264[46] = 0; - out_2270168032272230264[47] = 0; - out_2270168032272230264[48] = 0; - out_2270168032272230264[49] = 0; - out_2270168032272230264[50] = 0; - out_2270168032272230264[51] = 0; - out_2270168032272230264[52] = 0; - out_2270168032272230264[53] = 0; - out_2270168032272230264[54] = 0; - out_2270168032272230264[55] = 0; - out_2270168032272230264[56] = 0; - out_2270168032272230264[57] = 0; - out_2270168032272230264[58] = 0; - out_2270168032272230264[59] = 0; - out_2270168032272230264[60] = 0; - out_2270168032272230264[61] = 0; - out_2270168032272230264[62] = 0; - out_2270168032272230264[63] = 0; - out_2270168032272230264[64] = 0; - out_2270168032272230264[65] = 0; - out_2270168032272230264[66] = -0.5*state[4]; - out_2270168032272230264[67] = -0.5*state[5]; - out_2270168032272230264[68] = -0.5*state[6]; - out_2270168032272230264[69] = 0; - out_2270168032272230264[70] = 0; - out_2270168032272230264[71] = 0; - out_2270168032272230264[72] = 0; - out_2270168032272230264[73] = 0; - out_2270168032272230264[74] = 0; - out_2270168032272230264[75] = 0; - out_2270168032272230264[76] = 0; - out_2270168032272230264[77] = 0; - out_2270168032272230264[78] = 0; - out_2270168032272230264[79] = 0; - out_2270168032272230264[80] = 0; - out_2270168032272230264[81] = 0; - out_2270168032272230264[82] = 0; - out_2270168032272230264[83] = 0; - out_2270168032272230264[84] = 0; - out_2270168032272230264[85] = 0; - out_2270168032272230264[86] = 0; - out_2270168032272230264[87] = 0.5*state[3]; - out_2270168032272230264[88] = 0.5*state[6]; - out_2270168032272230264[89] = -0.5*state[5]; - out_2270168032272230264[90] = 0; - out_2270168032272230264[91] = 0; - out_2270168032272230264[92] = 0; - out_2270168032272230264[93] = 0; - out_2270168032272230264[94] = 0; - out_2270168032272230264[95] = 0; - out_2270168032272230264[96] = 0; - out_2270168032272230264[97] = 0; - out_2270168032272230264[98] = 0; - out_2270168032272230264[99] = 0; - out_2270168032272230264[100] = 0; - out_2270168032272230264[101] = 0; - out_2270168032272230264[102] = 0; - out_2270168032272230264[103] = 0; - out_2270168032272230264[104] = 0; - out_2270168032272230264[105] = 0; - out_2270168032272230264[106] = 0; - out_2270168032272230264[107] = 0; - out_2270168032272230264[108] = -0.5*state[6]; - out_2270168032272230264[109] = 0.5*state[3]; - out_2270168032272230264[110] = 0.5*state[4]; - out_2270168032272230264[111] = 0; - out_2270168032272230264[112] = 0; - out_2270168032272230264[113] = 0; - out_2270168032272230264[114] = 0; - out_2270168032272230264[115] = 0; - out_2270168032272230264[116] = 0; - out_2270168032272230264[117] = 0; - out_2270168032272230264[118] = 0; - out_2270168032272230264[119] = 0; - out_2270168032272230264[120] = 0; - out_2270168032272230264[121] = 0; - out_2270168032272230264[122] = 0; - out_2270168032272230264[123] = 0; - out_2270168032272230264[124] = 0; - out_2270168032272230264[125] = 0; - out_2270168032272230264[126] = 0; - out_2270168032272230264[127] = 0; - out_2270168032272230264[128] = 0; - out_2270168032272230264[129] = 0.5*state[5]; - out_2270168032272230264[130] = -0.5*state[4]; - out_2270168032272230264[131] = 0.5*state[3]; - out_2270168032272230264[132] = 0; - out_2270168032272230264[133] = 0; - out_2270168032272230264[134] = 0; - out_2270168032272230264[135] = 0; - out_2270168032272230264[136] = 0; - out_2270168032272230264[137] = 0; - out_2270168032272230264[138] = 0; - out_2270168032272230264[139] = 0; - out_2270168032272230264[140] = 0; - out_2270168032272230264[141] = 0; - out_2270168032272230264[142] = 0; - out_2270168032272230264[143] = 0; - out_2270168032272230264[144] = 0; - out_2270168032272230264[145] = 0; - out_2270168032272230264[146] = 0; - out_2270168032272230264[147] = 0; - out_2270168032272230264[148] = 0; - out_2270168032272230264[149] = 0; - out_2270168032272230264[150] = 0; - out_2270168032272230264[151] = 0; - out_2270168032272230264[152] = 0; - out_2270168032272230264[153] = 1.0; - out_2270168032272230264[154] = 0; - out_2270168032272230264[155] = 0; - out_2270168032272230264[156] = 0; - out_2270168032272230264[157] = 0; - out_2270168032272230264[158] = 0; - out_2270168032272230264[159] = 0; - out_2270168032272230264[160] = 0; - out_2270168032272230264[161] = 0; - out_2270168032272230264[162] = 0; - out_2270168032272230264[163] = 0; - out_2270168032272230264[164] = 0; - out_2270168032272230264[165] = 0; - out_2270168032272230264[166] = 0; - out_2270168032272230264[167] = 0; - out_2270168032272230264[168] = 0; - out_2270168032272230264[169] = 0; - out_2270168032272230264[170] = 0; - out_2270168032272230264[171] = 0; - out_2270168032272230264[172] = 0; - out_2270168032272230264[173] = 0; - out_2270168032272230264[174] = 0; - out_2270168032272230264[175] = 1.0; - out_2270168032272230264[176] = 0; - out_2270168032272230264[177] = 0; - out_2270168032272230264[178] = 0; - out_2270168032272230264[179] = 0; - out_2270168032272230264[180] = 0; - out_2270168032272230264[181] = 0; - out_2270168032272230264[182] = 0; - out_2270168032272230264[183] = 0; - out_2270168032272230264[184] = 0; - out_2270168032272230264[185] = 0; - out_2270168032272230264[186] = 0; - out_2270168032272230264[187] = 0; - out_2270168032272230264[188] = 0; - out_2270168032272230264[189] = 0; - out_2270168032272230264[190] = 0; - out_2270168032272230264[191] = 0; - out_2270168032272230264[192] = 0; - out_2270168032272230264[193] = 0; - out_2270168032272230264[194] = 0; - out_2270168032272230264[195] = 0; - out_2270168032272230264[196] = 0; - out_2270168032272230264[197] = 1.0; - out_2270168032272230264[198] = 0; - out_2270168032272230264[199] = 0; - out_2270168032272230264[200] = 0; - out_2270168032272230264[201] = 0; - out_2270168032272230264[202] = 0; - out_2270168032272230264[203] = 0; - out_2270168032272230264[204] = 0; - out_2270168032272230264[205] = 0; - out_2270168032272230264[206] = 0; - out_2270168032272230264[207] = 0; - out_2270168032272230264[208] = 0; - out_2270168032272230264[209] = 0; - out_2270168032272230264[210] = 0; - out_2270168032272230264[211] = 0; - out_2270168032272230264[212] = 0; - out_2270168032272230264[213] = 0; - out_2270168032272230264[214] = 0; - out_2270168032272230264[215] = 0; - out_2270168032272230264[216] = 0; - out_2270168032272230264[217] = 0; - out_2270168032272230264[218] = 0; - out_2270168032272230264[219] = 1.0; - out_2270168032272230264[220] = 0; - out_2270168032272230264[221] = 0; - out_2270168032272230264[222] = 0; - out_2270168032272230264[223] = 0; - out_2270168032272230264[224] = 0; - out_2270168032272230264[225] = 0; - out_2270168032272230264[226] = 0; - out_2270168032272230264[227] = 0; - out_2270168032272230264[228] = 0; - out_2270168032272230264[229] = 0; - out_2270168032272230264[230] = 0; - out_2270168032272230264[231] = 0; - out_2270168032272230264[232] = 0; - out_2270168032272230264[233] = 0; - out_2270168032272230264[234] = 0; - out_2270168032272230264[235] = 0; - out_2270168032272230264[236] = 0; - out_2270168032272230264[237] = 0; - out_2270168032272230264[238] = 0; - out_2270168032272230264[239] = 0; - out_2270168032272230264[240] = 0; - out_2270168032272230264[241] = 1.0; - out_2270168032272230264[242] = 0; - out_2270168032272230264[243] = 0; - out_2270168032272230264[244] = 0; - out_2270168032272230264[245] = 0; - out_2270168032272230264[246] = 0; - out_2270168032272230264[247] = 0; - out_2270168032272230264[248] = 0; - out_2270168032272230264[249] = 0; - out_2270168032272230264[250] = 0; - out_2270168032272230264[251] = 0; - out_2270168032272230264[252] = 0; - out_2270168032272230264[253] = 0; - out_2270168032272230264[254] = 0; - out_2270168032272230264[255] = 0; - out_2270168032272230264[256] = 0; - out_2270168032272230264[257] = 0; - out_2270168032272230264[258] = 0; - out_2270168032272230264[259] = 0; - out_2270168032272230264[260] = 0; - out_2270168032272230264[261] = 0; - out_2270168032272230264[262] = 0; - out_2270168032272230264[263] = 1.0; - out_2270168032272230264[264] = 0; - out_2270168032272230264[265] = 0; - out_2270168032272230264[266] = 0; - out_2270168032272230264[267] = 0; - out_2270168032272230264[268] = 0; - out_2270168032272230264[269] = 0; - out_2270168032272230264[270] = 0; - out_2270168032272230264[271] = 0; - out_2270168032272230264[272] = 0; - out_2270168032272230264[273] = 0; - out_2270168032272230264[274] = 0; - out_2270168032272230264[275] = 0; - out_2270168032272230264[276] = 0; - out_2270168032272230264[277] = 0; - out_2270168032272230264[278] = 0; - out_2270168032272230264[279] = 0; - out_2270168032272230264[280] = 0; - out_2270168032272230264[281] = 0; - out_2270168032272230264[282] = 0; - out_2270168032272230264[283] = 0; - out_2270168032272230264[284] = 0; - out_2270168032272230264[285] = 1.0; - out_2270168032272230264[286] = 0; - out_2270168032272230264[287] = 0; - out_2270168032272230264[288] = 0; - out_2270168032272230264[289] = 0; - out_2270168032272230264[290] = 0; - out_2270168032272230264[291] = 0; - out_2270168032272230264[292] = 0; - out_2270168032272230264[293] = 0; - out_2270168032272230264[294] = 0; - out_2270168032272230264[295] = 0; - out_2270168032272230264[296] = 0; - out_2270168032272230264[297] = 0; - out_2270168032272230264[298] = 0; - out_2270168032272230264[299] = 0; - out_2270168032272230264[300] = 0; - out_2270168032272230264[301] = 0; - out_2270168032272230264[302] = 0; - out_2270168032272230264[303] = 0; - out_2270168032272230264[304] = 0; - out_2270168032272230264[305] = 0; - out_2270168032272230264[306] = 0; - out_2270168032272230264[307] = 1.0; - out_2270168032272230264[308] = 0; - out_2270168032272230264[309] = 0; - out_2270168032272230264[310] = 0; - out_2270168032272230264[311] = 0; - out_2270168032272230264[312] = 0; - out_2270168032272230264[313] = 0; - out_2270168032272230264[314] = 0; - out_2270168032272230264[315] = 0; - out_2270168032272230264[316] = 0; - out_2270168032272230264[317] = 0; - out_2270168032272230264[318] = 0; - out_2270168032272230264[319] = 0; - out_2270168032272230264[320] = 0; - out_2270168032272230264[321] = 0; - out_2270168032272230264[322] = 0; - out_2270168032272230264[323] = 0; - out_2270168032272230264[324] = 0; - out_2270168032272230264[325] = 0; - out_2270168032272230264[326] = 0; - out_2270168032272230264[327] = 0; - out_2270168032272230264[328] = 0; - out_2270168032272230264[329] = 1.0; - out_2270168032272230264[330] = 0; - out_2270168032272230264[331] = 0; - out_2270168032272230264[332] = 0; - out_2270168032272230264[333] = 0; - out_2270168032272230264[334] = 0; - out_2270168032272230264[335] = 0; - out_2270168032272230264[336] = 0; - out_2270168032272230264[337] = 0; - out_2270168032272230264[338] = 0; - out_2270168032272230264[339] = 0; - out_2270168032272230264[340] = 0; - out_2270168032272230264[341] = 0; - out_2270168032272230264[342] = 0; - out_2270168032272230264[343] = 0; - out_2270168032272230264[344] = 0; - out_2270168032272230264[345] = 0; - out_2270168032272230264[346] = 0; - out_2270168032272230264[347] = 0; - out_2270168032272230264[348] = 0; - out_2270168032272230264[349] = 0; - out_2270168032272230264[350] = 0; - out_2270168032272230264[351] = 1.0; - out_2270168032272230264[352] = 0; - out_2270168032272230264[353] = 0; - out_2270168032272230264[354] = 0; - out_2270168032272230264[355] = 0; - out_2270168032272230264[356] = 0; - out_2270168032272230264[357] = 0; - out_2270168032272230264[358] = 0; - out_2270168032272230264[359] = 0; - out_2270168032272230264[360] = 0; - out_2270168032272230264[361] = 0; - out_2270168032272230264[362] = 0; - out_2270168032272230264[363] = 0; - out_2270168032272230264[364] = 0; - out_2270168032272230264[365] = 0; - out_2270168032272230264[366] = 0; - out_2270168032272230264[367] = 0; - out_2270168032272230264[368] = 0; - out_2270168032272230264[369] = 0; - out_2270168032272230264[370] = 0; - out_2270168032272230264[371] = 0; - out_2270168032272230264[372] = 0; - out_2270168032272230264[373] = 1.0; - out_2270168032272230264[374] = 0; - out_2270168032272230264[375] = 0; - out_2270168032272230264[376] = 0; - out_2270168032272230264[377] = 0; - out_2270168032272230264[378] = 0; - out_2270168032272230264[379] = 0; - out_2270168032272230264[380] = 0; - out_2270168032272230264[381] = 0; - out_2270168032272230264[382] = 0; - out_2270168032272230264[383] = 0; - out_2270168032272230264[384] = 0; - out_2270168032272230264[385] = 0; - out_2270168032272230264[386] = 0; - out_2270168032272230264[387] = 0; - out_2270168032272230264[388] = 0; - out_2270168032272230264[389] = 0; - out_2270168032272230264[390] = 0; - out_2270168032272230264[391] = 0; - out_2270168032272230264[392] = 0; - out_2270168032272230264[393] = 0; - out_2270168032272230264[394] = 0; - out_2270168032272230264[395] = 1.0; - out_2270168032272230264[396] = 0; - out_2270168032272230264[397] = 0; - out_2270168032272230264[398] = 0; - out_2270168032272230264[399] = 0; - out_2270168032272230264[400] = 0; - out_2270168032272230264[401] = 0; - out_2270168032272230264[402] = 0; - out_2270168032272230264[403] = 0; - out_2270168032272230264[404] = 0; - out_2270168032272230264[405] = 0; - out_2270168032272230264[406] = 0; - out_2270168032272230264[407] = 0; - out_2270168032272230264[408] = 0; - out_2270168032272230264[409] = 0; - out_2270168032272230264[410] = 0; - out_2270168032272230264[411] = 0; - out_2270168032272230264[412] = 0; - out_2270168032272230264[413] = 0; - out_2270168032272230264[414] = 0; - out_2270168032272230264[415] = 0; - out_2270168032272230264[416] = 0; - out_2270168032272230264[417] = 1.0; - out_2270168032272230264[418] = 0; - out_2270168032272230264[419] = 0; - out_2270168032272230264[420] = 0; - out_2270168032272230264[421] = 0; - out_2270168032272230264[422] = 0; - out_2270168032272230264[423] = 0; - out_2270168032272230264[424] = 0; - out_2270168032272230264[425] = 0; - out_2270168032272230264[426] = 0; - out_2270168032272230264[427] = 0; - out_2270168032272230264[428] = 0; - out_2270168032272230264[429] = 0; - out_2270168032272230264[430] = 0; - out_2270168032272230264[431] = 0; - out_2270168032272230264[432] = 0; - out_2270168032272230264[433] = 0; - out_2270168032272230264[434] = 0; - out_2270168032272230264[435] = 0; - out_2270168032272230264[436] = 0; - out_2270168032272230264[437] = 0; - out_2270168032272230264[438] = 0; - out_2270168032272230264[439] = 1.0; - out_2270168032272230264[440] = 0; - out_2270168032272230264[441] = 0; - out_2270168032272230264[442] = 0; - out_2270168032272230264[443] = 0; - out_2270168032272230264[444] = 0; - out_2270168032272230264[445] = 0; - out_2270168032272230264[446] = 0; - out_2270168032272230264[447] = 0; - out_2270168032272230264[448] = 0; - out_2270168032272230264[449] = 0; - out_2270168032272230264[450] = 0; - out_2270168032272230264[451] = 0; - out_2270168032272230264[452] = 0; - out_2270168032272230264[453] = 0; - out_2270168032272230264[454] = 0; - out_2270168032272230264[455] = 0; - out_2270168032272230264[456] = 0; - out_2270168032272230264[457] = 0; - out_2270168032272230264[458] = 0; - out_2270168032272230264[459] = 0; - out_2270168032272230264[460] = 0; - out_2270168032272230264[461] = 1.0; +void H_mod_fun(double *state, double *out_3350621260021879835) { + out_3350621260021879835[0] = 1.0; + out_3350621260021879835[1] = 0; + out_3350621260021879835[2] = 0; + out_3350621260021879835[3] = 0; + out_3350621260021879835[4] = 0; + out_3350621260021879835[5] = 0; + out_3350621260021879835[6] = 0; + out_3350621260021879835[7] = 0; + out_3350621260021879835[8] = 0; + out_3350621260021879835[9] = 0; + out_3350621260021879835[10] = 0; + out_3350621260021879835[11] = 0; + out_3350621260021879835[12] = 0; + out_3350621260021879835[13] = 0; + out_3350621260021879835[14] = 0; + out_3350621260021879835[15] = 0; + out_3350621260021879835[16] = 0; + out_3350621260021879835[17] = 0; + out_3350621260021879835[18] = 0; + out_3350621260021879835[19] = 0; + out_3350621260021879835[20] = 0; + out_3350621260021879835[21] = 0; + out_3350621260021879835[22] = 1.0; + out_3350621260021879835[23] = 0; + out_3350621260021879835[24] = 0; + out_3350621260021879835[25] = 0; + out_3350621260021879835[26] = 0; + out_3350621260021879835[27] = 0; + out_3350621260021879835[28] = 0; + out_3350621260021879835[29] = 0; + out_3350621260021879835[30] = 0; + out_3350621260021879835[31] = 0; + out_3350621260021879835[32] = 0; + out_3350621260021879835[33] = 0; + out_3350621260021879835[34] = 0; + out_3350621260021879835[35] = 0; + out_3350621260021879835[36] = 0; + out_3350621260021879835[37] = 0; + out_3350621260021879835[38] = 0; + out_3350621260021879835[39] = 0; + out_3350621260021879835[40] = 0; + out_3350621260021879835[41] = 0; + out_3350621260021879835[42] = 0; + out_3350621260021879835[43] = 0; + out_3350621260021879835[44] = 1.0; + out_3350621260021879835[45] = 0; + out_3350621260021879835[46] = 0; + out_3350621260021879835[47] = 0; + out_3350621260021879835[48] = 0; + out_3350621260021879835[49] = 0; + out_3350621260021879835[50] = 0; + out_3350621260021879835[51] = 0; + out_3350621260021879835[52] = 0; + out_3350621260021879835[53] = 0; + out_3350621260021879835[54] = 0; + out_3350621260021879835[55] = 0; + out_3350621260021879835[56] = 0; + out_3350621260021879835[57] = 0; + out_3350621260021879835[58] = 0; + out_3350621260021879835[59] = 0; + out_3350621260021879835[60] = 0; + out_3350621260021879835[61] = 0; + out_3350621260021879835[62] = 0; + out_3350621260021879835[63] = 0; + out_3350621260021879835[64] = 0; + out_3350621260021879835[65] = 0; + out_3350621260021879835[66] = -0.5*state[4]; + out_3350621260021879835[67] = -0.5*state[5]; + out_3350621260021879835[68] = -0.5*state[6]; + out_3350621260021879835[69] = 0; + out_3350621260021879835[70] = 0; + out_3350621260021879835[71] = 0; + out_3350621260021879835[72] = 0; + out_3350621260021879835[73] = 0; + out_3350621260021879835[74] = 0; + out_3350621260021879835[75] = 0; + out_3350621260021879835[76] = 0; + out_3350621260021879835[77] = 0; + out_3350621260021879835[78] = 0; + out_3350621260021879835[79] = 0; + out_3350621260021879835[80] = 0; + out_3350621260021879835[81] = 0; + out_3350621260021879835[82] = 0; + out_3350621260021879835[83] = 0; + out_3350621260021879835[84] = 0; + out_3350621260021879835[85] = 0; + out_3350621260021879835[86] = 0; + out_3350621260021879835[87] = 0.5*state[3]; + out_3350621260021879835[88] = 0.5*state[6]; + out_3350621260021879835[89] = -0.5*state[5]; + out_3350621260021879835[90] = 0; + out_3350621260021879835[91] = 0; + out_3350621260021879835[92] = 0; + out_3350621260021879835[93] = 0; + out_3350621260021879835[94] = 0; + out_3350621260021879835[95] = 0; + out_3350621260021879835[96] = 0; + out_3350621260021879835[97] = 0; + out_3350621260021879835[98] = 0; + out_3350621260021879835[99] = 0; + out_3350621260021879835[100] = 0; + out_3350621260021879835[101] = 0; + out_3350621260021879835[102] = 0; + out_3350621260021879835[103] = 0; + out_3350621260021879835[104] = 0; + out_3350621260021879835[105] = 0; + out_3350621260021879835[106] = 0; + out_3350621260021879835[107] = 0; + out_3350621260021879835[108] = -0.5*state[6]; + out_3350621260021879835[109] = 0.5*state[3]; + out_3350621260021879835[110] = 0.5*state[4]; + out_3350621260021879835[111] = 0; + out_3350621260021879835[112] = 0; + out_3350621260021879835[113] = 0; + out_3350621260021879835[114] = 0; + out_3350621260021879835[115] = 0; + out_3350621260021879835[116] = 0; + out_3350621260021879835[117] = 0; + out_3350621260021879835[118] = 0; + out_3350621260021879835[119] = 0; + out_3350621260021879835[120] = 0; + out_3350621260021879835[121] = 0; + out_3350621260021879835[122] = 0; + out_3350621260021879835[123] = 0; + out_3350621260021879835[124] = 0; + out_3350621260021879835[125] = 0; + out_3350621260021879835[126] = 0; + out_3350621260021879835[127] = 0; + out_3350621260021879835[128] = 0; + out_3350621260021879835[129] = 0.5*state[5]; + out_3350621260021879835[130] = -0.5*state[4]; + out_3350621260021879835[131] = 0.5*state[3]; + out_3350621260021879835[132] = 0; + out_3350621260021879835[133] = 0; + out_3350621260021879835[134] = 0; + out_3350621260021879835[135] = 0; + out_3350621260021879835[136] = 0; + out_3350621260021879835[137] = 0; + out_3350621260021879835[138] = 0; + out_3350621260021879835[139] = 0; + out_3350621260021879835[140] = 0; + out_3350621260021879835[141] = 0; + out_3350621260021879835[142] = 0; + out_3350621260021879835[143] = 0; + out_3350621260021879835[144] = 0; + out_3350621260021879835[145] = 0; + out_3350621260021879835[146] = 0; + out_3350621260021879835[147] = 0; + out_3350621260021879835[148] = 0; + out_3350621260021879835[149] = 0; + out_3350621260021879835[150] = 0; + out_3350621260021879835[151] = 0; + out_3350621260021879835[152] = 0; + out_3350621260021879835[153] = 1.0; + out_3350621260021879835[154] = 0; + out_3350621260021879835[155] = 0; + out_3350621260021879835[156] = 0; + out_3350621260021879835[157] = 0; + out_3350621260021879835[158] = 0; + out_3350621260021879835[159] = 0; + out_3350621260021879835[160] = 0; + out_3350621260021879835[161] = 0; + out_3350621260021879835[162] = 0; + out_3350621260021879835[163] = 0; + out_3350621260021879835[164] = 0; + out_3350621260021879835[165] = 0; + out_3350621260021879835[166] = 0; + out_3350621260021879835[167] = 0; + out_3350621260021879835[168] = 0; + out_3350621260021879835[169] = 0; + out_3350621260021879835[170] = 0; + out_3350621260021879835[171] = 0; + out_3350621260021879835[172] = 0; + out_3350621260021879835[173] = 0; + out_3350621260021879835[174] = 0; + out_3350621260021879835[175] = 1.0; + out_3350621260021879835[176] = 0; + out_3350621260021879835[177] = 0; + out_3350621260021879835[178] = 0; + out_3350621260021879835[179] = 0; + out_3350621260021879835[180] = 0; + out_3350621260021879835[181] = 0; + out_3350621260021879835[182] = 0; + out_3350621260021879835[183] = 0; + out_3350621260021879835[184] = 0; + out_3350621260021879835[185] = 0; + out_3350621260021879835[186] = 0; + out_3350621260021879835[187] = 0; + out_3350621260021879835[188] = 0; + out_3350621260021879835[189] = 0; + out_3350621260021879835[190] = 0; + out_3350621260021879835[191] = 0; + out_3350621260021879835[192] = 0; + out_3350621260021879835[193] = 0; + out_3350621260021879835[194] = 0; + out_3350621260021879835[195] = 0; + out_3350621260021879835[196] = 0; + out_3350621260021879835[197] = 1.0; + out_3350621260021879835[198] = 0; + out_3350621260021879835[199] = 0; + out_3350621260021879835[200] = 0; + out_3350621260021879835[201] = 0; + out_3350621260021879835[202] = 0; + out_3350621260021879835[203] = 0; + out_3350621260021879835[204] = 0; + out_3350621260021879835[205] = 0; + out_3350621260021879835[206] = 0; + out_3350621260021879835[207] = 0; + out_3350621260021879835[208] = 0; + out_3350621260021879835[209] = 0; + out_3350621260021879835[210] = 0; + out_3350621260021879835[211] = 0; + out_3350621260021879835[212] = 0; + out_3350621260021879835[213] = 0; + out_3350621260021879835[214] = 0; + out_3350621260021879835[215] = 0; + out_3350621260021879835[216] = 0; + out_3350621260021879835[217] = 0; + out_3350621260021879835[218] = 0; + out_3350621260021879835[219] = 1.0; + out_3350621260021879835[220] = 0; + out_3350621260021879835[221] = 0; + out_3350621260021879835[222] = 0; + out_3350621260021879835[223] = 0; + out_3350621260021879835[224] = 0; + out_3350621260021879835[225] = 0; + out_3350621260021879835[226] = 0; + out_3350621260021879835[227] = 0; + out_3350621260021879835[228] = 0; + out_3350621260021879835[229] = 0; + out_3350621260021879835[230] = 0; + out_3350621260021879835[231] = 0; + out_3350621260021879835[232] = 0; + out_3350621260021879835[233] = 0; + out_3350621260021879835[234] = 0; + out_3350621260021879835[235] = 0; + out_3350621260021879835[236] = 0; + out_3350621260021879835[237] = 0; + out_3350621260021879835[238] = 0; + out_3350621260021879835[239] = 0; + out_3350621260021879835[240] = 0; + out_3350621260021879835[241] = 1.0; + out_3350621260021879835[242] = 0; + out_3350621260021879835[243] = 0; + out_3350621260021879835[244] = 0; + out_3350621260021879835[245] = 0; + out_3350621260021879835[246] = 0; + out_3350621260021879835[247] = 0; + out_3350621260021879835[248] = 0; + out_3350621260021879835[249] = 0; + out_3350621260021879835[250] = 0; + out_3350621260021879835[251] = 0; + out_3350621260021879835[252] = 0; + out_3350621260021879835[253] = 0; + out_3350621260021879835[254] = 0; + out_3350621260021879835[255] = 0; + out_3350621260021879835[256] = 0; + out_3350621260021879835[257] = 0; + out_3350621260021879835[258] = 0; + out_3350621260021879835[259] = 0; + out_3350621260021879835[260] = 0; + out_3350621260021879835[261] = 0; + out_3350621260021879835[262] = 0; + out_3350621260021879835[263] = 1.0; + out_3350621260021879835[264] = 0; + out_3350621260021879835[265] = 0; + out_3350621260021879835[266] = 0; + out_3350621260021879835[267] = 0; + out_3350621260021879835[268] = 0; + out_3350621260021879835[269] = 0; + out_3350621260021879835[270] = 0; + out_3350621260021879835[271] = 0; + out_3350621260021879835[272] = 0; + out_3350621260021879835[273] = 0; + out_3350621260021879835[274] = 0; + out_3350621260021879835[275] = 0; + out_3350621260021879835[276] = 0; + out_3350621260021879835[277] = 0; + out_3350621260021879835[278] = 0; + out_3350621260021879835[279] = 0; + out_3350621260021879835[280] = 0; + out_3350621260021879835[281] = 0; + out_3350621260021879835[282] = 0; + out_3350621260021879835[283] = 0; + out_3350621260021879835[284] = 0; + out_3350621260021879835[285] = 1.0; + out_3350621260021879835[286] = 0; + out_3350621260021879835[287] = 0; + out_3350621260021879835[288] = 0; + out_3350621260021879835[289] = 0; + out_3350621260021879835[290] = 0; + out_3350621260021879835[291] = 0; + out_3350621260021879835[292] = 0; + out_3350621260021879835[293] = 0; + out_3350621260021879835[294] = 0; + out_3350621260021879835[295] = 0; + out_3350621260021879835[296] = 0; + out_3350621260021879835[297] = 0; + out_3350621260021879835[298] = 0; + out_3350621260021879835[299] = 0; + out_3350621260021879835[300] = 0; + out_3350621260021879835[301] = 0; + out_3350621260021879835[302] = 0; + out_3350621260021879835[303] = 0; + out_3350621260021879835[304] = 0; + out_3350621260021879835[305] = 0; + out_3350621260021879835[306] = 0; + out_3350621260021879835[307] = 1.0; + out_3350621260021879835[308] = 0; + out_3350621260021879835[309] = 0; + out_3350621260021879835[310] = 0; + out_3350621260021879835[311] = 0; + out_3350621260021879835[312] = 0; + out_3350621260021879835[313] = 0; + out_3350621260021879835[314] = 0; + out_3350621260021879835[315] = 0; + out_3350621260021879835[316] = 0; + out_3350621260021879835[317] = 0; + out_3350621260021879835[318] = 0; + out_3350621260021879835[319] = 0; + out_3350621260021879835[320] = 0; + out_3350621260021879835[321] = 0; + out_3350621260021879835[322] = 0; + out_3350621260021879835[323] = 0; + out_3350621260021879835[324] = 0; + out_3350621260021879835[325] = 0; + out_3350621260021879835[326] = 0; + out_3350621260021879835[327] = 0; + out_3350621260021879835[328] = 0; + out_3350621260021879835[329] = 1.0; + out_3350621260021879835[330] = 0; + out_3350621260021879835[331] = 0; + out_3350621260021879835[332] = 0; + out_3350621260021879835[333] = 0; + out_3350621260021879835[334] = 0; + out_3350621260021879835[335] = 0; + out_3350621260021879835[336] = 0; + out_3350621260021879835[337] = 0; + out_3350621260021879835[338] = 0; + out_3350621260021879835[339] = 0; + out_3350621260021879835[340] = 0; + out_3350621260021879835[341] = 0; + out_3350621260021879835[342] = 0; + out_3350621260021879835[343] = 0; + out_3350621260021879835[344] = 0; + out_3350621260021879835[345] = 0; + out_3350621260021879835[346] = 0; + out_3350621260021879835[347] = 0; + out_3350621260021879835[348] = 0; + out_3350621260021879835[349] = 0; + out_3350621260021879835[350] = 0; + out_3350621260021879835[351] = 1.0; + out_3350621260021879835[352] = 0; + out_3350621260021879835[353] = 0; + out_3350621260021879835[354] = 0; + out_3350621260021879835[355] = 0; + out_3350621260021879835[356] = 0; + out_3350621260021879835[357] = 0; + out_3350621260021879835[358] = 0; + out_3350621260021879835[359] = 0; + out_3350621260021879835[360] = 0; + out_3350621260021879835[361] = 0; + out_3350621260021879835[362] = 0; + out_3350621260021879835[363] = 0; + out_3350621260021879835[364] = 0; + out_3350621260021879835[365] = 0; + out_3350621260021879835[366] = 0; + out_3350621260021879835[367] = 0; + out_3350621260021879835[368] = 0; + out_3350621260021879835[369] = 0; + out_3350621260021879835[370] = 0; + out_3350621260021879835[371] = 0; + out_3350621260021879835[372] = 0; + out_3350621260021879835[373] = 1.0; + out_3350621260021879835[374] = 0; + out_3350621260021879835[375] = 0; + out_3350621260021879835[376] = 0; + out_3350621260021879835[377] = 0; + out_3350621260021879835[378] = 0; + out_3350621260021879835[379] = 0; + out_3350621260021879835[380] = 0; + out_3350621260021879835[381] = 0; + out_3350621260021879835[382] = 0; + out_3350621260021879835[383] = 0; + out_3350621260021879835[384] = 0; + out_3350621260021879835[385] = 0; + out_3350621260021879835[386] = 0; + out_3350621260021879835[387] = 0; + out_3350621260021879835[388] = 0; + out_3350621260021879835[389] = 0; + out_3350621260021879835[390] = 0; + out_3350621260021879835[391] = 0; + out_3350621260021879835[392] = 0; + out_3350621260021879835[393] = 0; + out_3350621260021879835[394] = 0; + out_3350621260021879835[395] = 1.0; + out_3350621260021879835[396] = 0; + out_3350621260021879835[397] = 0; + out_3350621260021879835[398] = 0; + out_3350621260021879835[399] = 0; + out_3350621260021879835[400] = 0; + out_3350621260021879835[401] = 0; + out_3350621260021879835[402] = 0; + out_3350621260021879835[403] = 0; + out_3350621260021879835[404] = 0; + out_3350621260021879835[405] = 0; + out_3350621260021879835[406] = 0; + out_3350621260021879835[407] = 0; + out_3350621260021879835[408] = 0; + out_3350621260021879835[409] = 0; + out_3350621260021879835[410] = 0; + out_3350621260021879835[411] = 0; + out_3350621260021879835[412] = 0; + out_3350621260021879835[413] = 0; + out_3350621260021879835[414] = 0; + out_3350621260021879835[415] = 0; + out_3350621260021879835[416] = 0; + out_3350621260021879835[417] = 1.0; + out_3350621260021879835[418] = 0; + out_3350621260021879835[419] = 0; + out_3350621260021879835[420] = 0; + out_3350621260021879835[421] = 0; + out_3350621260021879835[422] = 0; + out_3350621260021879835[423] = 0; + out_3350621260021879835[424] = 0; + out_3350621260021879835[425] = 0; + out_3350621260021879835[426] = 0; + out_3350621260021879835[427] = 0; + out_3350621260021879835[428] = 0; + out_3350621260021879835[429] = 0; + out_3350621260021879835[430] = 0; + out_3350621260021879835[431] = 0; + out_3350621260021879835[432] = 0; + out_3350621260021879835[433] = 0; + out_3350621260021879835[434] = 0; + out_3350621260021879835[435] = 0; + out_3350621260021879835[436] = 0; + out_3350621260021879835[437] = 0; + out_3350621260021879835[438] = 0; + out_3350621260021879835[439] = 1.0; + out_3350621260021879835[440] = 0; + out_3350621260021879835[441] = 0; + out_3350621260021879835[442] = 0; + out_3350621260021879835[443] = 0; + out_3350621260021879835[444] = 0; + out_3350621260021879835[445] = 0; + out_3350621260021879835[446] = 0; + out_3350621260021879835[447] = 0; + out_3350621260021879835[448] = 0; + out_3350621260021879835[449] = 0; + out_3350621260021879835[450] = 0; + out_3350621260021879835[451] = 0; + out_3350621260021879835[452] = 0; + out_3350621260021879835[453] = 0; + out_3350621260021879835[454] = 0; + out_3350621260021879835[455] = 0; + out_3350621260021879835[456] = 0; + out_3350621260021879835[457] = 0; + out_3350621260021879835[458] = 0; + out_3350621260021879835[459] = 0; + out_3350621260021879835[460] = 0; + out_3350621260021879835[461] = 1.0; } -void f_fun(double *state, double dt, double *out_9047640957774126431) { - out_9047640957774126431[0] = dt*state[7] + state[0]; - out_9047640957774126431[1] = dt*state[8] + state[1]; - out_9047640957774126431[2] = dt*state[9] + state[2]; - out_9047640957774126431[3] = dt*(-0.5*state[4]*state[10] - 0.5*state[5]*state[11] - 0.5*state[6]*state[12]) + state[3]; - out_9047640957774126431[4] = dt*(0.5*state[3]*state[10] + 0.5*state[5]*state[12] - 0.5*state[6]*state[11]) + state[4]; - out_9047640957774126431[5] = dt*(0.5*state[3]*state[11] - 0.5*state[4]*state[12] + 0.5*state[6]*state[10]) + state[5]; - out_9047640957774126431[6] = dt*(0.5*state[3]*state[12] + 0.5*state[4]*state[11] - 0.5*state[5]*state[10]) + state[6]; - out_9047640957774126431[7] = dt*((2*state[3]*state[5] + 2*state[4]*state[6])*state[18] + (-2*state[3]*state[6] + 2*state[4]*state[5])*state[17] + (pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2))*state[16]) + state[7]; - out_9047640957774126431[8] = dt*((-2*state[3]*state[4] + 2*state[5]*state[6])*state[18] + (2*state[3]*state[6] + 2*state[4]*state[5])*state[16] + (pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2))*state[17]) + state[8]; - out_9047640957774126431[9] = dt*((2*state[3]*state[4] + 2*state[5]*state[6])*state[17] + (-2*state[3]*state[5] + 2*state[4]*state[6])*state[16] + (pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[18]) + state[9]; - out_9047640957774126431[10] = state[10]; - out_9047640957774126431[11] = state[11]; - out_9047640957774126431[12] = state[12]; - out_9047640957774126431[13] = state[13]; - out_9047640957774126431[14] = state[14]; - out_9047640957774126431[15] = state[15]; - out_9047640957774126431[16] = state[16]; - out_9047640957774126431[17] = state[17]; - out_9047640957774126431[18] = state[18]; - out_9047640957774126431[19] = state[19]; - out_9047640957774126431[20] = state[20]; - out_9047640957774126431[21] = state[21]; +void f_fun(double *state, double dt, double *out_9110479569516509106) { + out_9110479569516509106[0] = dt*state[7] + state[0]; + out_9110479569516509106[1] = dt*state[8] + state[1]; + out_9110479569516509106[2] = dt*state[9] + state[2]; + out_9110479569516509106[3] = dt*(-0.5*state[4]*state[10] - 0.5*state[5]*state[11] - 0.5*state[6]*state[12]) + state[3]; + out_9110479569516509106[4] = dt*(0.5*state[3]*state[10] + 0.5*state[5]*state[12] - 0.5*state[6]*state[11]) + state[4]; + out_9110479569516509106[5] = dt*(0.5*state[3]*state[11] - 0.5*state[4]*state[12] + 0.5*state[6]*state[10]) + state[5]; + out_9110479569516509106[6] = dt*(0.5*state[3]*state[12] + 0.5*state[4]*state[11] - 0.5*state[5]*state[10]) + state[6]; + out_9110479569516509106[7] = dt*((2*state[3]*state[5] + 2*state[4]*state[6])*state[18] + (-2*state[3]*state[6] + 2*state[4]*state[5])*state[17] + (pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2))*state[16]) + state[7]; + out_9110479569516509106[8] = dt*((-2*state[3]*state[4] + 2*state[5]*state[6])*state[18] + (2*state[3]*state[6] + 2*state[4]*state[5])*state[16] + (pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2))*state[17]) + state[8]; + out_9110479569516509106[9] = dt*((2*state[3]*state[4] + 2*state[5]*state[6])*state[17] + (-2*state[3]*state[5] + 2*state[4]*state[6])*state[16] + (pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[18]) + state[9]; + out_9110479569516509106[10] = state[10]; + out_9110479569516509106[11] = state[11]; + out_9110479569516509106[12] = state[12]; + out_9110479569516509106[13] = state[13]; + out_9110479569516509106[14] = state[14]; + out_9110479569516509106[15] = state[15]; + out_9110479569516509106[16] = state[16]; + out_9110479569516509106[17] = state[17]; + out_9110479569516509106[18] = state[18]; + out_9110479569516509106[19] = state[19]; + out_9110479569516509106[20] = state[20]; + out_9110479569516509106[21] = state[21]; } -void F_fun(double *state, double dt, double *out_4752414459068816126) { - out_4752414459068816126[0] = 1; - out_4752414459068816126[1] = 0; - out_4752414459068816126[2] = 0; - out_4752414459068816126[3] = 0; - out_4752414459068816126[4] = 0; - out_4752414459068816126[5] = 0; - out_4752414459068816126[6] = dt; - out_4752414459068816126[7] = 0; - out_4752414459068816126[8] = 0; - out_4752414459068816126[9] = 0; - out_4752414459068816126[10] = 0; - out_4752414459068816126[11] = 0; - out_4752414459068816126[12] = 0; - out_4752414459068816126[13] = 0; - out_4752414459068816126[14] = 0; - out_4752414459068816126[15] = 0; - out_4752414459068816126[16] = 0; - out_4752414459068816126[17] = 0; - out_4752414459068816126[18] = 0; - out_4752414459068816126[19] = 0; - out_4752414459068816126[20] = 0; - out_4752414459068816126[21] = 0; - out_4752414459068816126[22] = 1; - out_4752414459068816126[23] = 0; - out_4752414459068816126[24] = 0; - out_4752414459068816126[25] = 0; - out_4752414459068816126[26] = 0; - out_4752414459068816126[27] = 0; - out_4752414459068816126[28] = dt; - out_4752414459068816126[29] = 0; - out_4752414459068816126[30] = 0; - out_4752414459068816126[31] = 0; - out_4752414459068816126[32] = 0; - out_4752414459068816126[33] = 0; - out_4752414459068816126[34] = 0; - out_4752414459068816126[35] = 0; - out_4752414459068816126[36] = 0; - out_4752414459068816126[37] = 0; - out_4752414459068816126[38] = 0; - out_4752414459068816126[39] = 0; - out_4752414459068816126[40] = 0; - out_4752414459068816126[41] = 0; - out_4752414459068816126[42] = 0; - out_4752414459068816126[43] = 0; - out_4752414459068816126[44] = 1; - out_4752414459068816126[45] = 0; - out_4752414459068816126[46] = 0; - out_4752414459068816126[47] = 0; - out_4752414459068816126[48] = 0; - out_4752414459068816126[49] = 0; - out_4752414459068816126[50] = dt; - out_4752414459068816126[51] = 0; - out_4752414459068816126[52] = 0; - out_4752414459068816126[53] = 0; - out_4752414459068816126[54] = 0; - out_4752414459068816126[55] = 0; - out_4752414459068816126[56] = 0; - out_4752414459068816126[57] = 0; - out_4752414459068816126[58] = 0; - out_4752414459068816126[59] = 0; - out_4752414459068816126[60] = 0; - out_4752414459068816126[61] = 0; - out_4752414459068816126[62] = 0; - out_4752414459068816126[63] = 0; - out_4752414459068816126[64] = 0; - out_4752414459068816126[65] = 0; - out_4752414459068816126[66] = 1; - out_4752414459068816126[67] = dt*((2*state[3]*state[4] + 2*state[5]*state[6])*state[11] + (-2*state[3]*state[5] + 2*state[4]*state[6])*state[10] + (pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[12]); - out_4752414459068816126[68] = dt*((2*state[3]*state[4] - 2*state[5]*state[6])*state[12] + (-2*state[3]*state[6] - 2*state[4]*state[5])*state[10] + (-pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[11]); - out_4752414459068816126[69] = 0; - out_4752414459068816126[70] = 0; - out_4752414459068816126[71] = 0; - out_4752414459068816126[72] = dt*(pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2)); - out_4752414459068816126[73] = dt*(-2*state[3]*state[6] + 2*state[4]*state[5]); - out_4752414459068816126[74] = dt*(2*state[3]*state[5] + 2*state[4]*state[6]); - out_4752414459068816126[75] = 0; - out_4752414459068816126[76] = 0; - out_4752414459068816126[77] = 0; - out_4752414459068816126[78] = 0; - out_4752414459068816126[79] = 0; - out_4752414459068816126[80] = 0; - out_4752414459068816126[81] = 0; - out_4752414459068816126[82] = 0; - out_4752414459068816126[83] = 0; - out_4752414459068816126[84] = 0; - out_4752414459068816126[85] = 0; - out_4752414459068816126[86] = 0; - out_4752414459068816126[87] = dt*(-(2*state[3]*state[4] + 2*state[5]*state[6])*state[11] - (-2*state[3]*state[5] + 2*state[4]*state[6])*state[10] - (pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[12]); - out_4752414459068816126[88] = 1; - out_4752414459068816126[89] = dt*((2*state[3]*state[5] + 2*state[4]*state[6])*state[12] + (-2*state[3]*state[6] + 2*state[4]*state[5])*state[11] + (pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2))*state[10]); - out_4752414459068816126[90] = 0; - out_4752414459068816126[91] = 0; - out_4752414459068816126[92] = 0; - out_4752414459068816126[93] = dt*(2*state[3]*state[6] + 2*state[4]*state[5]); - out_4752414459068816126[94] = dt*(pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2)); - out_4752414459068816126[95] = dt*(-2*state[3]*state[4] + 2*state[5]*state[6]); - out_4752414459068816126[96] = 0; - out_4752414459068816126[97] = 0; - out_4752414459068816126[98] = 0; - out_4752414459068816126[99] = 0; - out_4752414459068816126[100] = 0; - out_4752414459068816126[101] = 0; - out_4752414459068816126[102] = 0; - out_4752414459068816126[103] = 0; - out_4752414459068816126[104] = 0; - out_4752414459068816126[105] = 0; - out_4752414459068816126[106] = 0; - out_4752414459068816126[107] = 0; - out_4752414459068816126[108] = dt*((-2*state[3]*state[4] + 2*state[5]*state[6])*state[12] + (2*state[3]*state[6] + 2*state[4]*state[5])*state[10] + (pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2))*state[11]); - out_4752414459068816126[109] = dt*((-2*state[3]*state[5] - 2*state[4]*state[6])*state[12] + (2*state[3]*state[6] - 2*state[4]*state[5])*state[11] + (-pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) + pow(state[6], 2))*state[10]); - out_4752414459068816126[110] = 1; - out_4752414459068816126[111] = 0; - out_4752414459068816126[112] = 0; - out_4752414459068816126[113] = 0; - out_4752414459068816126[114] = dt*(-2*state[3]*state[5] + 2*state[4]*state[6]); - out_4752414459068816126[115] = dt*(2*state[3]*state[4] + 2*state[5]*state[6]); - out_4752414459068816126[116] = dt*(pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2)); - out_4752414459068816126[117] = 0; - out_4752414459068816126[118] = 0; - out_4752414459068816126[119] = 0; - out_4752414459068816126[120] = 0; - out_4752414459068816126[121] = 0; - out_4752414459068816126[122] = 0; - out_4752414459068816126[123] = 0; - out_4752414459068816126[124] = 0; - out_4752414459068816126[125] = 0; - out_4752414459068816126[126] = 0; - out_4752414459068816126[127] = 0; - out_4752414459068816126[128] = 0; - out_4752414459068816126[129] = 0; - out_4752414459068816126[130] = dt*((2*state[3]*state[4] + 2*state[5]*state[6])*state[17] + (-2*state[3]*state[5] + 2*state[4]*state[6])*state[16] + (pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[18]); - out_4752414459068816126[131] = dt*((2*state[3]*state[4] - 2*state[5]*state[6])*state[18] + (-2*state[3]*state[6] - 2*state[4]*state[5])*state[16] + (-pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[17]); - out_4752414459068816126[132] = 1; - out_4752414459068816126[133] = 0; - out_4752414459068816126[134] = 0; - out_4752414459068816126[135] = 0; - out_4752414459068816126[136] = 0; - out_4752414459068816126[137] = 0; - out_4752414459068816126[138] = 0; - out_4752414459068816126[139] = 0; - out_4752414459068816126[140] = 0; - out_4752414459068816126[141] = dt*(pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2)); - out_4752414459068816126[142] = dt*(-2*state[3]*state[6] + 2*state[4]*state[5]); - out_4752414459068816126[143] = dt*(2*state[3]*state[5] + 2*state[4]*state[6]); - out_4752414459068816126[144] = 0; - out_4752414459068816126[145] = 0; - out_4752414459068816126[146] = 0; - out_4752414459068816126[147] = 0; - out_4752414459068816126[148] = 0; - out_4752414459068816126[149] = 0; - out_4752414459068816126[150] = dt*(-(2*state[3]*state[4] + 2*state[5]*state[6])*state[17] - (-2*state[3]*state[5] + 2*state[4]*state[6])*state[16] - (pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[18]); - out_4752414459068816126[151] = 0; - out_4752414459068816126[152] = dt*((2*state[3]*state[5] + 2*state[4]*state[6])*state[18] + (-2*state[3]*state[6] + 2*state[4]*state[5])*state[17] + (pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2))*state[16]); - out_4752414459068816126[153] = 0; - out_4752414459068816126[154] = 1; - out_4752414459068816126[155] = 0; - out_4752414459068816126[156] = 0; - out_4752414459068816126[157] = 0; - out_4752414459068816126[158] = 0; - out_4752414459068816126[159] = 0; - out_4752414459068816126[160] = 0; - out_4752414459068816126[161] = 0; - out_4752414459068816126[162] = dt*(2*state[3]*state[6] + 2*state[4]*state[5]); - out_4752414459068816126[163] = dt*(pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2)); - out_4752414459068816126[164] = dt*(-2*state[3]*state[4] + 2*state[5]*state[6]); - out_4752414459068816126[165] = 0; - out_4752414459068816126[166] = 0; - out_4752414459068816126[167] = 0; - out_4752414459068816126[168] = 0; - out_4752414459068816126[169] = 0; - out_4752414459068816126[170] = 0; - out_4752414459068816126[171] = dt*((-2*state[3]*state[4] + 2*state[5]*state[6])*state[18] + (2*state[3]*state[6] + 2*state[4]*state[5])*state[16] + (pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2))*state[17]); - out_4752414459068816126[172] = dt*((-2*state[3]*state[5] - 2*state[4]*state[6])*state[18] + (2*state[3]*state[6] - 2*state[4]*state[5])*state[17] + (-pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) + pow(state[6], 2))*state[16]); - out_4752414459068816126[173] = 0; - out_4752414459068816126[174] = 0; - out_4752414459068816126[175] = 0; - out_4752414459068816126[176] = 1; - out_4752414459068816126[177] = 0; - out_4752414459068816126[178] = 0; - out_4752414459068816126[179] = 0; - out_4752414459068816126[180] = 0; - out_4752414459068816126[181] = 0; - out_4752414459068816126[182] = 0; - out_4752414459068816126[183] = dt*(-2*state[3]*state[5] + 2*state[4]*state[6]); - out_4752414459068816126[184] = dt*(2*state[3]*state[4] + 2*state[5]*state[6]); - out_4752414459068816126[185] = dt*(pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2)); - out_4752414459068816126[186] = 0; - out_4752414459068816126[187] = 0; - out_4752414459068816126[188] = 0; - out_4752414459068816126[189] = 0; - out_4752414459068816126[190] = 0; - out_4752414459068816126[191] = 0; - out_4752414459068816126[192] = 0; - out_4752414459068816126[193] = 0; - out_4752414459068816126[194] = 0; - out_4752414459068816126[195] = 0; - out_4752414459068816126[196] = 0; - out_4752414459068816126[197] = 0; - out_4752414459068816126[198] = 1; - out_4752414459068816126[199] = 0; - out_4752414459068816126[200] = 0; - out_4752414459068816126[201] = 0; - out_4752414459068816126[202] = 0; - out_4752414459068816126[203] = 0; - out_4752414459068816126[204] = 0; - out_4752414459068816126[205] = 0; - out_4752414459068816126[206] = 0; - out_4752414459068816126[207] = 0; - out_4752414459068816126[208] = 0; - out_4752414459068816126[209] = 0; - out_4752414459068816126[210] = 0; - out_4752414459068816126[211] = 0; - out_4752414459068816126[212] = 0; - out_4752414459068816126[213] = 0; - out_4752414459068816126[214] = 0; - out_4752414459068816126[215] = 0; - out_4752414459068816126[216] = 0; - out_4752414459068816126[217] = 0; - out_4752414459068816126[218] = 0; - out_4752414459068816126[219] = 0; - out_4752414459068816126[220] = 1; - out_4752414459068816126[221] = 0; - out_4752414459068816126[222] = 0; - out_4752414459068816126[223] = 0; - out_4752414459068816126[224] = 0; - out_4752414459068816126[225] = 0; - out_4752414459068816126[226] = 0; - out_4752414459068816126[227] = 0; - out_4752414459068816126[228] = 0; - out_4752414459068816126[229] = 0; - out_4752414459068816126[230] = 0; - out_4752414459068816126[231] = 0; - out_4752414459068816126[232] = 0; - out_4752414459068816126[233] = 0; - out_4752414459068816126[234] = 0; - out_4752414459068816126[235] = 0; - out_4752414459068816126[236] = 0; - out_4752414459068816126[237] = 0; - out_4752414459068816126[238] = 0; - out_4752414459068816126[239] = 0; - out_4752414459068816126[240] = 0; - out_4752414459068816126[241] = 0; - out_4752414459068816126[242] = 1; - out_4752414459068816126[243] = 0; - out_4752414459068816126[244] = 0; - out_4752414459068816126[245] = 0; - out_4752414459068816126[246] = 0; - out_4752414459068816126[247] = 0; - out_4752414459068816126[248] = 0; - out_4752414459068816126[249] = 0; - out_4752414459068816126[250] = 0; - out_4752414459068816126[251] = 0; - out_4752414459068816126[252] = 0; - out_4752414459068816126[253] = 0; - out_4752414459068816126[254] = 0; - out_4752414459068816126[255] = 0; - out_4752414459068816126[256] = 0; - out_4752414459068816126[257] = 0; - out_4752414459068816126[258] = 0; - out_4752414459068816126[259] = 0; - out_4752414459068816126[260] = 0; - out_4752414459068816126[261] = 0; - out_4752414459068816126[262] = 0; - out_4752414459068816126[263] = 0; - out_4752414459068816126[264] = 1; - out_4752414459068816126[265] = 0; - out_4752414459068816126[266] = 0; - out_4752414459068816126[267] = 0; - out_4752414459068816126[268] = 0; - out_4752414459068816126[269] = 0; - out_4752414459068816126[270] = 0; - out_4752414459068816126[271] = 0; - out_4752414459068816126[272] = 0; - out_4752414459068816126[273] = 0; - out_4752414459068816126[274] = 0; - out_4752414459068816126[275] = 0; - out_4752414459068816126[276] = 0; - out_4752414459068816126[277] = 0; - out_4752414459068816126[278] = 0; - out_4752414459068816126[279] = 0; - out_4752414459068816126[280] = 0; - out_4752414459068816126[281] = 0; - out_4752414459068816126[282] = 0; - out_4752414459068816126[283] = 0; - out_4752414459068816126[284] = 0; - out_4752414459068816126[285] = 0; - out_4752414459068816126[286] = 1; - out_4752414459068816126[287] = 0; - out_4752414459068816126[288] = 0; - out_4752414459068816126[289] = 0; - out_4752414459068816126[290] = 0; - out_4752414459068816126[291] = 0; - out_4752414459068816126[292] = 0; - out_4752414459068816126[293] = 0; - out_4752414459068816126[294] = 0; - out_4752414459068816126[295] = 0; - out_4752414459068816126[296] = 0; - out_4752414459068816126[297] = 0; - out_4752414459068816126[298] = 0; - out_4752414459068816126[299] = 0; - out_4752414459068816126[300] = 0; - out_4752414459068816126[301] = 0; - out_4752414459068816126[302] = 0; - out_4752414459068816126[303] = 0; - out_4752414459068816126[304] = 0; - out_4752414459068816126[305] = 0; - out_4752414459068816126[306] = 0; - out_4752414459068816126[307] = 0; - out_4752414459068816126[308] = 1; - out_4752414459068816126[309] = 0; - out_4752414459068816126[310] = 0; - out_4752414459068816126[311] = 0; - out_4752414459068816126[312] = 0; - out_4752414459068816126[313] = 0; - out_4752414459068816126[314] = 0; - out_4752414459068816126[315] = 0; - out_4752414459068816126[316] = 0; - out_4752414459068816126[317] = 0; - out_4752414459068816126[318] = 0; - out_4752414459068816126[319] = 0; - out_4752414459068816126[320] = 0; - out_4752414459068816126[321] = 0; - out_4752414459068816126[322] = 0; - out_4752414459068816126[323] = 0; - out_4752414459068816126[324] = 0; - out_4752414459068816126[325] = 0; - out_4752414459068816126[326] = 0; - out_4752414459068816126[327] = 0; - out_4752414459068816126[328] = 0; - out_4752414459068816126[329] = 0; - out_4752414459068816126[330] = 1; - out_4752414459068816126[331] = 0; - out_4752414459068816126[332] = 0; - out_4752414459068816126[333] = 0; - out_4752414459068816126[334] = 0; - out_4752414459068816126[335] = 0; - out_4752414459068816126[336] = 0; - out_4752414459068816126[337] = 0; - out_4752414459068816126[338] = 0; - out_4752414459068816126[339] = 0; - out_4752414459068816126[340] = 0; - out_4752414459068816126[341] = 0; - out_4752414459068816126[342] = 0; - out_4752414459068816126[343] = 0; - out_4752414459068816126[344] = 0; - out_4752414459068816126[345] = 0; - out_4752414459068816126[346] = 0; - out_4752414459068816126[347] = 0; - out_4752414459068816126[348] = 0; - out_4752414459068816126[349] = 0; - out_4752414459068816126[350] = 0; - out_4752414459068816126[351] = 0; - out_4752414459068816126[352] = 1; - out_4752414459068816126[353] = 0; - out_4752414459068816126[354] = 0; - out_4752414459068816126[355] = 0; - out_4752414459068816126[356] = 0; - out_4752414459068816126[357] = 0; - out_4752414459068816126[358] = 0; - out_4752414459068816126[359] = 0; - out_4752414459068816126[360] = 0; - out_4752414459068816126[361] = 0; - out_4752414459068816126[362] = 0; - out_4752414459068816126[363] = 0; - out_4752414459068816126[364] = 0; - out_4752414459068816126[365] = 0; - out_4752414459068816126[366] = 0; - out_4752414459068816126[367] = 0; - out_4752414459068816126[368] = 0; - out_4752414459068816126[369] = 0; - out_4752414459068816126[370] = 0; - out_4752414459068816126[371] = 0; - out_4752414459068816126[372] = 0; - out_4752414459068816126[373] = 0; - out_4752414459068816126[374] = 1; - out_4752414459068816126[375] = 0; - out_4752414459068816126[376] = 0; - out_4752414459068816126[377] = 0; - out_4752414459068816126[378] = 0; - out_4752414459068816126[379] = 0; - out_4752414459068816126[380] = 0; - out_4752414459068816126[381] = 0; - out_4752414459068816126[382] = 0; - out_4752414459068816126[383] = 0; - out_4752414459068816126[384] = 0; - out_4752414459068816126[385] = 0; - out_4752414459068816126[386] = 0; - out_4752414459068816126[387] = 0; - out_4752414459068816126[388] = 0; - out_4752414459068816126[389] = 0; - out_4752414459068816126[390] = 0; - out_4752414459068816126[391] = 0; - out_4752414459068816126[392] = 0; - out_4752414459068816126[393] = 0; - out_4752414459068816126[394] = 0; - out_4752414459068816126[395] = 0; - out_4752414459068816126[396] = 1; - out_4752414459068816126[397] = 0; - out_4752414459068816126[398] = 0; - out_4752414459068816126[399] = 0; - out_4752414459068816126[400] = 0; - out_4752414459068816126[401] = 0; - out_4752414459068816126[402] = 0; - out_4752414459068816126[403] = 0; - out_4752414459068816126[404] = 0; - out_4752414459068816126[405] = 0; - out_4752414459068816126[406] = 0; - out_4752414459068816126[407] = 0; - out_4752414459068816126[408] = 0; - out_4752414459068816126[409] = 0; - out_4752414459068816126[410] = 0; - out_4752414459068816126[411] = 0; - out_4752414459068816126[412] = 0; - out_4752414459068816126[413] = 0; - out_4752414459068816126[414] = 0; - out_4752414459068816126[415] = 0; - out_4752414459068816126[416] = 0; - out_4752414459068816126[417] = 0; - out_4752414459068816126[418] = 1; - out_4752414459068816126[419] = 0; - out_4752414459068816126[420] = 0; - out_4752414459068816126[421] = 0; - out_4752414459068816126[422] = 0; - out_4752414459068816126[423] = 0; - out_4752414459068816126[424] = 0; - out_4752414459068816126[425] = 0; - out_4752414459068816126[426] = 0; - out_4752414459068816126[427] = 0; - out_4752414459068816126[428] = 0; - out_4752414459068816126[429] = 0; - out_4752414459068816126[430] = 0; - out_4752414459068816126[431] = 0; - out_4752414459068816126[432] = 0; - out_4752414459068816126[433] = 0; - out_4752414459068816126[434] = 0; - out_4752414459068816126[435] = 0; - out_4752414459068816126[436] = 0; - out_4752414459068816126[437] = 0; - out_4752414459068816126[438] = 0; - out_4752414459068816126[439] = 0; - out_4752414459068816126[440] = 1; +void F_fun(double *state, double dt, double *out_956757865849250644) { + out_956757865849250644[0] = 1; + out_956757865849250644[1] = 0; + out_956757865849250644[2] = 0; + out_956757865849250644[3] = 0; + out_956757865849250644[4] = 0; + out_956757865849250644[5] = 0; + out_956757865849250644[6] = dt; + out_956757865849250644[7] = 0; + out_956757865849250644[8] = 0; + out_956757865849250644[9] = 0; + out_956757865849250644[10] = 0; + out_956757865849250644[11] = 0; + out_956757865849250644[12] = 0; + out_956757865849250644[13] = 0; + out_956757865849250644[14] = 0; + out_956757865849250644[15] = 0; + out_956757865849250644[16] = 0; + out_956757865849250644[17] = 0; + out_956757865849250644[18] = 0; + out_956757865849250644[19] = 0; + out_956757865849250644[20] = 0; + out_956757865849250644[21] = 0; + out_956757865849250644[22] = 1; + out_956757865849250644[23] = 0; + out_956757865849250644[24] = 0; + out_956757865849250644[25] = 0; + out_956757865849250644[26] = 0; + out_956757865849250644[27] = 0; + out_956757865849250644[28] = dt; + out_956757865849250644[29] = 0; + out_956757865849250644[30] = 0; + out_956757865849250644[31] = 0; + out_956757865849250644[32] = 0; + out_956757865849250644[33] = 0; + out_956757865849250644[34] = 0; + out_956757865849250644[35] = 0; + out_956757865849250644[36] = 0; + out_956757865849250644[37] = 0; + out_956757865849250644[38] = 0; + out_956757865849250644[39] = 0; + out_956757865849250644[40] = 0; + out_956757865849250644[41] = 0; + out_956757865849250644[42] = 0; + out_956757865849250644[43] = 0; + out_956757865849250644[44] = 1; + out_956757865849250644[45] = 0; + out_956757865849250644[46] = 0; + out_956757865849250644[47] = 0; + out_956757865849250644[48] = 0; + out_956757865849250644[49] = 0; + out_956757865849250644[50] = dt; + out_956757865849250644[51] = 0; + out_956757865849250644[52] = 0; + out_956757865849250644[53] = 0; + out_956757865849250644[54] = 0; + out_956757865849250644[55] = 0; + out_956757865849250644[56] = 0; + out_956757865849250644[57] = 0; + out_956757865849250644[58] = 0; + out_956757865849250644[59] = 0; + out_956757865849250644[60] = 0; + out_956757865849250644[61] = 0; + out_956757865849250644[62] = 0; + out_956757865849250644[63] = 0; + out_956757865849250644[64] = 0; + out_956757865849250644[65] = 0; + out_956757865849250644[66] = 1; + out_956757865849250644[67] = dt*((2*state[3]*state[4] + 2*state[5]*state[6])*state[11] + (-2*state[3]*state[5] + 2*state[4]*state[6])*state[10] + (pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[12]); + out_956757865849250644[68] = dt*((2*state[3]*state[4] - 2*state[5]*state[6])*state[12] + (-2*state[3]*state[6] - 2*state[4]*state[5])*state[10] + (-pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[11]); + out_956757865849250644[69] = 0; + out_956757865849250644[70] = 0; + out_956757865849250644[71] = 0; + out_956757865849250644[72] = dt*(pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2)); + out_956757865849250644[73] = dt*(-2*state[3]*state[6] + 2*state[4]*state[5]); + out_956757865849250644[74] = dt*(2*state[3]*state[5] + 2*state[4]*state[6]); + out_956757865849250644[75] = 0; + out_956757865849250644[76] = 0; + out_956757865849250644[77] = 0; + out_956757865849250644[78] = 0; + out_956757865849250644[79] = 0; + out_956757865849250644[80] = 0; + out_956757865849250644[81] = 0; + out_956757865849250644[82] = 0; + out_956757865849250644[83] = 0; + out_956757865849250644[84] = 0; + out_956757865849250644[85] = 0; + out_956757865849250644[86] = 0; + out_956757865849250644[87] = dt*(-(2*state[3]*state[4] + 2*state[5]*state[6])*state[11] - (-2*state[3]*state[5] + 2*state[4]*state[6])*state[10] - (pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[12]); + out_956757865849250644[88] = 1; + out_956757865849250644[89] = dt*((2*state[3]*state[5] + 2*state[4]*state[6])*state[12] + (-2*state[3]*state[6] + 2*state[4]*state[5])*state[11] + (pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2))*state[10]); + out_956757865849250644[90] = 0; + out_956757865849250644[91] = 0; + out_956757865849250644[92] = 0; + out_956757865849250644[93] = dt*(2*state[3]*state[6] + 2*state[4]*state[5]); + out_956757865849250644[94] = dt*(pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2)); + out_956757865849250644[95] = dt*(-2*state[3]*state[4] + 2*state[5]*state[6]); + out_956757865849250644[96] = 0; + out_956757865849250644[97] = 0; + out_956757865849250644[98] = 0; + out_956757865849250644[99] = 0; + out_956757865849250644[100] = 0; + out_956757865849250644[101] = 0; + out_956757865849250644[102] = 0; + out_956757865849250644[103] = 0; + out_956757865849250644[104] = 0; + out_956757865849250644[105] = 0; + out_956757865849250644[106] = 0; + out_956757865849250644[107] = 0; + out_956757865849250644[108] = dt*((-2*state[3]*state[4] + 2*state[5]*state[6])*state[12] + (2*state[3]*state[6] + 2*state[4]*state[5])*state[10] + (pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2))*state[11]); + out_956757865849250644[109] = dt*((-2*state[3]*state[5] - 2*state[4]*state[6])*state[12] + (2*state[3]*state[6] - 2*state[4]*state[5])*state[11] + (-pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) + pow(state[6], 2))*state[10]); + out_956757865849250644[110] = 1; + out_956757865849250644[111] = 0; + out_956757865849250644[112] = 0; + out_956757865849250644[113] = 0; + out_956757865849250644[114] = dt*(-2*state[3]*state[5] + 2*state[4]*state[6]); + out_956757865849250644[115] = dt*(2*state[3]*state[4] + 2*state[5]*state[6]); + out_956757865849250644[116] = dt*(pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2)); + out_956757865849250644[117] = 0; + out_956757865849250644[118] = 0; + out_956757865849250644[119] = 0; + out_956757865849250644[120] = 0; + out_956757865849250644[121] = 0; + out_956757865849250644[122] = 0; + out_956757865849250644[123] = 0; + out_956757865849250644[124] = 0; + out_956757865849250644[125] = 0; + out_956757865849250644[126] = 0; + out_956757865849250644[127] = 0; + out_956757865849250644[128] = 0; + out_956757865849250644[129] = 0; + out_956757865849250644[130] = dt*((2*state[3]*state[4] + 2*state[5]*state[6])*state[17] + (-2*state[3]*state[5] + 2*state[4]*state[6])*state[16] + (pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[18]); + out_956757865849250644[131] = dt*((2*state[3]*state[4] - 2*state[5]*state[6])*state[18] + (-2*state[3]*state[6] - 2*state[4]*state[5])*state[16] + (-pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[17]); + out_956757865849250644[132] = 1; + out_956757865849250644[133] = 0; + out_956757865849250644[134] = 0; + out_956757865849250644[135] = 0; + out_956757865849250644[136] = 0; + out_956757865849250644[137] = 0; + out_956757865849250644[138] = 0; + out_956757865849250644[139] = 0; + out_956757865849250644[140] = 0; + out_956757865849250644[141] = dt*(pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2)); + out_956757865849250644[142] = dt*(-2*state[3]*state[6] + 2*state[4]*state[5]); + out_956757865849250644[143] = dt*(2*state[3]*state[5] + 2*state[4]*state[6]); + out_956757865849250644[144] = 0; + out_956757865849250644[145] = 0; + out_956757865849250644[146] = 0; + out_956757865849250644[147] = 0; + out_956757865849250644[148] = 0; + out_956757865849250644[149] = 0; + out_956757865849250644[150] = dt*(-(2*state[3]*state[4] + 2*state[5]*state[6])*state[17] - (-2*state[3]*state[5] + 2*state[4]*state[6])*state[16] - (pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[18]); + out_956757865849250644[151] = 0; + out_956757865849250644[152] = dt*((2*state[3]*state[5] + 2*state[4]*state[6])*state[18] + (-2*state[3]*state[6] + 2*state[4]*state[5])*state[17] + (pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2))*state[16]); + out_956757865849250644[153] = 0; + out_956757865849250644[154] = 1; + out_956757865849250644[155] = 0; + out_956757865849250644[156] = 0; + out_956757865849250644[157] = 0; + out_956757865849250644[158] = 0; + out_956757865849250644[159] = 0; + out_956757865849250644[160] = 0; + out_956757865849250644[161] = 0; + out_956757865849250644[162] = dt*(2*state[3]*state[6] + 2*state[4]*state[5]); + out_956757865849250644[163] = dt*(pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2)); + out_956757865849250644[164] = dt*(-2*state[3]*state[4] + 2*state[5]*state[6]); + out_956757865849250644[165] = 0; + out_956757865849250644[166] = 0; + out_956757865849250644[167] = 0; + out_956757865849250644[168] = 0; + out_956757865849250644[169] = 0; + out_956757865849250644[170] = 0; + out_956757865849250644[171] = dt*((-2*state[3]*state[4] + 2*state[5]*state[6])*state[18] + (2*state[3]*state[6] + 2*state[4]*state[5])*state[16] + (pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2))*state[17]); + out_956757865849250644[172] = dt*((-2*state[3]*state[5] - 2*state[4]*state[6])*state[18] + (2*state[3]*state[6] - 2*state[4]*state[5])*state[17] + (-pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) + pow(state[6], 2))*state[16]); + out_956757865849250644[173] = 0; + out_956757865849250644[174] = 0; + out_956757865849250644[175] = 0; + out_956757865849250644[176] = 1; + out_956757865849250644[177] = 0; + out_956757865849250644[178] = 0; + out_956757865849250644[179] = 0; + out_956757865849250644[180] = 0; + out_956757865849250644[181] = 0; + out_956757865849250644[182] = 0; + out_956757865849250644[183] = dt*(-2*state[3]*state[5] + 2*state[4]*state[6]); + out_956757865849250644[184] = dt*(2*state[3]*state[4] + 2*state[5]*state[6]); + out_956757865849250644[185] = dt*(pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2)); + out_956757865849250644[186] = 0; + out_956757865849250644[187] = 0; + out_956757865849250644[188] = 0; + out_956757865849250644[189] = 0; + out_956757865849250644[190] = 0; + out_956757865849250644[191] = 0; + out_956757865849250644[192] = 0; + out_956757865849250644[193] = 0; + out_956757865849250644[194] = 0; + out_956757865849250644[195] = 0; + out_956757865849250644[196] = 0; + out_956757865849250644[197] = 0; + out_956757865849250644[198] = 1; + out_956757865849250644[199] = 0; + out_956757865849250644[200] = 0; + out_956757865849250644[201] = 0; + out_956757865849250644[202] = 0; + out_956757865849250644[203] = 0; + out_956757865849250644[204] = 0; + out_956757865849250644[205] = 0; + out_956757865849250644[206] = 0; + out_956757865849250644[207] = 0; + out_956757865849250644[208] = 0; + out_956757865849250644[209] = 0; + out_956757865849250644[210] = 0; + out_956757865849250644[211] = 0; + out_956757865849250644[212] = 0; + out_956757865849250644[213] = 0; + out_956757865849250644[214] = 0; + out_956757865849250644[215] = 0; + out_956757865849250644[216] = 0; + out_956757865849250644[217] = 0; + out_956757865849250644[218] = 0; + out_956757865849250644[219] = 0; + out_956757865849250644[220] = 1; + out_956757865849250644[221] = 0; + out_956757865849250644[222] = 0; + out_956757865849250644[223] = 0; + out_956757865849250644[224] = 0; + out_956757865849250644[225] = 0; + out_956757865849250644[226] = 0; + out_956757865849250644[227] = 0; + out_956757865849250644[228] = 0; + out_956757865849250644[229] = 0; + out_956757865849250644[230] = 0; + out_956757865849250644[231] = 0; + out_956757865849250644[232] = 0; + out_956757865849250644[233] = 0; + out_956757865849250644[234] = 0; + out_956757865849250644[235] = 0; + out_956757865849250644[236] = 0; + out_956757865849250644[237] = 0; + out_956757865849250644[238] = 0; + out_956757865849250644[239] = 0; + out_956757865849250644[240] = 0; + out_956757865849250644[241] = 0; + out_956757865849250644[242] = 1; + out_956757865849250644[243] = 0; + out_956757865849250644[244] = 0; + out_956757865849250644[245] = 0; + out_956757865849250644[246] = 0; + out_956757865849250644[247] = 0; + out_956757865849250644[248] = 0; + out_956757865849250644[249] = 0; + out_956757865849250644[250] = 0; + out_956757865849250644[251] = 0; + out_956757865849250644[252] = 0; + out_956757865849250644[253] = 0; + out_956757865849250644[254] = 0; + out_956757865849250644[255] = 0; + out_956757865849250644[256] = 0; + out_956757865849250644[257] = 0; + out_956757865849250644[258] = 0; + out_956757865849250644[259] = 0; + out_956757865849250644[260] = 0; + out_956757865849250644[261] = 0; + out_956757865849250644[262] = 0; + out_956757865849250644[263] = 0; + out_956757865849250644[264] = 1; + out_956757865849250644[265] = 0; + out_956757865849250644[266] = 0; + out_956757865849250644[267] = 0; + out_956757865849250644[268] = 0; + out_956757865849250644[269] = 0; + out_956757865849250644[270] = 0; + out_956757865849250644[271] = 0; + out_956757865849250644[272] = 0; + out_956757865849250644[273] = 0; + out_956757865849250644[274] = 0; + out_956757865849250644[275] = 0; + out_956757865849250644[276] = 0; + out_956757865849250644[277] = 0; + out_956757865849250644[278] = 0; + out_956757865849250644[279] = 0; + out_956757865849250644[280] = 0; + out_956757865849250644[281] = 0; + out_956757865849250644[282] = 0; + out_956757865849250644[283] = 0; + out_956757865849250644[284] = 0; + out_956757865849250644[285] = 0; + out_956757865849250644[286] = 1; + out_956757865849250644[287] = 0; + out_956757865849250644[288] = 0; + out_956757865849250644[289] = 0; + out_956757865849250644[290] = 0; + out_956757865849250644[291] = 0; + out_956757865849250644[292] = 0; + out_956757865849250644[293] = 0; + out_956757865849250644[294] = 0; + out_956757865849250644[295] = 0; + out_956757865849250644[296] = 0; + out_956757865849250644[297] = 0; + out_956757865849250644[298] = 0; + out_956757865849250644[299] = 0; + out_956757865849250644[300] = 0; + out_956757865849250644[301] = 0; + out_956757865849250644[302] = 0; + out_956757865849250644[303] = 0; + out_956757865849250644[304] = 0; + out_956757865849250644[305] = 0; + out_956757865849250644[306] = 0; + out_956757865849250644[307] = 0; + out_956757865849250644[308] = 1; + out_956757865849250644[309] = 0; + out_956757865849250644[310] = 0; + out_956757865849250644[311] = 0; + out_956757865849250644[312] = 0; + out_956757865849250644[313] = 0; + out_956757865849250644[314] = 0; + out_956757865849250644[315] = 0; + out_956757865849250644[316] = 0; + out_956757865849250644[317] = 0; + out_956757865849250644[318] = 0; + out_956757865849250644[319] = 0; + out_956757865849250644[320] = 0; + out_956757865849250644[321] = 0; + out_956757865849250644[322] = 0; + out_956757865849250644[323] = 0; + out_956757865849250644[324] = 0; + out_956757865849250644[325] = 0; + out_956757865849250644[326] = 0; + out_956757865849250644[327] = 0; + out_956757865849250644[328] = 0; + out_956757865849250644[329] = 0; + out_956757865849250644[330] = 1; + out_956757865849250644[331] = 0; + out_956757865849250644[332] = 0; + out_956757865849250644[333] = 0; + out_956757865849250644[334] = 0; + out_956757865849250644[335] = 0; + out_956757865849250644[336] = 0; + out_956757865849250644[337] = 0; + out_956757865849250644[338] = 0; + out_956757865849250644[339] = 0; + out_956757865849250644[340] = 0; + out_956757865849250644[341] = 0; + out_956757865849250644[342] = 0; + out_956757865849250644[343] = 0; + out_956757865849250644[344] = 0; + out_956757865849250644[345] = 0; + out_956757865849250644[346] = 0; + out_956757865849250644[347] = 0; + out_956757865849250644[348] = 0; + out_956757865849250644[349] = 0; + out_956757865849250644[350] = 0; + out_956757865849250644[351] = 0; + out_956757865849250644[352] = 1; + out_956757865849250644[353] = 0; + out_956757865849250644[354] = 0; + out_956757865849250644[355] = 0; + out_956757865849250644[356] = 0; + out_956757865849250644[357] = 0; + out_956757865849250644[358] = 0; + out_956757865849250644[359] = 0; + out_956757865849250644[360] = 0; + out_956757865849250644[361] = 0; + out_956757865849250644[362] = 0; + out_956757865849250644[363] = 0; + out_956757865849250644[364] = 0; + out_956757865849250644[365] = 0; + out_956757865849250644[366] = 0; + out_956757865849250644[367] = 0; + out_956757865849250644[368] = 0; + out_956757865849250644[369] = 0; + out_956757865849250644[370] = 0; + out_956757865849250644[371] = 0; + out_956757865849250644[372] = 0; + out_956757865849250644[373] = 0; + out_956757865849250644[374] = 1; + out_956757865849250644[375] = 0; + out_956757865849250644[376] = 0; + out_956757865849250644[377] = 0; + out_956757865849250644[378] = 0; + out_956757865849250644[379] = 0; + out_956757865849250644[380] = 0; + out_956757865849250644[381] = 0; + out_956757865849250644[382] = 0; + out_956757865849250644[383] = 0; + out_956757865849250644[384] = 0; + out_956757865849250644[385] = 0; + out_956757865849250644[386] = 0; + out_956757865849250644[387] = 0; + out_956757865849250644[388] = 0; + out_956757865849250644[389] = 0; + out_956757865849250644[390] = 0; + out_956757865849250644[391] = 0; + out_956757865849250644[392] = 0; + out_956757865849250644[393] = 0; + out_956757865849250644[394] = 0; + out_956757865849250644[395] = 0; + out_956757865849250644[396] = 1; + out_956757865849250644[397] = 0; + out_956757865849250644[398] = 0; + out_956757865849250644[399] = 0; + out_956757865849250644[400] = 0; + out_956757865849250644[401] = 0; + out_956757865849250644[402] = 0; + out_956757865849250644[403] = 0; + out_956757865849250644[404] = 0; + out_956757865849250644[405] = 0; + out_956757865849250644[406] = 0; + out_956757865849250644[407] = 0; + out_956757865849250644[408] = 0; + out_956757865849250644[409] = 0; + out_956757865849250644[410] = 0; + out_956757865849250644[411] = 0; + out_956757865849250644[412] = 0; + out_956757865849250644[413] = 0; + out_956757865849250644[414] = 0; + out_956757865849250644[415] = 0; + out_956757865849250644[416] = 0; + out_956757865849250644[417] = 0; + out_956757865849250644[418] = 1; + out_956757865849250644[419] = 0; + out_956757865849250644[420] = 0; + out_956757865849250644[421] = 0; + out_956757865849250644[422] = 0; + out_956757865849250644[423] = 0; + out_956757865849250644[424] = 0; + out_956757865849250644[425] = 0; + out_956757865849250644[426] = 0; + out_956757865849250644[427] = 0; + out_956757865849250644[428] = 0; + out_956757865849250644[429] = 0; + out_956757865849250644[430] = 0; + out_956757865849250644[431] = 0; + out_956757865849250644[432] = 0; + out_956757865849250644[433] = 0; + out_956757865849250644[434] = 0; + out_956757865849250644[435] = 0; + out_956757865849250644[436] = 0; + out_956757865849250644[437] = 0; + out_956757865849250644[438] = 0; + out_956757865849250644[439] = 0; + out_956757865849250644[440] = 1; } -void h_4(double *state, double *unused, double *out_1938047718740512528) { - out_1938047718740512528[0] = state[10] + state[13]; - out_1938047718740512528[1] = state[11] + state[14]; - out_1938047718740512528[2] = state[12] + state[15]; +void h_4(double *state, double *unused, double *out_396243034408503816) { + out_396243034408503816[0] = state[10] + state[13]; + out_396243034408503816[1] = state[11] + state[14]; + out_396243034408503816[2] = state[12] + state[15]; } -void H_4(double *state, double *unused, double *out_8437989887064667391) { - out_8437989887064667391[0] = 0; - out_8437989887064667391[1] = 0; - out_8437989887064667391[2] = 0; - out_8437989887064667391[3] = 0; - out_8437989887064667391[4] = 0; - out_8437989887064667391[5] = 0; - out_8437989887064667391[6] = 0; - out_8437989887064667391[7] = 0; - out_8437989887064667391[8] = 0; - out_8437989887064667391[9] = 0; - out_8437989887064667391[10] = 1; - out_8437989887064667391[11] = 0; - out_8437989887064667391[12] = 0; - out_8437989887064667391[13] = 1; - out_8437989887064667391[14] = 0; - out_8437989887064667391[15] = 0; - out_8437989887064667391[16] = 0; - out_8437989887064667391[17] = 0; - out_8437989887064667391[18] = 0; - out_8437989887064667391[19] = 0; - out_8437989887064667391[20] = 0; - out_8437989887064667391[21] = 0; - out_8437989887064667391[22] = 0; - out_8437989887064667391[23] = 0; - out_8437989887064667391[24] = 0; - out_8437989887064667391[25] = 0; - out_8437989887064667391[26] = 0; - out_8437989887064667391[27] = 0; - out_8437989887064667391[28] = 0; - out_8437989887064667391[29] = 0; - out_8437989887064667391[30] = 0; - out_8437989887064667391[31] = 0; - out_8437989887064667391[32] = 0; - out_8437989887064667391[33] = 1; - out_8437989887064667391[34] = 0; - out_8437989887064667391[35] = 0; - out_8437989887064667391[36] = 1; - out_8437989887064667391[37] = 0; - out_8437989887064667391[38] = 0; - out_8437989887064667391[39] = 0; - out_8437989887064667391[40] = 0; - out_8437989887064667391[41] = 0; - out_8437989887064667391[42] = 0; - out_8437989887064667391[43] = 0; - out_8437989887064667391[44] = 0; - out_8437989887064667391[45] = 0; - out_8437989887064667391[46] = 0; - out_8437989887064667391[47] = 0; - out_8437989887064667391[48] = 0; - out_8437989887064667391[49] = 0; - out_8437989887064667391[50] = 0; - out_8437989887064667391[51] = 0; - out_8437989887064667391[52] = 0; - out_8437989887064667391[53] = 0; - out_8437989887064667391[54] = 0; - out_8437989887064667391[55] = 0; - out_8437989887064667391[56] = 1; - out_8437989887064667391[57] = 0; - out_8437989887064667391[58] = 0; - out_8437989887064667391[59] = 1; - out_8437989887064667391[60] = 0; - out_8437989887064667391[61] = 0; - out_8437989887064667391[62] = 0; - out_8437989887064667391[63] = 0; - out_8437989887064667391[64] = 0; - out_8437989887064667391[65] = 0; +void H_4(double *state, double *unused, double *out_7955964066782090966) { + out_7955964066782090966[0] = 0; + out_7955964066782090966[1] = 0; + out_7955964066782090966[2] = 0; + out_7955964066782090966[3] = 0; + out_7955964066782090966[4] = 0; + out_7955964066782090966[5] = 0; + out_7955964066782090966[6] = 0; + out_7955964066782090966[7] = 0; + out_7955964066782090966[8] = 0; + out_7955964066782090966[9] = 0; + out_7955964066782090966[10] = 1; + out_7955964066782090966[11] = 0; + out_7955964066782090966[12] = 0; + out_7955964066782090966[13] = 1; + out_7955964066782090966[14] = 0; + out_7955964066782090966[15] = 0; + out_7955964066782090966[16] = 0; + out_7955964066782090966[17] = 0; + out_7955964066782090966[18] = 0; + out_7955964066782090966[19] = 0; + out_7955964066782090966[20] = 0; + out_7955964066782090966[21] = 0; + out_7955964066782090966[22] = 0; + out_7955964066782090966[23] = 0; + out_7955964066782090966[24] = 0; + out_7955964066782090966[25] = 0; + out_7955964066782090966[26] = 0; + out_7955964066782090966[27] = 0; + out_7955964066782090966[28] = 0; + out_7955964066782090966[29] = 0; + out_7955964066782090966[30] = 0; + out_7955964066782090966[31] = 0; + out_7955964066782090966[32] = 0; + out_7955964066782090966[33] = 1; + out_7955964066782090966[34] = 0; + out_7955964066782090966[35] = 0; + out_7955964066782090966[36] = 1; + out_7955964066782090966[37] = 0; + out_7955964066782090966[38] = 0; + out_7955964066782090966[39] = 0; + out_7955964066782090966[40] = 0; + out_7955964066782090966[41] = 0; + out_7955964066782090966[42] = 0; + out_7955964066782090966[43] = 0; + out_7955964066782090966[44] = 0; + out_7955964066782090966[45] = 0; + out_7955964066782090966[46] = 0; + out_7955964066782090966[47] = 0; + out_7955964066782090966[48] = 0; + out_7955964066782090966[49] = 0; + out_7955964066782090966[50] = 0; + out_7955964066782090966[51] = 0; + out_7955964066782090966[52] = 0; + out_7955964066782090966[53] = 0; + out_7955964066782090966[54] = 0; + out_7955964066782090966[55] = 0; + out_7955964066782090966[56] = 1; + out_7955964066782090966[57] = 0; + out_7955964066782090966[58] = 0; + out_7955964066782090966[59] = 1; + out_7955964066782090966[60] = 0; + out_7955964066782090966[61] = 0; + out_7955964066782090966[62] = 0; + out_7955964066782090966[63] = 0; + out_7955964066782090966[64] = 0; + out_7955964066782090966[65] = 0; } -void h_9(double *state, double *unused, double *out_2016376091952434025) { - out_2016376091952434025[0] = state[10]; - out_2016376091952434025[1] = state[11]; - out_2016376091952434025[2] = state[12]; +void h_9(double *state, double *unused, double *out_3280179861815054133) { + out_3280179861815054133[0] = state[10]; + out_3280179861815054133[1] = state[11]; + out_3280179861815054133[2] = state[12]; } -void H_9(double *state, double *unused, double *out_2721535251380436755) { - out_2721535251380436755[0] = 0; - out_2721535251380436755[1] = 0; - out_2721535251380436755[2] = 0; - out_2721535251380436755[3] = 0; - out_2721535251380436755[4] = 0; - out_2721535251380436755[5] = 0; - out_2721535251380436755[6] = 0; - out_2721535251380436755[7] = 0; - out_2721535251380436755[8] = 0; - out_2721535251380436755[9] = 0; - out_2721535251380436755[10] = 1; - out_2721535251380436755[11] = 0; - out_2721535251380436755[12] = 0; - out_2721535251380436755[13] = 0; - out_2721535251380436755[14] = 0; - out_2721535251380436755[15] = 0; - out_2721535251380436755[16] = 0; - out_2721535251380436755[17] = 0; - out_2721535251380436755[18] = 0; - out_2721535251380436755[19] = 0; - out_2721535251380436755[20] = 0; - out_2721535251380436755[21] = 0; - out_2721535251380436755[22] = 0; - out_2721535251380436755[23] = 0; - out_2721535251380436755[24] = 0; - out_2721535251380436755[25] = 0; - out_2721535251380436755[26] = 0; - out_2721535251380436755[27] = 0; - out_2721535251380436755[28] = 0; - out_2721535251380436755[29] = 0; - out_2721535251380436755[30] = 0; - out_2721535251380436755[31] = 0; - out_2721535251380436755[32] = 0; - out_2721535251380436755[33] = 1; - out_2721535251380436755[34] = 0; - out_2721535251380436755[35] = 0; - out_2721535251380436755[36] = 0; - out_2721535251380436755[37] = 0; - out_2721535251380436755[38] = 0; - out_2721535251380436755[39] = 0; - out_2721535251380436755[40] = 0; - out_2721535251380436755[41] = 0; - out_2721535251380436755[42] = 0; - out_2721535251380436755[43] = 0; - out_2721535251380436755[44] = 0; - out_2721535251380436755[45] = 0; - out_2721535251380436755[46] = 0; - out_2721535251380436755[47] = 0; - out_2721535251380436755[48] = 0; - out_2721535251380436755[49] = 0; - out_2721535251380436755[50] = 0; - out_2721535251380436755[51] = 0; - out_2721535251380436755[52] = 0; - out_2721535251380436755[53] = 0; - out_2721535251380436755[54] = 0; - out_2721535251380436755[55] = 0; - out_2721535251380436755[56] = 1; - out_2721535251380436755[57] = 0; - out_2721535251380436755[58] = 0; - out_2721535251380436755[59] = 0; - out_2721535251380436755[60] = 0; - out_2721535251380436755[61] = 0; - out_2721535251380436755[62] = 0; - out_2721535251380436755[63] = 0; - out_2721535251380436755[64] = 0; - out_2721535251380436755[65] = 0; +void H_9(double *state, double *unused, double *out_8197153713411681611) { + out_8197153713411681611[0] = 0; + out_8197153713411681611[1] = 0; + out_8197153713411681611[2] = 0; + out_8197153713411681611[3] = 0; + out_8197153713411681611[4] = 0; + out_8197153713411681611[5] = 0; + out_8197153713411681611[6] = 0; + out_8197153713411681611[7] = 0; + out_8197153713411681611[8] = 0; + out_8197153713411681611[9] = 0; + out_8197153713411681611[10] = 1; + out_8197153713411681611[11] = 0; + out_8197153713411681611[12] = 0; + out_8197153713411681611[13] = 0; + out_8197153713411681611[14] = 0; + out_8197153713411681611[15] = 0; + out_8197153713411681611[16] = 0; + out_8197153713411681611[17] = 0; + out_8197153713411681611[18] = 0; + out_8197153713411681611[19] = 0; + out_8197153713411681611[20] = 0; + out_8197153713411681611[21] = 0; + out_8197153713411681611[22] = 0; + out_8197153713411681611[23] = 0; + out_8197153713411681611[24] = 0; + out_8197153713411681611[25] = 0; + out_8197153713411681611[26] = 0; + out_8197153713411681611[27] = 0; + out_8197153713411681611[28] = 0; + out_8197153713411681611[29] = 0; + out_8197153713411681611[30] = 0; + out_8197153713411681611[31] = 0; + out_8197153713411681611[32] = 0; + out_8197153713411681611[33] = 1; + out_8197153713411681611[34] = 0; + out_8197153713411681611[35] = 0; + out_8197153713411681611[36] = 0; + out_8197153713411681611[37] = 0; + out_8197153713411681611[38] = 0; + out_8197153713411681611[39] = 0; + out_8197153713411681611[40] = 0; + out_8197153713411681611[41] = 0; + out_8197153713411681611[42] = 0; + out_8197153713411681611[43] = 0; + out_8197153713411681611[44] = 0; + out_8197153713411681611[45] = 0; + out_8197153713411681611[46] = 0; + out_8197153713411681611[47] = 0; + out_8197153713411681611[48] = 0; + out_8197153713411681611[49] = 0; + out_8197153713411681611[50] = 0; + out_8197153713411681611[51] = 0; + out_8197153713411681611[52] = 0; + out_8197153713411681611[53] = 0; + out_8197153713411681611[54] = 0; + out_8197153713411681611[55] = 0; + out_8197153713411681611[56] = 1; + out_8197153713411681611[57] = 0; + out_8197153713411681611[58] = 0; + out_8197153713411681611[59] = 0; + out_8197153713411681611[60] = 0; + out_8197153713411681611[61] = 0; + out_8197153713411681611[62] = 0; + out_8197153713411681611[63] = 0; + out_8197153713411681611[64] = 0; + out_8197153713411681611[65] = 0; } -void h_10(double *state, double *unused, double *out_8252027734007822314) { - out_8252027734007822314[0] = 398600500000000.0*(-2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2] + 398600500000000.0*(2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1] + 398600500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*(pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2))*state[0] + state[16] + state[19]; - out_8252027734007822314[1] = 398600500000000.0*(2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2] + 398600500000000.0*(-2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0] + 398600500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*(pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2))*state[1] + state[17] + state[20]; - out_8252027734007822314[2] = 398600500000000.0*(-2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1] + 398600500000000.0*(2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0] + 398600500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*(pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[2] + state[18] + state[21]; +void h_10(double *state, double *unused, double *out_7028739412274946671) { + out_7028739412274946671[0] = 398600500000000.0*(-2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2] + 398600500000000.0*(2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1] + 398600500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*(pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2))*state[0] + state[16] + state[19]; + out_7028739412274946671[1] = 398600500000000.0*(2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2] + 398600500000000.0*(-2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0] + 398600500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*(pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2))*state[1] + state[17] + state[20]; + out_7028739412274946671[2] = 398600500000000.0*(-2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1] + 398600500000000.0*(2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0] + 398600500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*(pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[2] + state[18] + state[21]; } -void H_10(double *state, double *unused, double *out_1022365631619946756) { - out_1022365631619946756[0] = -1195801500000000.0*(-2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[0]*state[2] - 1195801500000000.0*(2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[0]*state[1] - 1195801500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*(pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2))*pow(state[0], 2) + 398600500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*(pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2)); - out_1022365631619946756[1] = -1195801500000000.0*(-2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[1]*state[2] - 1195801500000000.0*(2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*pow(state[1], 2) + 398600500000000.0*(2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5) - 1195801500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*(pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2))*state[0]*state[1]; - out_1022365631619946756[2] = -1195801500000000.0*(-2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*pow(state[2], 2) + 398600500000000.0*(-2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5) - 1195801500000000.0*(2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[1]*state[2] - 1195801500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*(pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2))*state[0]*state[2]; - out_1022365631619946756[3] = 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[3] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[6] - 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[5]; - out_1022365631619946756[4] = 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[4] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[5] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[6]; - out_1022365631619946756[5] = -797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[5] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[4] - 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[3]; - out_1022365631619946756[6] = -797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[6] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[3] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[4]; - out_1022365631619946756[7] = 0; - out_1022365631619946756[8] = 0; - out_1022365631619946756[9] = 0; - out_1022365631619946756[10] = 0; - out_1022365631619946756[11] = 0; - out_1022365631619946756[12] = 0; - out_1022365631619946756[13] = 0; - out_1022365631619946756[14] = 0; - out_1022365631619946756[15] = 0; - out_1022365631619946756[16] = 1; - out_1022365631619946756[17] = 0; - out_1022365631619946756[18] = 0; - out_1022365631619946756[19] = 1; - out_1022365631619946756[20] = 0; - out_1022365631619946756[21] = 0; - out_1022365631619946756[22] = -1195801500000000.0*(2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[0]*state[2] - 1195801500000000.0*(-2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*pow(state[0], 2) + 398600500000000.0*(-2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5) - 1195801500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*(pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2))*state[0]*state[1]; - out_1022365631619946756[23] = -1195801500000000.0*(2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[1]*state[2] - 1195801500000000.0*(-2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[0]*state[1] - 1195801500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*(pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2))*pow(state[1], 2) + 398600500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*(pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2)); - out_1022365631619946756[24] = -1195801500000000.0*(2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*pow(state[2], 2) + 398600500000000.0*(2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5) - 1195801500000000.0*(-2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[0]*state[2] - 1195801500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*(pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2))*state[1]*state[2]; - out_1022365631619946756[25] = -797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[6] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[3] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[4]; - out_1022365631619946756[26] = 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[5] - 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[4] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[3]; - out_1022365631619946756[27] = 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[4] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[5] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[6]; - out_1022365631619946756[28] = -797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[3] - 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[6] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[5]; - out_1022365631619946756[29] = 0; - out_1022365631619946756[30] = 0; - out_1022365631619946756[31] = 0; - out_1022365631619946756[32] = 0; - out_1022365631619946756[33] = 0; - out_1022365631619946756[34] = 0; - out_1022365631619946756[35] = 0; - out_1022365631619946756[36] = 0; - out_1022365631619946756[37] = 0; - out_1022365631619946756[38] = 0; - out_1022365631619946756[39] = 1; - out_1022365631619946756[40] = 0; - out_1022365631619946756[41] = 0; - out_1022365631619946756[42] = 1; - out_1022365631619946756[43] = 0; - out_1022365631619946756[44] = -1195801500000000.0*(-2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[0]*state[1] - 1195801500000000.0*(2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*pow(state[0], 2) + 398600500000000.0*(2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5) - 1195801500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*(pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[0]*state[2]; - out_1022365631619946756[45] = -1195801500000000.0*(-2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*pow(state[1], 2) + 398600500000000.0*(-2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5) - 1195801500000000.0*(2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[0]*state[1] - 1195801500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*(pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[1]*state[2]; - out_1022365631619946756[46] = -1195801500000000.0*(-2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[1]*state[2] - 1195801500000000.0*(2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[0]*state[2] - 1195801500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*(pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*pow(state[2], 2) + 398600500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*(pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2)); - out_1022365631619946756[47] = 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[5] - 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[4] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[3]; - out_1022365631619946756[48] = 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[6] - 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[3] - 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[4]; - out_1022365631619946756[49] = 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[3] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[6] - 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[5]; - out_1022365631619946756[50] = 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[4] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[5] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[6]; - out_1022365631619946756[51] = 0; - out_1022365631619946756[52] = 0; - out_1022365631619946756[53] = 0; - out_1022365631619946756[54] = 0; - out_1022365631619946756[55] = 0; - out_1022365631619946756[56] = 0; - out_1022365631619946756[57] = 0; - out_1022365631619946756[58] = 0; - out_1022365631619946756[59] = 0; - out_1022365631619946756[60] = 0; - out_1022365631619946756[61] = 0; - out_1022365631619946756[62] = 1; - out_1022365631619946756[63] = 0; - out_1022365631619946756[64] = 0; - out_1022365631619946756[65] = 1; +void H_10(double *state, double *unused, double *out_5406505055183973833) { + out_5406505055183973833[0] = -1195801500000000.0*(-2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[0]*state[2] - 1195801500000000.0*(2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[0]*state[1] - 1195801500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*(pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2))*pow(state[0], 2) + 398600500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*(pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2)); + out_5406505055183973833[1] = -1195801500000000.0*(-2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[1]*state[2] - 1195801500000000.0*(2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*pow(state[1], 2) + 398600500000000.0*(2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5) - 1195801500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*(pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2))*state[0]*state[1]; + out_5406505055183973833[2] = -1195801500000000.0*(-2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*pow(state[2], 2) + 398600500000000.0*(-2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5) - 1195801500000000.0*(2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[1]*state[2] - 1195801500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*(pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2))*state[0]*state[2]; + out_5406505055183973833[3] = 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[3] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[6] - 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[5]; + out_5406505055183973833[4] = 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[4] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[5] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[6]; + out_5406505055183973833[5] = -797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[5] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[4] - 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[3]; + out_5406505055183973833[6] = -797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[6] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[3] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[4]; + out_5406505055183973833[7] = 0; + out_5406505055183973833[8] = 0; + out_5406505055183973833[9] = 0; + out_5406505055183973833[10] = 0; + out_5406505055183973833[11] = 0; + out_5406505055183973833[12] = 0; + out_5406505055183973833[13] = 0; + out_5406505055183973833[14] = 0; + out_5406505055183973833[15] = 0; + out_5406505055183973833[16] = 1; + out_5406505055183973833[17] = 0; + out_5406505055183973833[18] = 0; + out_5406505055183973833[19] = 1; + out_5406505055183973833[20] = 0; + out_5406505055183973833[21] = 0; + out_5406505055183973833[22] = -1195801500000000.0*(2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[0]*state[2] - 1195801500000000.0*(-2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*pow(state[0], 2) + 398600500000000.0*(-2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5) - 1195801500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*(pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2))*state[0]*state[1]; + out_5406505055183973833[23] = -1195801500000000.0*(2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[1]*state[2] - 1195801500000000.0*(-2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[0]*state[1] - 1195801500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*(pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2))*pow(state[1], 2) + 398600500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*(pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2)); + out_5406505055183973833[24] = -1195801500000000.0*(2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*pow(state[2], 2) + 398600500000000.0*(2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5) - 1195801500000000.0*(-2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[0]*state[2] - 1195801500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*(pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2))*state[1]*state[2]; + out_5406505055183973833[25] = -797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[6] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[3] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[4]; + out_5406505055183973833[26] = 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[5] - 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[4] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[3]; + out_5406505055183973833[27] = 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[4] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[5] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[6]; + out_5406505055183973833[28] = -797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[3] - 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[6] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[5]; + out_5406505055183973833[29] = 0; + out_5406505055183973833[30] = 0; + out_5406505055183973833[31] = 0; + out_5406505055183973833[32] = 0; + out_5406505055183973833[33] = 0; + out_5406505055183973833[34] = 0; + out_5406505055183973833[35] = 0; + out_5406505055183973833[36] = 0; + out_5406505055183973833[37] = 0; + out_5406505055183973833[38] = 0; + out_5406505055183973833[39] = 1; + out_5406505055183973833[40] = 0; + out_5406505055183973833[41] = 0; + out_5406505055183973833[42] = 1; + out_5406505055183973833[43] = 0; + out_5406505055183973833[44] = -1195801500000000.0*(-2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[0]*state[1] - 1195801500000000.0*(2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*pow(state[0], 2) + 398600500000000.0*(2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5) - 1195801500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*(pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[0]*state[2]; + out_5406505055183973833[45] = -1195801500000000.0*(-2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*pow(state[1], 2) + 398600500000000.0*(-2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5) - 1195801500000000.0*(2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[0]*state[1] - 1195801500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*(pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[1]*state[2]; + out_5406505055183973833[46] = -1195801500000000.0*(-2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[1]*state[2] - 1195801500000000.0*(2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[0]*state[2] - 1195801500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*(pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*pow(state[2], 2) + 398600500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*(pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2)); + out_5406505055183973833[47] = 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[5] - 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[4] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[3]; + out_5406505055183973833[48] = 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[6] - 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[3] - 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[4]; + out_5406505055183973833[49] = 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[3] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[6] - 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[5]; + out_5406505055183973833[50] = 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[4] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[5] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[6]; + out_5406505055183973833[51] = 0; + out_5406505055183973833[52] = 0; + out_5406505055183973833[53] = 0; + out_5406505055183973833[54] = 0; + out_5406505055183973833[55] = 0; + out_5406505055183973833[56] = 0; + out_5406505055183973833[57] = 0; + out_5406505055183973833[58] = 0; + out_5406505055183973833[59] = 0; + out_5406505055183973833[60] = 0; + out_5406505055183973833[61] = 0; + out_5406505055183973833[62] = 1; + out_5406505055183973833[63] = 0; + out_5406505055183973833[64] = 0; + out_5406505055183973833[65] = 1; } -void h_12(double *state, double *unused, double *out_490832941153373832) { - out_490832941153373832[0] = state[0]; - out_490832941153373832[1] = state[1]; - out_490832941153373832[2] = state[2]; +void h_12(double *state, double *unused, double *out_2939119697401536762) { + out_2939119697401536762[0] = state[0]; + out_2939119697401536762[1] = state[1]; + out_2939119697401536762[2] = state[2]; } -void H_12(double *state, double *unused, double *out_4989297778612922430) { - out_4989297778612922430[0] = 1; - out_4989297778612922430[1] = 0; - out_4989297778612922430[2] = 0; - out_4989297778612922430[3] = 0; - out_4989297778612922430[4] = 0; - out_4989297778612922430[5] = 0; - out_4989297778612922430[6] = 0; - out_4989297778612922430[7] = 0; - out_4989297778612922430[8] = 0; - out_4989297778612922430[9] = 0; - out_4989297778612922430[10] = 0; - out_4989297778612922430[11] = 0; - out_4989297778612922430[12] = 0; - out_4989297778612922430[13] = 0; - out_4989297778612922430[14] = 0; - out_4989297778612922430[15] = 0; - out_4989297778612922430[16] = 0; - out_4989297778612922430[17] = 0; - out_4989297778612922430[18] = 0; - out_4989297778612922430[19] = 0; - out_4989297778612922430[20] = 0; - out_4989297778612922430[21] = 0; - out_4989297778612922430[22] = 0; - out_4989297778612922430[23] = 1; - out_4989297778612922430[24] = 0; - out_4989297778612922430[25] = 0; - out_4989297778612922430[26] = 0; - out_4989297778612922430[27] = 0; - out_4989297778612922430[28] = 0; - out_4989297778612922430[29] = 0; - out_4989297778612922430[30] = 0; - out_4989297778612922430[31] = 0; - out_4989297778612922430[32] = 0; - out_4989297778612922430[33] = 0; - out_4989297778612922430[34] = 0; - out_4989297778612922430[35] = 0; - out_4989297778612922430[36] = 0; - out_4989297778612922430[37] = 0; - out_4989297778612922430[38] = 0; - out_4989297778612922430[39] = 0; - out_4989297778612922430[40] = 0; - out_4989297778612922430[41] = 0; - out_4989297778612922430[42] = 0; - out_4989297778612922430[43] = 0; - out_4989297778612922430[44] = 0; - out_4989297778612922430[45] = 0; - out_4989297778612922430[46] = 1; - out_4989297778612922430[47] = 0; - out_4989297778612922430[48] = 0; - out_4989297778612922430[49] = 0; - out_4989297778612922430[50] = 0; - out_4989297778612922430[51] = 0; - out_4989297778612922430[52] = 0; - out_4989297778612922430[53] = 0; - out_4989297778612922430[54] = 0; - out_4989297778612922430[55] = 0; - out_4989297778612922430[56] = 0; - out_4989297778612922430[57] = 0; - out_4989297778612922430[58] = 0; - out_4989297778612922430[59] = 0; - out_4989297778612922430[60] = 0; - out_4989297778612922430[61] = 0; - out_4989297778612922430[62] = 0; - out_4989297778612922430[63] = 0; - out_4989297778612922430[64] = 0; - out_4989297778612922430[65] = 0; +void H_12(double *state, double *unused, double *out_8577063091829684633) { + out_8577063091829684633[0] = 1; + out_8577063091829684633[1] = 0; + out_8577063091829684633[2] = 0; + out_8577063091829684633[3] = 0; + out_8577063091829684633[4] = 0; + out_8577063091829684633[5] = 0; + out_8577063091829684633[6] = 0; + out_8577063091829684633[7] = 0; + out_8577063091829684633[8] = 0; + out_8577063091829684633[9] = 0; + out_8577063091829684633[10] = 0; + out_8577063091829684633[11] = 0; + out_8577063091829684633[12] = 0; + out_8577063091829684633[13] = 0; + out_8577063091829684633[14] = 0; + out_8577063091829684633[15] = 0; + out_8577063091829684633[16] = 0; + out_8577063091829684633[17] = 0; + out_8577063091829684633[18] = 0; + out_8577063091829684633[19] = 0; + out_8577063091829684633[20] = 0; + out_8577063091829684633[21] = 0; + out_8577063091829684633[22] = 0; + out_8577063091829684633[23] = 1; + out_8577063091829684633[24] = 0; + out_8577063091829684633[25] = 0; + out_8577063091829684633[26] = 0; + out_8577063091829684633[27] = 0; + out_8577063091829684633[28] = 0; + out_8577063091829684633[29] = 0; + out_8577063091829684633[30] = 0; + out_8577063091829684633[31] = 0; + out_8577063091829684633[32] = 0; + out_8577063091829684633[33] = 0; + out_8577063091829684633[34] = 0; + out_8577063091829684633[35] = 0; + out_8577063091829684633[36] = 0; + out_8577063091829684633[37] = 0; + out_8577063091829684633[38] = 0; + out_8577063091829684633[39] = 0; + out_8577063091829684633[40] = 0; + out_8577063091829684633[41] = 0; + out_8577063091829684633[42] = 0; + out_8577063091829684633[43] = 0; + out_8577063091829684633[44] = 0; + out_8577063091829684633[45] = 0; + out_8577063091829684633[46] = 1; + out_8577063091829684633[47] = 0; + out_8577063091829684633[48] = 0; + out_8577063091829684633[49] = 0; + out_8577063091829684633[50] = 0; + out_8577063091829684633[51] = 0; + out_8577063091829684633[52] = 0; + out_8577063091829684633[53] = 0; + out_8577063091829684633[54] = 0; + out_8577063091829684633[55] = 0; + out_8577063091829684633[56] = 0; + out_8577063091829684633[57] = 0; + out_8577063091829684633[58] = 0; + out_8577063091829684633[59] = 0; + out_8577063091829684633[60] = 0; + out_8577063091829684633[61] = 0; + out_8577063091829684633[62] = 0; + out_8577063091829684633[63] = 0; + out_8577063091829684633[64] = 0; + out_8577063091829684633[65] = 0; } -void h_35(double *state, double *unused, double *out_851812883202032952) { - out_851812883202032952[0] = state[7]; - out_851812883202032952[1] = state[8]; - out_851812883202032952[2] = state[9]; +void h_35(double *state, double *unused, double *out_3733220149839256661) { + out_3733220149839256661[0] = state[7]; + out_3733220149839256661[1] = state[8]; + out_3733220149839256661[2] = state[9]; } -void H_35(double *state, double *unused, double *out_6642092129272276849) { - out_6642092129272276849[0] = 0; - out_6642092129272276849[1] = 0; - out_6642092129272276849[2] = 0; - out_6642092129272276849[3] = 0; - out_6642092129272276849[4] = 0; - out_6642092129272276849[5] = 0; - out_6642092129272276849[6] = 0; - out_6642092129272276849[7] = 1; - out_6642092129272276849[8] = 0; - out_6642092129272276849[9] = 0; - out_6642092129272276849[10] = 0; - out_6642092129272276849[11] = 0; - out_6642092129272276849[12] = 0; - out_6642092129272276849[13] = 0; - out_6642092129272276849[14] = 0; - out_6642092129272276849[15] = 0; - out_6642092129272276849[16] = 0; - out_6642092129272276849[17] = 0; - out_6642092129272276849[18] = 0; - out_6642092129272276849[19] = 0; - out_6642092129272276849[20] = 0; - out_6642092129272276849[21] = 0; - out_6642092129272276849[22] = 0; - out_6642092129272276849[23] = 0; - out_6642092129272276849[24] = 0; - out_6642092129272276849[25] = 0; - out_6642092129272276849[26] = 0; - out_6642092129272276849[27] = 0; - out_6642092129272276849[28] = 0; - out_6642092129272276849[29] = 0; - out_6642092129272276849[30] = 1; - out_6642092129272276849[31] = 0; - out_6642092129272276849[32] = 0; - out_6642092129272276849[33] = 0; - out_6642092129272276849[34] = 0; - out_6642092129272276849[35] = 0; - out_6642092129272276849[36] = 0; - out_6642092129272276849[37] = 0; - out_6642092129272276849[38] = 0; - out_6642092129272276849[39] = 0; - out_6642092129272276849[40] = 0; - out_6642092129272276849[41] = 0; - out_6642092129272276849[42] = 0; - out_6642092129272276849[43] = 0; - out_6642092129272276849[44] = 0; - out_6642092129272276849[45] = 0; - out_6642092129272276849[46] = 0; - out_6642092129272276849[47] = 0; - out_6642092129272276849[48] = 0; - out_6642092129272276849[49] = 0; - out_6642092129272276849[50] = 0; - out_6642092129272276849[51] = 0; - out_6642092129272276849[52] = 0; - out_6642092129272276849[53] = 1; - out_6642092129272276849[54] = 0; - out_6642092129272276849[55] = 0; - out_6642092129272276849[56] = 0; - out_6642092129272276849[57] = 0; - out_6642092129272276849[58] = 0; - out_6642092129272276849[59] = 0; - out_6642092129272276849[60] = 0; - out_6642092129272276849[61] = 0; - out_6642092129272276849[62] = 0; - out_6642092129272276849[63] = 0; - out_6642092129272276849[64] = 0; - out_6642092129272276849[65] = 0; +void H_35(double *state, double *unused, double *out_7124117949554853274) { + out_7124117949554853274[0] = 0; + out_7124117949554853274[1] = 0; + out_7124117949554853274[2] = 0; + out_7124117949554853274[3] = 0; + out_7124117949554853274[4] = 0; + out_7124117949554853274[5] = 0; + out_7124117949554853274[6] = 0; + out_7124117949554853274[7] = 1; + out_7124117949554853274[8] = 0; + out_7124117949554853274[9] = 0; + out_7124117949554853274[10] = 0; + out_7124117949554853274[11] = 0; + out_7124117949554853274[12] = 0; + out_7124117949554853274[13] = 0; + out_7124117949554853274[14] = 0; + out_7124117949554853274[15] = 0; + out_7124117949554853274[16] = 0; + out_7124117949554853274[17] = 0; + out_7124117949554853274[18] = 0; + out_7124117949554853274[19] = 0; + out_7124117949554853274[20] = 0; + out_7124117949554853274[21] = 0; + out_7124117949554853274[22] = 0; + out_7124117949554853274[23] = 0; + out_7124117949554853274[24] = 0; + out_7124117949554853274[25] = 0; + out_7124117949554853274[26] = 0; + out_7124117949554853274[27] = 0; + out_7124117949554853274[28] = 0; + out_7124117949554853274[29] = 0; + out_7124117949554853274[30] = 1; + out_7124117949554853274[31] = 0; + out_7124117949554853274[32] = 0; + out_7124117949554853274[33] = 0; + out_7124117949554853274[34] = 0; + out_7124117949554853274[35] = 0; + out_7124117949554853274[36] = 0; + out_7124117949554853274[37] = 0; + out_7124117949554853274[38] = 0; + out_7124117949554853274[39] = 0; + out_7124117949554853274[40] = 0; + out_7124117949554853274[41] = 0; + out_7124117949554853274[42] = 0; + out_7124117949554853274[43] = 0; + out_7124117949554853274[44] = 0; + out_7124117949554853274[45] = 0; + out_7124117949554853274[46] = 0; + out_7124117949554853274[47] = 0; + out_7124117949554853274[48] = 0; + out_7124117949554853274[49] = 0; + out_7124117949554853274[50] = 0; + out_7124117949554853274[51] = 0; + out_7124117949554853274[52] = 0; + out_7124117949554853274[53] = 1; + out_7124117949554853274[54] = 0; + out_7124117949554853274[55] = 0; + out_7124117949554853274[56] = 0; + out_7124117949554853274[57] = 0; + out_7124117949554853274[58] = 0; + out_7124117949554853274[59] = 0; + out_7124117949554853274[60] = 0; + out_7124117949554853274[61] = 0; + out_7124117949554853274[62] = 0; + out_7124117949554853274[63] = 0; + out_7124117949554853274[64] = 0; + out_7124117949554853274[65] = 0; } -void h_32(double *state, double *unused, double *out_7198045605532929596) { - out_7198045605532929596[0] = state[3]; - out_7198045605532929596[1] = state[4]; - out_7198045605532929596[2] = state[5]; - out_7198045605532929596[3] = state[6]; +void h_32(double *state, double *unused, double *out_6268450557573639622) { + out_6268450557573639622[0] = state[3]; + out_6268450557573639622[1] = state[4]; + out_6268450557573639622[2] = state[5]; + out_6268450557573639622[3] = state[6]; } -void H_32(double *state, double *unused, double *out_6510927344331536380) { - out_6510927344331536380[0] = 0; - out_6510927344331536380[1] = 0; - out_6510927344331536380[2] = 0; - out_6510927344331536380[3] = 1; - out_6510927344331536380[4] = 0; - out_6510927344331536380[5] = 0; - out_6510927344331536380[6] = 0; - out_6510927344331536380[7] = 0; - out_6510927344331536380[8] = 0; - out_6510927344331536380[9] = 0; - out_6510927344331536380[10] = 0; - out_6510927344331536380[11] = 0; - out_6510927344331536380[12] = 0; - out_6510927344331536380[13] = 0; - out_6510927344331536380[14] = 0; - out_6510927344331536380[15] = 0; - out_6510927344331536380[16] = 0; - out_6510927344331536380[17] = 0; - out_6510927344331536380[18] = 0; - out_6510927344331536380[19] = 0; - out_6510927344331536380[20] = 0; - out_6510927344331536380[21] = 0; - out_6510927344331536380[22] = 0; - out_6510927344331536380[23] = 0; - out_6510927344331536380[24] = 0; - out_6510927344331536380[25] = 0; - out_6510927344331536380[26] = 1; - out_6510927344331536380[27] = 0; - out_6510927344331536380[28] = 0; - out_6510927344331536380[29] = 0; - out_6510927344331536380[30] = 0; - out_6510927344331536380[31] = 0; - out_6510927344331536380[32] = 0; - out_6510927344331536380[33] = 0; - out_6510927344331536380[34] = 0; - out_6510927344331536380[35] = 0; - out_6510927344331536380[36] = 0; - out_6510927344331536380[37] = 0; - out_6510927344331536380[38] = 0; - out_6510927344331536380[39] = 0; - out_6510927344331536380[40] = 0; - out_6510927344331536380[41] = 0; - out_6510927344331536380[42] = 0; - out_6510927344331536380[43] = 0; - out_6510927344331536380[44] = 0; - out_6510927344331536380[45] = 0; - out_6510927344331536380[46] = 0; - out_6510927344331536380[47] = 0; - out_6510927344331536380[48] = 0; - out_6510927344331536380[49] = 1; - out_6510927344331536380[50] = 0; - out_6510927344331536380[51] = 0; - out_6510927344331536380[52] = 0; - out_6510927344331536380[53] = 0; - out_6510927344331536380[54] = 0; - out_6510927344331536380[55] = 0; - out_6510927344331536380[56] = 0; - out_6510927344331536380[57] = 0; - out_6510927344331536380[58] = 0; - out_6510927344331536380[59] = 0; - out_6510927344331536380[60] = 0; - out_6510927344331536380[61] = 0; - out_6510927344331536380[62] = 0; - out_6510927344331536380[63] = 0; - out_6510927344331536380[64] = 0; - out_6510927344331536380[65] = 0; - out_6510927344331536380[66] = 0; - out_6510927344331536380[67] = 0; - out_6510927344331536380[68] = 0; - out_6510927344331536380[69] = 0; - out_6510927344331536380[70] = 0; - out_6510927344331536380[71] = 0; - out_6510927344331536380[72] = 1; - out_6510927344331536380[73] = 0; - out_6510927344331536380[74] = 0; - out_6510927344331536380[75] = 0; - out_6510927344331536380[76] = 0; - out_6510927344331536380[77] = 0; - out_6510927344331536380[78] = 0; - out_6510927344331536380[79] = 0; - out_6510927344331536380[80] = 0; - out_6510927344331536380[81] = 0; - out_6510927344331536380[82] = 0; - out_6510927344331536380[83] = 0; - out_6510927344331536380[84] = 0; - out_6510927344331536380[85] = 0; - out_6510927344331536380[86] = 0; - out_6510927344331536380[87] = 0; +void H_32(double *state, double *unused, double *out_4419093436653103337) { + out_4419093436653103337[0] = 0; + out_4419093436653103337[1] = 0; + out_4419093436653103337[2] = 0; + out_4419093436653103337[3] = 1; + out_4419093436653103337[4] = 0; + out_4419093436653103337[5] = 0; + out_4419093436653103337[6] = 0; + out_4419093436653103337[7] = 0; + out_4419093436653103337[8] = 0; + out_4419093436653103337[9] = 0; + out_4419093436653103337[10] = 0; + out_4419093436653103337[11] = 0; + out_4419093436653103337[12] = 0; + out_4419093436653103337[13] = 0; + out_4419093436653103337[14] = 0; + out_4419093436653103337[15] = 0; + out_4419093436653103337[16] = 0; + out_4419093436653103337[17] = 0; + out_4419093436653103337[18] = 0; + out_4419093436653103337[19] = 0; + out_4419093436653103337[20] = 0; + out_4419093436653103337[21] = 0; + out_4419093436653103337[22] = 0; + out_4419093436653103337[23] = 0; + out_4419093436653103337[24] = 0; + out_4419093436653103337[25] = 0; + out_4419093436653103337[26] = 1; + out_4419093436653103337[27] = 0; + out_4419093436653103337[28] = 0; + out_4419093436653103337[29] = 0; + out_4419093436653103337[30] = 0; + out_4419093436653103337[31] = 0; + out_4419093436653103337[32] = 0; + out_4419093436653103337[33] = 0; + out_4419093436653103337[34] = 0; + out_4419093436653103337[35] = 0; + out_4419093436653103337[36] = 0; + out_4419093436653103337[37] = 0; + out_4419093436653103337[38] = 0; + out_4419093436653103337[39] = 0; + out_4419093436653103337[40] = 0; + out_4419093436653103337[41] = 0; + out_4419093436653103337[42] = 0; + out_4419093436653103337[43] = 0; + out_4419093436653103337[44] = 0; + out_4419093436653103337[45] = 0; + out_4419093436653103337[46] = 0; + out_4419093436653103337[47] = 0; + out_4419093436653103337[48] = 0; + out_4419093436653103337[49] = 1; + out_4419093436653103337[50] = 0; + out_4419093436653103337[51] = 0; + out_4419093436653103337[52] = 0; + out_4419093436653103337[53] = 0; + out_4419093436653103337[54] = 0; + out_4419093436653103337[55] = 0; + out_4419093436653103337[56] = 0; + out_4419093436653103337[57] = 0; + out_4419093436653103337[58] = 0; + out_4419093436653103337[59] = 0; + out_4419093436653103337[60] = 0; + out_4419093436653103337[61] = 0; + out_4419093436653103337[62] = 0; + out_4419093436653103337[63] = 0; + out_4419093436653103337[64] = 0; + out_4419093436653103337[65] = 0; + out_4419093436653103337[66] = 0; + out_4419093436653103337[67] = 0; + out_4419093436653103337[68] = 0; + out_4419093436653103337[69] = 0; + out_4419093436653103337[70] = 0; + out_4419093436653103337[71] = 0; + out_4419093436653103337[72] = 1; + out_4419093436653103337[73] = 0; + out_4419093436653103337[74] = 0; + out_4419093436653103337[75] = 0; + out_4419093436653103337[76] = 0; + out_4419093436653103337[77] = 0; + out_4419093436653103337[78] = 0; + out_4419093436653103337[79] = 0; + out_4419093436653103337[80] = 0; + out_4419093436653103337[81] = 0; + out_4419093436653103337[82] = 0; + out_4419093436653103337[83] = 0; + out_4419093436653103337[84] = 0; + out_4419093436653103337[85] = 0; + out_4419093436653103337[86] = 0; + out_4419093436653103337[87] = 0; } -void h_13(double *state, double *unused, double *out_6813957582124674447) { - out_6813957582124674447[0] = (-2*state[3]*state[5] + 2*state[4]*state[6])*state[9] + (2*state[3]*state[6] + 2*state[4]*state[5])*state[8] + (pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2))*state[7]; - out_6813957582124674447[1] = (2*state[3]*state[4] + 2*state[5]*state[6])*state[9] + (-2*state[3]*state[6] + 2*state[4]*state[5])*state[7] + (pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2))*state[8]; - out_6813957582124674447[2] = (-2*state[3]*state[4] + 2*state[5]*state[6])*state[8] + (2*state[3]*state[5] + 2*state[4]*state[6])*state[7] + (pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[9]; +void h_13(double *state, double *unused, double *out_7986377932969783217) { + out_7986377932969783217[0] = (-2*state[3]*state[5] + 2*state[4]*state[6])*state[9] + (2*state[3]*state[6] + 2*state[4]*state[5])*state[8] + (pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2))*state[7]; + out_7986377932969783217[1] = (2*state[3]*state[4] + 2*state[5]*state[6])*state[9] + (-2*state[3]*state[6] + 2*state[4]*state[5])*state[7] + (pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2))*state[8]; + out_7986377932969783217[2] = (-2*state[3]*state[4] + 2*state[5]*state[6])*state[8] + (2*state[3]*state[5] + 2*state[4]*state[6])*state[7] + (pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[9]; } -void H_13(double *state, double *unused, double *out_7851984426394690165) { - out_7851984426394690165[0] = 0; - out_7851984426394690165[1] = 0; - out_7851984426394690165[2] = 0; - out_7851984426394690165[3] = 2*state[3]*state[7] - 2*state[5]*state[9] + 2*state[6]*state[8]; - out_7851984426394690165[4] = 2*state[4]*state[7] + 2*state[5]*state[8] + 2*state[6]*state[9]; - out_7851984426394690165[5] = -2*state[3]*state[9] + 2*state[4]*state[8] - 2*state[5]*state[7]; - out_7851984426394690165[6] = 2*state[3]*state[8] + 2*state[4]*state[9] - 2*state[6]*state[7]; - out_7851984426394690165[7] = pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2); - out_7851984426394690165[8] = 2*state[3]*state[6] + 2*state[4]*state[5]; - out_7851984426394690165[9] = -2*state[3]*state[5] + 2*state[4]*state[6]; - out_7851984426394690165[10] = 0; - out_7851984426394690165[11] = 0; - out_7851984426394690165[12] = 0; - out_7851984426394690165[13] = 0; - out_7851984426394690165[14] = 0; - out_7851984426394690165[15] = 0; - out_7851984426394690165[16] = 0; - out_7851984426394690165[17] = 0; - out_7851984426394690165[18] = 0; - out_7851984426394690165[19] = 0; - out_7851984426394690165[20] = 0; - out_7851984426394690165[21] = 0; - out_7851984426394690165[22] = 0; - out_7851984426394690165[23] = 0; - out_7851984426394690165[24] = 0; - out_7851984426394690165[25] = 2*state[3]*state[8] + 2*state[4]*state[9] - 2*state[6]*state[7]; - out_7851984426394690165[26] = 2*state[3]*state[9] - 2*state[4]*state[8] + 2*state[5]*state[7]; - out_7851984426394690165[27] = 2*state[4]*state[7] + 2*state[5]*state[8] + 2*state[6]*state[9]; - out_7851984426394690165[28] = -2*state[3]*state[7] + 2*state[5]*state[9] - 2*state[6]*state[8]; - out_7851984426394690165[29] = -2*state[3]*state[6] + 2*state[4]*state[5]; - out_7851984426394690165[30] = pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2); - out_7851984426394690165[31] = 2*state[3]*state[4] + 2*state[5]*state[6]; - out_7851984426394690165[32] = 0; - out_7851984426394690165[33] = 0; - out_7851984426394690165[34] = 0; - out_7851984426394690165[35] = 0; - out_7851984426394690165[36] = 0; - out_7851984426394690165[37] = 0; - out_7851984426394690165[38] = 0; - out_7851984426394690165[39] = 0; - out_7851984426394690165[40] = 0; - out_7851984426394690165[41] = 0; - out_7851984426394690165[42] = 0; - out_7851984426394690165[43] = 0; - out_7851984426394690165[44] = 0; - out_7851984426394690165[45] = 0; - out_7851984426394690165[46] = 0; - out_7851984426394690165[47] = 2*state[3]*state[9] - 2*state[4]*state[8] + 2*state[5]*state[7]; - out_7851984426394690165[48] = -2*state[3]*state[8] - 2*state[4]*state[9] + 2*state[6]*state[7]; - out_7851984426394690165[49] = 2*state[3]*state[7] - 2*state[5]*state[9] + 2*state[6]*state[8]; - out_7851984426394690165[50] = 2*state[4]*state[7] + 2*state[5]*state[8] + 2*state[6]*state[9]; - out_7851984426394690165[51] = 2*state[3]*state[5] + 2*state[4]*state[6]; - out_7851984426394690165[52] = -2*state[3]*state[4] + 2*state[5]*state[6]; - out_7851984426394690165[53] = pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2); - out_7851984426394690165[54] = 0; - out_7851984426394690165[55] = 0; - out_7851984426394690165[56] = 0; - out_7851984426394690165[57] = 0; - out_7851984426394690165[58] = 0; - out_7851984426394690165[59] = 0; - out_7851984426394690165[60] = 0; - out_7851984426394690165[61] = 0; - out_7851984426394690165[62] = 0; - out_7851984426394690165[63] = 0; - out_7851984426394690165[64] = 0; - out_7851984426394690165[65] = 0; +void H_13(double *state, double *unused, double *out_276341309716065550) { + out_276341309716065550[0] = 0; + out_276341309716065550[1] = 0; + out_276341309716065550[2] = 0; + out_276341309716065550[3] = 2*state[3]*state[7] - 2*state[5]*state[9] + 2*state[6]*state[8]; + out_276341309716065550[4] = 2*state[4]*state[7] + 2*state[5]*state[8] + 2*state[6]*state[9]; + out_276341309716065550[5] = -2*state[3]*state[9] + 2*state[4]*state[8] - 2*state[5]*state[7]; + out_276341309716065550[6] = 2*state[3]*state[8] + 2*state[4]*state[9] - 2*state[6]*state[7]; + out_276341309716065550[7] = pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2); + out_276341309716065550[8] = 2*state[3]*state[6] + 2*state[4]*state[5]; + out_276341309716065550[9] = -2*state[3]*state[5] + 2*state[4]*state[6]; + out_276341309716065550[10] = 0; + out_276341309716065550[11] = 0; + out_276341309716065550[12] = 0; + out_276341309716065550[13] = 0; + out_276341309716065550[14] = 0; + out_276341309716065550[15] = 0; + out_276341309716065550[16] = 0; + out_276341309716065550[17] = 0; + out_276341309716065550[18] = 0; + out_276341309716065550[19] = 0; + out_276341309716065550[20] = 0; + out_276341309716065550[21] = 0; + out_276341309716065550[22] = 0; + out_276341309716065550[23] = 0; + out_276341309716065550[24] = 0; + out_276341309716065550[25] = 2*state[3]*state[8] + 2*state[4]*state[9] - 2*state[6]*state[7]; + out_276341309716065550[26] = 2*state[3]*state[9] - 2*state[4]*state[8] + 2*state[5]*state[7]; + out_276341309716065550[27] = 2*state[4]*state[7] + 2*state[5]*state[8] + 2*state[6]*state[9]; + out_276341309716065550[28] = -2*state[3]*state[7] + 2*state[5]*state[9] - 2*state[6]*state[8]; + out_276341309716065550[29] = -2*state[3]*state[6] + 2*state[4]*state[5]; + out_276341309716065550[30] = pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2); + out_276341309716065550[31] = 2*state[3]*state[4] + 2*state[5]*state[6]; + out_276341309716065550[32] = 0; + out_276341309716065550[33] = 0; + out_276341309716065550[34] = 0; + out_276341309716065550[35] = 0; + out_276341309716065550[36] = 0; + out_276341309716065550[37] = 0; + out_276341309716065550[38] = 0; + out_276341309716065550[39] = 0; + out_276341309716065550[40] = 0; + out_276341309716065550[41] = 0; + out_276341309716065550[42] = 0; + out_276341309716065550[43] = 0; + out_276341309716065550[44] = 0; + out_276341309716065550[45] = 0; + out_276341309716065550[46] = 0; + out_276341309716065550[47] = 2*state[3]*state[9] - 2*state[4]*state[8] + 2*state[5]*state[7]; + out_276341309716065550[48] = -2*state[3]*state[8] - 2*state[4]*state[9] + 2*state[6]*state[7]; + out_276341309716065550[49] = 2*state[3]*state[7] - 2*state[5]*state[9] + 2*state[6]*state[8]; + out_276341309716065550[50] = 2*state[4]*state[7] + 2*state[5]*state[8] + 2*state[6]*state[9]; + out_276341309716065550[51] = 2*state[3]*state[5] + 2*state[4]*state[6]; + out_276341309716065550[52] = -2*state[3]*state[4] + 2*state[5]*state[6]; + out_276341309716065550[53] = pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2); + out_276341309716065550[54] = 0; + out_276341309716065550[55] = 0; + out_276341309716065550[56] = 0; + out_276341309716065550[57] = 0; + out_276341309716065550[58] = 0; + out_276341309716065550[59] = 0; + out_276341309716065550[60] = 0; + out_276341309716065550[61] = 0; + out_276341309716065550[62] = 0; + out_276341309716065550[63] = 0; + out_276341309716065550[64] = 0; + out_276341309716065550[65] = 0; } -void h_14(double *state, double *unused, double *out_2016376091952434025) { - out_2016376091952434025[0] = state[10]; - out_2016376091952434025[1] = state[11]; - out_2016376091952434025[2] = state[12]; +void h_14(double *state, double *unused, double *out_3280179861815054133) { + out_3280179861815054133[0] = state[10]; + out_3280179861815054133[1] = state[11]; + out_3280179861815054133[2] = state[12]; } -void H_14(double *state, double *unused, double *out_2721535251380436755) { - out_2721535251380436755[0] = 0; - out_2721535251380436755[1] = 0; - out_2721535251380436755[2] = 0; - out_2721535251380436755[3] = 0; - out_2721535251380436755[4] = 0; - out_2721535251380436755[5] = 0; - out_2721535251380436755[6] = 0; - out_2721535251380436755[7] = 0; - out_2721535251380436755[8] = 0; - out_2721535251380436755[9] = 0; - out_2721535251380436755[10] = 1; - out_2721535251380436755[11] = 0; - out_2721535251380436755[12] = 0; - out_2721535251380436755[13] = 0; - out_2721535251380436755[14] = 0; - out_2721535251380436755[15] = 0; - out_2721535251380436755[16] = 0; - out_2721535251380436755[17] = 0; - out_2721535251380436755[18] = 0; - out_2721535251380436755[19] = 0; - out_2721535251380436755[20] = 0; - out_2721535251380436755[21] = 0; - out_2721535251380436755[22] = 0; - out_2721535251380436755[23] = 0; - out_2721535251380436755[24] = 0; - out_2721535251380436755[25] = 0; - out_2721535251380436755[26] = 0; - out_2721535251380436755[27] = 0; - out_2721535251380436755[28] = 0; - out_2721535251380436755[29] = 0; - out_2721535251380436755[30] = 0; - out_2721535251380436755[31] = 0; - out_2721535251380436755[32] = 0; - out_2721535251380436755[33] = 1; - out_2721535251380436755[34] = 0; - out_2721535251380436755[35] = 0; - out_2721535251380436755[36] = 0; - out_2721535251380436755[37] = 0; - out_2721535251380436755[38] = 0; - out_2721535251380436755[39] = 0; - out_2721535251380436755[40] = 0; - out_2721535251380436755[41] = 0; - out_2721535251380436755[42] = 0; - out_2721535251380436755[43] = 0; - out_2721535251380436755[44] = 0; - out_2721535251380436755[45] = 0; - out_2721535251380436755[46] = 0; - out_2721535251380436755[47] = 0; - out_2721535251380436755[48] = 0; - out_2721535251380436755[49] = 0; - out_2721535251380436755[50] = 0; - out_2721535251380436755[51] = 0; - out_2721535251380436755[52] = 0; - out_2721535251380436755[53] = 0; - out_2721535251380436755[54] = 0; - out_2721535251380436755[55] = 0; - out_2721535251380436755[56] = 1; - out_2721535251380436755[57] = 0; - out_2721535251380436755[58] = 0; - out_2721535251380436755[59] = 0; - out_2721535251380436755[60] = 0; - out_2721535251380436755[61] = 0; - out_2721535251380436755[62] = 0; - out_2721535251380436755[63] = 0; - out_2721535251380436755[64] = 0; - out_2721535251380436755[65] = 0; +void H_14(double *state, double *unused, double *out_8197153713411681611) { + out_8197153713411681611[0] = 0; + out_8197153713411681611[1] = 0; + out_8197153713411681611[2] = 0; + out_8197153713411681611[3] = 0; + out_8197153713411681611[4] = 0; + out_8197153713411681611[5] = 0; + out_8197153713411681611[6] = 0; + out_8197153713411681611[7] = 0; + out_8197153713411681611[8] = 0; + out_8197153713411681611[9] = 0; + out_8197153713411681611[10] = 1; + out_8197153713411681611[11] = 0; + out_8197153713411681611[12] = 0; + out_8197153713411681611[13] = 0; + out_8197153713411681611[14] = 0; + out_8197153713411681611[15] = 0; + out_8197153713411681611[16] = 0; + out_8197153713411681611[17] = 0; + out_8197153713411681611[18] = 0; + out_8197153713411681611[19] = 0; + out_8197153713411681611[20] = 0; + out_8197153713411681611[21] = 0; + out_8197153713411681611[22] = 0; + out_8197153713411681611[23] = 0; + out_8197153713411681611[24] = 0; + out_8197153713411681611[25] = 0; + out_8197153713411681611[26] = 0; + out_8197153713411681611[27] = 0; + out_8197153713411681611[28] = 0; + out_8197153713411681611[29] = 0; + out_8197153713411681611[30] = 0; + out_8197153713411681611[31] = 0; + out_8197153713411681611[32] = 0; + out_8197153713411681611[33] = 1; + out_8197153713411681611[34] = 0; + out_8197153713411681611[35] = 0; + out_8197153713411681611[36] = 0; + out_8197153713411681611[37] = 0; + out_8197153713411681611[38] = 0; + out_8197153713411681611[39] = 0; + out_8197153713411681611[40] = 0; + out_8197153713411681611[41] = 0; + out_8197153713411681611[42] = 0; + out_8197153713411681611[43] = 0; + out_8197153713411681611[44] = 0; + out_8197153713411681611[45] = 0; + out_8197153713411681611[46] = 0; + out_8197153713411681611[47] = 0; + out_8197153713411681611[48] = 0; + out_8197153713411681611[49] = 0; + out_8197153713411681611[50] = 0; + out_8197153713411681611[51] = 0; + out_8197153713411681611[52] = 0; + out_8197153713411681611[53] = 0; + out_8197153713411681611[54] = 0; + out_8197153713411681611[55] = 0; + out_8197153713411681611[56] = 1; + out_8197153713411681611[57] = 0; + out_8197153713411681611[58] = 0; + out_8197153713411681611[59] = 0; + out_8197153713411681611[60] = 0; + out_8197153713411681611[61] = 0; + out_8197153713411681611[62] = 0; + out_8197153713411681611[63] = 0; + out_8197153713411681611[64] = 0; + out_8197153713411681611[65] = 0; } -void h_33(double *state, double *unused, double *out_1521077794722315231) { - out_1521077794722315231[0] = state[16]; - out_1521077794722315231[1] = state[17]; - out_1521077794722315231[2] = state[18]; +void h_33(double *state, double *unused, double *out_3797754961266519421) { + out_3797754961266519421[0] = state[16]; + out_3797754961266519421[1] = state[17]; + out_3797754961266519421[2] = state[18]; } -void H_33(double *state, double *unused, double *out_3491535124633419245) { - out_3491535124633419245[0] = 0; - out_3491535124633419245[1] = 0; - out_3491535124633419245[2] = 0; - out_3491535124633419245[3] = 0; - out_3491535124633419245[4] = 0; - out_3491535124633419245[5] = 0; - out_3491535124633419245[6] = 0; - out_3491535124633419245[7] = 0; - out_3491535124633419245[8] = 0; - out_3491535124633419245[9] = 0; - out_3491535124633419245[10] = 0; - out_3491535124633419245[11] = 0; - out_3491535124633419245[12] = 0; - out_3491535124633419245[13] = 0; - out_3491535124633419245[14] = 0; - out_3491535124633419245[15] = 0; - out_3491535124633419245[16] = 1; - out_3491535124633419245[17] = 0; - out_3491535124633419245[18] = 0; - out_3491535124633419245[19] = 0; - out_3491535124633419245[20] = 0; - out_3491535124633419245[21] = 0; - out_3491535124633419245[22] = 0; - out_3491535124633419245[23] = 0; - out_3491535124633419245[24] = 0; - out_3491535124633419245[25] = 0; - out_3491535124633419245[26] = 0; - out_3491535124633419245[27] = 0; - out_3491535124633419245[28] = 0; - out_3491535124633419245[29] = 0; - out_3491535124633419245[30] = 0; - out_3491535124633419245[31] = 0; - out_3491535124633419245[32] = 0; - out_3491535124633419245[33] = 0; - out_3491535124633419245[34] = 0; - out_3491535124633419245[35] = 0; - out_3491535124633419245[36] = 0; - out_3491535124633419245[37] = 0; - out_3491535124633419245[38] = 0; - out_3491535124633419245[39] = 1; - out_3491535124633419245[40] = 0; - out_3491535124633419245[41] = 0; - out_3491535124633419245[42] = 0; - out_3491535124633419245[43] = 0; - out_3491535124633419245[44] = 0; - out_3491535124633419245[45] = 0; - out_3491535124633419245[46] = 0; - out_3491535124633419245[47] = 0; - out_3491535124633419245[48] = 0; - out_3491535124633419245[49] = 0; - out_3491535124633419245[50] = 0; - out_3491535124633419245[51] = 0; - out_3491535124633419245[52] = 0; - out_3491535124633419245[53] = 0; - out_3491535124633419245[54] = 0; - out_3491535124633419245[55] = 0; - out_3491535124633419245[56] = 0; - out_3491535124633419245[57] = 0; - out_3491535124633419245[58] = 0; - out_3491535124633419245[59] = 0; - out_3491535124633419245[60] = 0; - out_3491535124633419245[61] = 0; - out_3491535124633419245[62] = 1; - out_3491535124633419245[63] = 0; - out_3491535124633419245[64] = 0; - out_3491535124633419245[65] = 0; +void H_33(double *state, double *unused, double *out_3973560944915995670) { + out_3973560944915995670[0] = 0; + out_3973560944915995670[1] = 0; + out_3973560944915995670[2] = 0; + out_3973560944915995670[3] = 0; + out_3973560944915995670[4] = 0; + out_3973560944915995670[5] = 0; + out_3973560944915995670[6] = 0; + out_3973560944915995670[7] = 0; + out_3973560944915995670[8] = 0; + out_3973560944915995670[9] = 0; + out_3973560944915995670[10] = 0; + out_3973560944915995670[11] = 0; + out_3973560944915995670[12] = 0; + out_3973560944915995670[13] = 0; + out_3973560944915995670[14] = 0; + out_3973560944915995670[15] = 0; + out_3973560944915995670[16] = 1; + out_3973560944915995670[17] = 0; + out_3973560944915995670[18] = 0; + out_3973560944915995670[19] = 0; + out_3973560944915995670[20] = 0; + out_3973560944915995670[21] = 0; + out_3973560944915995670[22] = 0; + out_3973560944915995670[23] = 0; + out_3973560944915995670[24] = 0; + out_3973560944915995670[25] = 0; + out_3973560944915995670[26] = 0; + out_3973560944915995670[27] = 0; + out_3973560944915995670[28] = 0; + out_3973560944915995670[29] = 0; + out_3973560944915995670[30] = 0; + out_3973560944915995670[31] = 0; + out_3973560944915995670[32] = 0; + out_3973560944915995670[33] = 0; + out_3973560944915995670[34] = 0; + out_3973560944915995670[35] = 0; + out_3973560944915995670[36] = 0; + out_3973560944915995670[37] = 0; + out_3973560944915995670[38] = 0; + out_3973560944915995670[39] = 1; + out_3973560944915995670[40] = 0; + out_3973560944915995670[41] = 0; + out_3973560944915995670[42] = 0; + out_3973560944915995670[43] = 0; + out_3973560944915995670[44] = 0; + out_3973560944915995670[45] = 0; + out_3973560944915995670[46] = 0; + out_3973560944915995670[47] = 0; + out_3973560944915995670[48] = 0; + out_3973560944915995670[49] = 0; + out_3973560944915995670[50] = 0; + out_3973560944915995670[51] = 0; + out_3973560944915995670[52] = 0; + out_3973560944915995670[53] = 0; + out_3973560944915995670[54] = 0; + out_3973560944915995670[55] = 0; + out_3973560944915995670[56] = 0; + out_3973560944915995670[57] = 0; + out_3973560944915995670[58] = 0; + out_3973560944915995670[59] = 0; + out_3973560944915995670[60] = 0; + out_3973560944915995670[61] = 0; + out_3973560944915995670[62] = 1; + out_3973560944915995670[63] = 0; + out_3973560944915995670[64] = 0; + out_3973560944915995670[65] = 0; } #include #include @@ -1855,77 +1855,77 @@ void live_update_14(double *in_x, double *in_P, double *in_z, double *in_R, doub void live_update_33(double *in_x, double *in_P, double *in_z, double *in_R, double *in_ea) { update<3, 3, 0>(in_x, in_P, h_33, H_33, NULL, in_z, in_R, in_ea, MAHA_THRESH_33); } -void live_H(double *in_vec, double *out_2107061543090158966) { - H(in_vec, out_2107061543090158966); +void live_H(double *in_vec, double *out_5027207160750161004) { + H(in_vec, out_5027207160750161004); } -void live_err_fun(double *nom_x, double *delta_x, double *out_1090842864546838841) { - err_fun(nom_x, delta_x, out_1090842864546838841); +void live_err_fun(double *nom_x, double *delta_x, double *out_812293829444590878) { + err_fun(nom_x, delta_x, out_812293829444590878); } -void live_inv_err_fun(double *nom_x, double *true_x, double *out_1751534880763809428) { - inv_err_fun(nom_x, true_x, out_1751534880763809428); +void live_inv_err_fun(double *nom_x, double *true_x, double *out_2331899367078236024) { + inv_err_fun(nom_x, true_x, out_2331899367078236024); } -void live_H_mod_fun(double *state, double *out_2270168032272230264) { - H_mod_fun(state, out_2270168032272230264); +void live_H_mod_fun(double *state, double *out_3350621260021879835) { + H_mod_fun(state, out_3350621260021879835); } -void live_f_fun(double *state, double dt, double *out_9047640957774126431) { - f_fun(state, dt, out_9047640957774126431); +void live_f_fun(double *state, double dt, double *out_9110479569516509106) { + f_fun(state, dt, out_9110479569516509106); } -void live_F_fun(double *state, double dt, double *out_4752414459068816126) { - F_fun(state, dt, out_4752414459068816126); +void live_F_fun(double *state, double dt, double *out_956757865849250644) { + F_fun(state, dt, out_956757865849250644); } -void live_h_4(double *state, double *unused, double *out_1938047718740512528) { - h_4(state, unused, out_1938047718740512528); +void live_h_4(double *state, double *unused, double *out_396243034408503816) { + h_4(state, unused, out_396243034408503816); } -void live_H_4(double *state, double *unused, double *out_8437989887064667391) { - H_4(state, unused, out_8437989887064667391); +void live_H_4(double *state, double *unused, double *out_7955964066782090966) { + H_4(state, unused, out_7955964066782090966); } -void live_h_9(double *state, double *unused, double *out_2016376091952434025) { - h_9(state, unused, out_2016376091952434025); +void live_h_9(double *state, double *unused, double *out_3280179861815054133) { + h_9(state, unused, out_3280179861815054133); } -void live_H_9(double *state, double *unused, double *out_2721535251380436755) { - H_9(state, unused, out_2721535251380436755); +void live_H_9(double *state, double *unused, double *out_8197153713411681611) { + H_9(state, unused, out_8197153713411681611); } -void live_h_10(double *state, double *unused, double *out_8252027734007822314) { - h_10(state, unused, out_8252027734007822314); +void live_h_10(double *state, double *unused, double *out_7028739412274946671) { + h_10(state, unused, out_7028739412274946671); } -void live_H_10(double *state, double *unused, double *out_1022365631619946756) { - H_10(state, unused, out_1022365631619946756); +void live_H_10(double *state, double *unused, double *out_5406505055183973833) { + H_10(state, unused, out_5406505055183973833); } -void live_h_12(double *state, double *unused, double *out_490832941153373832) { - h_12(state, unused, out_490832941153373832); +void live_h_12(double *state, double *unused, double *out_2939119697401536762) { + h_12(state, unused, out_2939119697401536762); } -void live_H_12(double *state, double *unused, double *out_4989297778612922430) { - H_12(state, unused, out_4989297778612922430); +void live_H_12(double *state, double *unused, double *out_8577063091829684633) { + H_12(state, unused, out_8577063091829684633); } -void live_h_35(double *state, double *unused, double *out_851812883202032952) { - h_35(state, unused, out_851812883202032952); +void live_h_35(double *state, double *unused, double *out_3733220149839256661) { + h_35(state, unused, out_3733220149839256661); } -void live_H_35(double *state, double *unused, double *out_6642092129272276849) { - H_35(state, unused, out_6642092129272276849); +void live_H_35(double *state, double *unused, double *out_7124117949554853274) { + H_35(state, unused, out_7124117949554853274); } -void live_h_32(double *state, double *unused, double *out_7198045605532929596) { - h_32(state, unused, out_7198045605532929596); +void live_h_32(double *state, double *unused, double *out_6268450557573639622) { + h_32(state, unused, out_6268450557573639622); } -void live_H_32(double *state, double *unused, double *out_6510927344331536380) { - H_32(state, unused, out_6510927344331536380); +void live_H_32(double *state, double *unused, double *out_4419093436653103337) { + H_32(state, unused, out_4419093436653103337); } -void live_h_13(double *state, double *unused, double *out_6813957582124674447) { - h_13(state, unused, out_6813957582124674447); +void live_h_13(double *state, double *unused, double *out_7986377932969783217) { + h_13(state, unused, out_7986377932969783217); } -void live_H_13(double *state, double *unused, double *out_7851984426394690165) { - H_13(state, unused, out_7851984426394690165); +void live_H_13(double *state, double *unused, double *out_276341309716065550) { + H_13(state, unused, out_276341309716065550); } -void live_h_14(double *state, double *unused, double *out_2016376091952434025) { - h_14(state, unused, out_2016376091952434025); +void live_h_14(double *state, double *unused, double *out_3280179861815054133) { + h_14(state, unused, out_3280179861815054133); } -void live_H_14(double *state, double *unused, double *out_2721535251380436755) { - H_14(state, unused, out_2721535251380436755); +void live_H_14(double *state, double *unused, double *out_8197153713411681611) { + H_14(state, unused, out_8197153713411681611); } -void live_h_33(double *state, double *unused, double *out_1521077794722315231) { - h_33(state, unused, out_1521077794722315231); +void live_h_33(double *state, double *unused, double *out_3797754961266519421) { + h_33(state, unused, out_3797754961266519421); } -void live_H_33(double *state, double *unused, double *out_3491535124633419245) { - H_33(state, unused, out_3491535124633419245); +void live_H_33(double *state, double *unused, double *out_3973560944915995670) { + H_33(state, unused, out_3973560944915995670); } void live_predict(double *in_x, double *in_P, double *in_Q, double dt) { predict(in_x, in_P, in_Q, dt); diff --git a/selfdrive/locationd/models/generated/live.h b/selfdrive/locationd/models/generated/live.h index 2c8518a9c..cc6c9d145 100644 --- a/selfdrive/locationd/models/generated/live.h +++ b/selfdrive/locationd/models/generated/live.h @@ -10,29 +10,29 @@ void live_update_32(double *in_x, double *in_P, double *in_z, double *in_R, doub void live_update_13(double *in_x, double *in_P, double *in_z, double *in_R, double *in_ea); void live_update_14(double *in_x, double *in_P, double *in_z, double *in_R, double *in_ea); void live_update_33(double *in_x, double *in_P, double *in_z, double *in_R, double *in_ea); -void live_H(double *in_vec, double *out_2107061543090158966); -void live_err_fun(double *nom_x, double *delta_x, double *out_1090842864546838841); -void live_inv_err_fun(double *nom_x, double *true_x, double *out_1751534880763809428); -void live_H_mod_fun(double *state, double *out_2270168032272230264); -void live_f_fun(double *state, double dt, double *out_9047640957774126431); -void live_F_fun(double *state, double dt, double *out_4752414459068816126); -void live_h_4(double *state, double *unused, double *out_1938047718740512528); -void live_H_4(double *state, double *unused, double *out_8437989887064667391); -void live_h_9(double *state, double *unused, double *out_2016376091952434025); -void live_H_9(double *state, double *unused, double *out_2721535251380436755); -void live_h_10(double *state, double *unused, double *out_8252027734007822314); -void live_H_10(double *state, double *unused, double *out_1022365631619946756); -void live_h_12(double *state, double *unused, double *out_490832941153373832); -void live_H_12(double *state, double *unused, double *out_4989297778612922430); -void live_h_35(double *state, double *unused, double *out_851812883202032952); -void live_H_35(double *state, double *unused, double *out_6642092129272276849); -void live_h_32(double *state, double *unused, double *out_7198045605532929596); -void live_H_32(double *state, double *unused, double *out_6510927344331536380); -void live_h_13(double *state, double *unused, double *out_6813957582124674447); -void live_H_13(double *state, double *unused, double *out_7851984426394690165); -void live_h_14(double *state, double *unused, double *out_2016376091952434025); -void live_H_14(double *state, double *unused, double *out_2721535251380436755); -void live_h_33(double *state, double *unused, double *out_1521077794722315231); -void live_H_33(double *state, double *unused, double *out_3491535124633419245); +void live_H(double *in_vec, double *out_5027207160750161004); +void live_err_fun(double *nom_x, double *delta_x, double *out_812293829444590878); +void live_inv_err_fun(double *nom_x, double *true_x, double *out_2331899367078236024); +void live_H_mod_fun(double *state, double *out_3350621260021879835); +void live_f_fun(double *state, double dt, double *out_9110479569516509106); +void live_F_fun(double *state, double dt, double *out_956757865849250644); +void live_h_4(double *state, double *unused, double *out_396243034408503816); +void live_H_4(double *state, double *unused, double *out_7955964066782090966); +void live_h_9(double *state, double *unused, double *out_3280179861815054133); +void live_H_9(double *state, double *unused, double *out_8197153713411681611); +void live_h_10(double *state, double *unused, double *out_7028739412274946671); +void live_H_10(double *state, double *unused, double *out_5406505055183973833); +void live_h_12(double *state, double *unused, double *out_2939119697401536762); +void live_H_12(double *state, double *unused, double *out_8577063091829684633); +void live_h_35(double *state, double *unused, double *out_3733220149839256661); +void live_H_35(double *state, double *unused, double *out_7124117949554853274); +void live_h_32(double *state, double *unused, double *out_6268450557573639622); +void live_H_32(double *state, double *unused, double *out_4419093436653103337); +void live_h_13(double *state, double *unused, double *out_7986377932969783217); +void live_H_13(double *state, double *unused, double *out_276341309716065550); +void live_h_14(double *state, double *unused, double *out_3280179861815054133); +void live_H_14(double *state, double *unused, double *out_8197153713411681611); +void live_h_33(double *state, double *unused, double *out_3797754961266519421); +void live_H_33(double *state, double *unused, double *out_3973560944915995670); void live_predict(double *in_x, double *in_P, double *in_Q, double dt); } \ No newline at end of file diff --git a/selfdrive/locationd/torqued.py b/selfdrive/locationd/torqued.py index e02a2f7e3..d640a6181 100755 --- a/selfdrive/locationd/torqued.py +++ b/selfdrive/locationd/torqued.py @@ -63,7 +63,7 @@ class PointBuckets: def __init__(self, x_bounds, min_points, min_points_total): self.x_bounds = x_bounds self.buckets = {bounds: NPQueue(maxlen=POINTS_PER_BUCKET, rowsize=3) for bounds in x_bounds} - self.buckets_min_points = {bounds: min_point for bounds, min_point in zip(x_bounds, min_points)} + self.buckets_min_points = dict(zip(x_bounds, min_points, strict=True)) self.min_points_total = min_points_total def bucket_lengths(self): @@ -73,7 +73,8 @@ class PointBuckets: return sum(self.bucket_lengths()) def is_valid(self): - return all(len(v) >= min_pts for v, min_pts in zip(self.buckets.values(), self.buckets_min_points.values())) and (self.__len__() >= self.min_points_total) + return all(len(v) >= min_pts for v, min_pts in zip(self.buckets.values(), self.buckets_min_points.values(), strict=True)) \ + and (self.__len__() >= self.min_points_total) def add_point(self, x, y): for bound_min, bound_max in self.x_bounds: @@ -230,7 +231,7 @@ class TorqueEstimator: liveTorqueParameters.latAccelOffsetRaw = float(latAccelOffset) liveTorqueParameters.frictionCoefficientRaw = float(frictionCoeff) - if any([val is None or np.isnan(val) for val in [latAccelFactor, latAccelOffset, frictionCoeff]]): + if any(val is None or np.isnan(val) for val in [latAccelFactor, latAccelOffset, frictionCoeff]): cloudlog.exception("Live torque parameters are invalid.") liveTorqueParameters.liveValid = False self.reset() diff --git a/selfdrive/manager/build.py b/selfdrive/manager/build.py index 8bcbceeeb..5c80b308e 100755 --- a/selfdrive/manager/build.py +++ b/selfdrive/manager/build.py @@ -16,7 +16,7 @@ from system.version import is_dirty MAX_CACHE_SIZE = 4e9 if "CI" in os.environ else 2e9 CACHE_DIR = Path("/data/scons_cache" if AGNOS else "/tmp/scons_cache") -TOTAL_SCONS_NODES = 2460 +TOTAL_SCONS_NODES = 2560 MAX_BUILD_PROGRESS = 100 PREBUILT = os.path.exists(os.path.join(BASEDIR, 'prebuilt')) diff --git a/selfdrive/manager/manager.py b/selfdrive/manager/manager.py index 430dd2d05..eb4137c55 100755 --- a/selfdrive/manager/manager.py +++ b/selfdrive/manager/manager.py @@ -76,6 +76,8 @@ def manager_init() -> None: ("dp_long_taco", "0"), ("dp_long_stock_mode", "0"), ("dp_long_missing_lead_warning", "0"), + ("dp_lateral_road_edge_detection", "0"), + ("dp_nav_voice_guidance", "0"), ] if not PC: default_params.append(("LastUpdateTime", datetime.datetime.utcnow().isoformat().encode('utf8'))) @@ -179,10 +181,14 @@ def manager_thread() -> None: if not params.get_bool("dp_otisserv"): ignore += ["otisserv"] + dpdmonitoringd_ignored = True if not is_registered_device(): ignore += ["uploader"] if params.get_bool("dp_device_dm_unavailable"): ignore += ["dmonitoringd", "dmonitoringmodeld"] + dpdmonitoringd_ignored = False + if dpdmonitoringd_ignored: + ignore += ["dpdmonitoringd"] sm = messaging.SubMaster(['deviceState', 'carParams'], poll=['deviceState']) pm = messaging.PubMaster(['managerState']) diff --git a/selfdrive/manager/process.py b/selfdrive/manager/process.py index 5262ccf9f..f819a3080 100644 --- a/selfdrive/manager/process.py +++ b/selfdrive/manager/process.py @@ -39,7 +39,7 @@ def launcher(proc: str, name: str) -> None: sentry.set_tag("daemon", name) # exec the process - getattr(mod, 'main')() + mod.main() except KeyboardInterrupt: cloudlog.warning(f"child {proc} got SIGINT") except Exception: diff --git a/selfdrive/manager/process_config.py b/selfdrive/manager/process_config.py index 16928b294..263612738 100644 --- a/selfdrive/manager/process_config.py +++ b/selfdrive/manager/process_config.py @@ -13,6 +13,9 @@ def driverview(started: bool, params: Params, CP: car.CarParams) -> bool: def notcar(started: bool, params: Params, CP: car.CarParams) -> bool: return CP.notCar # type: ignore +def iscar(started: bool, params: Params, CP: car.CarParams) -> bool: + return not CP.notCar + def logging(started, params, CP: car.CarParams) -> bool: run = (not CP.notCar) or not params.get_bool("DisableLogging") return started and run @@ -35,12 +38,13 @@ procs = [ NativeProcess("logcatd", "system/logcatd", ["./logcatd"]), NativeProcess("proclogd", "system/proclogd", ["./proclogd"]), PythonProcess("logmessaged", "system.logmessaged", offroad=True), - PythonProcess("micd", "system.micd"), + PythonProcess("micd", "system.micd", callback=iscar), PythonProcess("timezoned", "system.timezoned", enabled=not PC, offroad=True), DaemonProcess("manage_athenad", "selfdrive.athena.manage_athenad", "AthenadPid"), NativeProcess("dmonitoringmodeld", "selfdrive/modeld", ["./dmonitoringmodeld"], enabled=(not PC or WEBCAM), callback=driverview), NativeProcess("encoderd", "system/loggerd", ["./encoderd"]), + NativeProcess("stream_encoderd", "system/loggerd", ["./encoderd", "--stream"], onroad=False, callback=notcar), NativeProcess("loggerd", "system/loggerd", ["./loggerd"], onroad=False, callback=logging), NativeProcess("modeld", "selfdrive/modeld", ["./modeld"]), NativeProcess("mapsd", "selfdrive/navd", ["./mapsd"]), @@ -80,6 +84,7 @@ procs = [ # gpxd PythonProcess("gpxd", "selfdrive.dragonpilot.gpxd"), PythonProcess("gpx_uploader", "selfdrive.dragonpilot.gpx_uploader", offroad=True), + PythonProcess("dpdmonitoringd", "selfdrive.dragonpilot.dpdmonitoringd"), NativeProcess("fileserv", "selfdrive/dragonpilot", ['./fileserv'], offroad=True), ] diff --git a/selfdrive/modeld/_dmonitoringmodeld b/selfdrive/modeld/_dmonitoringmodeld index 5505af46d..6b96ad0d3 100755 Binary files a/selfdrive/modeld/_dmonitoringmodeld and b/selfdrive/modeld/_dmonitoringmodeld differ diff --git a/selfdrive/modeld/_modeld b/selfdrive/modeld/_modeld index 14f3c5277..9f37becbf 100755 Binary files a/selfdrive/modeld/_modeld and b/selfdrive/modeld/_modeld differ diff --git a/selfdrive/modeld/_navmodeld b/selfdrive/modeld/_navmodeld index 7a26e32f5..cb4f19999 100755 Binary files a/selfdrive/modeld/_navmodeld and b/selfdrive/modeld/_navmodeld differ diff --git a/selfdrive/modeld/models/supercombo.thneed b/selfdrive/modeld/models/supercombo.thneed index 05bbfae48..c6445c370 100644 Binary files a/selfdrive/modeld/models/supercombo.thneed and b/selfdrive/modeld/models/supercombo.thneed differ diff --git a/selfdrive/monitoring/driver_monitor.py b/selfdrive/monitoring/driver_monitor.py index 7d7a55e5d..97407e25e 100644 --- a/selfdrive/monitoring/driver_monitor.py +++ b/selfdrive/monitoring/driver_monitor.py @@ -119,7 +119,9 @@ class DriverBlink(): self.right_blink = 0. class DriverStatus(): - def __init__(self, rhd_saved=False, settings=DRIVER_MONITOR_SETTINGS()): + def __init__(self, rhd_saved=False, settings=None): + if settings is None: + settings = DRIVER_MONITOR_SETTINGS() # init policy settings self.settings = settings diff --git a/selfdrive/navd/libmaprender.so b/selfdrive/navd/libmaprender.so index 72b08db66..b58db8180 100755 Binary files a/selfdrive/navd/libmaprender.so and b/selfdrive/navd/libmaprender.so differ diff --git a/selfdrive/navd/mapsd b/selfdrive/navd/mapsd index 29b7b5fbf..444dbc6aa 100755 Binary files a/selfdrive/navd/mapsd and b/selfdrive/navd/mapsd differ diff --git a/selfdrive/sentry.py b/selfdrive/sentry.py index 3c90af6ba..5a6f1ee6f 100644 --- a/selfdrive/sentry.py +++ b/selfdrive/sentry.py @@ -34,14 +34,18 @@ try: except AttributeError: dongle_id = "None" try: - gitname = Params().get("GithubUsername", encoding='utf-8') + gitname = params.get("GithubUsername", encoding='utf-8') except Exception: gitname = "" -try: - ip = requests.get('https://checkip.amazonaws.com/').text.strip() -except Exception: - ip = "255.255.255.255" -error_tags = {'dirty': is_dirty(), 'dongle_id': dongle_id, 'branch': get_branch(), 'remote': get_origin(), 'fingerprintedAs': candidate, 'gitname':gitname} +error_tags = { + 'dirty': is_dirty(), + 'dongle_id': dongle_id, + 'branch': get_branch(), + 'remote': get_origin(), + 'fingerprintedAs': candidate, + 'gitname': gitname +} +ip = "{{auto}}" try: cached_params = params.get("CarParams") @@ -66,6 +70,7 @@ def report_tombstone(fn: str, message: str, contents: str) -> None: def capture_exception(*args, **kwargs) -> None: save_exception(traceback.format_exc()) cloudlog.error("crash", exc_info=kwargs.get('exc_info', 1)) + bind_user(id=dongle_id, ip_address=ip, username=gitname) try: sentry_sdk.capture_exception(*args, **kwargs) @@ -84,17 +89,21 @@ def save_exception(exc_text): def bind_user(**kwargs) -> None: sentry_sdk.set_user(kwargs) + sentry_sdk.flush() def capture_warning(warning_string): bind_user(id=dongle_id, ip_address=ip, name=gitname) sentry_sdk.capture_message(warning_string, level='warning') + sentry_sdk.flush() def capture_info(info_string): bind_user(id=dongle_id, ip_address=ip, name=gitname) sentry_sdk.capture_message(info_string, level='info') + sentry_sdk.flush() def set_tag(key: str, value: str) -> None: sentry_sdk.set_tag(key, value) + sentry_sdk.flush() def init(project: SentryProject) -> None: @@ -104,8 +113,10 @@ def init(project: SentryProject) -> None: #return env = "release" if is_tested_branch() else "master" - dongle_id = Params().get("DongleId", encoding='utf-8') - gitname = Params().get("GithubUsername", encoding='utf-8') + dongle_id = params.get("DongleId", encoding='utf-8') + gitname = params.get("GithubUsername", encoding='utf-8') + ip = "{{auto}}" + integrations = [] if project == SentryProject.SELFDRIVE: @@ -118,10 +129,12 @@ def init(project: SentryProject) -> None: release=get_version(), integrations=integrations, traces_sample_rate=1.0, - environment=env) + environment=env, + send_default_pii=True) sentry_sdk.set_user({"id": dongle_id}) sentry_sdk.set_user({"gitname": gitname}) + sentry_sdk.set_user({"ip_address": ip}) sentry_sdk.set_tag("dirty", is_dirty()) sentry_sdk.set_tag("origin", get_origin()) sentry_sdk.set_tag("branch", get_branch()) diff --git a/selfdrive/statsd.py b/selfdrive/statsd.py index e64907149..a444a6231 100755 --- a/selfdrive/statsd.py +++ b/selfdrive/statsd.py @@ -23,6 +23,8 @@ class METRIC_TYPE: class StatLog: def __init__(self): self.pid = None + self.zctx = None + self.sock = None def connect(self) -> None: self.zctx = zmq.Context() @@ -31,6 +33,12 @@ class StatLog: self.sock.connect(STATS_SOCKET) self.pid = os.getpid() + def __del__(self): + if self.sock is not None: + self.sock.close() + if self.zctx is not None: + self.zctx.term() + def _send(self, metric: str) -> None: if os.getpid() != self.pid: self.connect() @@ -68,7 +76,7 @@ def main() -> NoReturn: return res # open statistics socket - ctx = zmq.Context().instance() + ctx = zmq.Context.instance() sock = ctx.socket(zmq.PULL) sock.bind(STATS_SOCKET) @@ -92,70 +100,74 @@ def main() -> NoReturn: last_flush_time = time.monotonic() gauges = {} samples: Dict[str, List[float]] = defaultdict(list) - while True: - started_prev = sm['deviceState'].started - sm.update() - - # Update metrics + try: while True: - try: - metric = sock.recv_string(zmq.NOBLOCK) + started_prev = sm['deviceState'].started + sm.update() + + # Update metrics + while True: try: - metric_type = metric.split('|')[1] - metric_name = metric.split(':')[0] - metric_value = float(metric.split('|')[0].split(':')[1]) + metric = sock.recv_string(zmq.NOBLOCK) + try: + metric_type = metric.split('|')[1] + metric_name = metric.split(':')[0] + metric_value = float(metric.split('|')[0].split(':')[1]) - if metric_type == METRIC_TYPE.GAUGE: - gauges[metric_name] = metric_value - elif metric_type == METRIC_TYPE.SAMPLE: - samples[metric_name].append(metric_value) - else: - cloudlog.event("unknown metric type", metric_type=metric_type) - except Exception: - cloudlog.event("malformed metric", metric=metric) - except zmq.error.Again: - break + if metric_type == METRIC_TYPE.GAUGE: + gauges[metric_name] = metric_value + elif metric_type == METRIC_TYPE.SAMPLE: + samples[metric_name].append(metric_value) + else: + cloudlog.event("unknown metric type", metric_type=metric_type) + except Exception: + cloudlog.event("malformed metric", metric=metric) + except zmq.error.Again: + break - # flush when started state changes or after FLUSH_TIME_S - if (time.monotonic() > last_flush_time + STATS_FLUSH_TIME_S) or (sm['deviceState'].started != started_prev): - result = "" - current_time = datetime.utcnow().replace(tzinfo=timezone.utc) - tags['started'] = sm['deviceState'].started + # flush when started state changes or after FLUSH_TIME_S + if (time.monotonic() > last_flush_time + STATS_FLUSH_TIME_S) or (sm['deviceState'].started != started_prev): + result = "" + current_time = datetime.utcnow().replace(tzinfo=timezone.utc) + tags['started'] = sm['deviceState'].started - for key, value in gauges.items(): - result += get_influxdb_line(f"gauge.{key}", value, current_time, tags) + for key, value in gauges.items(): + result += get_influxdb_line(f"gauge.{key}", value, current_time, tags) - for key, values in samples.items(): - values.sort() - sample_count = len(values) - sample_sum = sum(values) + for key, values in samples.items(): + values.sort() + sample_count = len(values) + sample_sum = sum(values) - stats = { - 'count': sample_count, - 'min': values[0], - 'max': values[-1], - 'mean': sample_sum / sample_count, - } - for percentile in [0.05, 0.5, 0.95]: - value = values[int(round(percentile * (sample_count - 1)))] - stats[f"p{int(percentile * 100)}"] = value + stats = { + 'count': sample_count, + 'min': values[0], + 'max': values[-1], + 'mean': sample_sum / sample_count, + } + for percentile in [0.05, 0.5, 0.95]: + value = values[int(round(percentile * (sample_count - 1)))] + stats[f"p{int(percentile * 100)}"] = value - result += get_influxdb_line(f"sample.{key}", stats, current_time, tags) + result += get_influxdb_line(f"sample.{key}", stats, current_time, tags) - # clear intermediate data - gauges.clear() - samples.clear() - last_flush_time = time.monotonic() + # clear intermediate data + gauges.clear() + samples.clear() + last_flush_time = time.monotonic() - # check that we aren't filling up the drive - if len(os.listdir(STATS_DIR)) < STATS_DIR_FILE_LIMIT: - if len(result) > 0: - stats_path = os.path.join(STATS_DIR, f"{current_time.timestamp():.0f}_{idx}") - with atomic_write_in_dir(stats_path) as f: - f.write(result) - idx += 1 - else: - cloudlog.error("stats dir full") + # check that we aren't filling up the drive + if len(os.listdir(STATS_DIR)) < STATS_DIR_FILE_LIMIT: + if len(result) > 0: + stats_path = os.path.join(STATS_DIR, f"{current_time.timestamp():.0f}_{idx}") + with atomic_write_in_dir(stats_path) as f: + f.write(result) + idx += 1 + else: + cloudlog.error("stats dir full") + finally: + sock.close() + ctx.term() if __name__ == "__main__": diff --git a/selfdrive/test/fuzzy_generation.py b/selfdrive/test/fuzzy_generation.py index 0b8bd0206..28c70a0ff 100644 --- a/selfdrive/test/fuzzy_generation.py +++ b/selfdrive/test/fuzzy_generation.py @@ -70,7 +70,7 @@ class FuzzyGenerator: def generate_struct(self, schema: capnp.lib.capnp._StructSchema, event: Optional[str] = None) -> st.SearchStrategy[Dict[str, Any]]: full_fill: List[str] = list(schema.non_union_fields) single_fill: List[str] = [event] if event else [self.draw(st.sampled_from(schema.union_fields))] if schema.union_fields else [] - return st.fixed_dictionaries(dict((field, self.generate_field(schema.fields[field])) for field in full_fill + single_fill)) + return st.fixed_dictionaries({field: self.generate_field(schema.fields[field]) for field in full_fill + single_fill}) @classmethod def get_random_msg(cls, draw: DrawType, struct: capnp.lib.capnp._StructModule, real_floats: bool = False) -> Dict[str, Any]: diff --git a/selfdrive/test/setup_device_ci.sh b/selfdrive/test/setup_device_ci.sh index 4ac970740..1b99c3103 100755 --- a/selfdrive/test/setup_device_ci.sh +++ b/selfdrive/test/setup_device_ci.sh @@ -42,6 +42,13 @@ while true; do if ! sudo systemctl is-active -q ssh; then sudo systemctl start ssh fi + + if ! pgrep -f 'ciui.py' > /dev/null 2>&1; then + echo 'starting UI' + cp $SOURCE_DIR/selfdrive/test/ciui.py /data/ + /data/ciui.py & + fi + sleep 5s done diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py index e6c3658a1..d71f49dc3 100755 --- a/selfdrive/test/test_onroad.py +++ b/selfdrive/test/test_onroad.py @@ -69,7 +69,7 @@ PROCS.update({ "./boardd": 19.0, "system.sensord.rawgps.rawgpsd": 1.0, } -}[HARDWARE.get_device_type()]) +}.get(HARDWARE.get_device_type(), {})) TIMINGS = { # rtols: max/min, rsd @@ -258,7 +258,7 @@ class TestOnroad(unittest.TestCase): cpu_ok = False # Ensure there's no missing procs - all_procs = set([p.name for p in self.service_msgs['managerState'][0].managerState.processes if p.shouldBeRunning]) + all_procs = {p.name for p in self.service_msgs['managerState'][0].managerState.processes if p.shouldBeRunning} for p in all_procs: with self.subTest(proc=p): assert any(p in pp for pp in PROCS.keys()), f"Expected CPU usage missing for {p}" @@ -282,7 +282,7 @@ class TestOnroad(unittest.TestCase): result += "-------------- Debayer Timing ------------------\n" result += "------------------------------------------------\n" - ts = [getattr(getattr(m, m.which()), "processingTime") for m in self.lr if 'CameraState' in m.which()] + ts = [getattr(m, m.which()).processingTime for m in self.lr if 'CameraState' in m.which()] self.assertLess(min(ts), 0.025, f"high execution time: {min(ts)}") result += f"execution time: min {min(ts):.5f}s\n" result += f"execution time: max {max(ts):.5f}s\n" @@ -297,7 +297,7 @@ class TestOnroad(unittest.TestCase): result += "----------------- SoF Timing ------------------\n" result += "------------------------------------------------\n" for name in ['roadCameraState', 'wideRoadCameraState', 'driverCameraState']: - ts = [getattr(getattr(m, m.which()), "timestampSof") for m in self.lr if name in m.which()] + ts = [getattr(m, m.which()).timestampSof for m in self.lr if name in m.which()] d_ms = np.diff(ts) / 1e6 d50 = np.abs(d_ms-50) self.assertLess(max(d50), 1.0, f"high sof delta vs 50ms: {max(d50)}") @@ -315,7 +315,7 @@ class TestOnroad(unittest.TestCase): cfgs = [("lateralPlan", 0.05, 0.05), ("longitudinalPlan", 0.05, 0.05)] for (s, instant_max, avg_max) in cfgs: - ts = [getattr(getattr(m, s), "solverExecutionTime") for m in self.service_msgs[s]] + ts = [getattr(m, s).solverExecutionTime for m in self.service_msgs[s]] self.assertLess(max(ts), instant_max, f"high '{s}' execution time: {max(ts)}") self.assertLess(np.mean(ts), avg_max, f"high avg '{s}' execution time: {np.mean(ts)}") result += f"'{s}' execution time: min {min(ts):.5f}s\n" @@ -335,7 +335,7 @@ class TestOnroad(unittest.TestCase): ("driverStateV2", 0.050, 0.026), ] for (s, instant_max, avg_max) in cfgs: - ts = [getattr(getattr(m, s), "modelExecutionTime") for m in self.service_msgs[s]] + ts = [getattr(m, s).modelExecutionTime for m in self.service_msgs[s]] self.assertLess(max(ts), instant_max, f"high '{s}' execution time: {max(ts)}") self.assertLess(np.mean(ts), avg_max, f"high avg '{s}' execution time: {np.mean(ts)}") result += f"'{s}' execution time: min {min(ts):.5f}s\n" diff --git a/selfdrive/thermald/thermald.py b/selfdrive/thermald/thermald.py index 104c9a982..d1b01f8bd 100755 --- a/selfdrive/thermald/thermald.py +++ b/selfdrive/thermald/thermald.py @@ -61,7 +61,7 @@ def populate_tz_by_type(): if not n.startswith("thermal_zone"): continue with open(os.path.join("/sys/devices/virtual/thermal", n, "type")) as f: - tz_by_type[f.read().strip()] = int(n.lstrip("thermal_zone")) + tz_by_type[f.read().strip()] = int(n.removeprefix("thermal_zone")) def read_tz(x): if x is None: diff --git a/selfdrive/tombstoned.py b/selfdrive/tombstoned.py index 65fb45b67..b1086305b 100755 --- a/selfdrive/tombstoned.py +++ b/selfdrive/tombstoned.py @@ -54,7 +54,7 @@ def get_tombstones(): with os.scandir(folder) as d: # Loop over first 1000 directory entries - for _, f in zip(range(1000), d): + for _, f in zip(range(1000), d, strict=False): if f.name.startswith("tombstone"): files.append((f.path, int(f.stat().st_ctime))) elif f.name.endswith(".crash") and f.stat().st_mode == 0o100640: diff --git a/selfdrive/ui/_ui b/selfdrive/ui/_ui index 2d7c3cb9d..98677494c 100755 Binary files a/selfdrive/ui/_ui and b/selfdrive/ui/_ui differ diff --git a/selfdrive/ui/qt/libpython_helpers.so b/selfdrive/ui/qt/libpython_helpers.so index 6f6837215..ab3a77c99 100755 Binary files a/selfdrive/ui/qt/libpython_helpers.so and b/selfdrive/ui/qt/libpython_helpers.so differ diff --git a/selfdrive/ui/qt/spinner b/selfdrive/ui/qt/spinner index 0afaa5359..888cd7550 100755 Binary files a/selfdrive/ui/qt/spinner and b/selfdrive/ui/qt/spinner differ diff --git a/selfdrive/ui/qt/text b/selfdrive/ui/qt/text index 5808f90b6..3f4afac2a 100755 Binary files a/selfdrive/ui/qt/text and b/selfdrive/ui/qt/text differ diff --git a/selfdrive/ui/soundd/_soundd b/selfdrive/ui/soundd/_soundd index d598f4d46..eb046f286 100755 Binary files a/selfdrive/ui/soundd/_soundd and b/selfdrive/ui/soundd/_soundd differ diff --git a/selfdrive/ui/tests/test_translations.py b/selfdrive/ui/tests/test_translations.py index 26d6c3934..5e52eabe3 100755 --- a/selfdrive/ui/tests/test_translations.py +++ b/selfdrive/ui/tests/test_translations.py @@ -88,7 +88,7 @@ class TestTranslations(unittest.TestCase): continue self.assertNotIn(None, numerusform, "Ensure all plural translation forms are completed.") - self.assertTrue(all([re.search("%[0-9]+", t) is None for t in numerusform]), + self.assertTrue(all(re.search("%[0-9]+", t) is None for t in numerusform), "Plural translations must use %n, not %1, %2, etc.: {}".format(numerusform)) def test_no_locations(self): diff --git a/selfdrive/ui/translations/languages.json b/selfdrive/ui/translations/languages.json index 86d3e62d8..6207b5f50 100644 --- a/selfdrive/ui/translations/languages.json +++ b/selfdrive/ui/translations/languages.json @@ -1,6 +1,7 @@ { "English": "main_en", "Deutsch": "main_de", + "Français": "main_fr", "Português": "main_pt-BR", "中文(繁體)": "main_zh-CHT", "中文(简体)": "main_zh-CHS", diff --git a/selfdrive/ui/translations/main_de.qm b/selfdrive/ui/translations/main_de.qm index c2646e7b0..0d8e6424f 100644 Binary files a/selfdrive/ui/translations/main_de.qm and b/selfdrive/ui/translations/main_de.qm differ diff --git a/selfdrive/ui/translations/main_de.ts b/selfdrive/ui/translations/main_de.ts index b3f31afee..c6477835b 100644 --- a/selfdrive/ui/translations/main_de.ts +++ b/selfdrive/ui/translations/main_de.ts @@ -91,19 +91,35 @@ km - km + km m - m + m mi - mi + mi ft - fuß + fuß + + + km + km + + + m + + + + mi + mi + + + ft + @@ -297,6 +313,15 @@ Reboot Required. Reboot Required. + + Road Edge Detection + + + + When enabled, openpilot will block lane change if road edge is detected. +Reboot required. + + Enable TACO Tune @@ -362,10 +387,6 @@ NOR - Normal tune. SPT - Sport tune. - - *β* Enable Otisserv - - When enabled, you will be able to access some features remotely through dragonpilot.org. @@ -379,6 +400,18 @@ SPT - Sport tune. Reboot Required. + + *α* Enable Otisserv + + + + *α* Enable NOO Voice Guidance + + + + When enabled and NOO is active, dragonpilot will audibly instruct the driver when and where to turn. + + DeclinePage diff --git a/selfdrive/ui/translations/main_fr.qm b/selfdrive/ui/translations/main_fr.qm new file mode 100644 index 000000000..8f525c9c6 Binary files /dev/null and b/selfdrive/ui/translations/main_fr.qm differ diff --git a/selfdrive/ui/translations/main_fr.ts b/selfdrive/ui/translations/main_fr.ts new file mode 100644 index 000000000..dcdcaf9d4 --- /dev/null +++ b/selfdrive/ui/translations/main_fr.ts @@ -0,0 +1,1554 @@ + + + + + AbstractAlert + + Close + Fermer + + + Snooze Update + Reporter la mise à jour + + + Reboot and Update + Redémarrer et mettre à jour + + + + AdvancedNetworking + + Back + Retour + + + Enable Tethering + Activer le partage de connexion + + + Tethering Password + Mot de passe du partage de connexion + + + EDIT + MODIFIER + + + Enter new tethering password + Entrez le nouveau mot de passe du partage de connexion + + + IP Address + Adresse IP + + + Enable Roaming + Activer l'itinérance + + + APN Setting + Paramètre APN + + + Enter APN + Entrer le nom du point d'accès + + + leave blank for automatic configuration + laisser vide pour une configuration automatique + + + Cellular Metered + Connexion cellulaire limitée + + + Prevent large data uploads when on a metered connection + Éviter les transferts de données importants sur une connexion limitée + + + + AnnotatedCameraWidget + + km/h + km/h + + + mph + mi/h + + + MAX + MAX + + + SPEED + VITESSE + + + LIMIT + LIMITE + + + km + km + + + m + m + + + mi + mi + + + ft + ft + + + km + km + + + m + + + + mi + mi + + + ft + + + + + CarSelectionPanel + + [AUTO SELECT] + + + + + ConfirmationDialog + + Ok + Ok + + + Cancel + Annuler + + + + DPCtrlPanel + + Ctrl - Lateral + + + + Enable ALKA + + + + When enabled, openpilot lateral Control will be always on when ACC MAIN is ON. +Reboot required. + + + + Enable Lane Priority Mode + + + + When enabled, openpilot will use lane lines for lateral control, fallback to laneless mode automatically when lane lines probabilities are low. +Reboot required. + + + + Road Edge Detection + + + + When enabled, openpilot will block lane change if road edge is detected. +Reboot required. + + + + Ctrl - Longitudinal + + + + Enable TACO Tune + + + + When enabled, openpilot will use slow down for turns from taco2 branch. +See https://github.com/commaai/openpilot/commit/7b97ddb3aacb222bfaf0b978c49cb5b756903ef7 for more information. +This is tune for KIA EV6 and may not work on your vehicle. +Reboot required. + + + + Enable Dynamic Following + + + + When enabled, openpilot will dynamically adjust following distance based on your "Driving Personality" setting. + + + + Enable Dynamic End-to-End Longitudinal Control + + + + When enabled, openpilot will dynamically change between End-to-End or ACC mode. +Your vehicle must support openpilot longitudinal control. + + + + Enable Turn Speed Control - Vision + + + + When enabled, openpilot will use path predictions from camera vision to estimate the appropriate speed to drive through turns ahead. + + + + Enable MapD + + + + When enabled, openpilot will display current road name on the screen. +Author: https://github.com/move-fast/ +Reboot required. + + + + OP + + + + ECO + + + + NOR + + + + SPT + + + + Acceleration Profile + + + + OP - Stock tune. +ECO - Eco tune. +NOR - Normal tune. +SPT - Sport tune. + + + + Device + Appareil + + + Disable Temp Check + + + + When enabled, openpilot will disable device temperature check. +**NOTED** An overheated device may result in random shutdowns or lag. +Reboot required. + + + + Enable Auto Shutdown + + + + When enabled, openpilot will shutdown the device automatically. +Reboot required. + + + + Standard + Standard + + + On-Road + + + + MAIN + + + + Off + + + + Display Mode + + + + On-Road - When driving, the display will be off (excl. warning). +MAIN - When ACC MAIN is on, the display will be off (excl. warning). +OP - When OP is enabled, the display will be off (excl. warning). +Off - the display will be off completely (incl. warning). +Reboot required. + + + + Warning + + + + Audible Alert Mode + + + + Warning - Only emits sound when there is a warning. +Off - Does not emit any sound at all. + + + + Auto Shutdown In + + + + Adjust your shutdown waiting period. + + + + mins + + + + Immediately + + + + Miscellaneous + + + + Enable File server + + + + When enabled, you will be able to access log data using browser through port 9000. +Needs to be in the same network. (e.g. LAN) +Reboot required. + + + + When enabled, you will be able to access some features remotely through dragonpilot.org. + + + + Toyota / Lexus + + + + Enable Stop and Go (SnG) Hack + + + + When enabled, openpilot will stop sending standstill signal when the car is fully stopped. +ONLY WORK ON SOME VEHICLES. +Reboot Required. + + + + Enable Enhanced BSM + + + + When enabled, openpilot will use debugging CAN messages to receive unfiltered BSM signals, allowing detection of more objects. +Tested on Prius TSS2 and RAV4 TSS1. +ONLY WORK ON SOME VEHICLES. +Reboot Required. + + + + Enable Door Auto Locking + + + + When enabled, openpilot will attempt to lock the doors when drive above 10 km/h (6.2 mph). +Reboot Required. + + + + Enable Door Auto Unlocking + + + + When enabled, openpilot will attempt to unlock the doors when shift to gear P. +Reboot Required. + + + + Enable Stock Longitudinal Control + + + + When enabled, openpilot will not handle longitudinal control. +Reboot Required. + + + + *α* Enable Otisserv + + + + *α* Enable NOO Voice Guidance + + + + When enabled and NOO is active, dragonpilot will audibly instruct the driver when and where to turn. + + + + + DeclinePage + + You must accept the Terms and Conditions in order to use openpilot. + Vous devez accepter les conditions générales pour utiliser openpilot. + + + Back + Retour + + + Decline, uninstall %1 + Refuser, désinstaller %1 + + + + DestinationWidget + + Home + Domicile + + + Work + Travail + + + No destination set + Aucune destination définie + + + home + domicile + + + work + travail + + + No %1 location set + Aucun lieu %1 défini + + + + DevicePanel + + Dongle ID + Dongle ID + + + N/A + N/A + + + Serial + N° de série + + + Driver Camera + Caméra conducteur + + + PREVIEW + APERÇU + + + Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off) + Aperçu de la caméra orientée vers le conducteur pour assurer une bonne visibilité de la surveillance du conducteur. (véhicule doit être éteint) + + + Reset Calibration + Réinitialiser la calibration + + + RESET + RÉINITIALISER + + + Are you sure you want to reset calibration? + Êtes-vous sûr de vouloir réinitialiser la calibration ? + + + Reset + Réinitialiser + + + Review Training Guide + Revoir le guide de formation + + + REVIEW + REVOIR + + + Review the rules, features, and limitations of openpilot + Revoir les règles, fonctionnalités et limitations d'openpilot + + + Are you sure you want to review the training guide? + Êtes-vous sûr de vouloir revoir le guide de formation ? + + + Review + Revoir + + + Regulatory + Réglementaire + + + VIEW + VOIR + + + Change Language + Changer de langue + + + CHANGE + CHANGER + + + Select a language + Choisir une langue + + + Reboot + Redémarrer + + + Power Off + Éteindre + + + openpilot requires the device to be mounted within 4° left or right and within 5° up or 8° down. openpilot is continuously calibrating, resetting is rarely required. + openpilot nécessite que l'appareil soit monté à 4° à gauche ou à droite et à 5° vers le haut ou 8° vers le bas. openpilot se calibre en continu, la réinitialisation est rarement nécessaire. + + + Your device is pointed %1° %2 and %3° %4. + Votre appareil est orienté %1° %2 et %3° %4. + + + down + bas + + + up + haut + + + left + gauche + + + right + droite + + + Are you sure you want to reboot? + Êtes-vous sûr de vouloir redémarrer ? + + + Disengage to Reboot + Désengager pour redémarrer + + + Are you sure you want to power off? + Êtes-vous sûr de vouloir éteindre ? + + + Disengage to Power Off + Désengager pour éteindre + + + Debug Console + + + + Error displaying tmux output. + + + + + DriveStats + + Drives + Trajets + + + Hours + Heures + + + ALL TIME + DEPUIS TOUJOURS + + + PAST WEEK + CETTE SEMAINE + + + KM + KM + + + Miles + Miles + + + + DriverViewScene + + camera starting + démarrage de la caméra + + + + ExperimentalModeButton + + EXPERIMENTAL MODE ON + MODE EXPÉRIMENTAL ACTIVÉ + + + CHILL MODE ON + MODE DÉTENTE ACTIVÉ + + + + InputDialog + + Cancel + Annuler + + + Need at least %n character(s)! + + Besoin d'au moins %n caractère ! + Besoin d'au moins %n caractères ! + + + + + Installer + + Installing... + Installation... + + + + MapETA + + eta + eta + + + min + min + + + hr + h + + + km + km + + + mi + mi + + + + MapInstructions + + km + km + + + m + m + + + mi + mi + + + ft + ft + + + + MapSettings + + NAVIGATION + NAVIGATION + + + Manage at connect.comma.ai + Gérer sur connect.comma.ai + + + + MapWindow + + Map Loading + Chargement de la carte + + + Waiting for GPS + En attente du GPS + + + Waiting for route + En attente d'un trajet + + + + MultiOptionDialog + + Select + Sélectionner + + + Cancel + Annuler + + + + Networking + + Advanced + Avancé + + + Enter password + Entrer le mot de passe + + + for "%1" + pour "%1" + + + Wrong password + Mot de passe incorrect + + + + OffroadAlert + + Device temperature too high. System cooling down before starting. Current internal component temperature: %1 + Température de l'appareil trop élevée. Le système doit refroidir avant de démarrer. Température actuelle de l'appareil : %1 + + + Immediately connect to the internet to check for updates. If you do not connect to the internet, openpilot won't engage in %1 + Connectez-vous immédiatement à internet pour vérifier les mises à jour. Si vous ne vous connectez pas à internet, openpilot ne s'engagera pas dans %1 + + + Connect to internet to check for updates. openpilot won't automatically start until it connects to internet to check for updates. + Connectez l'appareil à internet pour vérifier les mises à jour. openpilot ne démarrera pas automatiquement tant qu'il ne se connecte pas à internet pour vérifier les mises à jour. + + + Unable to download updates +%1 + Impossible de télécharger les mises à jour +%1 + + + Invalid date and time settings, system won't start. Connect to internet to set time. + Paramètres de date et d'heure invalides, le système ne démarrera pas. Connectez l'appareil à Internet pour régler l'heure. + + + Taking camera snapshots. System won't start until finished. + Capture de clichés photo. Le système ne démarrera pas tant qu'il n'est pas terminé. + + + An update to your device's operating system is downloading in the background. You will be prompted to update when it's ready to install. + Une mise à jour du système d'exploitation de votre appareil est en cours de téléchargement en arrière-plan. Vous serez invité à effectuer la mise à jour lorsqu'elle sera prête à être installée. + + + Device failed to register. It will not connect to or upload to comma.ai servers, and receives no support from comma.ai. If this is an official device, visit https://comma.ai/support. + L'appareil n'a pas réussi à s'enregistrer. Il ne se connectera pas aux serveurs de comma.ai, n'enverra rien et ne recevra aucune assistance de comma.ai. S'il s'agit d'un appareil officiel, visitez https://comma.ai/support. + + + NVMe drive not mounted. + Le disque NVMe n'est pas monté. + + + Unsupported NVMe drive detected. Device may draw significantly more power and overheat due to the unsupported NVMe. + Disque NVMe non supporté détecté. L'appareil peut consommer beaucoup plus d'énergie et surchauffer en raison du NVMe non supporté. + + + openpilot was unable to identify your car. Your car is either unsupported or its ECUs are not recognized. Please submit a pull request to add the firmware versions to the proper vehicle. Need help? Join discord.comma.ai. + openpilot n'a pas pu identifier votre voiture. Votre voiture n'est pas supportée ou ses ECUs ne sont pas reconnues. Veuillez soumettre un pull request pour ajouter les versions de firmware au véhicule approprié. Besoin d'aide ? Rejoignez discord.comma.ai. + + + openpilot was unable to identify your car. Check integrity of cables and ensure all connections are secure, particularly that the comma power is fully inserted in the OBD-II port of the vehicle. Need help? Join discord.comma.ai. + openpilot n'a pas pu identifier votre voiture. Vérifiez l'intégrité des câbles et assurez-vous que toutes les connexions sont correctes, en particulier l'alimentation du comma est totalement insérée dans le port OBD-II du véhicule. Besoin d'aide ? Rejoignez discord.comma.ai. + + + openpilot detected a change in the device's mounting position. Ensure the device is fully seated in the mount and the mount is firmly secured to the windshield. + openpilot a détecté un changement dans la position de montage de l'appareil. Assurez-vous que l'appareil est totalement inséré dans le support et que le support est fermement fixé au pare-brise. + + + + OffroadHome + + UPDATE + MISE À JOUR + + + ALERTS + ALERTES + + + ALERT + ALERTE + + + + PairingPopup + + Pair your device to your comma account + Associez votre appareil à votre compte comma + + + Go to https://connect.comma.ai on your phone + Allez sur https://connect.comma.ai sur votre téléphone + + + Click "add new device" and scan the QR code on the right + Cliquez sur "ajouter un nouvel appareil" et scannez le code QR à droite + + + Bookmark connect.comma.ai to your home screen to use it like an app + Ajoutez connect.comma.ai à votre écran d'accueil pour l'utiliser comme une application + + + + ParamControl + + Enable + Activer + + + Cancel + Annuler + + + + PrimeAdWidget + + Upgrade Now + Mettre à niveau maintenant + + + Become a comma prime member at connect.comma.ai + Devenez membre comma prime sur connect.comma.ai + + + PRIME FEATURES: + FONCTIONNALITÉS PRIME : + + + Remote access + Accès à distance + + + 24/7 LTE connectivity + Connexion LTE 24/7 + + + 1 year of drive storage + 1 an de stockage de trajets + + + Turn-by-turn navigation + Navigation étape par étape + + + + PrimeUserWidget + + ✓ SUBSCRIBED + ✓ ABONNÉ + + + comma prime + comma prime + + + + QObject + + Reboot + Redémarrer + + + Exit + Quitter + + + dashcam + dashcam + + + openpilot + openpilot + + + %n minute(s) ago + + il y a %n minute + il y a %n minutes + + + + %n hour(s) ago + + il y a %n heure + il y a %n heures + + + + %n day(s) ago + + il y a %n jour + il y a %n jours + + + + + Reset + + Reset failed. Reboot to try again. + Réinitialisation échouée. Redémarrez pour réessayer. + + + Resetting device... +This may take up to a minute. + Réinitialisation de l'appareil... +Cela peut prendre jusqu'à une minute. + + + Are you sure you want to reset your device? + Êtes-vous sûr de vouloir réinitialiser votre appareil ? + + + System Reset + Réinitialisation du système + + + Press confirm to erase all content and settings. Press cancel to resume boot. + Appuyez sur confirmer pour effacer tout le contenu et les paramètres. Appuyez sur annuler pour reprendre le démarrage. + + + Cancel + Annuler + + + Reboot + Redémarrer + + + Confirm + Confirmer + + + Unable to mount data partition. Partition may be corrupted. Press confirm to erase and reset your device. + Impossible de monter la partition data. La partition peut être corrompue. Appuyez sur confirmer pour effacer et réinitialiser votre appareil. + + + + SettingsWindow + + × + × + + + Device + Appareil + + + Network + Réseau + + + Toggles + Options + + + Software + Logiciel + + + Vehicle Model: + + + + [AUTO SELECT] + + + + + Setup + + Something went wrong. Reboot the device. + Un problème est survenu. Redémarrez l'appareil. + + + Ensure the entered URL is valid, and the device’s internet connection is good. + Assurez-vous que l'URL saisie est valide et que la connexion internet de l'appareil est bonne. + + + No custom software found at this URL. + Aucun logiciel personnalisé trouvé à cette URL. + + + WARNING: Low Voltage + ATTENTION : Tension faible + + + Power your device in a car with a harness or proceed at your own risk. + Alimentez votre appareil dans une voiture avec un harness ou continuez à vos risques et périls. + + + Power off + Éteindre + + + Continue + Continuer + + + Getting Started + Commencer + + + Before we get on the road, let’s finish installation and cover some details. + Avant de prendre la route, terminons l'installation et passons en revue quelques détails. + + + Connect to Wi-Fi + Se connecter au Wi-Fi + + + Back + Retour + + + Enter URL + Entrer l'URL + + + for Custom Software + pour logiciel personnalisé + + + Continue without Wi-Fi + Continuer sans Wi-Fi + + + Waiting for internet + En attente d'internet + + + Downloading... + Téléchargement... + + + Download Failed + Échec du téléchargement + + + Reboot device + Redémarrer l'appareil + + + Start over + Recommencer + + + + SetupWidget + + Finish Setup + Terminer l'installation + + + Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer. + Associez votre appareil avec comma connect (connect.comma.ai) et profitez de l'offre comma prime. + + + Pair device + Associer l'appareil + + + + Sidebar + + CONNECT + CONNECTER + + + OFFLINE + HORS LIGNE + + + ONLINE + EN LIGNE + + + ERROR + ERREUR + + + TEMP + TEMP + + + HIGH + HAUT + + + GOOD + BON + + + OK + OK + + + VEHICLE + VÉHICULE + + + NO + NON + + + PANDA + PANDA + + + GPS + GPS + + + SEARCH + RECHERCHE + + + -- + -- + + + Wi-Fi + Wi-Fi + + + ETH + ETH + + + 2G + 2G + + + 3G + 3G + + + LTE + LTE + + + 5G + 5G + + + + SoftwarePanel + + Updates are only downloaded while the car is off. + Les mises à jour sont téléchargées uniquement lorsque la voiture est éteinte. + + + Current Version + Version actuelle + + + Download + Télécharger + + + CHECK + VÉRIFIER + + + Install Update + Installer la mise à jour + + + INSTALL + INSTALLER + + + Target Branch + Branche cible + + + SELECT + SÉLECTIONNER + + + Select a branch + Sélectionner une branche + + + Uninstall %1 + Désinstaller %1 + + + UNINSTALL + DÉSINSTALLER + + + Are you sure you want to uninstall? + Êtes-vous sûr de vouloir désinstaller ? + + + Uninstall + Désinstaller + + + failed to check for update + échec de la vérification de la mise à jour + + + DOWNLOAD + TÉLÉCHARGER + + + update available + mise à jour disponible + + + never + jamais + + + up to date, last checked %1 + à jour, dernière vérification %1 + + + + SshControl + + SSH Keys + Clés SSH + + + Warning: This grants SSH access to all public keys in your GitHub settings. Never enter a GitHub username other than your own. A comma employee will NEVER ask you to add their GitHub username. + Attention : Ceci accorde l'accès SSH à toutes les clés publiques de vos paramètres GitHub. N'entrez jamais un nom d'utilisateur GitHub autre que le vôtre. Un employé de comma ne vous demandera JAMAIS d'ajouter son nom d'utilisateur GitHub. + + + ADD + AJOUTER + + + Enter your GitHub username + Entrez votre nom d'utilisateur GitHub + + + LOADING + CHARGEMENT + + + REMOVE + SUPPRIMER + + + Username '%1' has no keys on GitHub + L'utilisateur '%1' n'a pas de clés sur GitHub + + + Request timed out + Délai de la demande dépassé + + + Username '%1' doesn't exist on GitHub + L'utilisateur '%1' n'existe pas sur GitHub + + + + SshToggle + + Enable SSH + Activer SSH + + + + TermsPage + + Terms & Conditions + Termes & Conditions + + + Decline + Refuser + + + Scroll to accept + Faire défiler pour accepter + + + Agree + Accepter + + + + TogglesPanel + + Enable openpilot + Activer openpilot + + + Use the openpilot system for adaptive cruise control and lane keep driver assistance. Your attention is required at all times to use this feature. Changing this setting takes effect when the car is powered off. + Utilisez le système openpilot pour le régulateur de vitesse adaptatif et l'assistance au maintien de voie. Votre attention est requise en permanence pour utiliser cette fonctionnalité. La modification de ce paramètre prend effet lorsque la voiture est éteinte. + + + openpilot Longitudinal Control (Alpha) + Contrôle longitudinal openpilot (Alpha) + + + WARNING: openpilot longitudinal control is in alpha for this car and will disable Automatic Emergency Braking (AEB). + ATTENTION : le contrôle longitudinal openpilot est en alpha pour cette voiture et désactivera le freinage d'urgence automatique (AEB). + + + On this car, openpilot defaults to the car's built-in ACC instead of openpilot's longitudinal control. Enable this to switch to openpilot longitudinal control. Enabling Experimental mode is recommended when enabling openpilot longitudinal control alpha. + Sur cette voiture, openpilot utilise par défaut le régulateur de vitesse adaptatif intégré à la voiture plutôt que le contrôle longitudinal d'openpilot. Activez ceci pour passer au contrôle longitudinal openpilot. Il est recommandé d'activer le mode expérimental lors de l'activation du contrôle longitudinal openpilot alpha. + + + Experimental Mode + Mode expérimental + + + Disengage on Accelerator Pedal + Désengager avec la pédale d'accélérateur + + + When enabled, pressing the accelerator pedal will disengage openpilot. + Lorsqu'il est activé, appuyer sur la pédale d'accélérateur désengagera openpilot. + + + Enable Lane Departure Warnings + Activer les avertissements de sortie de voie + + + Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31 mph (50 km/h). + Recevez des alertes pour revenir dans la voie lorsque votre véhicule dérive au-delà d'une ligne de voie détectée sans clignotant activé en roulant à plus de 31 mph (50 km/h). + + + Record and Upload Driver Camera + Enregistrer et télécharger la caméra conducteur + + + Upload data from the driver facing camera and help improve the driver monitoring algorithm. + Publiez les données de la caméra orientée vers le conducteur et aidez à améliorer l'algorithme de surveillance du conducteur. + + + Use Metric System + Utiliser le système métrique + + + Display speed in km/h instead of mph. + Afficher la vitesse en km/h au lieu de mph. + + + Show ETA in 24h Format + Afficher l'heure d'arrivée en format 24h + + + Use 24h format instead of am/pm + Utiliser le format 24h plutôt que am/pm + + + Show Map on Left Side of UI + Afficher la carte à gauche de l'interface + + + Show map on left side when in split screen view. + Afficher la carte à gauche en mode écran scindé. + + + Aggressive + Aggressif + + + Standard + Standard + + + Relaxed + Détendu + + + Driving Personality + Personnalité de conduite + + + Standard is recommended. In aggressive mode, openpilot will follow lead cars closer and be more aggressive with the gas and brake. In relaxed mode openpilot will stay further away from lead cars. + Le mode standard est recommandé. En mode agressif, openpilot suivra de plus près les voitures de tête et sera plus agressif avec l'accélérateur et le frein. En mode détendu, openpilot restera plus éloigné des voitures de tête. + + + openpilot defaults to driving in <b>chill mode</b>. Experimental mode enables <b>alpha-level features</b> that aren't ready for chill mode. Experimental features are listed below: + Par défaut, openpilot conduit en <b>mode détente</b>. Le mode expérimental permet d'activer des <b>fonctionnalités alpha</b> qui ne sont pas prêtes pour le mode détente. Les fonctionnalités expérimentales sont listées ci-dessous : + + + Let the driving model control the gas and brakes. openpilot will drive as it thinks a human would, including stopping for red lights and stop signs. Since the driving model decides the speed to drive, the set speed will only act as an upper bound. This is an alpha quality feature; mistakes should be expected. + Laissez le modèle de conduite contrôler l'accélérateur et les freins. openpilot conduira comme il pense qu'un humain le ferait, y compris s'arrêter aux feux rouges et aux panneaux stop. Comme le modèle de conduite décide de la vitesse à adopter, la vitesse définie ne servira que de limite supérieure. Cette fonctionnalité est de qualité alpha ; des erreurs sont à prévoir. + + + New Driving Visualization + Nouvelle visualisation de la conduite + + + Experimental mode is currently unavailable on this car since the car's stock ACC is used for longitudinal control. + Le mode expérimental est actuellement indisponible pour cette voiture car le régulateur de vitesse adaptatif d'origine est utilisé pour le contrôle longitudinal. + + + openpilot longitudinal control may come in a future update. + Le contrôle longitudinal openpilot pourrait être disponible dans une future mise à jour. + + + An alpha version of openpilot longitudinal control can be tested, along with Experimental mode, on non-release branches. + Une version alpha du contrôle longitudinal openpilot peut être testée, avec le mode expérimental, sur des branches non publiées. + + + End-to-End Longitudinal Control + Contrôle longitudinal de bout en bout + + + Navigate on openpilot + Navigation avec openpilot + + + When navigation has a destination, openpilot will input the map information into the model. This provides useful context for the model and allows openpilot to keep left or right appropriately at forks/exits. Lane change behavior is unchanged and still activated by the driver. This is an alpha quality feature; mistakes should be expected, particularly around exits and forks. These mistakes can include unintended laneline crossings, late exit taking, driving towards dividing barriers in the gore areas, etc. + Lorsque la navigation dispose d'une destination, openpilot entrera les informations de la carte dans le modèle. Cela fournit un contexte utile pour le modèle et permet à openpilot de se diriger à gauche ou à droite de manière appropriée aux bifurcations/sorties. Le comportement relatif au changement de voie reste inchangé et doit toujours être activé par le conducteur. Il s'agit d'une fonctionnalité alpha ; il faut s'attendre à des erreurs, en particulier aux abords des sorties et des bifurcations. Ces erreurs peuvent inclure des franchissements involontaires de passages piétons, des prises de sortie tardives, la conduite vers des zones de séparation de type zebras, etc. + + + The driving visualization will transition to the road-facing wide-angle camera at low speeds to better show some turns. The Experimental mode logo will also be shown in the top right corner. When a navigation destination is set and the driving model is using it as input, the driving path on the map will turn green. + La visualisation de la conduite passera sur la caméra grand angle dirigée vers la route à faible vitesse afin de mieux montrer certains virages. Le logo du mode expérimental s'affichera également dans le coin supérieur droit. Lorsqu'une destination de navigation est définie et que le modèle de conduite l'utilise comme entrée, la trajectoire de conduite sur la carte deviendra verte. + + + Enable the openpilot longitudinal control (alpha) toggle to allow Experimental mode. + Activer le contrôle longitudinal d'openpilot (en alpha) pour autoriser le mode expérimental. + + + + Updater + + Update Required + Mise à jour requise + + + An operating system update is required. Connect your device to Wi-Fi for the fastest update experience. The download size is approximately 1GB. + Une mise à jour du système d'exploitation est requise. Connectez votre appareil au Wi-Fi pour une mise à jour plus rapide. La taille du téléchargement est d'environ 1 Go. + + + Connect to Wi-Fi + Se connecter au Wi-Fi + + + Install + Installer + + + Back + Retour + + + Loading... + Chargement... + + + Reboot + Redémarrer + + + Update failed + Échec de la mise à jour + + + + WiFiPromptWidget + + Setup Wi-Fi + Configurer le Wi-Fi + + + Connect to Wi-Fi to upload driving data and help improve openpilot + Connectez-vous au Wi-Fi pour publier les données de conduite et aider à améliorer openpilot + + + Open Settings + Ouvrir les paramètres + + + Ready to upload + Prêt à uploader + + + Training data will be pulled periodically while your device is on Wi-Fi + Les données d'entraînement seront envoyées périodiquement lorsque votre appareil est connecté au réseau Wi-Fi + + + + WifiUI + + Scanning for networks... + Recherche de réseaux... + + + CONNECTING... + CONNEXION... + + + FORGET + OUBLIER + + + Forget Wi-Fi Network "%1"? + Oublier le réseau Wi-Fi "%1" ? + + + Forget + Oublier + + + diff --git a/selfdrive/ui/translations/main_ja.qm b/selfdrive/ui/translations/main_ja.qm index bd79eb358..c8bafa974 100644 Binary files a/selfdrive/ui/translations/main_ja.qm and b/selfdrive/ui/translations/main_ja.qm differ diff --git a/selfdrive/ui/translations/main_ja.ts b/selfdrive/ui/translations/main_ja.ts index c8ae54193..2addfc0fd 100644 --- a/selfdrive/ui/translations/main_ja.ts +++ b/selfdrive/ui/translations/main_ja.ts @@ -91,19 +91,35 @@ km - キロメートル + キロメートル m - メートル + メートル mi - マイル + マイル ft - フィート + フィート + + + km + キロメートル + + + m + + + + mi + マイル + + + ft + @@ -297,6 +313,15 @@ Reboot Required. Reboot Required. + + Road Edge Detection + + + + When enabled, openpilot will block lane change if road edge is detected. +Reboot required. + + Enable TACO Tune @@ -362,10 +387,6 @@ NOR - Normal tune. SPT - Sport tune. - - *β* Enable Otisserv - - When enabled, you will be able to access some features remotely through dragonpilot.org. @@ -379,6 +400,18 @@ SPT - Sport tune. Reboot Required. + + *α* Enable Otisserv + + + + *α* Enable NOO Voice Guidance + + + + When enabled and NOO is active, dragonpilot will audibly instruct the driver when and where to turn. + + DeclinePage diff --git a/selfdrive/ui/translations/main_ko.qm b/selfdrive/ui/translations/main_ko.qm index 9c0d314fb..3b301e3da 100644 Binary files a/selfdrive/ui/translations/main_ko.qm and b/selfdrive/ui/translations/main_ko.qm differ diff --git a/selfdrive/ui/translations/main_ko.ts b/selfdrive/ui/translations/main_ko.ts index 27c5da6a5..2e85554c4 100644 --- a/selfdrive/ui/translations/main_ko.ts +++ b/selfdrive/ui/translations/main_ko.ts @@ -91,19 +91,35 @@ km - km + km m - m + m mi - mi + mi ft - ft + ft + + + km + km + + + m + + + + mi + mi + + + ft + @@ -297,6 +313,15 @@ Reboot Required. Reboot Required. + + Road Edge Detection + + + + When enabled, openpilot will block lane change if road edge is detected. +Reboot required. + + Enable TACO Tune @@ -362,10 +387,6 @@ NOR - Normal tune. SPT - Sport tune. - - *β* Enable Otisserv - - When enabled, you will be able to access some features remotely through dragonpilot.org. @@ -379,6 +400,18 @@ SPT - Sport tune. Reboot Required. + + *α* Enable Otisserv + + + + *α* Enable NOO Voice Guidance + + + + When enabled and NOO is active, dragonpilot will audibly instruct the driver when and where to turn. + + DeclinePage diff --git a/selfdrive/ui/translations/main_pt-BR.qm b/selfdrive/ui/translations/main_pt-BR.qm index 5784d06ad..3abd153fc 100644 Binary files a/selfdrive/ui/translations/main_pt-BR.qm and b/selfdrive/ui/translations/main_pt-BR.qm differ diff --git a/selfdrive/ui/translations/main_pt-BR.ts b/selfdrive/ui/translations/main_pt-BR.ts index de420c29c..ae627ce32 100644 --- a/selfdrive/ui/translations/main_pt-BR.ts +++ b/selfdrive/ui/translations/main_pt-BR.ts @@ -91,19 +91,35 @@ km - km + km m - m + m mi - milha + milha ft - pés + pés + + + km + km + + + m + + + + mi + mi + + + ft + @@ -297,6 +313,15 @@ Reboot Required. Reboot Required. + + Road Edge Detection + + + + When enabled, openpilot will block lane change if road edge is detected. +Reboot required. + + Enable TACO Tune @@ -362,10 +387,6 @@ NOR - Normal tune. SPT - Sport tune. - - *β* Enable Otisserv - - When enabled, you will be able to access some features remotely through dragonpilot.org. @@ -379,6 +400,18 @@ SPT - Sport tune. Reboot Required. + + *α* Enable Otisserv + + + + *α* Enable NOO Voice Guidance + + + + When enabled and NOO is active, dragonpilot will audibly instruct the driver when and where to turn. + + DeclinePage diff --git a/selfdrive/ui/translations/main_zh-CHS.qm b/selfdrive/ui/translations/main_zh-CHS.qm index 05a0c8850..73faeb78f 100644 Binary files a/selfdrive/ui/translations/main_zh-CHS.qm and b/selfdrive/ui/translations/main_zh-CHS.qm differ diff --git a/selfdrive/ui/translations/main_zh-CHS.ts b/selfdrive/ui/translations/main_zh-CHS.ts index 660568f53..0e8040659 100644 --- a/selfdrive/ui/translations/main_zh-CHS.ts +++ b/selfdrive/ui/translations/main_zh-CHS.ts @@ -91,19 +91,35 @@ km - km + km m - m + m mi - mi + mi ft - ft + ft + + + km + km + + + m + + + + mi + mi + + + ft + @@ -297,6 +313,15 @@ Reboot Required. Reboot Required. + + Road Edge Detection + + + + When enabled, openpilot will block lane change if road edge is detected. +Reboot required. + + Enable TACO Tune @@ -362,10 +387,6 @@ NOR - Normal tune. SPT - Sport tune. - - *β* Enable Otisserv - - When enabled, you will be able to access some features remotely through dragonpilot.org. @@ -379,6 +400,18 @@ SPT - Sport tune. Reboot Required. + + *α* Enable Otisserv + + + + *α* Enable NOO Voice Guidance + + + + When enabled and NOO is active, dragonpilot will audibly instruct the driver when and where to turn. + + DeclinePage diff --git a/selfdrive/ui/translations/main_zh-CHT.qm b/selfdrive/ui/translations/main_zh-CHT.qm index 61cdbe952..d3dd48ceb 100644 Binary files a/selfdrive/ui/translations/main_zh-CHT.qm and b/selfdrive/ui/translations/main_zh-CHT.qm differ diff --git a/selfdrive/ui/translations/main_zh-CHT.ts b/selfdrive/ui/translations/main_zh-CHT.ts index d7dd03db8..6b370dbe2 100644 --- a/selfdrive/ui/translations/main_zh-CHT.ts +++ b/selfdrive/ui/translations/main_zh-CHT.ts @@ -91,19 +91,35 @@ km - km + km m - m + m mi - mi + mi ft - ft + ft + + + km + km + + + m + + + + mi + mi + + + ft + @@ -297,6 +313,15 @@ Reboot Required. Reboot Required. + + Road Edge Detection + + + + When enabled, openpilot will block lane change if road edge is detected. +Reboot required. + + Enable TACO Tune @@ -362,10 +387,6 @@ NOR - Normal tune. SPT - Sport tune. - - *β* Enable Otisserv - - When enabled, you will be able to access some features remotely through dragonpilot.org. @@ -379,6 +400,18 @@ SPT - Sport tune. Reboot Required. + + *α* Enable Otisserv + + + + *α* Enable NOO Voice Guidance + + + + When enabled and NOO is active, dragonpilot will audibly instruct the driver when and where to turn. + + DeclinePage diff --git a/system/camerad/camerad b/system/camerad/camerad index d7d971863..ebf9d6418 100755 Binary files a/system/camerad/camerad and b/system/camerad/camerad differ diff --git a/system/clocksd/clocksd b/system/clocksd/clocksd index db965d721..2dbf52a28 100755 Binary files a/system/clocksd/clocksd and b/system/clocksd/clocksd differ diff --git a/system/hardware/tici/hardware.py b/system/hardware/tici/hardware.py index 8dc74ce3d..6932ea08b 100644 --- a/system/hardware/tici/hardware.py +++ b/system/hardware/tici/hardware.py @@ -83,6 +83,17 @@ def affine_irq(val, action): for i in irqs: sudo_write(str(val), f"/proc/irq/{i}/smp_affinity_list") +@lru_cache +def get_device_type(): + # lru_cache and cache can cause memory leaks when used in classes + with open("/sys/firmware/devicetree/base/model") as f: + model = f.read().strip('\x00') + model = model.split('comma ')[-1] + # TODO: remove this with AGNOS 7+ + if model.startswith('Qualcomm'): + model = 'tici' + return model + class Tici(HardwareBase): @cached_property def bus(self): @@ -105,15 +116,8 @@ class Tici(HardwareBase): with open("/VERSION") as f: return f.read().strip() - @lru_cache def get_device_type(self): - with open("/sys/firmware/devicetree/base/model") as f: - model = f.read().strip('\x00') - model = model.split('comma ')[-1] - # TODO: remove this with AGNOS 7+ - if model.startswith('Qualcomm'): - model = 'tici' - return model + return get_device_type() def get_sound_card_online(self): if os.path.isfile('/proc/asound/card0/state'): diff --git a/system/logcatd/logcatd b/system/logcatd/logcatd index 3225cdd8d..8f89f90d7 100755 Binary files a/system/logcatd/logcatd and b/system/logcatd/logcatd differ diff --git a/system/loggerd/bootlog b/system/loggerd/bootlog index 4255f0ee6..343b76c47 100755 Binary files a/system/loggerd/bootlog and b/system/loggerd/bootlog differ diff --git a/system/loggerd/encoderd b/system/loggerd/encoderd index 0149edf3e..027a995f9 100755 Binary files a/system/loggerd/encoderd and b/system/loggerd/encoderd differ diff --git a/system/loggerd/loggerd b/system/loggerd/loggerd index b1bb0b389..0ad64bd6f 100755 Binary files a/system/loggerd/loggerd and b/system/loggerd/loggerd differ diff --git a/system/loggerd/loggerd.h b/system/loggerd/loggerd.h index 4100f12f8..531b30e9f 100644 --- a/system/loggerd/loggerd.h +++ b/system/loggerd/loggerd.h @@ -12,7 +12,9 @@ #include "system/loggerd/logger.h" constexpr int MAIN_FPS = 20; -const int MAIN_BITRATE = 10000000; +const int MAIN_BITRATE = 1e7; +const int LIVESTREAM_BITRATE = 1e6; +const int QCAM_BITRATE = 256000; #define NO_CAMERA_PATIENCE 500 // fall back to time-based rotation if all cameras are dead @@ -26,11 +28,10 @@ const int SEGMENT_LENGTH = LOGGERD_TEST ? atoi(getenv("LOGGERD_SEGMENT_LENGTH")) constexpr char PRESERVE_ATTR_NAME[] = "user.preserve"; constexpr char PRESERVE_ATTR_VALUE = '1'; - class EncoderInfo { public: const char *publish_name; - const char *filename; + const char *filename = NULL; bool record = true; int frame_width = 1928; int frame_height = 1208; @@ -57,11 +58,13 @@ const EncoderInfo main_road_encoder_info = { .filename = "fcamera.hevc", INIT_ENCODE_FUNCTIONS(RoadEncode), }; + const EncoderInfo main_wide_road_encoder_info = { .publish_name = "wideRoadEncodeData", .filename = "ecamera.hevc", INIT_ENCODE_FUNCTIONS(WideRoadEncode), }; + const EncoderInfo main_driver_encoder_info = { .publish_name = "driverEncodeData", .filename = "dcamera.hevc", @@ -69,17 +72,40 @@ const EncoderInfo main_driver_encoder_info = { INIT_ENCODE_FUNCTIONS(DriverEncode), }; +const EncoderInfo stream_road_encoder_info = { + .publish_name = "livestreamRoadEncodeData", + .encode_type = cereal::EncodeIndex::Type::QCAMERA_H264, + .record = false, + .bitrate = LIVESTREAM_BITRATE, + INIT_ENCODE_FUNCTIONS(LivestreamRoadEncode), +}; + +const EncoderInfo stream_wide_road_encoder_info = { + .publish_name = "livestreamWideRoadEncodeData", + .encode_type = cereal::EncodeIndex::Type::QCAMERA_H264, + .record = false, + .bitrate = LIVESTREAM_BITRATE, + INIT_ENCODE_FUNCTIONS(LivestreamWideRoadEncode), +}; + +const EncoderInfo stream_driver_encoder_info = { + .publish_name = "livestreamDriverEncodeData", + .encode_type = cereal::EncodeIndex::Type::QCAMERA_H264, + .record = false, + .bitrate = LIVESTREAM_BITRATE, + INIT_ENCODE_FUNCTIONS(LivestreamDriverEncode), +}; + const EncoderInfo qcam_encoder_info = { .publish_name = "qRoadEncodeData", .filename = "qcamera.ts", - .bitrate = 256000, + .bitrate = QCAM_BITRATE, .encode_type = cereal::EncodeIndex::Type::QCAMERA_H264, .frame_width = 526, .frame_height = 330, INIT_ENCODE_FUNCTIONS(QRoadEncode), }; - const LogCameraInfo road_camera_info{ .thread_name = "road_cam_encoder", .type = RoadCam, @@ -101,4 +127,26 @@ const LogCameraInfo driver_camera_info{ .encoder_infos = {main_driver_encoder_info} }; +const LogCameraInfo stream_road_camera_info{ + .thread_name = "road_cam_encoder", + .type = RoadCam, + .stream_type = VISION_STREAM_ROAD, + .encoder_infos = {stream_road_encoder_info} +}; + +const LogCameraInfo stream_wide_road_camera_info{ + .thread_name = "wide_road_cam_encoder", + .type = WideRoadCam, + .stream_type = VISION_STREAM_WIDE_ROAD, + .encoder_infos = {stream_wide_road_encoder_info} +}; + +const LogCameraInfo stream_driver_camera_info{ + .thread_name = "driver_cam_encoder", + .type = DriverCam, + .stream_type = VISION_STREAM_DRIVER, + .encoder_infos = {stream_driver_encoder_info} +}; + const LogCameraInfo cameras_logged[] = {road_camera_info, wide_road_camera_info, driver_camera_info}; +const LogCameraInfo stream_cameras_logged[] = {stream_road_camera_info, stream_wide_road_camera_info, stream_driver_camera_info}; diff --git a/system/loggerd/uploader.py b/system/loggerd/uploader.py index 31ece0ae9..196e5b3c2 100644 --- a/system/loggerd/uploader.py +++ b/system/loggerd/uploader.py @@ -46,7 +46,7 @@ class FakeResponse: UploadResponse = Union[requests.Response, FakeResponse] def get_directory_sort(d: str) -> List[str]: - return list(map(lambda s: s.rjust(10, '0'), d.rsplit('--', 1))) + return [s.rjust(10, '0') for s in d.rsplit('--', 1)] def listdir_by_creation(d: str) -> List[str]: try: diff --git a/system/proclogd/proclogd b/system/proclogd/proclogd index 5bc72ecac..6cde1a859 100755 Binary files a/system/proclogd/proclogd and b/system/proclogd/proclogd differ diff --git a/system/sensord/_sensord b/system/sensord/_sensord index 1d3bb7c67..a049c27fd 100755 Binary files a/system/sensord/_sensord and b/system/sensord/_sensord differ diff --git a/system/sensord/rawgps/compare.py b/system/sensord/rawgps/compare.py index b2f4259e6..e1daa7f91 100755 --- a/system/sensord/rawgps/compare.py +++ b/system/sensord/rawgps/compare.py @@ -19,8 +19,8 @@ if __name__ == "__main__": recv_time = report.milliseconds / 1000 car = [] - print("qcom has ", list(sorted([x.svId for x in report.sv]))) - print("ublox has", list(sorted([x.svId for x in meas if x.gnssId == (6 if GLONASS else 0)]))) + print("qcom has ", sorted([x.svId for x in report.sv])) + print("ublox has", sorted([x.svId for x in meas if x.gnssId == (6 if GLONASS else 0)])) for i in report.sv: # match to ublox tm = None diff --git a/system/sensord/rawgps/rawgpsd.py b/system/sensord/rawgps/rawgpsd.py index 54106ca2f..d9b2c3773 100755 --- a/system/sensord/rawgps/rawgpsd.py +++ b/system/sensord/rawgps/rawgpsd.py @@ -446,7 +446,7 @@ def main() -> NoReturn: report.source = 1 # glonass measurement_status_fields = (measurementStatusFields.items(), measurementStatusGlonassFields.items()) else: - assert False + raise RuntimeError(f"invalid log_type: {log_type}") for k,v in dat.items(): if k == "version": diff --git a/system/sensord/rawgps/structs.py b/system/sensord/rawgps/structs.py index e2f1e1cdc..bde4e0049 100644 --- a/system/sensord/rawgps/structs.py +++ b/system/sensord/rawgps/structs.py @@ -317,8 +317,7 @@ def parse_struct(ss): elif typ in ["uint64", "uint64_t"]: st += "Q" else: - print("unknown type", typ) - assert False + raise RuntimeError(f"unknown type {typ}") if '[' in nam: cnt = int(nam.split("[")[1].split("]")[0]) st += st[-1]*(cnt-1) @@ -333,7 +332,7 @@ def dict_unpacker(ss, camelcase = False): if camelcase: nams = [name_to_camelcase(x) for x in nams] sz = calcsize(st) - return lambda x: dict(zip(nams, unpack_from(st, x))), sz + return lambda x: dict(zip(nams, unpack_from(st, x), strict=True)), sz def relist(dat): list_keys = set() diff --git a/system/ubloxd/ubloxd b/system/ubloxd/ubloxd index 0f4ab91a0..dd15b8577 100755 Binary files a/system/ubloxd/ubloxd and b/system/ubloxd/ubloxd differ diff --git a/system/version.py b/system/version.py index 55f80afa3..c9ab44369 100644 --- a/system/version.py +++ b/system/version.py @@ -90,7 +90,7 @@ def is_comma_remote() -> bool: if origin is None: return False - return origin.startswith('git@github.com:commaai') or origin.startswith('https://github.com/commaai') + return origin.startswith(('git@github.com:commaai', 'https://github.com/commaai')) @cache diff --git a/third_party/acados/acados_template/__init__.py b/third_party/acados/acados_template/__init__.py index f33b75bb7..bfbe90799 100644 --- a/third_party/acados/acados_template/__init__.py +++ b/third_party/acados/acados_template/__init__.py @@ -1,8 +1,5 @@ # -# Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, -# Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, -# Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, -# Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl +# Copyright (c) The acados authors. # # This file is part of acados. # @@ -31,13 +28,13 @@ # POSSIBILITY OF SUCH DAMAGE.; # -from .acados_model import * -from .generate_c_code_explicit_ode import * -from .generate_c_code_implicit_ode import * -from .generate_c_code_constraint import * -from .generate_c_code_nls_cost import * -from .acados_ocp import * -from .acados_sim import * -from .acados_ocp_solver import * -from .acados_sim_solver import * -from .utils import * +from .acados_model import AcadosModel +from .acados_ocp import AcadosOcp, AcadosOcpConstraints, AcadosOcpCost, AcadosOcpDims, AcadosOcpOptions +from .acados_sim import AcadosSim, AcadosSimDims, AcadosSimOpts +from .acados_ocp_solver import AcadosOcpSolver, get_simulink_default_opts, ocp_get_default_cmake_builder +from .acados_sim_solver import AcadosSimSolver, sim_get_default_cmake_builder +from .utils import print_casadi_expression, get_acados_path, get_python_interface_path, \ + get_tera_exec_path, get_tera, check_casadi_version, acados_dae_model_json_dump, \ + casadi_length, make_object_json_dumpable, J_to_idx, get_default_simulink_opts + +from .zoro_description import ZoroDescription, process_zoro_description diff --git a/third_party/acados/acados_template/__pycache__/__init__.cpython-311.pyc b/third_party/acados/acados_template/__pycache__/__init__.cpython-311.pyc index 3582cc18c..5a516620f 100644 Binary files a/third_party/acados/acados_template/__pycache__/__init__.cpython-311.pyc and b/third_party/acados/acados_template/__pycache__/__init__.cpython-311.pyc differ diff --git a/third_party/acados/acados_template/__pycache__/acados_model.cpython-311.pyc b/third_party/acados/acados_template/__pycache__/acados_model.cpython-311.pyc index be447a556..b6a140166 100644 Binary files a/third_party/acados/acados_template/__pycache__/acados_model.cpython-311.pyc and b/third_party/acados/acados_template/__pycache__/acados_model.cpython-311.pyc differ diff --git a/third_party/acados/acados_template/__pycache__/acados_ocp.cpython-311.pyc b/third_party/acados/acados_template/__pycache__/acados_ocp.cpython-311.pyc index b210bc0f4..f7ee01d68 100644 Binary files a/third_party/acados/acados_template/__pycache__/acados_ocp.cpython-311.pyc and b/third_party/acados/acados_template/__pycache__/acados_ocp.cpython-311.pyc differ diff --git a/third_party/acados/acados_template/__pycache__/acados_ocp_solver.cpython-311.pyc b/third_party/acados/acados_template/__pycache__/acados_ocp_solver.cpython-311.pyc index 43fd69ed6..d8e94be9f 100644 Binary files a/third_party/acados/acados_template/__pycache__/acados_ocp_solver.cpython-311.pyc and b/third_party/acados/acados_template/__pycache__/acados_ocp_solver.cpython-311.pyc differ diff --git a/third_party/acados/acados_template/__pycache__/acados_sim.cpython-311.pyc b/third_party/acados/acados_template/__pycache__/acados_sim.cpython-311.pyc index af2fd553d..13b069dae 100644 Binary files a/third_party/acados/acados_template/__pycache__/acados_sim.cpython-311.pyc and b/third_party/acados/acados_template/__pycache__/acados_sim.cpython-311.pyc differ diff --git a/third_party/acados/acados_template/__pycache__/acados_sim_solver.cpython-311.pyc b/third_party/acados/acados_template/__pycache__/acados_sim_solver.cpython-311.pyc index d2d2fd611..a8603d9cd 100644 Binary files a/third_party/acados/acados_template/__pycache__/acados_sim_solver.cpython-311.pyc and b/third_party/acados/acados_template/__pycache__/acados_sim_solver.cpython-311.pyc differ diff --git a/third_party/acados/acados_template/__pycache__/builders.cpython-311.pyc b/third_party/acados/acados_template/__pycache__/builders.cpython-311.pyc index 14464437f..ea82e3cb1 100644 Binary files a/third_party/acados/acados_template/__pycache__/builders.cpython-311.pyc and b/third_party/acados/acados_template/__pycache__/builders.cpython-311.pyc differ diff --git a/third_party/acados/acados_template/__pycache__/casadi_function_generation.cpython-311.pyc b/third_party/acados/acados_template/__pycache__/casadi_function_generation.cpython-311.pyc new file mode 100644 index 000000000..2582048a7 Binary files /dev/null and b/third_party/acados/acados_template/__pycache__/casadi_function_generation.cpython-311.pyc differ diff --git a/third_party/acados/acados_template/__pycache__/generate_c_code_constraint.cpython-311.pyc b/third_party/acados/acados_template/__pycache__/generate_c_code_constraint.cpython-311.pyc deleted file mode 100644 index 5b33866c2..000000000 Binary files a/third_party/acados/acados_template/__pycache__/generate_c_code_constraint.cpython-311.pyc and /dev/null differ diff --git a/third_party/acados/acados_template/__pycache__/generate_c_code_discrete_dynamics.cpython-311.pyc b/third_party/acados/acados_template/__pycache__/generate_c_code_discrete_dynamics.cpython-311.pyc deleted file mode 100644 index 940fd2547..000000000 Binary files a/third_party/acados/acados_template/__pycache__/generate_c_code_discrete_dynamics.cpython-311.pyc and /dev/null differ diff --git a/third_party/acados/acados_template/__pycache__/generate_c_code_explicit_ode.cpython-311.pyc b/third_party/acados/acados_template/__pycache__/generate_c_code_explicit_ode.cpython-311.pyc deleted file mode 100644 index 3eceeaeb3..000000000 Binary files a/third_party/acados/acados_template/__pycache__/generate_c_code_explicit_ode.cpython-311.pyc and /dev/null differ diff --git a/third_party/acados/acados_template/__pycache__/generate_c_code_external_cost.cpython-311.pyc b/third_party/acados/acados_template/__pycache__/generate_c_code_external_cost.cpython-311.pyc deleted file mode 100644 index 3411f9201..000000000 Binary files a/third_party/acados/acados_template/__pycache__/generate_c_code_external_cost.cpython-311.pyc and /dev/null differ diff --git a/third_party/acados/acados_template/__pycache__/generate_c_code_gnsf.cpython-311.pyc b/third_party/acados/acados_template/__pycache__/generate_c_code_gnsf.cpython-311.pyc deleted file mode 100644 index 726f8ec12..000000000 Binary files a/third_party/acados/acados_template/__pycache__/generate_c_code_gnsf.cpython-311.pyc and /dev/null differ diff --git a/third_party/acados/acados_template/__pycache__/generate_c_code_implicit_ode.cpython-311.pyc b/third_party/acados/acados_template/__pycache__/generate_c_code_implicit_ode.cpython-311.pyc deleted file mode 100644 index 06a2c0886..000000000 Binary files a/third_party/acados/acados_template/__pycache__/generate_c_code_implicit_ode.cpython-311.pyc and /dev/null differ diff --git a/third_party/acados/acados_template/__pycache__/generate_c_code_nls_cost.cpython-311.pyc b/third_party/acados/acados_template/__pycache__/generate_c_code_nls_cost.cpython-311.pyc deleted file mode 100644 index d8c1487a4..000000000 Binary files a/third_party/acados/acados_template/__pycache__/generate_c_code_nls_cost.cpython-311.pyc and /dev/null differ diff --git a/third_party/acados/acados_template/__pycache__/utils.cpython-311.pyc b/third_party/acados/acados_template/__pycache__/utils.cpython-311.pyc index bee25fb04..86d61276d 100644 Binary files a/third_party/acados/acados_template/__pycache__/utils.cpython-311.pyc and b/third_party/acados/acados_template/__pycache__/utils.cpython-311.pyc differ diff --git a/third_party/acados/acados_template/__pycache__/zoro_description.cpython-311.pyc b/third_party/acados/acados_template/__pycache__/zoro_description.cpython-311.pyc new file mode 100644 index 000000000..c6a9b6a18 Binary files /dev/null and b/third_party/acados/acados_template/__pycache__/zoro_description.cpython-311.pyc differ diff --git a/third_party/acados/acados_template/acados_layout.json b/third_party/acados/acados_template/acados_layout.json index c9f0b90c7..a1cc5bbdf 100644 --- a/third_party/acados/acados_template/acados_layout.json +++ b/third_party/acados/acados_template/acados_layout.json @@ -6,6 +6,12 @@ "str" ], "cython_include_dirs": [ + "list" + ], + "json_file": [ + "str" + ], + "shared_lib_ext": [ "str" ], "model": { @@ -15,7 +21,16 @@ "dyn_ext_fun_type" : [ "str" ], - "dyn_source_discrete" : [ + "dyn_generic_source" : [ + "str" + ], + "dyn_impl_dae_fun" : [ + "str" + ], + "dyn_impl_dae_fun_jac" : [ + "str" + ], + "dyn_impl_dae_jac" : [ "str" ], "dyn_disc_fun_jac_hess" : [ @@ -734,6 +749,9 @@ "sim_method_newton_iter": [ "int" ], + "sim_method_newton_tol": [ + "float" + ], "sim_method_jac_reuse": [ "ndarray", [ @@ -761,6 +779,12 @@ "qp_solver_iter_max": [ "int" ], + "qp_solver_cond_ric_alg": [ + "int" + ], + "qp_solver_ric_alg": [ + "int" + ], "nlp_solver_tol_stat": [ "float" ], @@ -776,6 +800,9 @@ "nlp_solver_max_iter": [ "int" ], + "nlp_solver_ext_qp_res": [ + "int" + ], "print_level": [ "int" ], @@ -794,6 +821,9 @@ "ext_cost_num_hess": [ "int" ], + "ext_fun_compile_flags": [ + "str" + ], "model_external_shared_lib_dir": [ "str" ], diff --git a/third_party/acados/acados_template/acados_model.py b/third_party/acados/acados_template/acados_model.py index e292cc747..b7c694544 100644 --- a/third_party/acados/acados_template/acados_model.py +++ b/third_party/acados/acados_template/acados_model.py @@ -1,8 +1,5 @@ # -# Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, -# Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, -# Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, -# Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl +# Copyright (c) The acados authors. # # This file is part of acados. # @@ -37,7 +34,7 @@ class AcadosModel(): Class containing all the information to code generate the external CasADi functions that are needed when creating an acados ocp solver or acados integrator. Thus, this class contains: - + a) the :py:attr:`name` of the model, b) all CasADi variables/expressions needed in the CasADi function generation process. """ @@ -73,7 +70,7 @@ class AcadosModel(): """ self.dyn_ext_fun_type = 'casadi' #: type of external functions for dynamics module; 'casadi' or 'generic'; Default: 'casadi' - self.dyn_source_discrete = None #: name of source file for discrete dyanamics; Default: :code:`None` + self.dyn_generic_source = None #: name of source file for discrete dyanamics; Default: :code:`None` self.dyn_disc_fun_jac_hess = None #: name of function discrete dyanamics + jacobian and hessian; Default: :code:`None` self.dyn_disc_fun_jac = None #: name of function discrete dyanamics + jacobian; Default: :code:`None` self.dyn_disc_fun = None #: name of function discrete dyanamics; Default: :code:`None` @@ -87,7 +84,9 @@ class AcadosModel(): ## for OCP # constraints + # BGH(default): lh <= h(x, u) <= uh self.con_h_expr = None #: CasADi expression for the constraint :math:`h`; Default: :code:`None` + # BGP(convex over nonlinear): lphi <= phi(r(x, u)) <= uphi self.con_phi_expr = None #: CasADi expression for the constraint phi; Default: :code:`None` self.con_r_expr = None #: CasADi expression for the constraint phi(r); Default: :code:`None` self.con_r_in_phi = None @@ -107,61 +106,49 @@ class AcadosModel(): self.cost_expr_ext_cost_custom_hess_e = None #: CasADi expression for custom hessian (only for external cost), terminal; Default: :code:`None` self.cost_expr_ext_cost_custom_hess_0 = None #: CasADi expression for custom hessian (only for external cost), initial; Default: :code:`None` - -def acados_model_strip_casadi_symbolics(model): - out = model - if 'f_impl_expr' in out.keys(): - del out['f_impl_expr'] - if 'f_expl_expr' in out.keys(): - del out['f_expl_expr'] - if 'disc_dyn_expr' in out.keys(): - del out['disc_dyn_expr'] - if 'x' in out.keys(): - del out['x'] - if 'xdot' in out.keys(): - del out['xdot'] - if 'u' in out.keys(): - del out['u'] - if 'z' in out.keys(): - del out['z'] - if 'p' in out.keys(): - del out['p'] - # constraints - if 'con_phi_expr' in out.keys(): - del out['con_phi_expr'] - if 'con_h_expr' in out.keys(): - del out['con_h_expr'] - if 'con_r_expr' in out.keys(): - del out['con_r_expr'] - if 'con_r_in_phi' in out.keys(): - del out['con_r_in_phi'] - # terminal - if 'con_phi_expr_e' in out.keys(): - del out['con_phi_expr_e'] - if 'con_h_expr_e' in out.keys(): - del out['con_h_expr_e'] - if 'con_r_expr_e' in out.keys(): - del out['con_r_expr_e'] - if 'con_r_in_phi_e' in out.keys(): - del out['con_r_in_phi_e'] - # cost - if 'cost_y_expr' in out.keys(): - del out['cost_y_expr'] - if 'cost_y_expr_e' in out.keys(): - del out['cost_y_expr_e'] - if 'cost_y_expr_0' in out.keys(): - del out['cost_y_expr_0'] - if 'cost_expr_ext_cost' in out.keys(): - del out['cost_expr_ext_cost'] - if 'cost_expr_ext_cost_e' in out.keys(): - del out['cost_expr_ext_cost_e'] - if 'cost_expr_ext_cost_0' in out.keys(): - del out['cost_expr_ext_cost_0'] - if 'cost_expr_ext_cost_custom_hess' in out.keys(): - del out['cost_expr_ext_cost_custom_hess'] - if 'cost_expr_ext_cost_custom_hess_e' in out.keys(): - del out['cost_expr_ext_cost_custom_hess_e'] - if 'cost_expr_ext_cost_custom_hess_0' in out.keys(): - del out['cost_expr_ext_cost_custom_hess_0'] - - return out + ## CONVEX_OVER_NONLINEAR convex-over-nonlinear cost: psi(y(x, u, p) - y_ref; p) + self.cost_psi_expr_0 = None + """ + CasADi expression for the outer loss function :math:`\psi(r, p)`, initial; Default: :code:`None` + Used if :py:attr:`acados_template.acados_ocp.AcadosOcpOptions.cost_type_0` == 'CONVEX_OVER_NONLINEAR'. + """ + self.cost_psi_expr = None + """ + CasADi expression for the outer loss function :math:`\psi(r, p)`; Default: :code:`None` + Used if :py:attr:`acados_template.acados_ocp.AcadosOcpOptions.cost_type` == 'CONVEX_OVER_NONLINEAR'. + """ + self.cost_psi_expr_e = None + """ + CasADi expression for the outer loss function :math:`\psi(r, p)`, terminal; Default: :code:`None` + Used if :py:attr:`acados_template.acados_ocp.AcadosOcpOptions.cost_type_e` == 'CONVEX_OVER_NONLINEAR'. + """ + self.cost_r_in_psi_expr_0 = None + """ + CasADi expression for the argument :math:`r`; to the outer loss function :math:`\psi(r, p)`, initial; Default: :code:`None` + Used if :py:attr:`acados_template.acados_ocp.AcadosOcpOptions.cost_type_0` == 'CONVEX_OVER_NONLINEAR'. + """ + self.cost_r_in_psi_expr = None + """ + CasADi expression for the argument :math:`r`; to the outer loss function :math:`\psi(r, p)`; Default: :code:`None` + Used if :py:attr:`acados_template.acados_ocp.AcadosOcpOptions.cost_type` == 'CONVEX_OVER_NONLINEAR'. + """ + self.cost_r_in_psi_expr_e = None + """ + CasADi expression for the argument :math:`r`; to the outer loss function :math:`\psi(r, p)`, terminal; Default: :code:`None` + Used if :py:attr:`acados_template.acados_ocp.AcadosOcpOptions.cost_type_e` == 'CONVEX_OVER_NONLINEAR'. + """ + self.cost_conl_custom_outer_hess_0 = None + """ + CasADi expression for the custom hessian of the outer loss function (only for convex-over-nonlinear cost), initial; Default: :code:`None` + Used if :py:attr:`acados_template.acados_ocp.AcadosOcpOptions.cost_type_0` == 'CONVEX_OVER_NONLINEAR'. + """ + self.cost_conl_custom_outer_hess = None + """ + CasADi expression for the custom hessian of the outer loss function (only for convex-over-nonlinear cost); Default: :code:`None` + Used if :py:attr:`acados_template.acados_ocp.AcadosOcpOptions.cost_type` == 'CONVEX_OVER_NONLINEAR'. + """ + self.cost_conl_custom_outer_hess_e = None + """ + CasADi expression for the custom hessian of the outer loss function (only for convex-over-nonlinear cost), terminal; Default: :code:`None` + Used if :py:attr:`acados_template.acados_ocp.AcadosOcpOptions.cost_type_e` == 'CONVEX_OVER_NONLINEAR'. + """ diff --git a/third_party/acados/acados_template/acados_ocp.py b/third_party/acados/acados_template/acados_ocp.py index 80970239e..ec02822ce 100644 --- a/third_party/acados/acados_template/acados_ocp.py +++ b/third_party/acados/acados_template/acados_ocp.py @@ -1,9 +1,6 @@ # -*- coding: future_fstrings -*- # -# Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, -# Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, -# Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, -# Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl +# Copyright (c) The acados authors. # # This file is part of acados. # @@ -35,7 +32,7 @@ import numpy as np import os from .acados_model import AcadosModel -from .utils import get_acados_path, J_to_idx, J_to_idx_slack +from .utils import get_acados_path, J_to_idx, J_to_idx_slack, get_lib_ext class AcadosOcpDims: """ @@ -273,224 +270,224 @@ class AcadosOcpDims: if isinstance(nx, int) and nx > 0: self.__nx = nx else: - raise Exception('Invalid nx value, expected positive integer. Exiting.') + raise Exception('Invalid nx value, expected positive integer.') @nz.setter def nz(self, nz): if isinstance(nz, int) and nz > -1: self.__nz = nz else: - raise Exception('Invalid nz value, expected nonnegative integer. Exiting.') + raise Exception('Invalid nz value, expected nonnegative integer.') @nu.setter def nu(self, nu): if isinstance(nu, int) and nu > -1: self.__nu = nu else: - raise Exception('Invalid nu value, expected nonnegative integer. Exiting.') + raise Exception('Invalid nu value, expected nonnegative integer.') @np.setter def np(self, np): if isinstance(np, int) and np > -1: self.__np = np else: - raise Exception('Invalid np value, expected nonnegative integer. Exiting.') + raise Exception('Invalid np value, expected nonnegative integer.') @ny_0.setter def ny_0(self, ny_0): if isinstance(ny_0, int) and ny_0 > -1: self.__ny_0 = ny_0 else: - raise Exception('Invalid ny_0 value, expected nonnegative integer. Exiting.') + raise Exception('Invalid ny_0 value, expected nonnegative integer.') @ny.setter def ny(self, ny): if isinstance(ny, int) and ny > -1: self.__ny = ny else: - raise Exception('Invalid ny value, expected nonnegative integer. Exiting.') + raise Exception('Invalid ny value, expected nonnegative integer.') @ny_e.setter def ny_e(self, ny_e): if isinstance(ny_e, int) and ny_e > -1: self.__ny_e = ny_e else: - raise Exception('Invalid ny_e value, expected nonnegative integer. Exiting.') + raise Exception('Invalid ny_e value, expected nonnegative integer.') @nr.setter def nr(self, nr): if isinstance(nr, int) and nr > -1: self.__nr = nr else: - raise Exception('Invalid nr value, expected nonnegative integer. Exiting.') + raise Exception('Invalid nr value, expected nonnegative integer.') @nr_e.setter def nr_e(self, nr_e): if isinstance(nr_e, int) and nr_e > -1: self.__nr_e = nr_e else: - raise Exception('Invalid nr_e value, expected nonnegative integer. Exiting.') + raise Exception('Invalid nr_e value, expected nonnegative integer.') @nh.setter def nh(self, nh): if isinstance(nh, int) and nh > -1: self.__nh = nh else: - raise Exception('Invalid nh value, expected nonnegative integer. Exiting.') + raise Exception('Invalid nh value, expected nonnegative integer.') @nh_e.setter def nh_e(self, nh_e): if isinstance(nh_e, int) and nh_e > -1: self.__nh_e = nh_e else: - raise Exception('Invalid nh_e value, expected nonnegative integer. Exiting.') + raise Exception('Invalid nh_e value, expected nonnegative integer.') @nphi.setter def nphi(self, nphi): if isinstance(nphi, int) and nphi > -1: self.__nphi = nphi else: - raise Exception('Invalid nphi value, expected nonnegative integer. Exiting.') + raise Exception('Invalid nphi value, expected nonnegative integer.') @nphi_e.setter def nphi_e(self, nphi_e): if isinstance(nphi_e, int) and nphi_e > -1: self.__nphi_e = nphi_e else: - raise Exception('Invalid nphi_e value, expected nonnegative integer. Exiting.') + raise Exception('Invalid nphi_e value, expected nonnegative integer.') @nbx.setter def nbx(self, nbx): if isinstance(nbx, int) and nbx > -1: self.__nbx = nbx else: - raise Exception('Invalid nbx value, expected nonnegative integer. Exiting.') + raise Exception('Invalid nbx value, expected nonnegative integer.') @nbxe_0.setter def nbxe_0(self, nbxe_0): if isinstance(nbxe_0, int) and nbxe_0 > -1: self.__nbxe_0 = nbxe_0 else: - raise Exception('Invalid nbxe_0 value, expected nonnegative integer. Exiting.') + raise Exception('Invalid nbxe_0 value, expected nonnegative integer.') @nbx_0.setter def nbx_0(self, nbx_0): if isinstance(nbx_0, int) and nbx_0 > -1: self.__nbx_0 = nbx_0 else: - raise Exception('Invalid nbx_0 value, expected nonnegative integer. Exiting.') + raise Exception('Invalid nbx_0 value, expected nonnegative integer.') @nbx_e.setter def nbx_e(self, nbx_e): if isinstance(nbx_e, int) and nbx_e > -1: self.__nbx_e = nbx_e else: - raise Exception('Invalid nbx_e value, expected nonnegative integer. Exiting.') + raise Exception('Invalid nbx_e value, expected nonnegative integer.') @nbu.setter def nbu(self, nbu): if isinstance(nbu, int) and nbu > -1: self.__nbu = nbu else: - raise Exception('Invalid nbu value, expected nonnegative integer. Exiting.') + raise Exception('Invalid nbu value, expected nonnegative integer.') @nsbx.setter def nsbx(self, nsbx): if isinstance(nsbx, int) and nsbx > -1: self.__nsbx = nsbx else: - raise Exception('Invalid nsbx value, expected nonnegative integer. Exiting.') + raise Exception('Invalid nsbx value, expected nonnegative integer.') @nsbx_e.setter def nsbx_e(self, nsbx_e): if isinstance(nsbx_e, int) and nsbx_e > -1: self.__nsbx_e = nsbx_e else: - raise Exception('Invalid nsbx_e value, expected nonnegative integer. Exiting.') + raise Exception('Invalid nsbx_e value, expected nonnegative integer.') @nsbu.setter def nsbu(self, nsbu): if isinstance(nsbu, int) and nsbu > -1: self.__nsbu = nsbu else: - raise Exception('Invalid nsbu value, expected nonnegative integer. Exiting.') + raise Exception('Invalid nsbu value, expected nonnegative integer.') @nsg.setter def nsg(self, nsg): if isinstance(nsg, int) and nsg > -1: self.__nsg = nsg else: - raise Exception('Invalid nsg value, expected nonnegative integer. Exiting.') + raise Exception('Invalid nsg value, expected nonnegative integer.') @nsg_e.setter def nsg_e(self, nsg_e): if isinstance(nsg_e, int) and nsg_e > -1: self.__nsg_e = nsg_e else: - raise Exception('Invalid nsg_e value, expected nonnegative integer. Exiting.') + raise Exception('Invalid nsg_e value, expected nonnegative integer.') @nsh.setter def nsh(self, nsh): if isinstance(nsh, int) and nsh > -1: self.__nsh = nsh else: - raise Exception('Invalid nsh value, expected nonnegative integer. Exiting.') + raise Exception('Invalid nsh value, expected nonnegative integer.') @nsh_e.setter def nsh_e(self, nsh_e): if isinstance(nsh_e, int) and nsh_e > -1: self.__nsh_e = nsh_e else: - raise Exception('Invalid nsh_e value, expected nonnegative integer. Exiting.') + raise Exception('Invalid nsh_e value, expected nonnegative integer.') @nsphi.setter def nsphi(self, nsphi): if isinstance(nsphi, int) and nsphi > -1: self.__nsphi = nsphi else: - raise Exception('Invalid nsphi value, expected nonnegative integer. Exiting.') + raise Exception('Invalid nsphi value, expected nonnegative integer.') @nsphi_e.setter def nsphi_e(self, nsphi_e): if isinstance(nsphi_e, int) and nsphi_e > -1: self.__nsphi_e = nsphi_e else: - raise Exception('Invalid nsphi_e value, expected nonnegative integer. Exiting.') + raise Exception('Invalid nsphi_e value, expected nonnegative integer.') @ns.setter def ns(self, ns): if isinstance(ns, int) and ns > -1: self.__ns = ns else: - raise Exception('Invalid ns value, expected nonnegative integer. Exiting.') + raise Exception('Invalid ns value, expected nonnegative integer.') @ns_e.setter def ns_e(self, ns_e): if isinstance(ns_e, int) and ns_e > -1: self.__ns_e = ns_e else: - raise Exception('Invalid ns_e value, expected nonnegative integer. Exiting.') + raise Exception('Invalid ns_e value, expected nonnegative integer.') @ng.setter def ng(self, ng): if isinstance(ng, int) and ng > -1: self.__ng = ng else: - raise Exception('Invalid ng value, expected nonnegative integer. Exiting.') + raise Exception('Invalid ng value, expected nonnegative integer.') @ng_e.setter def ng_e(self, ng_e): if isinstance(ng_e, int) and ng_e > -1: self.__ng_e = ng_e else: - raise Exception('Invalid ng_e value, expected nonnegative integer. Exiting.') + raise Exception('Invalid ng_e value, expected nonnegative integer.') @N.setter def N(self, N): if isinstance(N, int) and N > 0: self.__N = N else: - raise Exception('Invalid N value, expected positive integer. Exiting.') + raise Exception('Invalid N value, expected positive integer.') def set(self, attr, value): setattr(self, attr, value) @@ -500,6 +497,12 @@ class AcadosOcpCost: """ Class containing the numerical data of the cost: + NOTE: all cost terms, except for the terminal one are weighted with the corresponding time step. + This means given the time steps are :math:`\Delta t_0,..., \Delta t_N`, the total cost is given by: + :math:`c_\\text{total} = \Delta t_0 \cdot c_0(x_0, u_0, p_0, z_0) + ... + \Delta t_{N-1} \cdot c_{N-1}(x_0, u_0, p_0, z_0) + c_N(x_N, p_N)`. + + This means the Lagrange cost term is given in continuous time, this makes up for a seeminglessly OCP discretization with a nonuniform time grid. + In case of LINEAR_LS: stage cost is :math:`l(x,u,z) = || V_x \, x + V_u \, u + V_z \, z - y_\\text{ref}||^2_W`, @@ -508,9 +511,15 @@ class AcadosOcpCost: In case of NONLINEAR_LS: stage cost is - :math:`l(x,u,z) = || y(x,u,z) - y_\\text{ref}||^2_W`, + :math:`l(x,u,z,p) = || y(x,u,z,p) - y_\\text{ref}||^2_W`, terminal cost is - :math:`m(x) = || y^e(x) - y_\\text{ref}^e||^2_{W^e}` + :math:`m(x,p) = || y^e(x,p) - y_\\text{ref}^e||^2_{W^e}` + + In case of CONVEX_OVER_NONLINEAR: + stage cost is + :math:`l(x,u,p) = \psi(y(x,u,p) - y_\\text{ref}, p)`, + terminal cost is + :math:`m(x, p) = \psi^e (y^e(x,p) - y_\\text{ref}^e, p)` """ def __init__(self): # initial stage @@ -548,7 +557,7 @@ class AcadosOcpCost: @property def cost_type_0(self): """Cost type at initial shooting node (0) - -- string in {EXTERNAL, LINEAR_LS, NONLINEAR_LS} or :code:`None`. + -- string in {EXTERNAL, LINEAR_LS, NONLINEAR_LS, CONVEX_OVER_NONLINEAR} or :code:`None`. Default: :code:`None`. .. note:: Cost at initial stage is the same as for intermediate shooting nodes if not set differently explicitly. @@ -604,10 +613,10 @@ class AcadosOcpCost: @yref_0.setter def yref_0(self, yref_0): - if isinstance(yref_0, np.ndarray): + if isinstance(yref_0, np.ndarray) and len(yref_0.shape) == 1: self.__yref_0 = yref_0 else: - raise Exception('Invalid yref_0 value, expected numpy array. Exiting.') + raise Exception('Invalid yref_0 value, expected 1-dimensional numpy array.') @W_0.setter def W_0(self, W_0): @@ -615,7 +624,7 @@ class AcadosOcpCost: self.__W_0 = W_0 else: raise Exception('Invalid cost W_0 value. ' \ - + 'Should be 2 dimensional numpy array. Exiting.') + + 'Should be 2 dimensional numpy array.') @Vx_0.setter def Vx_0(self, Vx_0): @@ -623,7 +632,7 @@ class AcadosOcpCost: self.__Vx_0 = Vx_0 else: raise Exception('Invalid cost Vx_0 value. ' \ - + 'Should be 2 dimensional numpy array. Exiting.') + + 'Should be 2 dimensional numpy array.') @Vu_0.setter def Vu_0(self, Vu_0): @@ -631,7 +640,7 @@ class AcadosOcpCost: self.__Vu_0 = Vu_0 else: raise Exception('Invalid cost Vu_0 value. ' \ - + 'Should be 2 dimensional numpy array. Exiting.') + + 'Should be 2 dimensional numpy array.') @Vz_0.setter def Vz_0(self, Vz_0): @@ -639,21 +648,21 @@ class AcadosOcpCost: self.__Vz_0 = Vz_0 else: raise Exception('Invalid cost Vz_0 value. ' \ - + 'Should be 2 dimensional numpy array. Exiting.') + + 'Should be 2 dimensional numpy array.') @cost_ext_fun_type_0.setter def cost_ext_fun_type_0(self, cost_ext_fun_type_0): if cost_ext_fun_type_0 in ['casadi', 'generic']: self.__cost_ext_fun_type_0 = cost_ext_fun_type_0 else: - raise Exception('Invalid cost_ext_fun_type_0 value, expected numpy array. Exiting.') + raise Exception('Invalid cost_ext_fun_type_0 value, expected numpy array.') # Lagrange term @property def cost_type(self): """ Cost type at intermediate shooting nodes (1 to N-1) - -- string in {EXTERNAL, LINEAR_LS, NONLINEAR_LS}. + -- string in {EXTERNAL, LINEAR_LS, NONLINEAR_LS, CONVEX_OVER_NONLINEAR}. Default: 'LINEAR_LS'. """ return self.__cost_type @@ -695,28 +704,28 @@ class AcadosOcpCost: @property def Zl(self): - """:math:`Z_l` - diagonal of Hessian wrt lower slack at intermediate shooting nodes (1 to N-1). + """:math:`Z_l` - diagonal of Hessian wrt lower slack at intermediate shooting nodes (0 to N-1). Default: :code:`np.array([])`. """ return self.__Zl @property def Zu(self): - """:math:`Z_u` - diagonal of Hessian wrt upper slack at intermediate shooting nodes (1 to N-1). + """:math:`Z_u` - diagonal of Hessian wrt upper slack at intermediate shooting nodes (0 to N-1). Default: :code:`np.array([])`. """ return self.__Zu @property def zl(self): - """:math:`z_l` - gradient wrt lower slack at intermediate shooting nodes (1 to N-1). + """:math:`z_l` - gradient wrt lower slack at intermediate shooting nodes (0 to N-1). Default: :code:`np.array([])`. """ return self.__zl @property def zu(self): - """:math:`z_u` - gradient wrt upper slack at intermediate shooting nodes (1 to N-1). + """:math:`z_u` - gradient wrt upper slack at intermediate shooting nodes (0 to N-1). Default: :code:`np.array([])`. """ return self.__zu @@ -731,19 +740,19 @@ class AcadosOcpCost: @cost_type.setter def cost_type(self, cost_type): - cost_types = ('LINEAR_LS', 'NONLINEAR_LS', 'EXTERNAL') + cost_types = ('LINEAR_LS', 'NONLINEAR_LS', 'EXTERNAL', 'CONVEX_OVER_NONLINEAR') if cost_type in cost_types: self.__cost_type = cost_type else: - raise Exception('Invalid cost_type value. Exiting.') + raise Exception('Invalid cost_type value.') @cost_type_0.setter def cost_type_0(self, cost_type_0): - cost_types = ('LINEAR_LS', 'NONLINEAR_LS', 'EXTERNAL') + cost_types = ('LINEAR_LS', 'NONLINEAR_LS', 'EXTERNAL', 'CONVEX_OVER_NONLINEAR') if cost_type_0 in cost_types: self.__cost_type_0 = cost_type_0 else: - raise Exception('Invalid cost_type_0 value. Exiting.') + raise Exception('Invalid cost_type_0 value.') @W.setter def W(self, W): @@ -751,7 +760,7 @@ class AcadosOcpCost: self.__W = W else: raise Exception('Invalid cost W value. ' \ - + 'Should be 2 dimensional numpy array. Exiting.') + + 'Should be 2 dimensional numpy array.') @Vx.setter @@ -760,7 +769,7 @@ class AcadosOcpCost: self.__Vx = Vx else: raise Exception('Invalid cost Vx value. ' \ - + 'Should be 2 dimensional numpy array. Exiting.') + + 'Should be 2 dimensional numpy array.') @Vu.setter def Vu(self, Vu): @@ -768,7 +777,7 @@ class AcadosOcpCost: self.__Vu = Vu else: raise Exception('Invalid cost Vu value. ' \ - + 'Should be 2 dimensional numpy array. Exiting.') + + 'Should be 2 dimensional numpy array.') @Vz.setter def Vz(self, Vz): @@ -776,56 +785,56 @@ class AcadosOcpCost: self.__Vz = Vz else: raise Exception('Invalid cost Vz value. ' \ - + 'Should be 2 dimensional numpy array. Exiting.') + + 'Should be 2 dimensional numpy array.') @yref.setter def yref(self, yref): - if isinstance(yref, np.ndarray): + if isinstance(yref, np.ndarray) and len(yref.shape) == 1: self.__yref = yref else: - raise Exception('Invalid yref value, expected numpy array. Exiting.') + raise Exception('Invalid yref value, expected 1-dimensional numpy array.') @Zl.setter def Zl(self, Zl): if isinstance(Zl, np.ndarray): self.__Zl = Zl else: - raise Exception('Invalid Zl value, expected numpy array. Exiting.') + raise Exception('Invalid Zl value, expected numpy array.') @Zu.setter def Zu(self, Zu): if isinstance(Zu, np.ndarray): self.__Zu = Zu else: - raise Exception('Invalid Zu value, expected numpy array. Exiting.') + raise Exception('Invalid Zu value, expected numpy array.') @zl.setter def zl(self, zl): if isinstance(zl, np.ndarray): self.__zl = zl else: - raise Exception('Invalid zl value, expected numpy array. Exiting.') + raise Exception('Invalid zl value, expected numpy array.') @zu.setter def zu(self, zu): if isinstance(zu, np.ndarray): self.__zu = zu else: - raise Exception('Invalid zu value, expected numpy array. Exiting.') + raise Exception('Invalid zu value, expected numpy array.') @cost_ext_fun_type.setter def cost_ext_fun_type(self, cost_ext_fun_type): if cost_ext_fun_type in ['casadi', 'generic']: self.__cost_ext_fun_type = cost_ext_fun_type else: - raise Exception('Invalid cost_ext_fun_type value, expected numpy array. Exiting.') + raise Exception("Invalid cost_ext_fun_type value, expected one in ['casadi', 'generic'].") # Mayer term @property def cost_type_e(self): """ Cost type at terminal shooting node (N) - -- string in {EXTERNAL, LINEAR_LS, NONLINEAR_LS}. + -- string in {EXTERNAL, LINEAR_LS, NONLINEAR_LS, CONVEX_OVER_NONLINEAR}. Default: 'LINEAR_LS'. """ return self.__cost_type_e @@ -881,7 +890,7 @@ class AcadosOcpCost: @property def cost_ext_fun_type_e(self): - """Type of external function for cost at intermediate shooting nodes (1 to N-1). + """Type of external function for cost at terminal shooting node (N). -- string in {casadi, generic} Default: :code:'casadi'. """ @@ -889,12 +898,12 @@ class AcadosOcpCost: @cost_type_e.setter def cost_type_e(self, cost_type_e): - cost_types = ('LINEAR_LS', 'NONLINEAR_LS', 'EXTERNAL') + cost_types = ('LINEAR_LS', 'NONLINEAR_LS', 'EXTERNAL', 'CONVEX_OVER_NONLINEAR') if cost_type_e in cost_types: self.__cost_type_e = cost_type_e else: - raise Exception('Invalid cost_type_e value. Exiting.') + raise Exception('Invalid cost_type_e value.') @W_e.setter def W_e(self, W_e): @@ -902,7 +911,7 @@ class AcadosOcpCost: self.__W_e = W_e else: raise Exception('Invalid cost W_e value. ' \ - + 'Should be 2 dimensional numpy array. Exiting.') + + 'Should be 2 dimensional numpy array.') @Vx_e.setter def Vx_e(self, Vx_e): @@ -910,49 +919,49 @@ class AcadosOcpCost: self.__Vx_e = Vx_e else: raise Exception('Invalid cost Vx_e value. ' \ - + 'Should be 2 dimensional numpy array. Exiting.') + + 'Should be 2 dimensional numpy array.') @yref_e.setter def yref_e(self, yref_e): - if isinstance(yref_e, np.ndarray): + if isinstance(yref_e, np.ndarray) and len(yref_e.shape) == 1: self.__yref_e = yref_e else: - raise Exception('Invalid yref_e value, expected numpy array. Exiting.') + raise Exception('Invalid yref_e value, expected 1-dimensional numpy array.') @Zl_e.setter def Zl_e(self, Zl_e): if isinstance(Zl_e, np.ndarray): self.__Zl_e = Zl_e else: - raise Exception('Invalid Zl_e value, expected numpy array. Exiting.') + raise Exception('Invalid Zl_e value, expected numpy array.') @Zu_e.setter def Zu_e(self, Zu_e): if isinstance(Zu_e, np.ndarray): self.__Zu_e = Zu_e else: - raise Exception('Invalid Zu_e value, expected numpy array. Exiting.') + raise Exception('Invalid Zu_e value, expected numpy array.') @zl_e.setter def zl_e(self, zl_e): if isinstance(zl_e, np.ndarray): self.__zl_e = zl_e else: - raise Exception('Invalid zl_e value, expected numpy array. Exiting.') + raise Exception('Invalid zl_e value, expected numpy array.') @zu_e.setter def zu_e(self, zu_e): if isinstance(zu_e, np.ndarray): self.__zu_e = zu_e else: - raise Exception('Invalid zu_e value, expected numpy array. Exiting.') + raise Exception('Invalid zu_e value, expected numpy array.') @cost_ext_fun_type_e.setter def cost_ext_fun_type_e(self, cost_ext_fun_type_e): if cost_ext_fun_type_e in ['casadi', 'generic']: self.__cost_ext_fun_type_e = cost_ext_fun_type_e else: - raise Exception('Invalid cost_ext_fun_type_e value, expected numpy array. Exiting.') + raise Exception("Invalid cost_ext_fun_type_e value, expected one in ['casadi', 'generic'].") def set(self, attr, value): setattr(self, attr, value) @@ -1578,7 +1587,7 @@ class AcadosOcpConstraints: self.__constr_type = constr_type else: raise Exception('Invalid constr_type value. Possible values are:\n\n' \ - + ',\n'.join(constr_types) + '.\n\nYou have: ' + constr_type + '.\n\nExiting.') + + ',\n'.join(constr_types) + '.\n\nYou have: ' + constr_type + '.\n\n') @constr_type_e.setter def constr_type_e(self, constr_type_e): @@ -1587,7 +1596,7 @@ class AcadosOcpConstraints: self.__constr_type_e = constr_type_e else: raise Exception('Invalid constr_type_e value. Possible values are:\n\n' \ - + ',\n'.join(constr_types) + '.\n\nYou have: ' + constr_type_e + '.\n\nExiting.') + + ',\n'.join(constr_types) + '.\n\nYou have: ' + constr_type_e + '.\n\n') # initial x @lbx_0.setter @@ -1595,35 +1604,35 @@ class AcadosOcpConstraints: if isinstance(lbx_0, np.ndarray): self.__lbx_0 = lbx_0 else: - raise Exception('Invalid lbx_0 value. Exiting.') + raise Exception('Invalid lbx_0 value.') @ubx_0.setter def ubx_0(self, ubx_0): if isinstance(ubx_0, np.ndarray): self.__ubx_0 = ubx_0 else: - raise Exception('Invalid ubx_0 value. Exiting.') + raise Exception('Invalid ubx_0 value.') @idxbx_0.setter def idxbx_0(self, idxbx_0): if isinstance(idxbx_0, np.ndarray): self.__idxbx_0 = idxbx_0 else: - raise Exception('Invalid idxbx_0 value. Exiting.') + raise Exception('Invalid idxbx_0 value.') @Jbx_0.setter def Jbx_0(self, Jbx_0): if isinstance(Jbx_0, np.ndarray): self.__idxbx_0 = J_to_idx(Jbx_0) else: - raise Exception('Invalid Jbx_0 value. Exiting.') + raise Exception('Invalid Jbx_0 value.') @idxbxe_0.setter def idxbxe_0(self, idxbxe_0): if isinstance(idxbxe_0, np.ndarray): self.__idxbxe_0 = idxbxe_0 else: - raise Exception('Invalid idxbxe_0 value. Exiting.') + raise Exception('Invalid idxbxe_0 value.') @x0.setter @@ -1634,7 +1643,7 @@ class AcadosOcpConstraints: self.__idxbx_0 = np.arange(x0.size) self.__idxbxe_0 = np.arange(x0.size) else: - raise Exception('Invalid x0 value. Exiting.') + raise Exception('Invalid x0 value.') # bounds on x @lbx.setter @@ -1642,28 +1651,28 @@ class AcadosOcpConstraints: if isinstance(lbx, np.ndarray): self.__lbx = lbx else: - raise Exception('Invalid lbx value. Exiting.') + raise Exception('Invalid lbx value.') @ubx.setter def ubx(self, ubx): if isinstance(ubx, np.ndarray): self.__ubx = ubx else: - raise Exception('Invalid ubx value. Exiting.') + raise Exception('Invalid ubx value.') @idxbx.setter def idxbx(self, idxbx): if isinstance(idxbx, np.ndarray): self.__idxbx = idxbx else: - raise Exception('Invalid idxbx value. Exiting.') + raise Exception('Invalid idxbx value.') @Jbx.setter def Jbx(self, Jbx): if isinstance(Jbx, np.ndarray): self.__idxbx = J_to_idx(Jbx) else: - raise Exception('Invalid Jbx value. Exiting.') + raise Exception('Invalid Jbx value.') # bounds on u @lbu.setter @@ -1671,28 +1680,28 @@ class AcadosOcpConstraints: if isinstance(lbu, np.ndarray): self.__lbu = lbu else: - raise Exception('Invalid lbu value. Exiting.') + raise Exception('Invalid lbu value.') @ubu.setter def ubu(self, ubu): if isinstance(ubu, np.ndarray): self.__ubu = ubu else: - raise Exception('Invalid ubu value. Exiting.') + raise Exception('Invalid ubu value.') @idxbu.setter def idxbu(self, idxbu): if isinstance(idxbu, np.ndarray): self.__idxbu = idxbu else: - raise Exception('Invalid idxbu value. Exiting.') + raise Exception('Invalid idxbu value.') @Jbu.setter def Jbu(self, Jbu): if isinstance(Jbu, np.ndarray): self.__idxbu = J_to_idx(Jbu) else: - raise Exception('Invalid Jbu value. Exiting.') + raise Exception('Invalid Jbu value.') # bounds on x at shooting node N @lbx_e.setter @@ -1700,28 +1709,28 @@ class AcadosOcpConstraints: if isinstance(lbx_e, np.ndarray): self.__lbx_e = lbx_e else: - raise Exception('Invalid lbx_e value. Exiting.') + raise Exception('Invalid lbx_e value.') @ubx_e.setter def ubx_e(self, ubx_e): if isinstance(ubx_e, np.ndarray): self.__ubx_e = ubx_e else: - raise Exception('Invalid ubx_e value. Exiting.') + raise Exception('Invalid ubx_e value.') @idxbx_e.setter def idxbx_e(self, idxbx_e): if isinstance(idxbx_e, np.ndarray): self.__idxbx_e = idxbx_e else: - raise Exception('Invalid idxbx_e value. Exiting.') + raise Exception('Invalid idxbx_e value.') @Jbx_e.setter def Jbx_e(self, Jbx_e): if isinstance(Jbx_e, np.ndarray): self.__idxbx_e = J_to_idx(Jbx_e) else: - raise Exception('Invalid Jbx_e value. Exiting.') + raise Exception('Invalid Jbx_e value.') # polytopic constraints @D.setter @@ -1730,7 +1739,7 @@ class AcadosOcpConstraints: self.__D = D else: raise Exception('Invalid constraint D value.' \ - + 'Should be 2 dimensional numpy array. Exiting.') + + 'Should be 2 dimensional numpy array.') @C.setter def C(self, C): @@ -1738,21 +1747,21 @@ class AcadosOcpConstraints: self.__C = C else: raise Exception('Invalid constraint C value.' \ - + 'Should be 2 dimensional numpy array. Exiting.') + + 'Should be 2 dimensional numpy array.') @lg.setter def lg(self, lg): if isinstance(lg, np.ndarray): self.__lg = lg else: - raise Exception('Invalid lg value. Exiting.') + raise Exception('Invalid lg value.') @ug.setter def ug(self, ug): if isinstance(ug, np.ndarray): self.__ug = ug else: - raise Exception('Invalid ug value. Exiting.') + raise Exception('Invalid ug value.') # polytopic constraints at shooting node N @C_e.setter @@ -1761,21 +1770,21 @@ class AcadosOcpConstraints: self.__C_e = C_e else: raise Exception('Invalid constraint C_e value.' \ - + 'Should be 2 dimensional numpy array. Exiting.') + + 'Should be 2 dimensional numpy array.') @lg_e.setter def lg_e(self, lg_e): if isinstance(lg_e, np.ndarray): self.__lg_e = lg_e else: - raise Exception('Invalid lg_e value. Exiting.') + raise Exception('Invalid lg_e value.') @ug_e.setter def ug_e(self, ug_e): if isinstance(ug_e, np.ndarray): self.__ug_e = ug_e else: - raise Exception('Invalid ug_e value. Exiting.') + raise Exception('Invalid ug_e value.') # nonlinear constraints @lh.setter @@ -1783,14 +1792,14 @@ class AcadosOcpConstraints: if isinstance(lh, np.ndarray): self.__lh = lh else: - raise Exception('Invalid lh value. Exiting.') + raise Exception('Invalid lh value.') @uh.setter def uh(self, uh): if isinstance(uh, np.ndarray): self.__uh = uh else: - raise Exception('Invalid uh value. Exiting.') + raise Exception('Invalid uh value.') # convex-over-nonlinear constraints @lphi.setter @@ -1798,14 +1807,14 @@ class AcadosOcpConstraints: if isinstance(lphi, np.ndarray): self.__lphi = lphi else: - raise Exception('Invalid lphi value. Exiting.') + raise Exception('Invalid lphi value.') @uphi.setter def uphi(self, uphi): if isinstance(uphi, np.ndarray): self.__uphi = uphi else: - raise Exception('Invalid uphi value. Exiting.') + raise Exception('Invalid uphi value.') # nonlinear constraints at shooting node N @lh_e.setter @@ -1813,14 +1822,14 @@ class AcadosOcpConstraints: if isinstance(lh_e, np.ndarray): self.__lh_e = lh_e else: - raise Exception('Invalid lh_e value. Exiting.') + raise Exception('Invalid lh_e value.') @uh_e.setter def uh_e(self, uh_e): if isinstance(uh_e, np.ndarray): self.__uh_e = uh_e else: - raise Exception('Invalid uh_e value. Exiting.') + raise Exception('Invalid uh_e value.') # convex-over-nonlinear constraints at shooting node N @lphi_e.setter @@ -1828,14 +1837,14 @@ class AcadosOcpConstraints: if isinstance(lphi_e, np.ndarray): self.__lphi_e = lphi_e else: - raise Exception('Invalid lphi_e value. Exiting.') + raise Exception('Invalid lphi_e value.') @uphi_e.setter def uphi_e(self, uphi_e): if isinstance(uphi_e, np.ndarray): self.__uphi_e = uphi_e else: - raise Exception('Invalid uphi_e value. Exiting.') + raise Exception('Invalid uphi_e value.') # SLACK bounds # soft bounds on x @@ -1844,28 +1853,28 @@ class AcadosOcpConstraints: if isinstance(lsbx, np.ndarray): self.__lsbx = lsbx else: - raise Exception('Invalid lsbx value. Exiting.') + raise Exception('Invalid lsbx value.') @usbx.setter def usbx(self, usbx): if isinstance(usbx, np.ndarray): self.__usbx = usbx else: - raise Exception('Invalid usbx value. Exiting.') + raise Exception('Invalid usbx value.') @idxsbx.setter def idxsbx(self, idxsbx): if isinstance(idxsbx, np.ndarray): self.__idxsbx = idxsbx else: - raise Exception('Invalid idxsbx value. Exiting.') + raise Exception('Invalid idxsbx value.') @Jsbx.setter def Jsbx(self, Jsbx): if isinstance(Jsbx, np.ndarray): self.__idxsbx = J_to_idx_slack(Jsbx) else: - raise Exception('Invalid Jsbx value, expected numpy array. Exiting.') + raise Exception('Invalid Jsbx value, expected numpy array.') # soft bounds on u @lsbu.setter @@ -1873,28 +1882,28 @@ class AcadosOcpConstraints: if isinstance(lsbu, np.ndarray): self.__lsbu = lsbu else: - raise Exception('Invalid lsbu value. Exiting.') + raise Exception('Invalid lsbu value.') @usbu.setter def usbu(self, usbu): if isinstance(usbu, np.ndarray): self.__usbu = usbu else: - raise Exception('Invalid usbu value. Exiting.') + raise Exception('Invalid usbu value.') @idxsbu.setter def idxsbu(self, idxsbu): if isinstance(idxsbu, np.ndarray): self.__idxsbu = idxsbu else: - raise Exception('Invalid idxsbu value. Exiting.') + raise Exception('Invalid idxsbu value.') @Jsbu.setter def Jsbu(self, Jsbu): if isinstance(Jsbu, np.ndarray): self.__idxsbu = J_to_idx_slack(Jsbu) else: - raise Exception('Invalid Jsbu value. Exiting.') + raise Exception('Invalid Jsbu value.') # soft bounds on x at shooting node N @lsbx_e.setter @@ -1902,28 +1911,28 @@ class AcadosOcpConstraints: if isinstance(lsbx_e, np.ndarray): self.__lsbx_e = lsbx_e else: - raise Exception('Invalid lsbx_e value. Exiting.') + raise Exception('Invalid lsbx_e value.') @usbx_e.setter def usbx_e(self, usbx_e): if isinstance(usbx_e, np.ndarray): self.__usbx_e = usbx_e else: - raise Exception('Invalid usbx_e value. Exiting.') + raise Exception('Invalid usbx_e value.') @idxsbx_e.setter def idxsbx_e(self, idxsbx_e): if isinstance(idxsbx_e, np.ndarray): self.__idxsbx_e = idxsbx_e else: - raise Exception('Invalid idxsbx_e value. Exiting.') + raise Exception('Invalid idxsbx_e value.') @Jsbx_e.setter def Jsbx_e(self, Jsbx_e): if isinstance(Jsbx_e, np.ndarray): self.__idxsbx_e = J_to_idx_slack(Jsbx_e) else: - raise Exception('Invalid Jsbx_e value. Exiting.') + raise Exception('Invalid Jsbx_e value.') # soft bounds on general linear constraints @@ -1932,28 +1941,28 @@ class AcadosOcpConstraints: if isinstance(lsg, np.ndarray): self.__lsg = lsg else: - raise Exception('Invalid lsg value. Exiting.') + raise Exception('Invalid lsg value.') @usg.setter def usg(self, usg): if isinstance(usg, np.ndarray): self.__usg = usg else: - raise Exception('Invalid usg value. Exiting.') + raise Exception('Invalid usg value.') @idxsg.setter def idxsg(self, idxsg): if isinstance(idxsg, np.ndarray): self.__idxsg = idxsg else: - raise Exception('Invalid idxsg value. Exiting.') + raise Exception('Invalid idxsg value.') @Jsg.setter def Jsg(self, Jsg): if isinstance(Jsg, np.ndarray): self.__idxsg = J_to_idx_slack(Jsg) else: - raise Exception('Invalid Jsg value, expected numpy array. Exiting.') + raise Exception('Invalid Jsg value, expected numpy array.') # soft bounds on nonlinear constraints @@ -1962,21 +1971,21 @@ class AcadosOcpConstraints: if isinstance(lsh, np.ndarray): self.__lsh = lsh else: - raise Exception('Invalid lsh value. Exiting.') + raise Exception('Invalid lsh value.') @ush.setter def ush(self, ush): if isinstance(ush, np.ndarray): self.__ush = ush else: - raise Exception('Invalid ush value. Exiting.') + raise Exception('Invalid ush value.') @idxsh.setter def idxsh(self, idxsh): if isinstance(idxsh, np.ndarray): self.__idxsh = idxsh else: - raise Exception('Invalid idxsh value. Exiting.') + raise Exception('Invalid idxsh value.') @Jsh.setter @@ -1984,7 +1993,7 @@ class AcadosOcpConstraints: if isinstance(Jsh, np.ndarray): self.__idxsh = J_to_idx_slack(Jsh) else: - raise Exception('Invalid Jsh value, expected numpy array. Exiting.') + raise Exception('Invalid Jsh value, expected numpy array.') # soft bounds on convex-over-nonlinear constraints @lsphi.setter @@ -1992,28 +2001,28 @@ class AcadosOcpConstraints: if isinstance(lsphi, np.ndarray): self.__lsphi = lsphi else: - raise Exception('Invalid lsphi value. Exiting.') + raise Exception('Invalid lsphi value.') @usphi.setter def usphi(self, usphi): if isinstance(usphi, np.ndarray): self.__usphi = usphi else: - raise Exception('Invalid usphi value. Exiting.') + raise Exception('Invalid usphi value.') @idxsphi.setter def idxsphi(self, idxsphi): if isinstance(idxsphi, np.ndarray): self.__idxsphi = idxsphi else: - raise Exception('Invalid idxsphi value. Exiting.') + raise Exception('Invalid idxsphi value.') @Jsphi.setter def Jsphi(self, Jsphi): if isinstance(Jsphi, np.ndarray): self.__idxsphi = J_to_idx_slack(Jsphi) else: - raise Exception('Invalid Jsphi value, expected numpy array. Exiting.') + raise Exception('Invalid Jsphi value, expected numpy array.') # soft bounds on general linear constraints at shooting node N @lsg_e.setter @@ -2021,28 +2030,28 @@ class AcadosOcpConstraints: if isinstance(lsg_e, np.ndarray): self.__lsg_e = lsg_e else: - raise Exception('Invalid lsg_e value. Exiting.') + raise Exception('Invalid lsg_e value.') @usg_e.setter def usg_e(self, usg_e): if isinstance(usg_e, np.ndarray): self.__usg_e = usg_e else: - raise Exception('Invalid usg_e value. Exiting.') + raise Exception('Invalid usg_e value.') @idxsg_e.setter def idxsg_e(self, idxsg_e): if isinstance(idxsg_e, np.ndarray): self.__idxsg_e = idxsg_e else: - raise Exception('Invalid idxsg_e value. Exiting.') + raise Exception('Invalid idxsg_e value.') @Jsg_e.setter def Jsg_e(self, Jsg_e): if isinstance(Jsg_e, np.ndarray): self.__idxsg_e = J_to_idx_slack(Jsg_e) else: - raise Exception('Invalid Jsg_e value, expected numpy array. Exiting.') + raise Exception('Invalid Jsg_e value, expected numpy array.') # soft bounds on nonlinear constraints at shooting node N @lsh_e.setter @@ -2050,28 +2059,28 @@ class AcadosOcpConstraints: if isinstance(lsh_e, np.ndarray): self.__lsh_e = lsh_e else: - raise Exception('Invalid lsh_e value. Exiting.') + raise Exception('Invalid lsh_e value.') @ush_e.setter def ush_e(self, ush_e): if isinstance(ush_e, np.ndarray): self.__ush_e = ush_e else: - raise Exception('Invalid ush_e value. Exiting.') + raise Exception('Invalid ush_e value.') @idxsh_e.setter def idxsh_e(self, idxsh_e): if isinstance(idxsh_e, np.ndarray): self.__idxsh_e = idxsh_e else: - raise Exception('Invalid idxsh_e value. Exiting.') + raise Exception('Invalid idxsh_e value.') @Jsh_e.setter def Jsh_e(self, Jsh_e): if isinstance(Jsh_e, np.ndarray): self.__idxsh_e = J_to_idx_slack(Jsh_e) else: - raise Exception('Invalid Jsh_e value, expected numpy array. Exiting.') + raise Exception('Invalid Jsh_e value, expected numpy array.') # soft bounds on convex-over-nonlinear constraints at shooting node N @@ -2080,28 +2089,28 @@ class AcadosOcpConstraints: if isinstance(lsphi_e, np.ndarray): self.__lsphi_e = lsphi_e else: - raise Exception('Invalid lsphi_e value. Exiting.') + raise Exception('Invalid lsphi_e value.') @usphi_e.setter def usphi_e(self, usphi_e): if isinstance(usphi_e, np.ndarray): self.__usphi_e = usphi_e else: - raise Exception('Invalid usphi_e value. Exiting.') + raise Exception('Invalid usphi_e value.') @idxsphi_e.setter def idxsphi_e(self, idxsphi_e): if isinstance(idxsphi_e, np.ndarray): self.__idxsphi_e = idxsphi_e else: - raise Exception('Invalid idxsphi_e value. Exiting.') + raise Exception('Invalid idxsphi_e value.') @Jsphi_e.setter def Jsphi_e(self, Jsphi_e): if isinstance(Jsphi_e, np.ndarray): self.__idxsphi_e = J_to_idx_slack(Jsphi_e) else: - raise Exception('Invalid Jsphi_e value. Exiting.') + raise Exception('Invalid Jsphi_e value.') def set(self, attr, value): setattr(self, attr, value) @@ -2124,6 +2133,7 @@ class AcadosOcpOptions: self.__sim_method_num_stages = 4 # number of stages in the integrator self.__sim_method_num_steps = 1 # number of steps in the integrator self.__sim_method_newton_iter = 3 # number of Newton iterations in simulation method + self.__sim_method_newton_tol = 0.0 self.__sim_method_jac_reuse = 0 self.__qp_solver_tol_stat = None # QP solver stationarity tolerance self.__qp_solver_tol_eq = None # QP solver equality tolerance @@ -2132,16 +2142,17 @@ class AcadosOcpOptions: self.__qp_solver_iter_max = 50 # QP solver max iter self.__qp_solver_cond_N = None # QP solver: new horizon after partial condensing self.__qp_solver_warm_start = 0 + self.__qp_solver_cond_ric_alg = 1 + self.__qp_solver_ric_alg = 1 self.__nlp_solver_tol_stat = 1e-6 # NLP solver stationarity tolerance self.__nlp_solver_tol_eq = 1e-6 # NLP solver equality tolerance self.__nlp_solver_tol_ineq = 1e-6 # NLP solver inequality self.__nlp_solver_tol_comp = 1e-6 # NLP solver complementarity self.__nlp_solver_max_iter = 100 # NLP solver maximum number of iterations + self.__nlp_solver_ext_qp_res = 0 self.__Tsim = None # automatically calculated as tf/N self.__print_level = 0 # print level self.__initialize_t_slacks = 0 # possible values: 0, 1 - self.__model_external_shared_lib_dir = None # path to the the .so lib - self.__model_external_shared_lib_name = None # name of the the .so lib self.__regularize_method = None self.__time_steps = None self.__shooting_nodes = None @@ -2156,16 +2167,93 @@ class AcadosOcpOptions: self.__full_step_dual = 0 self.__eps_sufficient_descent = 1e-4 self.__hpipm_mode = 'BALANCE' - + # TODO: move those out? they are more about generation than about the acados OCP solver. + self.__ext_fun_compile_flags = '-O2' + self.__model_external_shared_lib_dir = None # path to the the .so lib + self.__model_external_shared_lib_name = None # name of the the .so lib + self.__custom_update_filename = '' + self.__custom_update_header_filename = '' + self.__custom_templates = [] + self.__custom_update_copy = True @property def qp_solver(self): """QP solver to be used in the NLP solver. - String in ('PARTIAL_CONDENSING_HPIPM', 'FULL_CONDENSING_QPOASES', 'FULL_CONDENSING_HPIPM', 'PARTIAL_CONDENSING_QPDUNES', 'PARTIAL_CONDENSING_OSQP'). + String in ('PARTIAL_CONDENSING_HPIPM', 'FULL_CONDENSING_QPOASES', 'FULL_CONDENSING_HPIPM', 'PARTIAL_CONDENSING_QPDUNES', 'PARTIAL_CONDENSING_OSQP', 'FULL_CONDENSING_DAQP'). Default: 'PARTIAL_CONDENSING_HPIPM'. """ return self.__qp_solver + @property + def ext_fun_compile_flags(self): + """ + String with compiler flags for external function compilation. + Default: '-O2'. + """ + return self.__ext_fun_compile_flags + + + @property + def custom_update_filename(self): + """ + Filename of the custom C function to update solver data and parameters in between solver calls + + This file has to implement the functions + int custom_update_init_function([model.name]_solver_capsule* capsule); + int custom_update_function([model.name]_solver_capsule* capsule); + int custom_update_terminate_function([model.name]_solver_capsule* capsule); + + + Default: ''. + """ + return self.__custom_update_filename + + + @property + def custom_templates(self): + """ + List of tuples of the form: + (input_filename, output_filename) + + Custom templates are render in OCP solver generation. + + Default: []. + """ + return self.__custom_templates + + + @property + def custom_update_header_filename(self): + """ + Header filename of the custom C function to update solver data and parameters in between solver calls + + This file has to declare the custom_update functions and look as follows: + + ``` + // Called at the end of solver creation. + // This is allowed to allocate memory and store the pointer to it into capsule->custom_update_memory. + int custom_update_init_function([model.name]_solver_capsule* capsule); + + // Custom update function that can be called between solver calls + int custom_update_function([model.name]_solver_capsule* capsule, double* data, int data_len); + + // Called just before destroying the solver. + // Responsible to free allocated memory, stored at capsule->custom_update_memory. + int custom_update_terminate_function([model.name]_solver_capsule* capsule); + + Default: ''. + """ + return self.__custom_update_header_filename + + @property + def custom_update_copy(self): + """ + Boolean; + If True, the custom update function files are copied into the `code_export_directory`. + """ + return self.__custom_update_copy + + @property def hpipm_mode(self): """ @@ -2230,6 +2318,13 @@ class AcadosOcpOptions: """Regularization method for the Hessian. String in ('NO_REGULARIZE', 'MIRROR', 'PROJECT', 'PROJECT_REDUC_HESS', 'CONVEXIFY') or :code:`None`. + - MIRROR: performs eigenvalue decomposition H = V^T D V and sets D_ii = max(eps, abs(D_ii)) + - PROJECT: performs eigenvalue decomposition H = V^T D V and sets D_ii = max(eps, D_ii) + - CONVEXIFY: Algorithm 6 from Verschueren2017, https://cdn.syscop.de/publications/Verschueren2017.pdf + - PROJECT_REDUC_HESS: experimental + + Note: default eps = 1e-4 + Default: :code:`None`. """ return self.__regularize_method @@ -2279,6 +2374,15 @@ class AcadosOcpOptions: """ return self.__sim_method_newton_iter + @property + def sim_method_newton_tol(self): + """ + Tolerance of Newton system in simulation method. + Type: float: 0.0 means not used + Default: 0.0 + """ + return self.__sim_method_newton_tol + @property def sim_method_jac_reuse(self): """ @@ -2328,10 +2432,42 @@ class AcadosOcpOptions: @property def qp_solver_warm_start(self): - """QP solver: Warm starting. - 0: no warm start; 1: warm start; 2: hot start.""" + """ + QP solver: Warm starting. + 0: no warm start; 1: warm start; 2: hot start. + Default: 0 + """ return self.__qp_solver_warm_start + @property + def qp_solver_cond_ric_alg(self): + """ + QP solver: Determines which algorithm is used in HPIPM condensing. + 0: dont factorize hessian in the condensing; 1: factorize. + Default: 1 + """ + return self.__qp_solver_cond_ric_alg + + @property + def qp_solver_ric_alg(self): + """ + QP solver: Determines which algorithm is used in HPIPM OCP QP solver. + 0 classical Riccati, 1 square-root Riccati. + + Note: taken from [HPIPM paper]: + + (a) the classical implementation requires the reduced Hessian with respect to the dynamics + equality constraints to be positive definite, but allows the full-space Hessian to be indefinite) + (b) the square-root implementation, which in order to reduce the flop count employs the Cholesky + factorization of the Riccati recursion matrix, and therefore requires the full-space Hessian to be positive definite + + [HPIPM paper]: HPIPM: a high-performance quadratic programming framework for model predictive control, Frison and Diehl, 2020 + https://cdn.syscop.de/publications/Frison2020a.pdf + + Default: 1 + """ + return self.__qp_solver_ric_alg + @property def qp_solver_iter_max(self): """ @@ -2429,6 +2565,15 @@ class AcadosOcpOptions: """NLP solver inequality tolerance""" return self.__nlp_solver_tol_ineq + @property + def nlp_solver_ext_qp_res(self): + """Determines if residuals of QP are computed externally within NLP solver (for debugging) + + Type: int; 0 or 1; + Default: 0. + """ + return self.__nlp_solver_ext_qp_res + @property def nlp_solver_tol_comp(self): """NLP solver complementarity tolerance""" @@ -2531,12 +2676,13 @@ class AcadosOcpOptions: def qp_solver(self, qp_solver): qp_solvers = ('PARTIAL_CONDENSING_HPIPM', \ 'FULL_CONDENSING_QPOASES', 'FULL_CONDENSING_HPIPM', \ - 'PARTIAL_CONDENSING_QPDUNES', 'PARTIAL_CONDENSING_OSQP') + 'PARTIAL_CONDENSING_QPDUNES', 'PARTIAL_CONDENSING_OSQP', \ + 'FULL_CONDENSING_DAQP') if qp_solver in qp_solvers: self.__qp_solver = qp_solver else: raise Exception('Invalid qp_solver value. Possible values are:\n\n' \ - + ',\n'.join(qp_solvers) + '.\n\nYou have: ' + qp_solver + '.\n\nExiting.') + + ',\n'.join(qp_solvers) + '.\n\nYou have: ' + qp_solver + '.\n\n') @regularize_method.setter def regularize_method(self, regularize_method): @@ -2546,7 +2692,7 @@ class AcadosOcpOptions: self.__regularize_method = regularize_method else: raise Exception('Invalid regularize_method value. Possible values are:\n\n' \ - + ',\n'.join(regularize_methods) + '.\n\nYou have: ' + regularize_method + '.\n\nExiting.') + + ',\n'.join(regularize_methods) + '.\n\nYou have: ' + regularize_method + '.\n\n') @collocation_type.setter def collocation_type(self, collocation_type): @@ -2555,7 +2701,7 @@ class AcadosOcpOptions: self.__collocation_type = collocation_type else: raise Exception('Invalid collocation_type value. Possible values are:\n\n' \ - + ',\n'.join(collocation_types) + '.\n\nYou have: ' + collocation_type + '.\n\nExiting.') + + ',\n'.join(collocation_types) + '.\n\nYou have: ' + collocation_type + '.\n\n') @hpipm_mode.setter def hpipm_mode(self, hpipm_mode): @@ -2564,7 +2710,48 @@ class AcadosOcpOptions: self.__hpipm_mode = hpipm_mode else: raise Exception('Invalid hpipm_mode value. Possible values are:\n\n' \ - + ',\n'.join(hpipm_modes) + '.\n\nYou have: ' + hpipm_mode + '.\n\nExiting.') + + ',\n'.join(hpipm_modes) + '.\n\nYou have: ' + hpipm_mode + '.\n\n') + + @ext_fun_compile_flags.setter + def ext_fun_compile_flags(self, ext_fun_compile_flags): + if isinstance(ext_fun_compile_flags, str): + self.__ext_fun_compile_flags = ext_fun_compile_flags + else: + raise Exception('Invalid ext_fun_compile_flags, expected a string.\n') + + + @custom_update_filename.setter + def custom_update_filename(self, custom_update_filename): + if isinstance(custom_update_filename, str): + self.__custom_update_filename = custom_update_filename + else: + raise Exception('Invalid custom_update_filename, expected a string.\n') + + @custom_templates.setter + def custom_templates(self, custom_templates): + if not isinstance(custom_templates, list): + raise Exception('Invalid custom_templates, expected a list.\n') + for tup in custom_templates: + if not isinstance(tup, tuple): + raise Exception('Invalid custom_templates, shoubld be list of tuples.\n') + for s in tup: + if not isinstance(s, str): + raise Exception('Invalid custom_templates, shoubld be list of tuples of strings.\n') + self.__custom_templates = custom_templates + + @custom_update_header_filename.setter + def custom_update_header_filename(self, custom_update_header_filename): + if isinstance(custom_update_header_filename, str): + self.__custom_update_header_filename = custom_update_header_filename + else: + raise Exception('Invalid custom_update_header_filename, expected a string.\n') + + @custom_update_copy.setter + def custom_update_copy(self, custom_update_copy): + if isinstance(custom_update_copy, bool): + self.__custom_update_copy = custom_update_copy + else: + raise Exception('Invalid custom_update_copy, expected a bool.\n') @hessian_approx.setter def hessian_approx(self, hessian_approx): @@ -2573,7 +2760,7 @@ class AcadosOcpOptions: self.__hessian_approx = hessian_approx else: raise Exception('Invalid hessian_approx value. Possible values are:\n\n' \ - + ',\n'.join(hessian_approxs) + '.\n\nYou have: ' + hessian_approx + '.\n\nExiting.') + + ',\n'.join(hessian_approxs) + '.\n\nYou have: ' + hessian_approx + '.\n\n') @integrator_type.setter def integrator_type(self, integrator_type): @@ -2582,7 +2769,7 @@ class AcadosOcpOptions: self.__integrator_type = integrator_type else: raise Exception('Invalid integrator_type value. Possible values are:\n\n' \ - + ',\n'.join(integrator_types) + '.\n\nYou have: ' + integrator_type + '.\n\nExiting.') + + ',\n'.join(integrator_types) + '.\n\nYou have: ' + integrator_type + '.\n\n') @tf.setter def tf(self, tf): @@ -2619,7 +2806,7 @@ class AcadosOcpOptions: self.__globalization = globalization else: raise Exception('Invalid globalization value. Possible values are:\n\n' \ - + ',\n'.join(globalization_types) + '.\n\nYou have: ' + globalization + '.\n\nExiting.') + + ',\n'.join(globalization_types) + '.\n\nYou have: ' + globalization + '.\n\n') @alpha_min.setter def alpha_min(self, alpha_min): @@ -2655,7 +2842,7 @@ class AcadosOcpOptions: if isinstance(eps_sufficient_descent, float) and eps_sufficient_descent > 0: self.__eps_sufficient_descent = eps_sufficient_descent else: - raise Exception('Invalid eps_sufficient_descent value. eps_sufficient_descent must be a positive float. Exiting') + raise Exception('Invalid eps_sufficient_descent value. eps_sufficient_descent must be a positive float.') @sim_method_num_stages.setter def sim_method_num_stages(self, sim_method_num_stages): @@ -2663,7 +2850,7 @@ class AcadosOcpOptions: # if isinstance(sim_method_num_stages, int): # self.__sim_method_num_stages = sim_method_num_stages # else: - # raise Exception('Invalid sim_method_num_stages value. sim_method_num_stages must be an integer. Exiting.') + # raise Exception('Invalid sim_method_num_stages value. sim_method_num_stages must be an integer.') self.__sim_method_num_stages = sim_method_num_stages @@ -2673,7 +2860,7 @@ class AcadosOcpOptions: # if isinstance(sim_method_num_steps, int): # self.__sim_method_num_steps = sim_method_num_steps # else: - # raise Exception('Invalid sim_method_num_steps value. sim_method_num_steps must be an integer. Exiting.') + # raise Exception('Invalid sim_method_num_steps value. sim_method_num_steps must be an integer.') self.__sim_method_num_steps = sim_method_num_steps @@ -2683,7 +2870,7 @@ class AcadosOcpOptions: if isinstance(sim_method_newton_iter, int): self.__sim_method_newton_iter = sim_method_newton_iter else: - raise Exception('Invalid sim_method_newton_iter value. sim_method_newton_iter must be an integer. Exiting.') + raise Exception('Invalid sim_method_newton_iter value. sim_method_newton_iter must be an integer.') @sim_method_jac_reuse.setter def sim_method_jac_reuse(self, sim_method_jac_reuse): @@ -2699,42 +2886,57 @@ class AcadosOcpOptions: self.__nlp_solver_type = nlp_solver_type else: raise Exception('Invalid nlp_solver_type value. Possible values are:\n\n' \ - + ',\n'.join(nlp_solver_types) + '.\n\nYou have: ' + nlp_solver_type + '.\n\nExiting.') + + ',\n'.join(nlp_solver_types) + '.\n\nYou have: ' + nlp_solver_type + '.\n\n') @nlp_solver_step_length.setter def nlp_solver_step_length(self, nlp_solver_step_length): if isinstance(nlp_solver_step_length, float) and nlp_solver_step_length > 0: self.__nlp_solver_step_length = nlp_solver_step_length else: - raise Exception('Invalid nlp_solver_step_length value. nlp_solver_step_length must be a positive float. Exiting') + raise Exception('Invalid nlp_solver_step_length value. nlp_solver_step_length must be a positive float.') @levenberg_marquardt.setter def levenberg_marquardt(self, levenberg_marquardt): if isinstance(levenberg_marquardt, float) and levenberg_marquardt >= 0: self.__levenberg_marquardt = levenberg_marquardt else: - raise Exception('Invalid levenberg_marquardt value. levenberg_marquardt must be a positive float. Exiting') + raise Exception('Invalid levenberg_marquardt value. levenberg_marquardt must be a positive float.') @qp_solver_iter_max.setter def qp_solver_iter_max(self, qp_solver_iter_max): if isinstance(qp_solver_iter_max, int) and qp_solver_iter_max > 0: self.__qp_solver_iter_max = qp_solver_iter_max else: - raise Exception('Invalid qp_solver_iter_max value. qp_solver_iter_max must be a positive int. Exiting') + raise Exception('Invalid qp_solver_iter_max value. qp_solver_iter_max must be a positive int.') + + @qp_solver_ric_alg.setter + def qp_solver_ric_alg(self, qp_solver_ric_alg): + if qp_solver_ric_alg in [0, 1]: + self.__qp_solver_ric_alg = qp_solver_ric_alg + else: + raise Exception(f'Invalid qp_solver_ric_alg value. qp_solver_ric_alg must be in [0, 1], got {qp_solver_ric_alg}.') + + @qp_solver_cond_ric_alg.setter + def qp_solver_cond_ric_alg(self, qp_solver_cond_ric_alg): + if qp_solver_cond_ric_alg in [0, 1]: + self.__qp_solver_cond_ric_alg = qp_solver_cond_ric_alg + else: + raise Exception(f'Invalid qp_solver_cond_ric_alg value. qp_solver_cond_ric_alg must be in [0, 1], got {qp_solver_cond_ric_alg}.') + @qp_solver_cond_N.setter def qp_solver_cond_N(self, qp_solver_cond_N): if isinstance(qp_solver_cond_N, int) and qp_solver_cond_N >= 0: self.__qp_solver_cond_N = qp_solver_cond_N else: - raise Exception('Invalid qp_solver_cond_N value. qp_solver_cond_N must be a positive int. Exiting') + raise Exception('Invalid qp_solver_cond_N value. qp_solver_cond_N must be a positive int.') @qp_solver_warm_start.setter def qp_solver_warm_start(self, qp_solver_warm_start): if qp_solver_warm_start in [0, 1, 2]: self.__qp_solver_warm_start = qp_solver_warm_start else: - raise Exception('Invalid qp_solver_warm_start value. qp_solver_warm_start must be 0 or 1 or 2. Exiting') + raise Exception('Invalid qp_solver_warm_start value. qp_solver_warm_start must be 0 or 1 or 2.') @qp_tol.setter def qp_tol(self, qp_tol): @@ -2744,35 +2946,35 @@ class AcadosOcpOptions: self.__qp_solver_tol_stat = qp_tol self.__qp_solver_tol_comp = qp_tol else: - raise Exception('Invalid qp_tol value. qp_tol must be a positive float. Exiting') + raise Exception('Invalid qp_tol value. qp_tol must be a positive float.') @qp_solver_tol_stat.setter def qp_solver_tol_stat(self, qp_solver_tol_stat): if isinstance(qp_solver_tol_stat, float) and qp_solver_tol_stat > 0: self.__qp_solver_tol_stat = qp_solver_tol_stat else: - raise Exception('Invalid qp_solver_tol_stat value. qp_solver_tol_stat must be a positive float. Exiting') + raise Exception('Invalid qp_solver_tol_stat value. qp_solver_tol_stat must be a positive float.') @qp_solver_tol_eq.setter def qp_solver_tol_eq(self, qp_solver_tol_eq): if isinstance(qp_solver_tol_eq, float) and qp_solver_tol_eq > 0: self.__qp_solver_tol_eq = qp_solver_tol_eq else: - raise Exception('Invalid qp_solver_tol_eq value. qp_solver_tol_eq must be a positive float. Exiting') + raise Exception('Invalid qp_solver_tol_eq value. qp_solver_tol_eq must be a positive float.') @qp_solver_tol_ineq.setter def qp_solver_tol_ineq(self, qp_solver_tol_ineq): if isinstance(qp_solver_tol_ineq, float) and qp_solver_tol_ineq > 0: self.__qp_solver_tol_ineq = qp_solver_tol_ineq else: - raise Exception('Invalid qp_solver_tol_ineq value. qp_solver_tol_ineq must be a positive float. Exiting') + raise Exception('Invalid qp_solver_tol_ineq value. qp_solver_tol_ineq must be a positive float.') @qp_solver_tol_comp.setter def qp_solver_tol_comp(self, qp_solver_tol_comp): if isinstance(qp_solver_tol_comp, float) and qp_solver_tol_comp > 0: self.__qp_solver_tol_comp = qp_solver_tol_comp else: - raise Exception('Invalid qp_solver_tol_comp value. qp_solver_tol_comp must be a positive float. Exiting') + raise Exception('Invalid qp_solver_tol_comp value. qp_solver_tol_comp must be a positive float.') @tol.setter def tol(self, tol): @@ -2782,35 +2984,42 @@ class AcadosOcpOptions: self.__nlp_solver_tol_stat = tol self.__nlp_solver_tol_comp = tol else: - raise Exception('Invalid tol value. tol must be a positive float. Exiting') + raise Exception('Invalid tol value. tol must be a positive float.') @nlp_solver_tol_stat.setter def nlp_solver_tol_stat(self, nlp_solver_tol_stat): if isinstance(nlp_solver_tol_stat, float) and nlp_solver_tol_stat > 0: self.__nlp_solver_tol_stat = nlp_solver_tol_stat else: - raise Exception('Invalid nlp_solver_tol_stat value. nlp_solver_tol_stat must be a positive float. Exiting') + raise Exception('Invalid nlp_solver_tol_stat value. nlp_solver_tol_stat must be a positive float.') @nlp_solver_tol_eq.setter def nlp_solver_tol_eq(self, nlp_solver_tol_eq): if isinstance(nlp_solver_tol_eq, float) and nlp_solver_tol_eq > 0: self.__nlp_solver_tol_eq = nlp_solver_tol_eq else: - raise Exception('Invalid nlp_solver_tol_eq value. nlp_solver_tol_eq must be a positive float. Exiting') + raise Exception('Invalid nlp_solver_tol_eq value. nlp_solver_tol_eq must be a positive float.') @nlp_solver_tol_ineq.setter def nlp_solver_tol_ineq(self, nlp_solver_tol_ineq): if isinstance(nlp_solver_tol_ineq, float) and nlp_solver_tol_ineq > 0: self.__nlp_solver_tol_ineq = nlp_solver_tol_ineq else: - raise Exception('Invalid nlp_solver_tol_ineq value. nlp_solver_tol_ineq must be a positive float. Exiting') + raise Exception('Invalid nlp_solver_tol_ineq value. nlp_solver_tol_ineq must be a positive float.') + + @nlp_solver_ext_qp_res.setter + def nlp_solver_ext_qp_res(self, nlp_solver_ext_qp_res): + if nlp_solver_ext_qp_res in [0, 1]: + self.__nlp_solver_ext_qp_res = nlp_solver_ext_qp_res + else: + raise Exception('Invalid nlp_solver_ext_qp_res value. nlp_solver_ext_qp_res must be in [0, 1].') @nlp_solver_tol_comp.setter def nlp_solver_tol_comp(self, nlp_solver_tol_comp): if isinstance(nlp_solver_tol_comp, float) and nlp_solver_tol_comp > 0: self.__nlp_solver_tol_comp = nlp_solver_tol_comp else: - raise Exception('Invalid nlp_solver_tol_comp value. nlp_solver_tol_comp must be a positive float. Exiting') + raise Exception('Invalid nlp_solver_tol_comp value. nlp_solver_tol_comp must be a positive float.') @nlp_solver_max_iter.setter def nlp_solver_max_iter(self, nlp_solver_max_iter): @@ -2818,14 +3027,14 @@ class AcadosOcpOptions: if isinstance(nlp_solver_max_iter, int) and nlp_solver_max_iter > 0: self.__nlp_solver_max_iter = nlp_solver_max_iter else: - raise Exception('Invalid nlp_solver_max_iter value. nlp_solver_max_iter must be a positive int. Exiting') + raise Exception('Invalid nlp_solver_max_iter value. nlp_solver_max_iter must be a positive int.') @print_level.setter def print_level(self, print_level): if isinstance(print_level, int) and print_level >= 0: self.__print_level = print_level else: - raise Exception('Invalid print_level value. print_level takes one of the values >=0. Exiting') + raise Exception('Invalid print_level value. print_level takes one of the values >=0.') @model_external_shared_lib_dir.setter def model_external_shared_lib_dir(self, model_external_shared_lib_dir): @@ -2833,47 +3042,47 @@ class AcadosOcpOptions: self.__model_external_shared_lib_dir = model_external_shared_lib_dir else: raise Exception('Invalid model_external_shared_lib_dir value. Str expected.' \ - + '.\n\nYou have: ' + type(model_external_shared_lib_dir) + '.\n\nExiting.') + + '.\n\nYou have: ' + type(model_external_shared_lib_dir) + '.\n\n') @model_external_shared_lib_name.setter def model_external_shared_lib_name(self, model_external_shared_lib_name): if isinstance(model_external_shared_lib_name, str) : if model_external_shared_lib_name[-3:] == '.so' : raise Exception('Invalid model_external_shared_lib_name value. Remove the .so extension.' \ - + '.\n\nYou have: ' + type(model_external_shared_lib_name) + '.\n\nExiting.') + + '.\n\nYou have: ' + type(model_external_shared_lib_name) + '.\n\n') else : self.__model_external_shared_lib_name = model_external_shared_lib_name else: raise Exception('Invalid model_external_shared_lib_name value. Str expected.' \ - + '.\n\nYou have: ' + type(model_external_shared_lib_name) + '.\n\nExiting.') + + '.\n\nYou have: ' + type(model_external_shared_lib_name) + '.\n\n') @exact_hess_constr.setter def exact_hess_constr(self, exact_hess_constr): if exact_hess_constr in [0, 1]: self.__exact_hess_constr = exact_hess_constr else: - raise Exception('Invalid exact_hess_constr value. exact_hess_constr takes one of the values 0, 1. Exiting') + raise Exception('Invalid exact_hess_constr value. exact_hess_constr takes one of the values 0, 1.') @exact_hess_cost.setter def exact_hess_cost(self, exact_hess_cost): if exact_hess_cost in [0, 1]: self.__exact_hess_cost = exact_hess_cost else: - raise Exception('Invalid exact_hess_cost value. exact_hess_cost takes one of the values 0, 1. Exiting') + raise Exception('Invalid exact_hess_cost value. exact_hess_cost takes one of the values 0, 1.') @exact_hess_dyn.setter def exact_hess_dyn(self, exact_hess_dyn): if exact_hess_dyn in [0, 1]: self.__exact_hess_dyn = exact_hess_dyn else: - raise Exception('Invalid exact_hess_dyn value. exact_hess_dyn takes one of the values 0, 1. Exiting') + raise Exception('Invalid exact_hess_dyn value. exact_hess_dyn takes one of the values 0, 1.') @ext_cost_num_hess.setter def ext_cost_num_hess(self, ext_cost_num_hess): if ext_cost_num_hess in [0, 1]: self.__ext_cost_num_hess = ext_cost_num_hess else: - raise Exception('Invalid ext_cost_num_hess value. ext_cost_num_hess takes one of the values 0, 1. Exiting') + raise Exception('Invalid ext_cost_num_hess value. ext_cost_num_hess takes one of the values 0, 1.') def set(self, attr, value): setattr(self, attr, value) @@ -2893,6 +3102,7 @@ class AcadosOcp: - :py:attr:`solver_options` of type :py:class:`acados_template.acados_ocp.AcadosOcpOptions` - :py:attr:`acados_include_path` (set automatically) + - :py:attr:`shared_lib_ext` (set automatically) - :py:attr:`acados_lib_path` (set automatically) - :py:attr:`parameter_values` - used to initialize the parameters (can be changed) """ @@ -2914,14 +3124,16 @@ class AcadosOcp: """Constraints definitions, type :py:class:`acados_template.acados_ocp.AcadosOcpConstraints`""" self.solver_options = AcadosOcpOptions() """Solver Options, type :py:class:`acados_template.acados_ocp.AcadosOcpOptions`""" - + self.acados_include_path = os.path.join(acados_path, 'include').replace(os.sep, '/') # the replace part is important on Windows for CMake """Path to acados include directory (set automatically), type: `string`""" self.acados_lib_path = os.path.join(acados_path, 'lib').replace(os.sep, '/') # the replace part is important on Windows for CMake """Path to where acados library is located, type: `string`""" + self.shared_lib_ext = get_lib_ext() - import numpy - self.cython_include_dirs = numpy.get_include() + # get cython paths + from sysconfig import get_paths + self.cython_include_dirs = [np.get_include(), get_paths()['include']] self.__parameter_values = np.array([]) self.__problem_class = 'OCP' diff --git a/third_party/acados/acados_template/acados_ocp_solver.py b/third_party/acados/acados_template/acados_ocp_solver.py index beeda2cb0..ffc9cf4b0 100644 --- a/third_party/acados/acados_template/acados_ocp_solver.py +++ b/third_party/acados/acados_template/acados_ocp_solver.py @@ -1,9 +1,6 @@ # -*- coding: future_fstrings -*- # -# Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, -# Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, -# Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, -# Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl +# Copyright (c) The acados authors. # # This file is part of acados. # @@ -38,26 +35,29 @@ import json import numpy as np from datetime import datetime import importlib +import shutil + +from subprocess import DEVNULL, call, STDOUT + from ctypes import POINTER, cast, CDLL, c_void_p, c_char_p, c_double, c_int, c_int64, byref from copy import deepcopy +from pathlib import Path -from .generate_c_code_explicit_ode import generate_c_code_explicit_ode -from .generate_c_code_implicit_ode import generate_c_code_implicit_ode -from .generate_c_code_gnsf import generate_c_code_gnsf -from .generate_c_code_discrete_dynamics import generate_c_code_discrete_dynamics -from .generate_c_code_constraint import generate_c_code_constraint -from .generate_c_code_nls_cost import generate_c_code_nls_cost -from .generate_c_code_external_cost import generate_c_code_external_cost +from .casadi_function_generation import generate_c_code_explicit_ode, \ + generate_c_code_implicit_ode, generate_c_code_gnsf, generate_c_code_discrete_dynamics, \ + generate_c_code_constraint, generate_c_code_nls_cost, generate_c_code_conl_cost, \ + generate_c_code_external_cost +from .gnsf.detect_gnsf_structure import detect_gnsf_structure from .acados_ocp import AcadosOcp -from .acados_model import acados_model_strip_casadi_symbolics +from .acados_model import AcadosModel from .utils import is_column, is_empty, casadi_length, render_template,\ - format_class_dict, ocp_check_against_layout, np_array_to_list, make_model_consistent,\ - set_up_imported_gnsf_model, get_ocp_nlp_layout, get_python_interface_path + format_class_dict, make_object_json_dumpable, make_model_consistent,\ + set_up_imported_gnsf_model, get_ocp_nlp_layout, get_python_interface_path, get_lib_ext, check_casadi_version from .builders import CMakeBuilder -def make_ocp_dims_consistent(acados_ocp): +def make_ocp_dims_consistent(acados_ocp: AcadosOcp): dims = acados_ocp.dims cost = acados_ocp.cost constraints = acados_ocp.constraints @@ -105,6 +105,9 @@ def make_ocp_dims_consistent(acados_ocp): model.cost_expr_ext_cost_0 = model.cost_expr_ext_cost model.cost_expr_ext_cost_custom_hess_0 = model.cost_expr_ext_cost_custom_hess + model.cost_psi_expr_0 = model.cost_psi_expr + model.cost_r_in_psi_expr_0 = model.cost_r_in_psi_expr + if cost.cost_type_0 == 'LINEAR_LS': ny_0 = cost.W_0.shape[0] if cost.Vx_0.shape[0] != ny_0 or cost.Vu_0.shape[0] != ny_0: @@ -133,6 +136,22 @@ def make_ocp_dims_consistent(acados_ocp): f'\nGot W_0[{cost.W.shape}], yref_0[{cost.yref_0.shape}]\n') dims.ny_0 = ny_0 + elif cost.cost_type_0 == 'CONVEX_OVER_NONLINEAR': + if is_empty(model.cost_y_expr_0): + raise Exception('cost_y_expr_0 and/or cost_y_expr not provided.') + ny_0 = casadi_length(model.cost_y_expr_0) + if is_empty(model.cost_r_in_psi_expr_0) or casadi_length(model.cost_r_in_psi_expr_0) != ny_0: + raise Exception('inconsistent dimension ny_0: regarding cost_y_expr_0 and cost_r_in_psi_0.') + if is_empty(model.cost_psi_expr_0) or casadi_length(model.cost_psi_expr_0) != 1: + raise Exception('cost_psi_expr_0 not provided or not scalar-valued.') + if cost.yref_0.shape[0] != ny_0: + raise Exception('inconsistent dimension: regarding yref_0 and cost_y_expr_0, cost_r_in_psi_0.') + dims.ny_0 = ny_0 + + if not (opts.hessian_approx=='EXACT' and opts.exact_hess_cost==False) and opts.hessian_approx != 'GAUSS_NEWTON': + raise Exception("\nWith CONVEX_OVER_NONLINEAR cost type, possible Hessian approximations are:\n" + "GAUSS_NEWTON or EXACT with 'exact_hess_cost' == False.\n") + elif cost.cost_type_0 == 'EXTERNAL': if opts.hessian_approx == 'GAUSS_NEWTON' and opts.ext_cost_num_hess == 0 and model.cost_expr_ext_cost_custom_hess_0 is None: print("\nWARNING: Gauss-Newton Hessian approximation with EXTERNAL cost type not possible!\n" @@ -171,6 +190,23 @@ def make_ocp_dims_consistent(acados_ocp): f'\nGot W[{cost.W.shape}], yref[{cost.yref.shape}]\n') dims.ny = ny + elif cost.cost_type == 'CONVEX_OVER_NONLINEAR': + if is_empty(model.cost_y_expr): + raise Exception('cost_y_expr and/or cost_y_expr not provided.') + ny = casadi_length(model.cost_y_expr) + if is_empty(model.cost_r_in_psi_expr) or casadi_length(model.cost_r_in_psi_expr) != ny: + raise Exception('inconsistent dimension ny: regarding cost_y_expr and cost_r_in_psi.') + if is_empty(model.cost_psi_expr) or casadi_length(model.cost_psi_expr) != 1: + raise Exception('cost_psi_expr not provided or not scalar-valued.') + if cost.yref.shape[0] != ny: + raise Exception('inconsistent dimension: regarding yref and cost_y_expr, cost_r_in_psi.') + dims.ny = ny + + if not (opts.hessian_approx=='EXACT' and opts.exact_hess_cost==False) and opts.hessian_approx != 'GAUSS_NEWTON': + raise Exception("\nWith CONVEX_OVER_NONLINEAR cost type, possible Hessian approximations are:\n" + "GAUSS_NEWTON or EXACT with 'exact_hess_cost' == False.\n") + + elif cost.cost_type == 'EXTERNAL': if opts.hessian_approx == 'GAUSS_NEWTON' and opts.ext_cost_num_hess == 0 and model.cost_expr_ext_cost_custom_hess is None: print("\nWARNING: Gauss-Newton Hessian approximation with EXTERNAL cost type not possible!\n" @@ -202,6 +238,24 @@ def make_ocp_dims_consistent(acados_ocp): raise Exception('inconsistent dimension: regarding W_e, yref_e.') dims.ny_e = ny_e + elif cost.cost_type_e == 'CONVEX_OVER_NONLINEAR': + if is_empty(model.cost_y_expr_e): + raise Exception('cost_y_expr_e not provided.') + ny_e = casadi_length(model.cost_y_expr_e) + if is_empty(model.cost_r_in_psi_expr_e) or casadi_length(model.cost_r_in_psi_expr_e) != ny_e: + raise Exception('inconsistent dimension ny_e: regarding cost_y_expr_e and cost_r_in_psi_e.') + if is_empty(model.cost_psi_expr_e) or casadi_length(model.cost_psi_expr_e) != 1: + raise Exception('cost_psi_expr_e not provided or not scalar-valued.') + if cost.yref_e.shape[0] != ny_e: + raise Exception('inconsistent dimension: regarding yref_e and cost_y_expr_e, cost_r_in_psi_e.') + dims.ny_e = ny_e + + if not (opts.hessian_approx=='EXACT' and opts.exact_hess_cost==False) and opts.hessian_approx != 'GAUSS_NEWTON': + raise Exception("\nWith CONVEX_OVER_NONLINEAR cost type, possible Hessian approximations are:\n" + "GAUSS_NEWTON or EXACT with 'exact_hess_cost' == False.\n") + + + elif cost.cost_type_e == 'EXTERNAL': if opts.hessian_approx == 'GAUSS_NEWTON' and opts.ext_cost_num_hess == 0 and model.cost_expr_ext_cost_custom_hess_e is None: print("\nWARNING: Gauss-Newton Hessian approximation with EXTERNAL cost type not possible!\n" @@ -213,16 +267,13 @@ def make_ocp_dims_consistent(acados_ocp): ## constraints # initial - if (constraints.lbx_0 == [] and constraints.ubx_0 == []): - dims.nbx_0 = 0 - else: - this_shape = constraints.lbx_0.shape - other_shape = constraints.ubx_0.shape - if not this_shape == other_shape: - raise Exception('lbx_0, ubx_0 have different shapes!') - if not is_column(constraints.lbx_0): - raise Exception('lbx_0, ubx_0 must be column vectors!') - dims.nbx_0 = constraints.lbx_0.size + this_shape = constraints.lbx_0.shape + other_shape = constraints.ubx_0.shape + if not this_shape == other_shape: + raise Exception('lbx_0, ubx_0 have different shapes!') + if not is_column(constraints.lbx_0): + raise Exception('lbx_0, ubx_0 must be column vectors!') + dims.nbx_0 = constraints.lbx_0.size if all(constraints.lbx_0 == constraints.ubx_0) and dims.nbx_0 == dims.nx \ and dims.nbxe_0 is None \ @@ -230,8 +281,10 @@ def make_ocp_dims_consistent(acados_ocp): and all(constraints.idxbxe_0 == constraints.idxbx_0): # case: x0 was set: nbx0 are all equlities. dims.nbxe_0 = dims.nbx_0 + elif constraints.idxbxe_0 is not None: + dims.nbxe_0 = constraints.idxbxe_0.shape[0] elif dims.nbxe_0 is None: - # case: x0 was not set -> dont assume nbx0 to be equality constraints. + # case: x0 and idxbxe_0 were not set -> dont assume nbx0 to be equality constraints. dims.nbxe_0 = 0 # path @@ -309,6 +362,8 @@ def make_ocp_dims_consistent(acados_ocp): # Slack dimensions nsbx = constraints.idxsbx.shape[0] + if nsbx > nbx: + raise Exception(f'inconsistent dimension nsbx = {nsbx}. Is greater than nbx = {nbx}.') if is_empty(constraints.lsbx): constraints.lsbx = np.zeros((nsbx,)) elif constraints.lsbx.shape[0] != nsbx: @@ -320,6 +375,8 @@ def make_ocp_dims_consistent(acados_ocp): dims.nsbx = nsbx nsbu = constraints.idxsbu.shape[0] + if nsbu > nbu: + raise Exception(f'inconsistent dimension nsbu = {nsbu}. Is greater than nbu = {nbu}.') if is_empty(constraints.lsbu): constraints.lsbu = np.zeros((nsbu,)) elif constraints.lsbu.shape[0] != nsbu: @@ -331,6 +388,8 @@ def make_ocp_dims_consistent(acados_ocp): dims.nsbu = nsbu nsh = constraints.idxsh.shape[0] + if nsh > nh: + raise Exception(f'inconsistent dimension nsh = {nsh}. Is greater than nh = {nh}.') if is_empty(constraints.lsh): constraints.lsh = np.zeros((nsh,)) elif constraints.lsh.shape[0] != nsh: @@ -342,6 +401,8 @@ def make_ocp_dims_consistent(acados_ocp): dims.nsh = nsh nsphi = constraints.idxsphi.shape[0] + if nsphi > dims.nphi: + raise Exception(f'inconsistent dimension nsphi = {nsphi}. Is greater than nphi = {dims.nphi}.') if is_empty(constraints.lsphi): constraints.lsphi = np.zeros((nsphi,)) elif constraints.lsphi.shape[0] != nsphi: @@ -353,6 +414,8 @@ def make_ocp_dims_consistent(acados_ocp): dims.nsphi = nsphi nsg = constraints.idxsg.shape[0] + if nsg > ng: + raise Exception(f'inconsistent dimension nsg = {nsg}. Is greater than ng = {ng}.') if is_empty(constraints.lsg): constraints.lsg = np.zeros((nsg,)) elif constraints.lsg.shape[0] != nsg: @@ -386,6 +449,8 @@ def make_ocp_dims_consistent(acados_ocp): dims.ns = ns nsbx_e = constraints.idxsbx_e.shape[0] + if nsbx_e > nbx_e: + raise Exception(f'inconsistent dimension nsbx_e = {nsbx_e}. Is greater than nbx_e = {nbx_e}.') if is_empty(constraints.lsbx_e): constraints.lsbx_e = np.zeros((nsbx_e,)) elif constraints.lsbx_e.shape[0] != nsbx_e: @@ -397,6 +462,8 @@ def make_ocp_dims_consistent(acados_ocp): dims.nsbx_e = nsbx_e nsh_e = constraints.idxsh_e.shape[0] + if nsh_e > nh_e: + raise Exception(f'inconsistent dimension nsh_e = {nsh_e}. Is greater than nh_e = {nh_e}.') if is_empty(constraints.lsh_e): constraints.lsh_e = np.zeros((nsh_e,)) elif constraints.lsh_e.shape[0] != nsh_e: @@ -408,6 +475,8 @@ def make_ocp_dims_consistent(acados_ocp): dims.nsh_e = nsh_e nsg_e = constraints.idxsg_e.shape[0] + if nsg_e > ng_e: + raise Exception(f'inconsistent dimension nsg_e = {nsg_e}. Is greater than ng_e = {ng_e}.') if is_empty(constraints.lsg_e): constraints.lsg_e = np.zeros((nsg_e,)) elif constraints.lsg_e.shape[0] != nsg_e: @@ -419,6 +488,8 @@ def make_ocp_dims_consistent(acados_ocp): dims.nsg_e = nsg_e nsphi_e = constraints.idxsphi_e.shape[0] + if nsphi_e > dims.nphi_e: + raise Exception(f'inconsistent dimension nsphi_e = {nsphi_e}. Is greater than nphi_e = {dims.nphi_e}.') if is_empty(constraints.lsphi_e): constraints.lsphi_e = np.zeros((nsphi_e,)) elif constraints.lsphi_e.shape[0] != nsphi_e: @@ -525,7 +596,7 @@ def get_simulink_default_opts(): return simulink_default_opts -def ocp_formulation_json_dump(acados_ocp, simulink_opts, json_file='acados_ocp_nlp.json'): +def ocp_formulation_json_dump(acados_ocp, simulink_opts=None, json_file='acados_ocp_nlp.json'): # Load acados_ocp_nlp structure description ocp_layout = get_ocp_nlp_layout() @@ -543,20 +614,11 @@ def ocp_formulation_json_dump(acados_ocp, simulink_opts, json_file='acados_ocp_n ocp_nlp_dict = format_class_dict(ocp_nlp_dict) - # strip symbolics - ocp_nlp_dict['model'] = acados_model_strip_casadi_symbolics(ocp_nlp_dict['model']) - - # strip shooting_nodes - ocp_nlp_dict['solver_options'].pop('shooting_nodes', None) - dims_dict = format_class_dict(acados_ocp.dims.__dict__) - - ocp_check_against_layout(ocp_nlp_dict, dims_dict) - - # add simulink options - ocp_nlp_dict['simulink_opts'] = simulink_opts + if simulink_opts is not None: + ocp_nlp_dict['simulink_opts'] = simulink_opts with open(json_file, 'w') as f: - json.dump(ocp_nlp_dict, f, default=np_array_to_list, indent=4, sort_keys=True) + json.dump(ocp_nlp_dict, f, default=make_object_json_dumpable, indent=4, sort_keys=True) @@ -587,7 +649,7 @@ def ocp_formulation_json_load(json_file='acados_ocp_nlp.json'): return acados_ocp -def ocp_generate_external_functions(acados_ocp, model): +def ocp_generate_external_functions(acados_ocp: AcadosOcp, model: AcadosModel): model = make_model_consistent(model) @@ -595,27 +657,32 @@ def ocp_generate_external_functions(acados_ocp, model): opts = dict(generate_hess=1) else: opts = dict(generate_hess=0) + + # create code_export_dir, model_dir code_export_dir = acados_ocp.code_export_directory opts['code_export_directory'] = code_export_dir + model_dir = os.path.join(code_export_dir, model.name + '_model') + if not os.path.exists(model_dir): + os.makedirs(model_dir) - if acados_ocp.model.dyn_ext_fun_type != 'casadi': - raise Exception("ocp_generate_external_functions: dyn_ext_fun_type only supports 'casadi' for now.\ - Extending the Python interface with generic function support is welcome.") - - if acados_ocp.solver_options.integrator_type == 'ERK': - # explicit model -- generate C code - generate_c_code_explicit_ode(model, opts) - elif acados_ocp.solver_options.integrator_type == 'IRK': - # implicit model -- generate C code - generate_c_code_implicit_ode(model, opts) - elif acados_ocp.solver_options.integrator_type == 'LIFTED_IRK': - generate_c_code_implicit_ode(model, opts) - elif acados_ocp.solver_options.integrator_type == 'GNSF': - generate_c_code_gnsf(model, opts) - elif acados_ocp.solver_options.integrator_type == 'DISCRETE': - generate_c_code_discrete_dynamics(model, opts) + check_casadi_version() + # TODO: remove dir gen from all the generate_c_* functions + if acados_ocp.model.dyn_ext_fun_type == 'casadi': + if acados_ocp.solver_options.integrator_type == 'ERK': + generate_c_code_explicit_ode(model, opts) + elif acados_ocp.solver_options.integrator_type == 'IRK': + generate_c_code_implicit_ode(model, opts) + elif acados_ocp.solver_options.integrator_type == 'LIFTED_IRK': + generate_c_code_implicit_ode(model, opts) + elif acados_ocp.solver_options.integrator_type == 'GNSF': + generate_c_code_gnsf(model, opts) + elif acados_ocp.solver_options.integrator_type == 'DISCRETE': + generate_c_code_discrete_dynamics(model, opts) + else: + raise Exception("ocp_generate_external_functions: unknown integrator type.") else: - raise Exception("ocp_generate_external_functions: unknown integrator type.") + target_location = os.path.join(code_export_dir, model_dir, model.dyn_generic_source) + shutil.copyfile(model.dyn_generic_source, target_location) if acados_ocp.dims.nphi > 0 or acados_ocp.dims.nh > 0: generate_c_code_constraint(model, model.name, False, opts) @@ -623,28 +690,24 @@ def ocp_generate_external_functions(acados_ocp, model): if acados_ocp.dims.nphi_e > 0 or acados_ocp.dims.nh_e > 0: generate_c_code_constraint(model, model.name, True, opts) - # dummy matrices - if not acados_ocp.cost.cost_type_0 == 'LINEAR_LS': - acados_ocp.cost.Vx_0 = np.zeros((acados_ocp.dims.ny_0, acados_ocp.dims.nx)) - acados_ocp.cost.Vu_0 = np.zeros((acados_ocp.dims.ny_0, acados_ocp.dims.nu)) - if not acados_ocp.cost.cost_type == 'LINEAR_LS': - acados_ocp.cost.Vx = np.zeros((acados_ocp.dims.ny, acados_ocp.dims.nx)) - acados_ocp.cost.Vu = np.zeros((acados_ocp.dims.ny, acados_ocp.dims.nu)) - if not acados_ocp.cost.cost_type_e == 'LINEAR_LS': - acados_ocp.cost.Vx_e = np.zeros((acados_ocp.dims.ny_e, acados_ocp.dims.nx)) - if acados_ocp.cost.cost_type_0 == 'NONLINEAR_LS': generate_c_code_nls_cost(model, model.name, 'initial', opts) + elif acados_ocp.cost.cost_type_0 == 'CONVEX_OVER_NONLINEAR': + generate_c_code_conl_cost(model, model.name, 'initial', opts) elif acados_ocp.cost.cost_type_0 == 'EXTERNAL': generate_c_code_external_cost(model, 'initial', opts) if acados_ocp.cost.cost_type == 'NONLINEAR_LS': generate_c_code_nls_cost(model, model.name, 'path', opts) + elif acados_ocp.cost.cost_type == 'CONVEX_OVER_NONLINEAR': + generate_c_code_conl_cost(model, model.name, 'path', opts) elif acados_ocp.cost.cost_type == 'EXTERNAL': generate_c_code_external_cost(model, 'path', opts) if acados_ocp.cost.cost_type_e == 'NONLINEAR_LS': generate_c_code_nls_cost(model, model.name, 'terminal', opts) + elif acados_ocp.cost.cost_type_e == 'CONVEX_OVER_NONLINEAR': + generate_c_code_conl_cost(model, model.name, 'terminal', opts) elif acados_ocp.cost.cost_type_e == 'EXTERNAL': generate_c_code_external_cost(model, 'terminal', opts) @@ -659,9 +722,8 @@ def ocp_get_default_cmake_builder() -> CMakeBuilder: return cmake_builder -def ocp_render_templates(acados_ocp, json_file, cmake_builder=None): - name = acados_ocp.model.name +def ocp_render_templates(acados_ocp: AcadosOcp, json_file, cmake_builder=None, simulink_opts=None): # setting up loader and environment json_path = os.path.abspath(json_file) @@ -669,132 +731,69 @@ def ocp_render_templates(acados_ocp, json_file, cmake_builder=None): if not os.path.exists(json_path): raise Exception(f'Path "{json_path}" not found!') - code_export_dir = acados_ocp.code_export_directory - template_dir = code_export_dir + # Render templates + template_list = __ocp_get_template_list(acados_ocp, cmake_builder=cmake_builder, simulink_opts=simulink_opts) + for tup in template_list: + if len(tup) > 2: + output_dir = tup[2] + else: + output_dir = acados_ocp.code_export_directory + render_template(tup[0], tup[1], output_dir, json_path) - ## Render templates - in_file = 'main.in.c' - out_file = f'main_{name}.c' - render_template(in_file, out_file, template_dir, json_path) + # Custom templates + acados_template_path = os.path.dirname(os.path.abspath(__file__)) + custom_template_glob = os.path.join(acados_template_path, 'custom_update_templates', '*') + for tup in acados_ocp.solver_options.custom_templates: + render_template(tup[0], tup[1], acados_ocp.code_export_directory, json_path, template_glob=custom_template_glob) - in_file = 'acados_solver.in.c' - out_file = f'acados_solver_{name}.c' - render_template(in_file, out_file, template_dir, json_path) + return - in_file = 'acados_solver.in.h' - out_file = f'acados_solver_{name}.h' - render_template(in_file, out_file, template_dir, json_path) - in_file = 'acados_solver.in.pxd' - out_file = f'acados_solver.pxd' - render_template(in_file, out_file, template_dir, json_path) +def __ocp_get_template_list(acados_ocp: AcadosOcp, cmake_builder=None, simulink_opts=None) -> list: + """ + returns a list of tuples in the form: + (input_filename, output_filname) + or + (input_filename, output_filname, output_directory) + """ + name = acados_ocp.model.name + code_export_directory = acados_ocp.code_export_directory + template_list = [] + + template_list.append(('main.in.c', f'main_{name}.c')) + template_list.append(('acados_solver.in.c', f'acados_solver_{name}.c')) + template_list.append(('acados_solver.in.h', f'acados_solver_{name}.h')) + template_list.append(('acados_solver.in.pxd', f'acados_solver.pxd')) if cmake_builder is not None: - in_file = 'CMakeLists.in.txt' - out_file = 'CMakeLists.txt' - render_template(in_file, out_file, template_dir, json_path) + template_list.append(('CMakeLists.in.txt', 'CMakeLists.txt')) else: - in_file = 'Makefile.in' - out_file = 'Makefile' - render_template(in_file, out_file, template_dir, json_path) + template_list.append(('Makefile.in', 'Makefile')) - in_file = 'acados_solver_sfun.in.c' - out_file = f'acados_solver_sfunction_{name}.c' - render_template(in_file, out_file, template_dir, json_path) - - in_file = 'make_sfun.in.m' - out_file = f'make_sfun_{name}.m' - render_template(in_file, out_file, template_dir, json_path) # sim - in_file = 'acados_sim_solver.in.c' - out_file = f'acados_sim_solver_{name}.c' - render_template(in_file, out_file, template_dir, json_path) + template_list.append(('acados_sim_solver.in.c', f'acados_sim_solver_{name}.c')) + template_list.append(('acados_sim_solver.in.h', f'acados_sim_solver_{name}.h')) + template_list.append(('main_sim.in.c', f'main_sim_{name}.c')) - in_file = 'acados_sim_solver.in.h' - out_file = f'acados_sim_solver_{name}.h' - render_template(in_file, out_file, template_dir, json_path) + # model + model_dir = os.path.join(code_export_directory, f'{name}_model') + template_list.append(('model.in.h', f'{name}_model.h', model_dir)) + # constraints + constraints_dir = os.path.join(code_export_directory, f'{name}_constraints') + template_list.append(('constraints.in.h', f'{name}_constraints.h', constraints_dir)) + # cost + cost_dir = os.path.join(code_export_directory, f'{name}_cost') + template_list.append(('cost.in.h', f'{name}_cost.h', cost_dir)) - in_file = 'main_sim.in.c' - out_file = f'main_sim_{name}.c' - render_template(in_file, out_file, template_dir, json_path) + # Simulink + if simulink_opts is not None: + template_file = os.path.join('matlab_templates', 'acados_solver_sfun.in.c') + template_list.append((template_file, f'acados_solver_sfunction_{name}.c')) + template_file = os.path.join('matlab_templates', 'acados_solver_sfun.in.c') + template_list.append((template_file, f'make_sfun_{name}.m')) - ## folder model - template_dir = os.path.join(code_export_dir, name + '_model') - in_file = 'model.in.h' - out_file = f'{name}_model.h' - render_template(in_file, out_file, template_dir, json_path) - - # constraints on convex over nonlinear function - if acados_ocp.constraints.constr_type == 'BGP' and acados_ocp.dims.nphi > 0: - # constraints on outer function - template_dir = os.path.join(code_export_dir, name + '_constraints') - in_file = 'phi_constraint.in.h' - out_file = f'{name}_phi_constraint.h' - render_template(in_file, out_file, template_dir, json_path) - - # terminal constraints on convex over nonlinear function - if acados_ocp.constraints.constr_type_e == 'BGP' and acados_ocp.dims.nphi_e > 0: - # terminal constraints on outer function - template_dir = os.path.join(code_export_dir, name + '_constraints') - in_file = 'phi_e_constraint.in.h' - out_file = f'{name}_phi_e_constraint.h' - render_template(in_file, out_file, template_dir, json_path) - - # nonlinear constraints - if acados_ocp.constraints.constr_type == 'BGH' and acados_ocp.dims.nh > 0: - template_dir = os.path.join(code_export_dir, name + '_constraints') - in_file = 'h_constraint.in.h' - out_file = f'{name}_h_constraint.h' - render_template(in_file, out_file, template_dir, json_path) - - # terminal nonlinear constraints - if acados_ocp.constraints.constr_type_e == 'BGH' and acados_ocp.dims.nh_e > 0: - template_dir = os.path.join(code_export_dir, name + '_constraints') - in_file = 'h_e_constraint.in.h' - out_file = f'{name}_h_e_constraint.h' - render_template(in_file, out_file, template_dir, json_path) - - # initial stage Nonlinear LS cost function - if acados_ocp.cost.cost_type_0 == 'NONLINEAR_LS': - template_dir = os.path.join(code_export_dir, name + '_cost') - in_file = 'cost_y_0_fun.in.h' - out_file = f'{name}_cost_y_0_fun.h' - render_template(in_file, out_file, template_dir, json_path) - # external cost - terminal - elif acados_ocp.cost.cost_type_0 == 'EXTERNAL': - template_dir = os.path.join(code_export_dir, name + '_cost') - in_file = 'external_cost_0.in.h' - out_file = f'{name}_external_cost_0.h' - render_template(in_file, out_file, template_dir, json_path) - - # path Nonlinear LS cost function - if acados_ocp.cost.cost_type == 'NONLINEAR_LS': - template_dir = os.path.join(code_export_dir, name + '_cost') - in_file = 'cost_y_fun.in.h' - out_file = f'{name}_cost_y_fun.h' - render_template(in_file, out_file, template_dir, json_path) - - # terminal Nonlinear LS cost function - if acados_ocp.cost.cost_type_e == 'NONLINEAR_LS': - template_dir = os.path.join(code_export_dir, name + '_cost') - in_file = 'cost_y_e_fun.in.h' - out_file = f'{name}_cost_y_e_fun.h' - render_template(in_file, out_file, template_dir, json_path) - - # external cost - if acados_ocp.cost.cost_type == 'EXTERNAL': - template_dir = os.path.join(code_export_dir, name + '_cost') - in_file = 'external_cost.in.h' - out_file = f'{name}_external_cost.h' - render_template(in_file, out_file, template_dir, json_path) - - # external cost - terminal - if acados_ocp.cost.cost_type_e == 'EXTERNAL': - template_dir = os.path.join(code_export_dir, name + '_cost') - in_file = 'external_cost_e.in.h' - out_file = f'{name}_external_cost_e.h' - render_template(in_file, out_file, template_dir, json_path) + return template_list def remove_x0_elimination(acados_ocp): @@ -820,7 +819,7 @@ class AcadosOcpSolver: dlclose.argtypes = [c_void_p] @classmethod - def generate(cls, acados_ocp, json_file='acados_ocp_nlp.json', simulink_opts=None, cmake_builder: CMakeBuilder = None): + def generate(cls, acados_ocp: AcadosOcp, json_file='acados_ocp_nlp.json', simulink_opts=None, cmake_builder: CMakeBuilder = None): """ Generates the code for an acados OCP solver, given the description in acados_ocp. :param acados_ocp: type AcadosOcp - description of the OCP for acados @@ -834,15 +833,15 @@ class AcadosOcpSolver: model = acados_ocp.model acados_ocp.code_export_directory = os.path.abspath(acados_ocp.code_export_directory) - if simulink_opts is None: - simulink_opts = get_simulink_default_opts() - # make dims consistent make_ocp_dims_consistent(acados_ocp) # module dependent post processing if acados_ocp.solver_options.integrator_type == 'GNSF': - set_up_imported_gnsf_model(acados_ocp) + if 'gnsf_model' in acados_ocp.__dict__: + set_up_imported_gnsf_model(acados_ocp) + else: + detect_gnsf_structure(acados_ocp) if acados_ocp.solver_options.qp_solver == 'PARTIAL_CONDENSING_QPDUNES': remove_x0_elimination(acados_ocp) @@ -854,15 +853,23 @@ class AcadosOcpSolver: ocp_generate_external_functions(acados_ocp, model) # dump to json - ocp_formulation_json_dump(acados_ocp, simulink_opts, json_file) + acados_ocp.json_file = json_file + ocp_formulation_json_dump(acados_ocp, simulink_opts=simulink_opts, json_file=json_file) # render templates - ocp_render_templates(acados_ocp, json_file, cmake_builder=cmake_builder) - acados_ocp.json_file = json_file + ocp_render_templates(acados_ocp, json_file, cmake_builder=cmake_builder, simulink_opts=simulink_opts) + + # copy custom update function + if acados_ocp.solver_options.custom_update_filename != "" and acados_ocp.solver_options.custom_update_copy: + target_location = os.path.join(acados_ocp.code_export_directory, acados_ocp.solver_options.custom_update_filename) + shutil.copyfile(acados_ocp.solver_options.custom_update_filename, target_location) + if acados_ocp.solver_options.custom_update_header_filename != "" and acados_ocp.solver_options.custom_update_copy: + target_location = os.path.join(acados_ocp.code_export_directory, acados_ocp.solver_options.custom_update_header_filename) + shutil.copyfile(acados_ocp.solver_options.custom_update_header_filename, target_location) @classmethod - def build(cls, code_export_dir, with_cython=False, cmake_builder: CMakeBuilder = None): + def build(cls, code_export_dir, with_cython=False, cmake_builder: CMakeBuilder = None, verbose: bool = True): """ Builds the code for an acados OCP solver, that has been generated in code_export_dir :param code_export_dir: directory in which acados OCP solver has been generated, see generate() @@ -870,19 +877,36 @@ class AcadosOcpSolver: :param cmake_builder: type :py:class:`~acados_template.builders.CMakeBuilder` generate a `CMakeLists.txt` and use the `CMake` pipeline instead of a `Makefile` (`CMake` seems to be the better option in conjunction with `MS Visual Studio`); default: `None` + :param verbose: indicating if build command is printed """ code_export_dir = os.path.abspath(code_export_dir) - cwd=os.getcwd() + cwd = os.getcwd() os.chdir(code_export_dir) if with_cython: - os.system('make clean_ocp_cython') - os.system('make ocp_cython') + call( + ['make', 'clean_all'], + stdout=None if verbose else DEVNULL, + stderr=None if verbose else STDOUT + ) + call( + ['make', 'ocp_cython'], + stdout=None if verbose else DEVNULL, + stderr=None if verbose else STDOUT + ) else: if cmake_builder is not None: cmake_builder.exec(code_export_dir) else: - os.system('make clean_ocp_shared_lib') - os.system('make ocp_shared_lib') + call( + ['make', 'clean_ocp_shared_lib'], + stdout=None if verbose else DEVNULL, + stderr=None if verbose else STDOUT + ) + call( + ['make', 'ocp_shared_lib'], + stdout=None if verbose else DEVNULL, + stderr=None if verbose else STDOUT + ) os.chdir(cwd) @@ -910,7 +934,7 @@ class AcadosOcpSolver: acados_ocp_json['dims']['N']) - def __init__(self, acados_ocp, json_file='acados_ocp_nlp.json', simulink_opts=None, build=True, generate=True, cmake_builder: CMakeBuilder = None): + def __init__(self, acados_ocp: AcadosOcp, json_file='acados_ocp_nlp.json', simulink_opts=None, build=True, generate=True, cmake_builder: CMakeBuilder = None, verbose=True): self.solver_created = False if generate: @@ -927,15 +951,13 @@ class AcadosOcpSolver: code_export_directory = acados_ocp_json['code_export_directory'] if build: - self.build(code_export_directory, with_cython=False, cmake_builder=cmake_builder) + self.build(code_export_directory, with_cython=False, cmake_builder=cmake_builder, verbose=verbose) # prepare library loading lib_prefix = 'lib' - lib_ext = '.so' + lib_ext = get_lib_ext() if os.name == 'nt': lib_prefix = '' - lib_ext = '' - # ToDo: check for mac # Load acados library to avoid unloading the library. # This is necessary if acados was compiled with OpenMP, since the OpenMP threads can't be destroyed. @@ -970,16 +992,23 @@ class AcadosOcpSolver: assert getattr(self.shared_lib, f"{self.model_name}_acados_create")(self.capsule)==0 self.solver_created = True + self.acados_ocp = acados_ocp + # get pointers solver self.__get_pointers_solver() self.status = 0 + # gettable fields + self.__qp_dynamics_fields = ['A', 'B', 'b'] + self.__qp_cost_fields = ['Q', 'R', 'S', 'q', 'r'] + self.__qp_constraint_fields = ['C', 'D', 'lg', 'ug', 'lbx', 'ubx', 'lbu', 'ubu'] + def __get_pointers_solver(self): - """ - Private function to get the pointers for solver - """ + # """ + # Private function to get the pointers for solver + # """ # get pointers solver getattr(self.shared_lib, f"{self.model_name}_acados_get_nlp_opts").argtypes = [c_void_p] getattr(self.shared_lib, f"{self.model_name}_acados_get_nlp_opts").restype = c_void_p @@ -1010,6 +1039,25 @@ class AcadosOcpSolver: self.nlp_solver = getattr(self.shared_lib, f"{self.model_name}_acados_get_nlp_solver")(self.capsule) + + def solve_for_x0(self, x0_bar): + """ + Wrapper around `solve()` which sets initial state constraint, solves the OCP, and returns u0. + """ + self.set(0, "lbx", x0_bar) + self.set(0, "ubx", x0_bar) + + status = self.solve() + + if status == 2: + print("Warning: acados_ocp_solver reached maximum iterations.") + elif status != 0: + raise Exception(f'acados acados_ocp_solver returned status {status}') + + u0 = self.get(0, "u") + return u0 + + def solve(self): """ Solve the ocp with current input. @@ -1021,13 +1069,31 @@ class AcadosOcpSolver: return self.status - def reset(self): + def custom_update(self, data_: np.ndarray): + """ + A custom function that can be implemented by a user to be called between solver calls. + By default this does nothing. + The idea is to have a convenient wrapper to do complex updates of parameters and numerical data efficiently in C, + in a function that is compiled into the solver library and can be conveniently used in the Python environment. + """ + data = np.ascontiguousarray(data_, dtype=np.float64) + c_data = cast(data.ctypes.data, POINTER(c_double)) + data_len = len(data) + + getattr(self.shared_lib, f"{self.model_name}_acados_custom_update").argtypes = [c_void_p, POINTER(c_double), c_int] + getattr(self.shared_lib, f"{self.model_name}_acados_custom_update").restype = c_int + status = getattr(self.shared_lib, f"{self.model_name}_acados_custom_update")(self.capsule, c_data, data_len) + + return status + + + def reset(self, reset_qp_solver_mem=1): """ Sets current iterate to all zeros. """ - getattr(self.shared_lib, f"{self.model_name}_acados_reset").argtypes = [c_void_p] + getattr(self.shared_lib, f"{self.model_name}_acados_reset").argtypes = [c_void_p, c_int] getattr(self.shared_lib, f"{self.model_name}_acados_reset").restype = c_int - getattr(self.shared_lib, f"{self.model_name}_acados_reset")(self.capsule) + getattr(self.shared_lib, f"{self.model_name}_acados_reset")(self.capsule, reset_qp_solver_mem) return @@ -1175,18 +1241,17 @@ class AcadosOcpSolver: field = field_ if (field_ not in all_fields): - raise Exception('AcadosOcpSolver.get(): {} is an invalid argument.\ - \n Possible values are {}. Exiting.'.format(field_, all_fields)) + raise Exception(f'AcadosOcpSolver.get(stage={stage_}, field={field_}): \'{field_}\' is an invalid argument.\ + \n Possible values are {all_fields}.') if not isinstance(stage_, int): - raise Exception('AcadosOcpSolver.get(): stage index must be Integer.') + raise Exception(f'AcadosOcpSolver.get(stage={stage_}, field={field_}): stage index must be an integer, got type {type(stage_)}.') if stage_ < 0 or stage_ > self.N: - raise Exception('AcadosOcpSolver.get(): stage index must be in [0, N], got: {}.'.format(stage_)) + raise Exception(f'AcadosOcpSolver.get(stage={stage_}, field={field_}): stage index must be in [0, {self.N}], got: {stage_}.') if stage_ == self.N and field_ == 'pi': - raise Exception('AcadosOcpSolver.get(): field {} does not exist at final stage {}.'\ - .format(field_, stage_)) + raise Exception(f'AcadosOcpSolver.get(stage={stage_}, field={field_}): field \'{field_}\' does not exist at final stage {stage_}.') if field_ in sens_fields: field = field_.replace('sens_', '') @@ -1265,15 +1330,15 @@ class AcadosOcpSolver: return - def store_iterate(self, filename='', overwrite=False): + def store_iterate(self, filename: str = '', overwrite=False): """ Stores the current iterate of the ocp solver in a json file. - :param filename: if not set, use model_name + timestamp + '.json' + :param filename: if not set, use f'{self.model_name}_iterate.json' :param overwrite: if false and filename exists add timestamp to filename """ if filename == '': - filename += self.model_name + '_' + 'iterate' + '.json' + filename = f'{self.model_name}_iterate.json' if not overwrite: # append timestamp @@ -1284,23 +1349,70 @@ class AcadosOcpSolver: # get iterate: solution = dict() + lN = len(str(self.N+1)) for i in range(self.N+1): - solution['x_'+str(i)] = self.get(i,'x') - solution['u_'+str(i)] = self.get(i,'u') - solution['z_'+str(i)] = self.get(i,'z') - solution['lam_'+str(i)] = self.get(i,'lam') - solution['t_'+str(i)] = self.get(i, 't') - solution['sl_'+str(i)] = self.get(i, 'sl') - solution['su_'+str(i)] = self.get(i, 'su') - for i in range(self.N): - solution['pi_'+str(i)] = self.get(i,'pi') + i_string = f'{i:0{lN}d}' + solution['x_'+i_string] = self.get(i,'x') + solution['u_'+i_string] = self.get(i,'u') + solution['z_'+i_string] = self.get(i,'z') + solution['lam_'+i_string] = self.get(i,'lam') + solution['t_'+i_string] = self.get(i, 't') + solution['sl_'+i_string] = self.get(i, 'sl') + solution['su_'+i_string] = self.get(i, 'su') + if i < self.N: + solution['pi_'+i_string] = self.get(i,'pi') + + for k in list(solution.keys()): + if len(solution[k]) == 0: + del solution[k] # save with open(filename, 'w') as f: - json.dump(solution, f, default=np_array_to_list, indent=4, sort_keys=True) + json.dump(solution, f, default=make_object_json_dumpable, indent=4, sort_keys=True) print("stored current iterate in ", os.path.join(os.getcwd(), filename)) + + def dump_last_qp_to_json(self, filename: str = '', overwrite=False): + """ + Dumps the latest QP data into a json file + + :param filename: if not set, use model_name + timestamp + '.json' + :param overwrite: if false and filename exists add timestamp to filename + """ + if filename == '': + filename = f'{self.model_name}_QP.json' + + if not overwrite: + # append timestamp + if os.path.isfile(filename): + filename = filename[:-5] + filename += datetime.utcnow().strftime('%Y-%m-%d-%H:%M:%S.%f') + '.json' + + # get QP data: + qp_data = dict() + + lN = len(str(self.N+1)) + for field in self.__qp_dynamics_fields: + for i in range(self.N): + qp_data[f'{field}_{i:0{lN}d}'] = self.get_from_qp_in(i,field) + + for field in self.__qp_constraint_fields + self.__qp_cost_fields: + for i in range(self.N+1): + qp_data[f'{field}_{i:0{lN}d}'] = self.get_from_qp_in(i,field) + + # remove empty fields + for k in list(qp_data.keys()): + if len(qp_data[k]) == 0: + del qp_data[k] + + # save + with open(filename, 'w') as f: + json.dump(qp_data, f, default=make_object_json_dumpable, indent=4, sort_keys=True) + print("stored qp from solver memory in ", os.path.join(os.getcwd(), filename)) + + + def load_iterate(self, filename): """ Loads the iterate stored in json file with filename into the ocp solver. @@ -1412,7 +1524,7 @@ class AcadosOcpSolver: return self.get_residuals() else: - raise Exception(f'AcadosOcpSolver.get_stats(): {field} is not a valid argument.' + raise Exception(f'AcadosOcpSolver.get_stats(): \'{field}\' is not a valid argument.' + f'\n Possible values are {fields}.') @@ -1440,6 +1552,12 @@ class AcadosOcpSolver: def get_residuals(self, recompute=False): """ Returns an array of the form [res_stat, res_eq, res_ineq, res_comp]. + This residual has to be computed for SQP_RTI solver, since it is not available by default. + + - res_stat: stationarity residual + - res_eq: residual wrt equality constraints (dynamics) + - res_ineq: residual wrt inequality constraints (constraints) + - res_comp: residual wrt complementarity conditions """ # compute residuals if RTI if self.solver_options['nlp_solver_type'] == 'SQP_RTI' or recompute: @@ -1499,24 +1617,22 @@ class AcadosOcpSolver: value_ = np.array([value_]) value_ = value_.astype(float) - field = field_ - field = field.encode('utf-8') + field = field_.encode('utf-8') stage = c_int(stage_) # treat parameters separately if field_ == 'p': - getattr(self.shared_lib, f"{self.model_name}_acados_update_params").argtypes = [c_void_p, c_int, POINTER(c_double)] + getattr(self.shared_lib, f"{self.model_name}_acados_update_params").argtypes = [c_void_p, c_int, POINTER(c_double), c_int] getattr(self.shared_lib, f"{self.model_name}_acados_update_params").restype = c_int value_data = cast(value_.ctypes.data, POINTER(c_double)) assert getattr(self.shared_lib, f"{self.model_name}_acados_update_params")(self.capsule, stage, value_data, value_.shape[0])==0 else: - if field_ not in constraints_fields + cost_fields + out_fields: - raise Exception("AcadosOcpSolver.set(): {} is not a valid argument.\ - \nPossible values are {}. Exiting.".format(field, \ - constraints_fields + cost_fields + out_fields + ['p'])) + if field_ not in constraints_fields + cost_fields + out_fields + mem_fields: + raise Exception(f"AcadosOcpSolver.set(): '{field}' is not a valid argument.\n" + f" Possible values are {constraints_fields + cost_fields + out_fields + mem_fields + ['p']}.") self.shared_lib.ocp_nlp_dims_get_from_attr.argtypes = \ [c_void_p, c_void_p, c_void_p, c_int, c_char_p] @@ -1526,8 +1642,8 @@ class AcadosOcpSolver: self.nlp_dims, self.nlp_out, stage_, field) if value_.shape[0] != dims: - msg = 'AcadosOcpSolver.set(): mismatching dimension for field "{}" '.format(field_) - msg += 'with dimension {} (you have {})'.format(dims, value_.shape[0]) + msg = f'AcadosOcpSolver.set(): mismatching dimension for field "{field_}" ' + msg += f'with dimension {dims} (you have {value_.shape[0]})' raise Exception(msg) value_data = cast(value_.ctypes.data, POINTER(c_double)) @@ -1553,6 +1669,13 @@ class AcadosOcpSolver: [c_void_p, c_void_p, c_int, c_char_p, c_void_p] self.shared_lib.ocp_nlp_set(self.nlp_config, \ self.nlp_solver, stage, field, value_data_p) + # also set z_guess, when setting z. + if field_ == 'z': + field = 'z_guess'.encode('utf-8') + self.shared_lib.ocp_nlp_set.argtypes = \ + [c_void_p, c_void_p, c_int, c_char_p, c_void_p] + self.shared_lib.ocp_nlp_set(self.nlp_config, \ + self.nlp_solver, stage, field, value_data_p) return @@ -1561,7 +1684,7 @@ class AcadosOcpSolver: Set numerical data in the cost module of the solver. :param stage: integer corresponding to shooting node - :param field: string, e.g. 'yref', 'W', 'ext_cost_num_hess' + :param field: string, e.g. 'yref', 'W', 'ext_cost_num_hess', 'zl', 'zu', 'Zl', 'Zu' :param value: of appropriate size """ # cast value_ to avoid conversion issues @@ -1595,7 +1718,7 @@ class AcadosOcpSolver: raise Exception("Ambiguity in API detected.\n" "Are you making an acados model from scrach? Add api='new' to cost_set and carry on.\n" "Are you seeing this error suddenly in previously running code? Read on.\n" - " You are relying on a now-fixed bug in cost_set for field '{}'.\n".format(field_) + + f" You are relying on a now-fixed bug in cost_set for field '{field_}'.\n" + " acados_template now correctly passes on any matrices to acados in column major format.\n" + " Two options to fix this error: \n" + " * Add api='old' to cost_set to restore old incorrect behaviour\n" + @@ -1663,7 +1786,7 @@ class AcadosOcpSolver: raise Exception("Ambiguity in API detected.\n" "Are you making an acados model from scrach? Add api='new' to constraints_set and carry on.\n" "Are you seeing this error suddenly in previously running code? Read on.\n" - " You are relying on a now-fixed bug in constraints_set for field '{}'.\n".format(field_) + + f" You are relying on a now-fixed bug in constraints_set for field '{field}'.\n" + " acados_template now correctly passes on any matrices to acados in column major format.\n" + " Two options to fix this error: \n" + " * Add api='old' to constraints_set to restore old incorrect behaviour\n" + @@ -1676,7 +1799,7 @@ class AcadosOcpSolver: # Get elements in column major order value_ = np.ravel(value_, order='F') else: - raise Exception("Unknown api: '{}'".format(api)) + raise Exception(f"Unknown api: '{api}'") if value_shape != tuple(dims): raise Exception(f'AcadosOcpSolver.constraints_set(): mismatching dimension' + @@ -1693,27 +1816,35 @@ class AcadosOcpSolver: return - def dynamics_get(self, stage_, field_): + def get_from_qp_in(self, stage_: int, field_: str): """ - Get numerical data from the dynamics module of the solver: + Get numerical data from the current QP. :param stage: integer corresponding to shooting node - :param field: string, e.g. 'A' + :param field: string in ['A', 'B', 'b', 'Q', 'R', 'S', 'q', 'r', 'C', 'D', 'lg', 'ug', 'lbx', 'ubx', 'lbu', 'ubu'] """ + # idx* should be added too.. + if not isinstance(stage_, int): + raise TypeError("stage should be int") + if stage_ > self.N: + raise Exception("stage should be <= self.N") + if field_ in self.__qp_dynamics_fields and stage_ >= self.N: + raise ValueError(f"dynamics field {field_} not available at terminal stage") + if field_ not in self.__qp_dynamics_fields + self.__qp_cost_fields + self.__qp_constraint_fields: + raise Exception(f"field {field_} not supported.") - field = field_ - field = field.encode('utf-8') + field = field_.encode('utf-8') stage = c_int(stage_) # get dims - self.shared_lib.ocp_nlp_dynamics_dims_get_from_attr.argtypes = \ + self.shared_lib.ocp_nlp_qp_dims_get_from_attr.argtypes = \ [c_void_p, c_void_p, c_void_p, c_int, c_char_p, POINTER(c_int)] - self.shared_lib.ocp_nlp_dynamics_dims_get_from_attr.restype = c_int + self.shared_lib.ocp_nlp_qp_dims_get_from_attr.restype = c_int dims = np.ascontiguousarray(np.zeros((2,)), dtype=np.intc) dims_data = cast(dims.ctypes.data, POINTER(c_int)) - self.shared_lib.ocp_nlp_dynamics_dims_get_from_attr(self.nlp_config, \ + self.shared_lib.ocp_nlp_qp_dims_get_from_attr(self.nlp_config, \ self.nlp_dims, self.nlp_out, stage_, field, dims_data) # create output data @@ -1748,32 +1879,34 @@ class AcadosOcpSolver: - qp_mu0: for HPIPM QP solvers: initial value for complementarity slackness - warm_start_first_qp: indicates if first QP in SQP is warm_started """ - int_fields = ['print_level', 'rti_phase', 'initialize_t_slacks', 'qp_warm_start', 'line_search_use_sufficient_descent', 'full_step_dual', 'globalization_use_SOC', 'warm_start_first_qp'] - double_fields = ['step_length', 'tol_eq', 'tol_stat', 'tol_ineq', 'tol_comp', 'alpha_min', 'alpha_reduction', 'eps_sufficient_descent', - 'qp_tol_stat', 'qp_tol_eq', 'qp_tol_ineq', 'qp_tol_comp', 'qp_tau_min', 'qp_mu0'] + int_fields = ['print_level', 'rti_phase', 'initialize_t_slacks', 'qp_warm_start', + 'line_search_use_sufficient_descent', 'full_step_dual', 'globalization_use_SOC', 'warm_start_first_qp'] + double_fields = ['step_length', 'tol_eq', 'tol_stat', 'tol_ineq', 'tol_comp', 'alpha_min', 'alpha_reduction', + 'eps_sufficient_descent', 'qp_tol_stat', 'qp_tol_eq', 'qp_tol_ineq', 'qp_tol_comp', 'qp_tau_min', 'qp_mu0'] string_fields = ['globalization'] # check field availability and type if field_ in int_fields: if not isinstance(value_, int): - raise Exception('solver option {} must be of type int. You have {}.'.format(field_, type(value_))) + raise Exception(f'solver option \'{field_}\' must be of type int. You have {type(value_)}.') else: value_ctypes = c_int(value_) elif field_ in double_fields: if not isinstance(value_, float): - raise Exception('solver option {} must be of type float. You have {}.'.format(field_, type(value_))) + raise Exception(f'solver option \'{field_}\' must be of type float. You have {type(value_)}.') else: value_ctypes = c_double(value_) elif field_ in string_fields: if not isinstance(value_, str): - raise Exception('solver option {} must be of type str. You have {}.'.format(field_, type(value_))) + raise Exception(f'solver option \'{field_}\' must be of type str. You have {type(value_)}.') else: value_ctypes = value_.encode('utf-8') else: - raise Exception('AcadosOcpSolver.options_set() does not support field {}.'\ - '\n Possible values are {}.'.format(field_, ', '.join(int_fields + double_fields + string_fields))) + fields = ', '.join(int_fields + double_fields + string_fields) + raise Exception(f'AcadosOcpSolver.options_set() does not support field \'{field_}\'.\n'\ + f' Possible values are {fields}.') if field_ == 'rti_phase': @@ -1802,6 +1935,44 @@ class AcadosOcpSolver: return + def set_params_sparse(self, stage_, idx_values_, param_values_): + """ + set parameters of the solvers external function partially: + Pseudo: solver.param[idx_values_] = param_values_; + Parameters: + :param stage_: integer corresponding to shooting node + :param idx_values_: 0 based np array (or iterable) of integers: indices of parameter to be set + :param param_values_: new parameter values as numpy array + """ + + # if not isinstance(idx_values_, np.ndarray) or not issubclass(type(idx_values_[0]), np.integer): + # raise Exception('idx_values_ must be np.array of integers.') + + if not isinstance(param_values_, np.ndarray): + raise Exception('param_values_ must be np.array.') + elif np.float64 != param_values_.dtype: + raise TypeError('param_values_ must be np.array of float64.') + + if param_values_.shape[0] != len(idx_values_): + raise Exception(f'param_values_ and idx_values_ must be of the same size.' + + f' Got sizes idx {param_values_.shape[0]}, param_values {len(idx_values_)}.') + + if any(idx_values_ >= self.acados_ocp.dims.np): + raise Exception(f'idx_values_ contains value >= np = {self.acados_ocp.dims.np}') + + stage = c_int(stage_) + n_update = c_int(len(param_values_)) + + param_data = cast(param_values_.ctypes.data, POINTER(c_double)) + c_idx_values = np.ascontiguousarray(idx_values_, dtype=np.intc) + idx_data = cast(c_idx_values.ctypes.data, POINTER(c_int)) + + getattr(self.shared_lib, f"{self.model_name}_acados_update_params_sparse").argtypes = \ + [c_void_p, c_int, POINTER(c_int), POINTER(c_double), c_int] + getattr(self.shared_lib, f"{self.model_name}_acados_update_params_sparse").restype = c_int + getattr(self.shared_lib, f"{self.model_name}_acados_update_params_sparse") \ + (self.capsule, stage, idx_data, param_data, n_update) + def __del__(self): if self.solver_created: getattr(self.shared_lib, f"{self.model_name}_acados_free").argtypes = [c_void_p] @@ -1815,4 +1986,6 @@ class AcadosOcpSolver: try: self.dlclose(self.shared_lib._handle) except: + print(f"WARNING: acados Python interface could not close shared_lib handle of AcadosOcpSolver {self.model_name}.\n", + "Attempting to create a new one with the same name will likely result in the old one being used!") pass diff --git a/third_party/acados/acados_template/acados_ocp_solver_pyx.pyx b/third_party/acados/acados_template/acados_ocp_solver_pyx.pyx index fe7fa8425..acd7f02d0 100644 --- a/third_party/acados/acados_template/acados_ocp_solver_pyx.pyx +++ b/third_party/acados/acados_template/acados_ocp_solver_pyx.pyx @@ -1,9 +1,6 @@ # -*- coding: future_fstrings -*- # -# Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, -# Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, -# Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, -# Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl +# Copyright (c) The acados authors. # # This file is part of acados. # @@ -63,7 +60,6 @@ cdef class AcadosOcpSolverCython: cdef acados_solver_common.ocp_nlp_in *nlp_in cdef acados_solver_common.ocp_nlp_solver *nlp_solver - cdef int status cdef bint solver_created cdef str model_name @@ -88,7 +84,6 @@ cdef class AcadosOcpSolverCython: # get pointers solver self.__get_pointers_solver() - self.status = 0 def __get_pointers_solver(self): @@ -105,6 +100,24 @@ cdef class AcadosOcpSolverCython: self.nlp_solver = acados_solver.acados_get_nlp_solver(self.capsule) + def solve_for_x0(self, x0_bar): + """ + Wrapper around `solve()` which sets initial state constraint, solves the OCP, and returns u0. + """ + self.set(0, "lbx", x0_bar) + self.set(0, "ubx", x0_bar) + + status = self.solve() + + if status == 2: + print("Warning: acados_ocp_solver reached maximum iterations.") + elif status != 0: + raise Exception(f'acados acados_ocp_solver returned status {status}') + + u0 = self.get(0, "u") + return u0 + + def solve(self): """ Solve the ocp with current input. @@ -112,11 +125,24 @@ cdef class AcadosOcpSolverCython: return acados_solver.acados_solve(self.capsule) - def reset(self): + def reset(self, reset_qp_solver_mem=1): """ Sets current iterate to all zeros. """ - return acados_solver.acados_reset(self.capsule) + return acados_solver.acados_reset(self.capsule, reset_qp_solver_mem) + + + def custom_update(self, data_): + """ + A custom function that can be implemented by a user to be called between solver calls. + By default this does nothing. + The idea is to have a convenient wrapper to do complex updates of parameters and numerical data efficiently in C, + in a function that is compiled into the solver library and can be conveniently used in the Python environment. + """ + data_len = len(data_) + cdef cnp.ndarray[cnp.float64_t, ndim=1] data = np.ascontiguousarray(data_, dtype=np.float64) + + return acados_solver.acados_custom_update(self.capsule, data.data, data_len) def set_new_time_steps(self, new_time_steps): @@ -253,7 +279,7 @@ cdef class AcadosOcpSolverCython: if field_ not in out_fields: raise Exception('AcadosOcpSolverCython.get(): {} is an invalid argument.\ - \n Possible values are {}. Exiting.'.format(field_, out_fields)) + \n Possible values are {}.'.format(field_, out_fields)) if stage < 0 or stage > self.N: raise Exception('AcadosOcpSolverCython.get(): stage index must be in [0, N], got: {}.'.format(self.N)) @@ -310,16 +336,22 @@ cdef class AcadosOcpSolverCython: # get iterate: solution = dict() + lN = len(str(self.N+1)) for i in range(self.N+1): - solution['x_'+str(i)] = self.get(i,'x') - solution['u_'+str(i)] = self.get(i,'u') - solution['z_'+str(i)] = self.get(i,'z') - solution['lam_'+str(i)] = self.get(i,'lam') - solution['t_'+str(i)] = self.get(i, 't') - solution['sl_'+str(i)] = self.get(i, 'sl') - solution['su_'+str(i)] = self.get(i, 'su') - for i in range(self.N): - solution['pi_'+str(i)] = self.get(i,'pi') + i_string = f'{i:0{lN}d}' + solution['x_'+i_string] = self.get(i,'x') + solution['u_'+i_string] = self.get(i,'u') + solution['z_'+i_string] = self.get(i,'z') + solution['lam_'+i_string] = self.get(i,'lam') + solution['t_'+i_string] = self.get(i, 't') + solution['sl_'+i_string] = self.get(i, 'sl') + solution['su_'+i_string] = self.get(i, 'su') + if i < self.N: + solution['pi_'+i_string] = self.get(i,'pi') + + for k in list(solution.keys()): + if len(solution[k]) == 0: + del solution[k] # save with open(filename, 'w') as f: @@ -508,6 +540,8 @@ cdef class AcadosOcpSolverCython: sl: slack variables of soft lower inequality constraints \n su: slack variables of soft upper inequality constraints \n """ + if not isinstance(value_, np.ndarray): + raise Exception(f"set: value must be numpy array, got {type(value_)}.") cost_fields = ['y_ref', 'yref'] constraints_fields = ['lbx', 'ubx', 'lbu', 'ubu'] out_fields = ['x', 'u', 'pi', 'lam', 't', 'z', 'sl', 'su'] @@ -523,7 +557,7 @@ cdef class AcadosOcpSolverCython: else: if field_ not in constraints_fields + cost_fields + out_fields: raise Exception("AcadosOcpSolverCython.set(): {} is not a valid argument.\ - \nPossible values are {}. Exiting.".format(field, \ + \nPossible values are {}.".format(field, \ constraints_fields + cost_fields + out_fields + ['p'])) dims = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, @@ -547,6 +581,11 @@ cdef class AcadosOcpSolverCython: acados_solver_common.ocp_nlp_set(self.nlp_config, \ self.nlp_solver, stage, field, value.data) + if field_ == 'z': + field = 'z_guess'.encode('utf-8') + acados_solver_common.ocp_nlp_set(self.nlp_config, \ + self.nlp_solver, stage, field, value.data) + return def cost_set(self, int stage, str field_, value_): """ @@ -556,6 +595,8 @@ cdef class AcadosOcpSolverCython: :param field: string, e.g. 'yref', 'W', 'ext_cost_num_hess' :param value: of appropriate size """ + if not isinstance(value_, np.ndarray): + raise Exception(f"cost_set: value must be numpy array, got {type(value_)}.") field = field_.encode('utf-8') cdef int dims[2] @@ -589,6 +630,9 @@ cdef class AcadosOcpSolverCython: :param field: string in ['lbx', 'ubx', 'lbu', 'ubu', 'lg', 'ug', 'lh', 'uh', 'uphi', 'C', 'D'] :param value: of appropriate size """ + if not isinstance(value_, np.ndarray): + raise Exception(f"constraints_set: value must be numpy array, got {type(value_)}.") + field = field_.encode('utf-8') cdef int dims[2] @@ -606,7 +650,7 @@ cdef class AcadosOcpSolverCython: # Get elements in column major order value = np.asfortranarray(value_) - if value_shape[0] != dims[0] or value_shape[1] != dims[1]: + if value_shape != tuple(dims): raise Exception(f'AcadosOcpSolverCython.constraints_set(): mismatching dimension' + f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') @@ -616,7 +660,7 @@ cdef class AcadosOcpSolverCython: return - def dynamics_get(self, int stage, str field_): + def get_from_qp_in(self, int stage, str field_): """ Get numerical data from the dynamics module of the solver: @@ -627,7 +671,7 @@ cdef class AcadosOcpSolverCython: # get dims cdef int[2] dims - acados_solver_common.ocp_nlp_dynamics_dims_get_from_attr(self.nlp_config, self.nlp_dims, self.nlp_out, stage, field, &dims[0]) + acados_solver_common.ocp_nlp_qp_dims_get_from_attr(self.nlp_config, self.nlp_dims, self.nlp_out, stage, field, &dims[0]) # create output data cdef cnp.ndarray[cnp.float64_t, ndim=2] out = np.zeros((dims[0], dims[1]), order='F') @@ -701,6 +745,50 @@ cdef class AcadosOcpSolverCython: '\n Possible values are {}.'.format(field_, ', '.join(int_fields + double_fields + string_fields))) + def set_params_sparse(self, int stage, idx_values_, param_values_): + """ + set parameters of the solvers external function partially: + Pseudo: solver.param[idx_values_] = param_values_; + Parameters: + :param stage_: integer corresponding to shooting node + :param idx_values_: 0 based integer array corresponding to parameter indices to be set + :param param_values_: new parameter values as numpy array + """ + + if not isinstance(param_values_, np.ndarray): + raise Exception('param_values_ must be np.array.') + + if param_values_.shape[0] != len(idx_values_): + raise Exception(f'param_values_ and idx_values_ must be of the same size.' + + f' Got sizes idx {param_values_.shape[0]}, param_values {len(idx_values_)}.') + + # n_update = c_int(len(param_values_)) + + # param_data = cast(param_values_.ctypes.data, POINTER(c_double)) + # c_idx_values = np.ascontiguousarray(idx_values_, dtype=np.intc) + # idx_data = cast(c_idx_values.ctypes.data, POINTER(c_int)) + + # getattr(self.shared_lib, f"{self.model_name}_acados_update_params_sparse").argtypes = \ + # [c_void_p, c_int, POINTER(c_int), POINTER(c_double), c_int] + # getattr(self.shared_lib, f"{self.model_name}_acados_update_params_sparse").restype = c_int + # getattr(self.shared_lib, f"{self.model_name}_acados_update_params_sparse") \ + # (self.capsule, stage, idx_data, param_data, n_update) + + cdef cnp.ndarray[cnp.float64_t, ndim=1] value = np.ascontiguousarray(param_values_, dtype=np.float64) + # cdef cnp.ndarray[cnp.intc, ndim=1] idx = np.ascontiguousarray(idx_values_, dtype=np.intc) + + # NOTE: this does throw an error somehow: + # ValueError: Buffer dtype mismatch, expected 'int object' but got 'int' + # cdef cnp.ndarray[cnp.int, ndim=1] idx = np.ascontiguousarray(idx_values_, dtype=np.intc) + + cdef cnp.ndarray[cnp.int32_t, ndim=1] idx = np.ascontiguousarray(idx_values_, dtype=np.int32) + cdef int n_update = value.shape[0] + # print(f"in set_params_sparse Cython n_update {n_update}") + + assert acados_solver.acados_update_params_sparse(self.capsule, stage, idx.data, value.data, n_update) == 0 + return + + def __del__(self): if self.solver_created: acados_solver.acados_free(self.capsule) diff --git a/third_party/acados/acados_template/acados_sim.py b/third_party/acados/acados_template/acados_sim.py index 93d5f298d..c0d6937a4 100644 --- a/third_party/acados/acados_template/acados_sim.py +++ b/third_party/acados/acados_template/acados_sim.py @@ -1,9 +1,6 @@ # -*- coding: future_fstrings -*- # -# Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, -# Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, -# Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, -# Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl +# Copyright (c) The acados authors. # # This file is part of acados. # @@ -33,10 +30,9 @@ # import numpy as np -import casadi as ca import os from .acados_model import AcadosModel -from .utils import get_acados_path +from .utils import get_acados_path, get_lib_ext class AcadosSimDims: """ @@ -73,28 +69,28 @@ class AcadosSimDims: if isinstance(nx, int) and nx > 0: self.__nx = nx else: - raise Exception('Invalid nx value, expected positive integer. Exiting.') + raise Exception('Invalid nx value, expected positive integer.') @nz.setter def nz(self, nz): if isinstance(nz, int) and nz > -1: self.__nz = nz else: - raise Exception('Invalid nz value, expected nonnegative integer. Exiting.') + raise Exception('Invalid nz value, expected nonnegative integer.') @nu.setter def nu(self, nu): if isinstance(nu, int) and nu > -1: self.__nu = nu else: - raise Exception('Invalid nu value, expected nonnegative integer. Exiting.') + raise Exception('Invalid nu value, expected nonnegative integer.') @np.setter def np(self, np): if isinstance(np, int) and np > -1: self.__np = np else: - raise Exception('Invalid np value, expected nonnegative integer. Exiting.') + raise Exception('Invalid np value, expected nonnegative integer.') def set(self, attr, value): setattr(self, attr, value) @@ -112,13 +108,16 @@ class AcadosSimOpts: self.__sim_method_num_stages = 1 self.__sim_method_num_steps = 1 self.__sim_method_newton_iter = 3 + # doubles + self.__sim_method_newton_tol = 0.0 # bools self.__sens_forw = True self.__sens_adj = False self.__sens_algebraic = False self.__sens_hess = False - self.__output_z = False + self.__output_z = True self.__sim_method_jac_reuse = 0 + self.__ext_fun_compile_flags = '-O2' @property def integrator_type(self): @@ -140,6 +139,15 @@ class AcadosSimOpts: """Number of Newton iterations in simulation method. Default: 3""" return self.__sim_method_newton_iter + @property + def newton_tol(self): + """ + Tolerance for Newton system solved in implicit integrator (IRK, GNSF). + 0.0 means this is not used and exactly newton_iter iterations are carried out. + Default: 0.0 + """ + return self.__sim_method_newton_tol + @property def sens_forw(self): """Boolean determining if forward sensitivities are computed. Default: True""" @@ -162,7 +170,7 @@ class AcadosSimOpts: @property def output_z(self): - """Boolean determining if values for algebraic variables (corresponding to start of simulation interval) are computed. Default: False""" + """Boolean determining if values for algebraic variables (corresponding to start of simulation interval) are computed. Default: True""" return self.__output_z @property @@ -184,6 +192,21 @@ class AcadosSimOpts: """ return self.__collocation_type + @property + def ext_fun_compile_flags(self): + """ + String with compiler flags for external function compilation. + Default: '-O2'. + """ + return self.__ext_fun_compile_flags + + @ext_fun_compile_flags.setter + def ext_fun_compile_flags(self, ext_fun_compile_flags): + if isinstance(ext_fun_compile_flags, str): + self.__ext_fun_compile_flags = ext_fun_compile_flags + else: + raise Exception('Invalid ext_fun_compile_flags, expected a string.\n') + @integrator_type.setter def integrator_type(self, integrator_type): integrator_types = ('ERK', 'IRK', 'GNSF') @@ -191,7 +214,7 @@ class AcadosSimOpts: self.__integrator_type = integrator_type else: raise Exception('Invalid integrator_type value. Possible values are:\n\n' \ - + ',\n'.join(integrator_types) + '.\n\nYou have: ' + integrator_type + '.\n\nExiting.') + + ',\n'.join(integrator_types) + '.\n\nYou have: ' + integrator_type + '.\n\n') @collocation_type.setter def collocation_type(self, collocation_type): @@ -200,7 +223,7 @@ class AcadosSimOpts: self.__collocation_type = collocation_type else: raise Exception('Invalid collocation_type value. Possible values are:\n\n' \ - + ',\n'.join(collocation_types) + '.\n\nYou have: ' + collocation_type + '.\n\nExiting.') + + ',\n'.join(collocation_types) + '.\n\nYou have: ' + collocation_type + '.\n\n') @T.setter def T(self, T): @@ -227,6 +250,13 @@ class AcadosSimOpts: else: raise Exception('Invalid newton_iter value. newton_iter must be an integer.') + @newton_tol.setter + def newton_tol(self, newton_tol): + if isinstance(newton_tol, float): + self.__sim_method_newton_tol = newton_tol + else: + raise Exception('Invalid newton_tol value. newton_tol must be an float.') + @sens_forw.setter def sens_forw(self, sens_forw): if sens_forw in (True, False): @@ -280,6 +310,7 @@ class AcadosSim: - :py:attr:`solver_options` of type :py:class:`acados_template.acados_sim.AcadosSimOpts` - :py:attr:`acados_include_path` (set automatically) + - :py:attr:`shared_lib_ext` (set automatically) - :py:attr:`acados_lib_path` (set automatically) - :py:attr:`parameter_values` - used to initialize the parameters (can be changed) @@ -301,9 +332,14 @@ class AcadosSim: self.code_export_directory = 'c_generated_code' """Path to where code will be exported. Default: `c_generated_code`.""" + self.shared_lib_ext = get_lib_ext() + + # get cython paths + from sysconfig import get_paths + self.cython_include_dirs = [np.get_include(), get_paths()['include']] - self.cython_include_dirs = '' self.__parameter_values = np.array([]) + self.__problem_class = 'SIM' @property def parameter_values(self): diff --git a/third_party/acados/acados_template/acados_sim_layout.json b/third_party/acados/acados_template/acados_sim_layout.json index 25b149613..e3ca4b575 100644 --- a/third_party/acados/acados_template/acados_sim_layout.json +++ b/third_party/acados/acados_template/acados_sim_layout.json @@ -42,6 +42,12 @@ ], "sim_method_newton_iter": [ "int" + ], + "sim_method_newton_tol": [ + "float" + ], + "ext_fun_compile_flags": [ + "str" ] } } diff --git a/third_party/acados/acados_template/acados_sim_solver.py b/third_party/acados/acados_template/acados_sim_solver.py index 3588dd38c..612f439ea 100644 --- a/third_party/acados/acados_template/acados_sim_solver.py +++ b/third_party/acados/acados_template/acados_sim_solver.py @@ -1,9 +1,6 @@ # -*- coding: future_fstrings -*- # -# Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, -# Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, -# Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, -# Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl +# Copyright (c) The acados authors. # # This file is part of acados. # @@ -32,56 +29,58 @@ # POSSIBILITY OF SUCH DAMAGE.; # -import sys, os, json +import sys +import os +import json +import importlib import numpy as np -from ctypes import * +from subprocess import DEVNULL, call, STDOUT + +from ctypes import POINTER, cast, CDLL, c_void_p, c_char_p, c_double, c_int, c_bool, byref from copy import deepcopy -from .generate_c_code_explicit_ode import generate_c_code_explicit_ode -from .generate_c_code_implicit_ode import generate_c_code_implicit_ode -from .generate_c_code_gnsf import generate_c_code_gnsf +from .casadi_function_generation import generate_c_code_implicit_ode, generate_c_code_gnsf, generate_c_code_explicit_ode from .acados_sim import AcadosSim from .acados_ocp import AcadosOcp -from .acados_model import acados_model_strip_casadi_symbolics -from .utils import is_column, render_template, format_class_dict, np_array_to_list,\ - make_model_consistent, set_up_imported_gnsf_model, get_python_interface_path +from .utils import is_column, render_template, format_class_dict, make_object_json_dumpable,\ + make_model_consistent, set_up_imported_gnsf_model, get_python_interface_path, get_lib_ext,\ + casadi_length, is_empty, check_casadi_version from .builders import CMakeBuilder +from .gnsf.detect_gnsf_structure import detect_gnsf_structure -def make_sim_dims_consistent(acados_sim): + +def make_sim_dims_consistent(acados_sim: AcadosSim): dims = acados_sim.dims model = acados_sim.model # nx if is_column(model.x): - dims.nx = model.x.shape[0] + dims.nx = casadi_length(model.x) else: - raise Exception("model.x should be column vector!") + raise Exception('model.x should be column vector!') # nu - if is_column(model.u): - dims.nu = model.u.shape[0] - elif model.u == None or model.u == []: + if is_empty(model.u): dims.nu = 0 else: - raise Exception("model.u should be column vector or None!") + dims.nu = casadi_length(model.u) # nz - if is_column(model.z): - dims.nz = model.z.shape[0] - elif model.z == None or model.z == []: + if is_empty(model.z): dims.nz = 0 else: - raise Exception("model.z should be column vector or None!") + dims.nz = casadi_length(model.z) # np - if is_column(model.p): - dims.np = model.p.shape[0] - elif model.p == None or model.p == []: + if is_empty(model.p): dims.np = 0 else: - raise Exception("model.p should be column vector or None!") + dims.np = casadi_length(model.p) + if acados_sim.parameter_values.shape[0] != dims.np: + raise Exception('inconsistent dimension np, regarding model.p and parameter_values.' + \ + f'\nGot np = {dims.np}, acados_sim.parameter_values.shape = {acados_sim.parameter_values.shape[0]}\n') def get_sim_layout(): @@ -92,7 +91,7 @@ def get_sim_layout(): return sim_layout -def sim_formulation_json_dump(acados_sim, json_file='acados_sim.json'): +def sim_formulation_json_dump(acados_sim: AcadosSim, json_file='acados_sim.json'): # Load acados_sim structure description sim_layout = get_sim_layout() @@ -105,11 +104,10 @@ def sim_formulation_json_dump(acados_sim, json_file='acados_sim.json'): # Copy sim object attributes dictionaries sim_dict[key]=dict(getattr(acados_sim, key).__dict__) - sim_dict['model'] = acados_model_strip_casadi_symbolics(sim_dict['model']) sim_json = format_class_dict(sim_dict) with open(json_file, 'w') as f: - json.dump(sim_json, f, default=np_array_to_list, indent=4, sort_keys=True) + json.dump(sim_json, f, default=make_object_json_dumpable, indent=4, sort_keys=True) def sim_get_default_cmake_builder() -> CMakeBuilder: @@ -122,47 +120,49 @@ def sim_get_default_cmake_builder() -> CMakeBuilder: return cmake_builder -def sim_render_templates(json_file, model_name, code_export_dir, cmake_options: CMakeBuilder = None): +def sim_render_templates(json_file, model_name: str, code_export_dir, cmake_options: CMakeBuilder = None): # setting up loader and environment json_path = os.path.join(os.getcwd(), json_file) if not os.path.exists(json_path): raise Exception(f"{json_path} not found!") - template_dir = code_export_dir - - ## Render templates + # Render templates in_file = 'acados_sim_solver.in.c' out_file = f'acados_sim_solver_{model_name}.c' - render_template(in_file, out_file, template_dir, json_path) + render_template(in_file, out_file, code_export_dir, json_path) in_file = 'acados_sim_solver.in.h' out_file = f'acados_sim_solver_{model_name}.h' - render_template(in_file, out_file, template_dir, json_path) + render_template(in_file, out_file, code_export_dir, json_path) + + in_file = 'acados_sim_solver.in.pxd' + out_file = f'acados_sim_solver.pxd' + render_template(in_file, out_file, code_export_dir, json_path) # Builder if cmake_options is not None: in_file = 'CMakeLists.in.txt' out_file = 'CMakeLists.txt' - render_template(in_file, out_file, template_dir, json_path) + render_template(in_file, out_file, code_export_dir, json_path) else: in_file = 'Makefile.in' out_file = 'Makefile' - render_template(in_file, out_file, template_dir, json_path) + render_template(in_file, out_file, code_export_dir, json_path) in_file = 'main_sim.in.c' out_file = f'main_sim_{model_name}.c' - render_template(in_file, out_file, template_dir, json_path) + render_template(in_file, out_file, code_export_dir, json_path) - ## folder model - template_dir = os.path.join(code_export_dir, model_name + '_model') + # folder model + model_dir = os.path.join(code_export_dir, model_name + '_model') in_file = 'model.in.h' out_file = f'{model_name}_model.h' - render_template(in_file, out_file, template_dir, json_path) + render_template(in_file, out_file, model_dir, json_path) -def sim_generate_casadi_functions(acados_sim): +def sim_generate_external_functions(acados_sim: AcadosSim): model = acados_sim.model model = make_model_consistent(model) @@ -170,7 +170,16 @@ def sim_generate_casadi_functions(acados_sim): opts = dict(generate_hess = acados_sim.solver_options.sens_hess, code_export_directory = acados_sim.code_export_directory) + + # create code_export_dir, model_dir + code_export_dir = acados_sim.code_export_directory + opts['code_export_directory'] = code_export_dir + model_dir = os.path.join(code_export_dir, model.name + '_model') + if not os.path.exists(model_dir): + os.makedirs(model_dir) + # generate external functions + check_casadi_version() if integrator_type == 'ERK': generate_c_code_explicit_ode(model, opts) elif integrator_type == 'IRK': @@ -190,62 +199,117 @@ class AcadosSimSolver: the `CMake` pipeline instead of a `Makefile` (`CMake` seems to be the better option in conjunction with `MS Visual Studio`); default: `None` """ - def __init__(self, acados_sim_, json_file='acados_sim.json', build=True, cmake_builder: CMakeBuilder = None): + if sys.platform=="win32": + from ctypes import wintypes + from ctypes import WinDLL + dlclose = WinDLL('kernel32', use_last_error=True).FreeLibrary + dlclose.argtypes = [wintypes.HMODULE] + else: + dlclose = CDLL(None).dlclose + dlclose.argtypes = [c_void_p] - self.solver_created = False - if isinstance(acados_sim_, AcadosOcp): - # set up acados_sim_ - acados_sim = AcadosSim() - acados_sim.model = acados_sim_.model - acados_sim.dims.nx = acados_sim_.dims.nx - acados_sim.dims.nu = acados_sim_.dims.nu - acados_sim.dims.nz = acados_sim_.dims.nz - acados_sim.dims.np = acados_sim_.dims.np - acados_sim.solver_options.integrator_type = acados_sim_.solver_options.integrator_type - acados_sim.code_export_directory = acados_sim_.code_export_directory + @classmethod + def generate(cls, acados_sim: AcadosSim, json_file='acados_sim.json', cmake_builder: CMakeBuilder = None): + """ + Generates the code for an acados sim solver, given the description in acados_sim + """ - elif isinstance(acados_sim_, AcadosSim): - acados_sim = acados_sim_ + acados_sim.code_export_directory = os.path.abspath(acados_sim.code_export_directory) - acados_sim.__problem_class = 'SIM' - - model_name = acados_sim.model.name + # make dims consistent make_sim_dims_consistent(acados_sim) - # reuse existing json and casadi functions, when creating integrator from ocp - if isinstance(acados_sim_, AcadosSim): - if acados_sim.solver_options.integrator_type == 'GNSF': + # module dependent post processing + if acados_sim.solver_options.integrator_type == 'GNSF': + if acados_sim.solver_options.sens_hess == True: + raise Exception("AcadosSimSolver: GNSF does not support sens_hess = True.") + if 'gnsf_model' in acados_sim.__dict__: set_up_imported_gnsf_model(acados_sim) - - sim_generate_casadi_functions(acados_sim) - sim_formulation_json_dump(acados_sim, json_file) - - code_export_dir = acados_sim.code_export_directory - if build: - # render templates - sim_render_templates(json_file, model_name, code_export_dir, cmake_builder) - - # Compile solver - cwd = os.getcwd() - code_export_dir = os.path.abspath(code_export_dir) - os.chdir(code_export_dir) - if cmake_builder is not None: - cmake_builder.exec(code_export_dir) else: - os.system('make sim_shared_lib') - os.chdir(cwd) + detect_gnsf_structure(acados_sim) - self.sim_struct = acados_sim - model_name = self.sim_struct.model.name + # generate external functions + sim_generate_external_functions(acados_sim) + + # dump to json + sim_formulation_json_dump(acados_sim, json_file) + + # render templates + sim_render_templates(json_file, acados_sim.model.name, acados_sim.code_export_directory, cmake_builder) + + + @classmethod + def build(cls, code_export_dir, with_cython=False, cmake_builder: CMakeBuilder = None, verbose: bool = True): + # Compile solver + cwd = os.getcwd() + os.chdir(code_export_dir) + if with_cython: + call( + ['make', 'clean_sim_cython'], + stdout=None if verbose else DEVNULL, + stderr=None if verbose else STDOUT + ) + call( + ['make', 'sim_cython'], + stdout=None if verbose else DEVNULL, + stderr=None if verbose else STDOUT + ) + else: + if cmake_builder is not None: + cmake_builder.exec(code_export_dir, verbose=verbose) + else: + call( + ['make', 'sim_shared_lib'], + stdout=None if verbose else DEVNULL, + stderr=None if verbose else STDOUT + ) + os.chdir(cwd) + + + @classmethod + def create_cython_solver(cls, json_file): + """ + """ + with open(json_file, 'r') as f: + acados_sim_json = json.load(f) + code_export_directory = acados_sim_json['code_export_directory'] + + importlib.invalidate_caches() + rel_code_export_directory = os.path.relpath(code_export_directory) + acados_sim_solver_pyx = importlib.import_module(f'{rel_code_export_directory}.acados_sim_solver_pyx') + + AcadosSimSolverCython = getattr(acados_sim_solver_pyx, 'AcadosSimSolverCython') + return AcadosSimSolverCython(acados_sim_json['model']['name']) + + def __init__(self, acados_sim, json_file='acados_sim.json', generate=True, build=True, cmake_builder: CMakeBuilder = None, verbose: bool = True): + + self.solver_created = False + self.acados_sim = acados_sim + model_name = acados_sim.model.name self.model_name = model_name + code_export_dir = os.path.abspath(acados_sim.code_export_directory) + + # reuse existing json and casadi functions, when creating integrator from ocp + if generate and not isinstance(acados_sim, AcadosOcp): + self.generate(acados_sim, json_file=json_file, cmake_builder=cmake_builder) + + if build: + self.build(code_export_dir, cmake_builder=cmake_builder, verbose=True) + + # prepare library loading + lib_prefix = 'lib' + lib_ext = get_lib_ext() + if os.name == 'nt': + lib_prefix = '' + # Load acados library to avoid unloading the library. # This is necessary if acados was compiled with OpenMP, since the OpenMP threads can't be destroyed. # Unloading a library which uses OpenMP results in a segfault (on any platform?). # see [https://stackoverflow.com/questions/34439956/vc-crash-when-freeing-a-dll-built-with-openmp] # or [https://python.hotexamples.com/examples/_ctypes/-/dlclose/python-dlclose-function-examples.html] - libacados_name = 'libacados.so' + libacados_name = f'{lib_prefix}acados{lib_ext}' libacados_filepath = os.path.join(acados_sim.acados_lib_path, libacados_name) self.__acados_lib = CDLL(libacados_filepath) # find out if acados was compiled with OpenMP @@ -257,19 +321,12 @@ class AcadosSimSolver: print('acados was compiled with OpenMP.') else: print('acados was compiled without OpenMP.') + libacados_sim_solver_name = f'{lib_prefix}acados_sim_solver_{self.model_name}{lib_ext}' + self.shared_lib_name = os.path.join(code_export_dir, libacados_sim_solver_name) - # Ctypes - lib_prefix = 'lib' - lib_ext = '.so' - if os.name == 'nt': - lib_prefix = '' - lib_ext = '' - self.shared_lib_name = os.path.join(code_export_dir, f'{lib_prefix}acados_sim_solver_{model_name}{lib_ext}') - print(f'self.shared_lib_name = "{self.shared_lib_name}"') - + # get shared_lib self.shared_lib = CDLL(self.shared_lib_name) - # create capsule getattr(self.shared_lib, f"{model_name}_acados_sim_solver_create_capsule").restype = c_void_p self.capsule = getattr(self.shared_lib, f"{model_name}_acados_sim_solver_create_capsule")() @@ -304,23 +361,34 @@ class AcadosSimSolver: getattr(self.shared_lib, f"{model_name}_acados_get_sim_solver").restype = c_void_p self.sim_solver = getattr(self.shared_lib, f"{model_name}_acados_get_sim_solver")(self.capsule) - nu = self.sim_struct.dims.nu - nx = self.sim_struct.dims.nx - nz = self.sim_struct.dims.nz - self.gettable = { - 'x': nx, - 'xn': nx, - 'u': nu, - 'z': nz, - 'S_forw': nx*(nx+nu), - 'Sx': nx*nx, - 'Su': nx*nu, - 'S_adj': nx+nu, - 'S_hess': (nx+nu)*(nx+nu), - 'S_algebraic': (nz)*(nx+nu), - } + self.gettable_vectors = ['x', 'u', 'z', 'S_adj'] + self.gettable_matrices = ['S_forw', 'Sx', 'Su', 'S_hess', 'S_algebraic'] + self.gettable_scalars = ['CPUtime', 'time_tot', 'ADtime', 'time_ad', 'LAtime', 'time_la'] - self.settable = ['S_adj', 'T', 'x', 'u', 'xdot', 'z', 'p'] # S_forw + + def simulate(self, x=None, u=None, z=None, p=None): + """ + Simulate the system forward for the given x, u, z, p and return x_next. + Wrapper around `solve()` taking care of setting/getting inputs/outputs. + """ + if x is not None: + self.set('x', x) + if u is not None: + self.set('u', u) + if z is not None: + self.set('z', z) + if p is not None: + self.set('p', p) + + status = self.solve() + + if status == 2: + print("Warning: acados_sim_solver reached maximum iterations.") + elif status != 0: + raise Exception(f'acados_sim_solver for model {self.model_name} returned status {status}.') + + x_next = self.get('x') + return x_next def solve(self): @@ -338,55 +406,64 @@ class AcadosSimSolver: """ Get the last solution of the solver. - :param str field: string in ['x', 'u', 'z', 'S_forw', 'Sx', 'Su', 'S_adj', 'S_hess', 'S_algebraic'] + :param str field: string in ['x', 'u', 'z', 'S_forw', 'Sx', 'Su', 'S_adj', 'S_hess', 'S_algebraic', 'CPUtime', 'time_tot', 'ADtime', 'time_ad', 'LAtime', 'time_la'] """ - field = field_ - field = field.encode('utf-8') + field = field_.encode('utf-8') - if field_ in self.gettable.keys(): + if field_ in self.gettable_vectors: + # get dims + dims = np.ascontiguousarray(np.zeros((2,)), dtype=np.intc) + dims_data = cast(dims.ctypes.data, POINTER(c_int)) + + self.shared_lib.sim_dims_get_from_attr.argtypes = [c_void_p, c_void_p, c_char_p, POINTER(c_int)] + self.shared_lib.sim_dims_get_from_attr(self.sim_config, self.sim_dims, field, dims_data) # allocate array - dims = self.gettable[field_] - out = np.ascontiguousarray(np.zeros((dims,)), dtype=np.float64) + out = np.ascontiguousarray(np.zeros((dims[0],)), dtype=np.float64) out_data = cast(out.ctypes.data, POINTER(c_double)) self.shared_lib.sim_out_get.argtypes = [c_void_p, c_void_p, c_void_p, c_char_p, c_void_p] self.shared_lib.sim_out_get(self.sim_config, self.sim_dims, self.sim_out, field, out_data) - if field_ == 'S_forw': - nu = self.sim_struct.dims.nu - nx = self.sim_struct.dims.nx - out = out.reshape(nx, nx+nu, order='F') - elif field_ == 'Sx': - nx = self.sim_struct.dims.nx - out = out.reshape(nx, nx, order='F') - elif field_ == 'Su': - nx = self.sim_struct.dims.nx - nu = self.sim_struct.dims.nu - out = out.reshape(nx, nu, order='F') - elif field_ == 'S_hess': - nx = self.sim_struct.dims.nx - nu = self.sim_struct.dims.nu - out = out.reshape(nx+nu, nx+nu, order='F') - elif field_ == 'S_algebraic': - nx = self.sim_struct.dims.nx - nu = self.sim_struct.dims.nu - nz = self.sim_struct.dims.nz - out = out.reshape(nz, nx+nu, order='F') + elif field_ in self.gettable_matrices: + # get dims + dims = np.ascontiguousarray(np.zeros((2,)), dtype=np.intc) + dims_data = cast(dims.ctypes.data, POINTER(c_int)) + + self.shared_lib.sim_dims_get_from_attr.argtypes = [c_void_p, c_void_p, c_char_p, POINTER(c_int)] + self.shared_lib.sim_dims_get_from_attr(self.sim_config, self.sim_dims, field, dims_data) + + out = np.zeros((dims[0], dims[1]), order='F') + out_data = cast(out.ctypes.data, POINTER(c_double)) + + self.shared_lib.sim_out_get.argtypes = [c_void_p, c_void_p, c_void_p, c_char_p, c_void_p] + self.shared_lib.sim_out_get(self.sim_config, self.sim_dims, self.sim_out, field, out_data) + + elif field_ in self.gettable_scalars: + scalar = c_double() + scalar_data = byref(scalar) + self.shared_lib.sim_out_get.argtypes = [c_void_p, c_void_p, c_void_p, c_char_p, c_void_p] + self.shared_lib.sim_out_get(self.sim_config, self.sim_dims, self.sim_out, field, scalar_data) + + out = scalar.value else: raise Exception(f'AcadosSimSolver.get(): Unknown field {field_},' \ - f' available fields are {", ".join(self.gettable.keys())}') + f' available fields are {", ".join(self.gettable_vectors+self.gettable_matrices)}, {", ".join(self.gettable_scalars)}') return out - def set(self, field_, value_): + + def set(self, field_: str, value_): """ Set numerical data inside the solver. - :param field: string in ['p', 'S_adj', 'T', 'x', 'u', 'xdot', 'z'] + :param field: string in ['x', 'u', 'p', 'xdot', 'z', 'seed_adj', 'T'] :param value: the value with appropriate size. """ + settable = ['x', 'u', 'p', 'xdot', 'z', 'seed_adj', 'T'] # S_forw + + # TODO: check and throw error here. then remove checks in Cython for speed # cast value_ to avoid conversion issues if isinstance(value_, (float, int)): value_ = np.array([value_]) @@ -395,12 +472,11 @@ class AcadosSimSolver: value_data = cast(value_.ctypes.data, POINTER(c_double)) value_data_p = cast((value_data), c_void_p) - field = field_ - field = field.encode('utf-8') + field = field_.encode('utf-8') # treat parameters separately if field_ == 'p': - model_name = self.sim_struct.model.name + model_name = self.acados_sim.model.name getattr(self.shared_lib, f"{model_name}_acados_sim_update_params").argtypes = [c_void_p, POINTER(c_double), c_int] value_data = cast(value_.ctypes.data, POINTER(c_double)) getattr(self.shared_lib, f"{model_name}_acados_sim_update_params")(self.capsule, value_data, value_.shape[0]) @@ -420,19 +496,46 @@ class AcadosSimSolver: value_shape = (value_shape[0], 0) if value_shape != tuple(dims): - raise Exception('AcadosSimSolver.set(): mismatching dimension' \ - ' for field "{}" with dimension {} (you have {})'.format(field_, tuple(dims), value_shape)) + raise Exception(f'AcadosSimSolver.set(): mismatching dimension' \ + f' for field "{field_}" with dimension {tuple(dims)} (you have {value_shape}).') # set if field_ in ['xdot', 'z']: self.shared_lib.sim_solver_set.argtypes = [c_void_p, c_char_p, c_void_p] self.shared_lib.sim_solver_set(self.sim_solver, field, value_data_p) - elif field_ in self.settable: + elif field_ in settable: self.shared_lib.sim_in_set.argtypes = [c_void_p, c_void_p, c_void_p, c_char_p, c_void_p] self.shared_lib.sim_in_set(self.sim_config, self.sim_dims, self.sim_in, field, value_data_p) else: raise Exception(f'AcadosSimSolver.set(): Unknown field {field_},' \ - f' available fields are {", ".join(self.settable)}') + f' available fields are {", ".join(settable)}') + + return + + + def options_set(self, field_: str, value_: bool): + """ + Set solver options + + :param field: string in ['sens_forw', 'sens_adj', 'sens_hess'] + :param value: Boolean + """ + fields = ['sens_forw', 'sens_adj', 'sens_hess'] + if field_ not in fields: + raise Exception(f"field {field_} not supported. Supported values are {', '.join(fields)}.\n") + + field = field_.encode('utf-8') + value_ctypes = c_bool(value_) + + if not isinstance(value_, bool): + raise TypeError("options_set: expected boolean for value") + + # only allow setting + if getattr(self.acados_sim.solver_options, field_) or value_ == False: + self.shared_lib.sim_opts_set.argtypes = [c_void_p, c_void_p, c_char_p, POINTER(c_bool)] + self.shared_lib.sim_opts_set(self.sim_config, self.sim_opts, field, value_ctypes) + else: + raise RuntimeError(f"Cannot set option {field_} to True, because it was False in original solver options.\n") return @@ -451,4 +554,6 @@ class AcadosSimSolver: try: self.dlclose(self.shared_lib._handle) except: + print(f"WARNING: acados Python interface could not close shared_lib handle of AcadosSimSolver {self.model_name}.\n", + "Attempting to create a new one with the same name will likely result in the old one being used!") pass diff --git a/third_party/acados/acados_template/acados_sim_solver_common.pxd b/third_party/acados/acados_template/acados_sim_solver_common.pxd new file mode 100644 index 000000000..cc6a58efd --- /dev/null +++ b/third_party/acados/acados_template/acados_sim_solver_common.pxd @@ -0,0 +1,64 @@ +# -*- coding: future_fstrings -*- +# +# Copyright (c) The acados authors. +# +# This file is part of acados. +# +# 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 HOLDER 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.; +# + + +cdef extern from "acados/sim/sim_common.h": + ctypedef struct sim_config: + pass + + ctypedef struct sim_opts: + pass + + ctypedef struct sim_in: + pass + + ctypedef struct sim_out: + pass + + +cdef extern from "acados_c/sim_interface.h": + + ctypedef struct sim_plan: + pass + + ctypedef struct sim_solver: + pass + + # out + void sim_out_get(sim_config *config, void *dims, sim_out *out, const char *field, void *value) + int sim_dims_get_from_attr(sim_config *config, void *dims, const char *field, void *dims_data) + + # opts + void sim_opts_set(sim_config *config, void *opts_, const char *field, void *value) + + # get/set + void sim_in_set(sim_config *config, void *dims, sim_in *sim_in, const char *field, void *value) + void sim_solver_set(sim_solver *solver, const char *field, void *value) \ No newline at end of file diff --git a/third_party/acados/acados_template/acados_sim_solver_pyx.pyx b/third_party/acados/acados_template/acados_sim_solver_pyx.pyx new file mode 100644 index 000000000..be400addc --- /dev/null +++ b/third_party/acados/acados_template/acados_sim_solver_pyx.pyx @@ -0,0 +1,256 @@ +# -*- coding: future_fstrings -*- +# +# Copyright (c) The acados authors. +# +# This file is part of acados. +# +# 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 HOLDER 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.; +# +# cython: language_level=3 +# cython: profile=False +# distutils: language=c + +cimport cython +from libc cimport string +# from libc cimport bool as bool_t + +cimport acados_sim_solver_common +cimport acados_sim_solver + +cimport numpy as cnp + +import os +from datetime import datetime +import numpy as np + + +cdef class AcadosSimSolverCython: + """ + Class to interact with the acados sim solver C object. + """ + + cdef acados_sim_solver.sim_solver_capsule *capsule + cdef void *sim_dims + cdef acados_sim_solver_common.sim_opts *sim_opts + cdef acados_sim_solver_common.sim_config *sim_config + cdef acados_sim_solver_common.sim_out *sim_out + cdef acados_sim_solver_common.sim_in *sim_in + cdef acados_sim_solver_common.sim_solver *sim_solver + + cdef bint solver_created + + cdef str model_name + + cdef str sim_solver_type + + cdef list gettable_vectors + cdef list gettable_matrices + cdef list gettable_scalars + + def __cinit__(self, model_name): + + self.solver_created = False + + self.model_name = model_name + + # create capsule + self.capsule = acados_sim_solver.acados_sim_solver_create_capsule() + + # create solver + assert acados_sim_solver.acados_sim_create(self.capsule) == 0 + self.solver_created = True + + # get pointers solver + self.__get_pointers_solver() + + self.gettable_vectors = ['x', 'u', 'z', 'S_adj'] + self.gettable_matrices = ['S_forw', 'Sx', 'Su', 'S_hess', 'S_algebraic'] + self.gettable_scalars = ['CPUtime', 'time_tot', 'ADtime', 'time_ad', 'LAtime', 'time_la'] + + def __get_pointers_solver(self): + """ + Private function to get the pointers for solver + """ + # get pointers solver + self.sim_opts = acados_sim_solver.acados_get_sim_opts(self.capsule) + self.sim_dims = acados_sim_solver.acados_get_sim_dims(self.capsule) + self.sim_config = acados_sim_solver.acados_get_sim_config(self.capsule) + self.sim_out = acados_sim_solver.acados_get_sim_out(self.capsule) + self.sim_in = acados_sim_solver.acados_get_sim_in(self.capsule) + self.sim_solver = acados_sim_solver.acados_get_sim_solver(self.capsule) + + + def simulate(self, x=None, u=None, z=None, p=None): + """ + Simulate the system forward for the given x, u, z, p and return x_next. + Wrapper around `solve()` taking care of setting/getting inputs/outputs. + """ + if x is not None: + self.set('x', x) + if u is not None: + self.set('u', u) + if z is not None: + self.set('z', z) + if p is not None: + self.set('p', p) + + status = self.solve() + + if status == 2: + print("Warning: acados_sim_solver reached maximum iterations.") + elif status != 0: + raise Exception(f'acados_sim_solver for model {self.model_name} returned status {status}.') + + x_next = self.get('x') + return x_next + + + def solve(self): + """ + Solve the sim with current input. + """ + return acados_sim_solver.acados_sim_solve(self.capsule) + + + def get(self, field_): + """ + Get the last solution of the solver. + + :param str field: string in ['x', 'u', 'z', 'S_forw', 'Sx', 'Su', 'S_adj', 'S_hess', 'S_algebraic', 'CPUtime', 'time_tot', 'ADtime', 'time_ad', 'LAtime', 'time_la'] + """ + field = field_.encode('utf-8') + + if field_ in self.gettable_vectors: + return self.__get_vector(field) + elif field_ in self.gettable_matrices: + return self.__get_matrix(field) + elif field_ in self.gettable_scalars: + return self.__get_scalar(field) + else: + raise Exception(f'AcadosSimSolver.get(): Unknown field {field_},' \ + f' available fields are {", ".join(self.gettable.keys())}') + + + def __get_scalar(self, field): + cdef double scalar + acados_sim_solver_common.sim_out_get(self.sim_config, self.sim_dims, self.sim_out, field, &scalar) + return scalar + + + def __get_vector(self, field): + cdef int[2] dims + acados_sim_solver_common.sim_dims_get_from_attr(self.sim_config, self.sim_dims, field, &dims[0]) + # cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.ascontiguousarray(np.zeros((dims[0],), dtype=np.float64)) + cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((dims[0]),) + acados_sim_solver_common.sim_out_get(self.sim_config, self.sim_dims, self.sim_out, field, out.data) + return out + + + def __get_matrix(self, field): + cdef int[2] dims + acados_sim_solver_common.sim_dims_get_from_attr(self.sim_config, self.sim_dims, field, &dims[0]) + cdef cnp.ndarray[cnp.float64_t, ndim=2] out = np.zeros((dims[0], dims[1]), order='F', dtype=np.float64) + acados_sim_solver_common.sim_out_get(self.sim_config, self.sim_dims, self.sim_out, field, out.data) + return out + + + def set(self, field_: str, value_): + """ + Set numerical data inside the solver. + + :param field: string in ['p', 'seed_adj', 'T', 'x', 'u', 'xdot', 'z'] + :param value: the value with appropriate size. + """ + settable = ['seed_adj', 'T', 'x', 'u', 'xdot', 'z', 'p'] # S_forw + + # cast value_ to avoid conversion issues + if isinstance(value_, (float, int)): + value_ = np.array([value_]) + # if len(value_.shape) > 1: + # raise RuntimeError('AcadosSimSolverCython.set(): value_ should be 1 dimensional') + + cdef cnp.ndarray[cnp.float64_t, ndim=1] value = np.ascontiguousarray(value_, dtype=np.float64).flatten() + + field = field_.encode('utf-8') + cdef int[2] dims + + # treat parameters separately + if field_ == 'p': + assert acados_sim_solver.acados_sim_update_params(self.capsule, value.data, value.shape[0]) == 0 + return + else: + acados_sim_solver_common.sim_dims_get_from_attr(self.sim_config, self.sim_dims, field, &dims[0]) + + value_ = np.ravel(value_, order='F') + + value_shape = value_.shape + if len(value_shape) == 1: + value_shape = (value_shape[0], 0) + + if value_shape != tuple(dims): + raise Exception(f'AcadosSimSolverCython.set(): mismatching dimension' \ + f' for field "{field_}" with dimension {tuple(dims)} (you have {value_shape}).') + + # set + if field_ in ['xdot', 'z']: + acados_sim_solver_common.sim_solver_set(self.sim_solver, field, value.data) + elif field_ in settable: + acados_sim_solver_common.sim_in_set(self.sim_config, self.sim_dims, self.sim_in, field, value.data) + else: + raise Exception(f'AcadosSimSolverCython.set(): Unknown field {field_},' \ + f' available fields are {", ".join(settable)}') + + + def options_set(self, field_: str, value_: bool): + """ + Set solver options + + :param field: string in ['sens_forw', 'sens_adj', 'sens_hess'] + :param value: Boolean + """ + fields = ['sens_forw', 'sens_adj', 'sens_hess'] + if field_ not in fields: + raise Exception(f"field {field_} not supported. Supported values are {', '.join(fields)}.\n") + + field = field_.encode('utf-8') + + if not isinstance(value_, bool): + raise TypeError("options_set: expected boolean for value") + + cdef bint bool_value = value_ + acados_sim_solver_common.sim_opts_set(self.sim_config, self.sim_opts, field, &bool_value) + # TODO: only allow setting + # if getattr(self.acados_sim.solver_options, field_) or value_ == False: + # acados_sim_solver_common.sim_opts_set(self.sim_config, self.sim_opts, field, &bool_value) + # else: + # raise RuntimeError(f"Cannot set option {field_} to True, because it was False in original solver options.\n") + + return + + + def __del__(self): + if self.solver_created: + acados_sim_solver.acados_sim_free(self.capsule) + acados_sim_solver.acados_sim_solver_free_capsule(self.capsule) diff --git a/third_party/acados/acados_template/acados_solver_common.pxd b/third_party/acados/acados_template/acados_solver_common.pxd index fedd7190d..c6d59d40a 100644 --- a/third_party/acados/acados_template/acados_solver_common.pxd +++ b/third_party/acados/acados_template/acados_solver_common.pxd @@ -1,9 +1,6 @@ # -*- coding: future_fstrings -*- # -# Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, -# Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, -# Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, -# Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl +# Copyright (c) The acados authors. # # This file is part of acados. # @@ -87,7 +84,7 @@ cdef extern from "acados_c/ocp_nlp_interface.h": 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, 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_qp_dims_get_from_attr(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_out *out, int stage, const char *field, int *dims_out) # opts diff --git a/third_party/acados/acados_template/builders.py b/third_party/acados/acados_template/builders.py index f595033ce..6f21bfe8c 100644 --- a/third_party/acados/acados_template/builders.py +++ b/third_party/acados/acados_template/builders.py @@ -34,7 +34,7 @@ import os import sys -from subprocess import call +from subprocess import DEVNULL, call, STDOUT class CMakeBuilder: @@ -78,7 +78,7 @@ class CMakeBuilder: def get_cmd3_install(self): return f'cmake --install "{self._build_dir}"' - def exec(self, code_export_directory): + def exec(self, code_export_directory, verbose=True): """ Execute the compilation using `CMake` with the given settings. :param code_export_directory: must be the absolute path to the directory where the code was exported to @@ -96,17 +96,32 @@ class CMakeBuilder: os.chdir(self._build_dir) cmd_str = self.get_cmd1_cmake() print(f'call("{cmd_str})"') - retcode = call(cmd_str, shell=True) + retcode = call( + cmd_str, + shell=True, + stdout=None if verbose else DEVNULL, + stderr=None if verbose else STDOUT + ) if retcode != 0: raise RuntimeError(f'CMake command "{cmd_str}" was terminated by signal {retcode}') cmd_str = self.get_cmd2_build() print(f'call("{cmd_str}")') - retcode = call(cmd_str, shell=True) + retcode = call( + cmd_str, + shell=True, + stdout=None if verbose else DEVNULL, + stderr=None if verbose else STDOUT + ) if retcode != 0: raise RuntimeError(f'Build command "{cmd_str}" was terminated by signal {retcode}') cmd_str = self.get_cmd3_install() print(f'call("{cmd_str}")') - retcode = call(cmd_str, shell=True) + retcode = call( + cmd_str, + shell=True, + stdout=None if verbose else DEVNULL, + stderr=None if verbose else STDOUT + ) if retcode != 0: raise RuntimeError(f'Install command "{cmd_str}" was terminated by signal {retcode}') except OSError as e: diff --git a/third_party/acados/acados_template/c_templates_tera/CMakeLists.in.txt b/third_party/acados/acados_template/c_templates_tera/CMakeLists.in.txt index 3d6483b5d..99bc26f75 100644 --- a/third_party/acados/acados_template/c_templates_tera/CMakeLists.in.txt +++ b/third_party/acados/acados_template/c_templates_tera/CMakeLists.in.txt @@ -1,8 +1,5 @@ # -# Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, -# Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, -# Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, -# Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl +# Copyright (c) The acados authors. # # This file is part of acados. # @@ -121,12 +118,14 @@ {%- set openmp_flag = " " %} {%- if qp_solver == "FULL_CONDENSING_QPOASES" %} {%- set link_libs = "-lqpOASES_e" %} + {%- elif qp_solver == "FULL_CONDENSING_DAQP" %} + {%- set link_libs = "-ldaqp" %} {%- else %} {%- set link_libs = "" %} {%- endif %} {%- endif %} -cmake_minimum_required(VERSION 3.10) +cmake_minimum_required(VERSION 3.13) project({{ model.name }}) @@ -139,6 +138,14 @@ option(BUILD_SIM_EXAMPLE "Should the simulation example main_sim_{{ model.name } option(BUILD_ACADOS_SIM_SOLVER_LIB "Should the simulation solver library acados_sim_solver_{{ model.name }} be build?" OFF) {%- endif %} + +if(CMAKE_CXX_COMPILER_ID MATCHES "GNU" AND CMAKE_SYSTEM_NAME MATCHES "Windows") + # MinGW, change to .lib such that mex recognizes it + set(CMAKE_SHARED_LIBRARY_SUFFIX ".lib") + set(CMAKE_SHARED_LIBRARY_PREFIX "") +endif() + + # object target names set(MODEL_OBJ model_{{ model.name }}) set(OCP_OBJ ocp_{{ model.name }}) @@ -146,9 +153,11 @@ set(SIM_OBJ sim_{{ model.name }}) # model set(MODEL_SRC + {%- if model.dyn_ext_fun_type == "casadi" %} {%- if solver_options.integrator_type == "ERK" %} {{ model.name }}_model/{{ model.name }}_expl_ode_fun.c {{ model.name }}_model/{{ model.name }}_expl_vde_forw.c + {{ model.name }}_model/{{ model.name }}_expl_vde_adj.c {%- if hessian_approx == "EXACT" %} {{ model.name }}_model/{{ model.name }}_expl_ode_hess.c {%- endif %} @@ -176,16 +185,15 @@ set(MODEL_SRC {%- endif %} {{ model.name }}_model/{{ model.name }}_gnsf_get_matrices_fun.c {%- elif solver_options.integrator_type == "DISCRETE" %} - {%- if model.dyn_ext_fun_type == "casadi" %} {{ model.name }}_model/{{ model.name }}_dyn_disc_phi_fun.c {{ model.name }}_model/{{ model.name }}_dyn_disc_phi_fun_jac.c {%- if hessian_approx == "EXACT" %} {{ model.name }}_model/{{ model.name }}_dyn_disc_phi_fun_jac_hess.c {%- endif %} - {%- else %} - {{ model.name }}_model/{{ model.dyn_source_discrete }} - {%- endif %} {%- endif -%} + {%- else %} + {{ model.name }}_model/{{ model.dyn_generic_source }} + {%- endif %} ) add_library(${MODEL_OBJ} OBJECT ${MODEL_SRC} ) @@ -219,6 +227,9 @@ if(${BUILD_ACADOS_SOLVER_LIB} OR ${BUILD_ACADOS_OCP_SOLVER_LIB} OR ${BUILD_EXAMP {{ model.name }}_cost/{{ model.name }}_cost_y_0_fun.c {{ model.name }}_cost/{{ model.name }}_cost_y_0_fun_jac_ut_xt.c {{ model.name }}_cost/{{ model.name }}_cost_y_0_hess.c +{%- elif cost_type_0 == "CONVEX_OVER_NONLINEAR" %} + {{ model.name }}_cost/{{ model.name }}_conl_cost_0_fun.c + {{ model.name }}_cost/{{ model.name }}_conl_cost_0_fun_jac_hess.c {%- elif cost_type_0 == "EXTERNAL" %} {%- if cost.cost_ext_fun_type_0 == "casadi" %} {{ model.name }}_cost/{{ model.name }}_cost_ext_cost_0_fun.c @@ -232,6 +243,9 @@ if(${BUILD_ACADOS_SOLVER_LIB} OR ${BUILD_ACADOS_OCP_SOLVER_LIB} OR ${BUILD_EXAMP {{ model.name }}_cost/{{ model.name }}_cost_y_fun.c {{ model.name }}_cost/{{ model.name }}_cost_y_fun_jac_ut_xt.c {{ model.name }}_cost/{{ model.name }}_cost_y_hess.c +{%- elif cost_type == "CONVEX_OVER_NONLINEAR" %} + {{ model.name }}_cost/{{ model.name }}_conl_cost_fun.c + {{ model.name }}_cost/{{ model.name }}_conl_cost_fun_jac_hess.c {%- elif cost_type == "EXTERNAL" %} {%- if cost.cost_ext_fun_type == "casadi" %} {{ model.name }}_cost/{{ model.name }}_cost_ext_cost_fun.c @@ -245,6 +259,9 @@ if(${BUILD_ACADOS_SOLVER_LIB} OR ${BUILD_ACADOS_OCP_SOLVER_LIB} OR ${BUILD_EXAMP {{ model.name }}_cost/{{ model.name }}_cost_y_e_fun.c {{ model.name }}_cost/{{ model.name }}_cost_y_e_fun_jac_ut_xt.c {{ model.name }}_cost/{{ model.name }}_cost_y_e_hess.c +{%- elif cost_type_e == "CONVEX_OVER_NONLINEAR" %} + {{ model.name }}_cost/{{ model.name }}_conl_cost_e_fun.c + {{ model.name }}_cost/{{ model.name }}_conl_cost_e_fun_jac_hess.c {%- elif cost_type_e == "EXTERNAL" %} {%- if cost.cost_ext_fun_type_e == "casadi" %} {{ model.name }}_cost/{{ model.name }}_cost_ext_cost_e_fun.c @@ -275,7 +292,7 @@ set(EX_SRC main_{{ model.name }}.c) set(EX_EXE main_{{ model.name }}) {%- if model_external_shared_lib_dir and model_external_shared_lib_name %} -set(EXTERNAL_DIR {{ model_external_shared_lib_dir }}) +set(EXTERNAL_DIR {{ model_external_shared_lib_dir | replace(from="\", to="/") }}) set(EXTERNAL_LIB {{ model_external_shared_lib_name }}) {%- else %} set(EXTERNAL_DIR) @@ -283,23 +300,26 @@ set(EXTERNAL_LIB) {%- endif %} # set some search paths for preprocessor and linker -set(ACADOS_INCLUDE_PATH {{ acados_include_path }} CACHE PATH "Define the path which contains the include directory for acados.") -set(ACADOS_LIB_PATH {{ acados_lib_path }} CACHE PATH "Define the path which contains the lib directory for acados.") +set(ACADOS_INCLUDE_PATH {{ acados_include_path | replace(from="\", to="/") }} CACHE PATH "Define the path which contains the include directory for acados.") +set(ACADOS_LIB_PATH {{ acados_lib_path | replace(from="\", to="/") }} CACHE PATH "Define the path which contains the lib directory for acados.") # c-compiler flags for debugging set(CMAKE_C_FLAGS_DEBUG "-O0 -ggdb") -set(CMAKE_C_FLAGS " +set(CMAKE_C_FLAGS "-fPIC -std=c99 {{ openmp_flag }} {%- if qp_solver == "FULL_CONDENSING_QPOASES" -%} - -DACADOS_WITH_QPOASES + -DACADOS_WITH_QPOASES +{%- endif -%} +{%- if qp_solver == "FULL_CONDENSING_DAQP" -%} + -DACADOS_WITH_DAQP {%- endif -%} {%- if qp_solver == "PARTIAL_CONDENSING_OSQP" -%} - -DACADOS_WITH_OSQP + -DACADOS_WITH_OSQP {%- endif -%} {%- if qp_solver == "PARTIAL_CONDENSING_QPDUNES" -%} - -DACADOS_WITH_QPDUNES + -DACADOS_WITH_QPDUNES {%- endif -%} - -fPIC -std=c99 {{ openmp_flag }}") +") #-fno-diagnostics-show-line-numbers -g include_directories( @@ -310,6 +330,9 @@ include_directories( {%- if qp_solver == "FULL_CONDENSING_QPOASES" %} ${ACADOS_INCLUDE_PATH}/qpOASES_e/ {%- endif %} +{%- if qp_solver == "FULL_CONDENSING_DAQP" %} + ${ACADOS_INCLUDE_PATH}/daqp/include +{%- endif %} ) # linker flags diff --git a/third_party/acados/acados_template/c_templates_tera/CPPLINT.cfg b/third_party/acados/acados_template/c_templates_tera/CPPLINT.cfg deleted file mode 100644 index bbd1caf05..000000000 --- a/third_party/acados/acados_template/c_templates_tera/CPPLINT.cfg +++ /dev/null @@ -1 +0,0 @@ -exclude_files=[main, acados_solver, acados_solver_sfun, Makefile, model].*\.? diff --git a/third_party/acados/acados_template/c_templates_tera/Makefile.in b/third_party/acados/acados_template/c_templates_tera/Makefile.in index d45be0a9c..fbefc08e3 100644 --- a/third_party/acados/acados_template/c_templates_tera/Makefile.in +++ b/third_party/acados/acados_template/c_templates_tera/Makefile.in @@ -1,8 +1,5 @@ # -# Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, -# Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, -# Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, -# Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl +# Copyright (c) The acados authors. # # This file is part of acados. # @@ -120,6 +117,8 @@ {%- set openmp_flag = " " %} {%- if qp_solver == "FULL_CONDENSING_QPOASES" %} {%- set link_libs = "-lqpOASES_e" %} + {%- elif qp_solver == "FULL_CONDENSING_DAQP" %} + {%- set link_libs = "-ldaqp" %} {%- else %} {%- set link_libs = "" %} {%- endif %} @@ -129,9 +128,11 @@ # model MODEL_SRC= -{%- if solver_options.integrator_type == "ERK" %} + {%- if model.dyn_ext_fun_type == "casadi" %} +{%- if solver_options.integrator_type == "ERK" %} MODEL_SRC+= {{ model.name }}_model/{{ model.name }}_expl_ode_fun.c MODEL_SRC+= {{ model.name }}_model/{{ model.name }}_expl_vde_forw.c +MODEL_SRC+= {{ model.name }}_model/{{ model.name }}_expl_vde_adj.c {%- if hessian_approx == "EXACT" %} MODEL_SRC+= {{ model.name }}_model/{{ model.name }}_expl_ode_hess.c {%- endif %} @@ -139,9 +140,9 @@ MODEL_SRC+= {{ model.name }}_model/{{ model.name }}_expl_ode_hess.c MODEL_SRC+= {{ model.name }}_model/{{ model.name }}_impl_dae_fun.c MODEL_SRC+= {{ model.name }}_model/{{ model.name }}_impl_dae_fun_jac_x_xdot_z.c MODEL_SRC+= {{ model.name }}_model/{{ model.name }}_impl_dae_jac_x_xdot_u_z.c - {%- if hessian_approx == "EXACT" %} + {%- if hessian_approx == "EXACT" %} MODEL_SRC+= {{ model.name }}_model/{{ model.name }}_impl_dae_hess.c - {%- endif %} + {%- endif %} {%- elif solver_options.integrator_type == "LIFTED_IRK" %} MODEL_SRC+= {{ model.name }}_model/{{ model.name }}_impl_dae_fun.c MODEL_SRC+= {{ model.name }}_model/{{ model.name }}_impl_dae_fun_jac_x_xdot_u.c @@ -159,16 +160,15 @@ MODEL_SRC+= {{ model.name }}_model/{{ model.name }}_gnsf_f_lo_fun_jac_x1k1uz.c {%- endif %} MODEL_SRC+= {{ model.name }}_model/{{ model.name }}_gnsf_get_matrices_fun.c {%- elif solver_options.integrator_type == "DISCRETE" %} - {%- if model.dyn_ext_fun_type == "casadi" %} MODEL_SRC+= {{ model.name }}_model/{{ model.name }}_dyn_disc_phi_fun.c MODEL_SRC+= {{ model.name }}_model/{{ model.name }}_dyn_disc_phi_fun_jac.c {%- if hessian_approx == "EXACT" %} MODEL_SRC+= {{ model.name }}_model/{{ model.name }}_dyn_disc_phi_fun_jac_hess.c {%- endif %} - {%- else %} -MODEL_SRC+= {{ model.name }}_model/{{ model.dyn_source_discrete }} - {%- endif %} {%- endif %} + {%- else %} +MODEL_SRC+= {{ model.name }}_model/{{ model.dyn_generic_source }} + {%- endif %} MODEL_OBJ := $(MODEL_SRC:.c=.o) # optimal control problem - mostly CasADi exports @@ -200,6 +200,9 @@ OCP_SRC+= {{ model.name }}_constraints/{{ model.name }}_constr_h_e_fun_jac_uxt_z OCP_SRC+= {{ model.name }}_cost/{{ model.name }}_cost_y_0_fun.c OCP_SRC+= {{ model.name }}_cost/{{ model.name }}_cost_y_0_fun_jac_ut_xt.c OCP_SRC+= {{ model.name }}_cost/{{ model.name }}_cost_y_0_hess.c +{%- elif cost_type_0 == "CONVEX_OVER_NONLINEAR" %} +OCP_SRC+= {{ model.name }}_cost/{{ model.name }}_conl_cost_0_fun.c +OCP_SRC+= {{ model.name }}_cost/{{ model.name }}_conl_cost_0_fun_jac_hess.c {%- elif cost_type_0 == "EXTERNAL" %} {%- if cost.cost_ext_fun_type_0 == "casadi" %} OCP_SRC+= {{ model.name }}_cost/{{ model.name }}_cost_ext_cost_0_fun.c @@ -213,6 +216,9 @@ OCP_SRC+= {{ model.name }}_cost/{{ cost.cost_source_ext_cost_0 }} OCP_SRC+= {{ model.name }}_cost/{{ model.name }}_cost_y_fun.c OCP_SRC+= {{ model.name }}_cost/{{ model.name }}_cost_y_fun_jac_ut_xt.c OCP_SRC+= {{ model.name }}_cost/{{ model.name }}_cost_y_hess.c +{%- elif cost_type == "CONVEX_OVER_NONLINEAR" %} +OCP_SRC+= {{ model.name }}_cost/{{ model.name }}_conl_cost_fun.c +OCP_SRC+= {{ model.name }}_cost/{{ model.name }}_conl_cost_fun_jac_hess.c {%- elif cost_type == "EXTERNAL" %} {%- if cost.cost_ext_fun_type == "casadi" %} OCP_SRC+= {{ model.name }}_cost/{{ model.name }}_cost_ext_cost_fun.c @@ -226,6 +232,9 @@ OCP_SRC+= {{ model.name }}_cost/{{ cost.cost_source_ext_cost }} OCP_SRC+= {{ model.name }}_cost/{{ model.name }}_cost_y_e_fun.c OCP_SRC+= {{ model.name }}_cost/{{ model.name }}_cost_y_e_fun_jac_ut_xt.c OCP_SRC+= {{ model.name }}_cost/{{ model.name }}_cost_y_e_hess.c +{%- elif cost_type_e == "CONVEX_OVER_NONLINEAR" %} +OCP_SRC+= {{ model.name }}_cost/{{ model.name }}_conl_cost_e_fun.c +OCP_SRC+= {{ model.name }}_cost/{{ model.name }}_conl_cost_e_fun_jac_hess.c {%- elif cost_type_e == "EXTERNAL" %} {%- if cost.cost_ext_fun_type_e == "casadi" %} OCP_SRC+= {{ model.name }}_cost/{{ model.name }}_cost_ext_cost_e_fun.c @@ -235,6 +244,12 @@ OCP_SRC+= {{ model.name }}_cost/{{ model.name }}_cost_ext_cost_e_fun_jac_hess.c OCP_SRC+= {{ model.name }}_cost/{{ cost.cost_source_ext_cost_e }} {%- endif %} {%- endif %} +{%- if solver_options.custom_update_filename %} + {%- if solver_options.custom_update_filename != "" %} +OCP_SRC+= {{ solver_options.custom_update_filename }} + {%- endif %} +{%- endif %} + OCP_SRC+= acados_solver_{{ model.name }}.c OCP_OBJ := $(OCP_SRC:.c=.o) @@ -275,6 +290,9 @@ LIB_PATH = {{ acados_lib_path }} {%- if qp_solver == "FULL_CONDENSING_QPOASES" %} CPPFLAGS += -DACADOS_WITH_QPOASES {%- endif %} +{%- if qp_solver == "FULL_CONDENSING_DAQP" %} +CPPFLAGS += -DACADOS_WITH_DAQP +{%- endif %} {%- if qp_solver == "PARTIAL_CONDENSING_OSQP" %} CPPFLAGS += -DACADOS_WITH_OSQP {%- endif %} @@ -288,10 +306,13 @@ CPPFLAGS+= -I$(INCLUDE_PATH)/hpipm/include {%- if qp_solver == "FULL_CONDENSING_QPOASES" %} CPPFLAGS+= -I $(INCLUDE_PATH)/qpOASES_e/ {%- endif %} + {%- if qp_solver == "FULL_CONDENSING_DAQP" %} +CPPFLAGS+= -I $(INCLUDE_PATH)/daqp/include + {%- endif %} {# c-compiler flags #} # define the c-compiler flags for make's implicit rules -CFLAGS = -fPIC -std=c99 {{ openmp_flag }} #-fno-diagnostics-show-line-numbers -g +CFLAGS = -fPIC -std=c99 {{ openmp_flag }} {{ solver_options.ext_fun_compile_flags }}#-fno-diagnostics-show-line-numbers -g # # Debugging # CFLAGS += -g3 @@ -306,9 +327,9 @@ LDLIBS+= -lm LDLIBS+= {{ link_libs }} # libraries -LIBACADOS_SOLVER=libacados_solver_{{ model.name }}.so -LIBACADOS_OCP_SOLVER=libacados_ocp_solver_{{ model.name }}.so -LIBACADOS_SIM_SOLVER=lib$(SIM_SRC:.c=.so) +LIBACADOS_SOLVER=libacados_solver_{{ model.name }}{{ shared_lib_ext }} +LIBACADOS_OCP_SOLVER=libacados_ocp_solver_{{ model.name }}{{ shared_lib_ext }} +LIBACADOS_SIM_SOLVER=lib$(SIM_SRC:.c={{ shared_lib_ext }}) # virtual targets .PHONY : all clean @@ -354,38 +375,73 @@ ocp_cython_o: ocp_cython_c $(CC) $(ACADOS_FLAGS) -c -O2 \ -fPIC \ -o acados_ocp_solver_pyx.o \ - -I /usr/include/python3.8 \ -I $(INCLUDE_PATH)/blasfeo/include/ \ -I $(INCLUDE_PATH)/hpipm/include/ \ -I $(INCLUDE_PATH) \ - -I {{ cython_include_dirs }} \ + {%- for path in cython_include_dirs %} + -I {{ path }} \ + {%- endfor %} acados_ocp_solver_pyx.c \ ocp_cython: ocp_cython_o $(CC) $(ACADOS_FLAGS) -shared \ - -o acados_ocp_solver_pyx.so \ + -o acados_ocp_solver_pyx{{ shared_lib_ext }} \ -Wl,-rpath=$(LIB_PATH) \ acados_ocp_solver_pyx.o \ - $(abspath .)/libacados_ocp_solver_{{ model.name }}.so \ + $(abspath .)/libacados_ocp_solver_{{ model.name }}{{ shared_lib_ext }} \ + $(LDFLAGS) $(LDLIBS) + +# Sim Cython targets +sim_cython_c: sim_shared_lib + cython \ + -o acados_sim_solver_pyx.c \ + -I $(INCLUDE_PATH)/../interfaces/acados_template/acados_template \ + $(INCLUDE_PATH)/../interfaces/acados_template/acados_template/acados_sim_solver_pyx.pyx \ + -I {{ code_export_directory }} \ + +sim_cython_o: sim_cython_c + $(CC) $(ACADOS_FLAGS) -c -O2 \ + -fPIC \ + -o acados_sim_solver_pyx.o \ + -I $(INCLUDE_PATH)/blasfeo/include/ \ + -I $(INCLUDE_PATH)/hpipm/include/ \ + -I $(INCLUDE_PATH) \ + {%- for path in cython_include_dirs %} + -I {{ path }} \ + {%- endfor %} + acados_sim_solver_pyx.c \ + +sim_cython: sim_cython_o + $(CC) $(ACADOS_FLAGS) -shared \ + -o acados_sim_solver_pyx{{ shared_lib_ext }} \ + -Wl,-rpath=$(LIB_PATH) \ + acados_sim_solver_pyx.o \ + $(abspath .)/libacados_sim_solver_{{ model.name }}{{ shared_lib_ext }} \ $(LDFLAGS) $(LDLIBS) {%- if os and os == "pc" %} clean: del \Q *.o 2>nul - del \Q *.so 2>nul + del \Q *{{ shared_lib_ext }} 2>nul del \Q main_{{ model.name }} 2>nul clean_ocp_shared_lib: - del \Q libacados_ocp_solver_{{ model.name }}.so 2>nul + del \Q libacados_ocp_solver_{{ model.name }}{{ shared_lib_ext }} 2>nul del \Q acados_solver_{{ model.name }}.o 2>nul clean_ocp_cython: - del \Q libacados_ocp_solver_{{ model.name }}.so 2>nul + del \Q libacados_ocp_solver_{{ model.name }}{{ shared_lib_ext }} 2>nul del \Q acados_solver_{{ model.name }}.o 2>nul - del \Q acados_ocp_solver_pyx.so 2>nul + del \Q acados_ocp_solver_pyx{{ shared_lib_ext }} 2>nul del \Q acados_ocp_solver_pyx.o 2>nul +clean_sim_cython: + del \Q libacados_sim_solver_{{ model.name }}{{ shared_lib_ext }} 2>nul + del \Q acados_sim_solver_{{ model.name }}.o 2>nul + del \Q acados_sim_solver_pyx{{ shared_lib_ext }} 2>nul + del \Q acados_sim_solver_pyx.o 2>nul + {%- else %} clean: @@ -398,9 +454,15 @@ clean_ocp_shared_lib: $(RM) $(OCP_OBJ) clean_ocp_cython: - $(RM) libacados_ocp_solver_{{ model.name }}.so + $(RM) libacados_ocp_solver_{{ model.name }}{{ shared_lib_ext }} $(RM) acados_solver_{{ model.name }}.o - $(RM) acados_ocp_solver_pyx.so + $(RM) acados_ocp_solver_pyx{{ shared_lib_ext }} $(RM) acados_ocp_solver_pyx.o +clean_sim_cython: + $(RM) libacados_sim_solver_{{ model.name }}{{ shared_lib_ext }} + $(RM) acados_sim_solver_{{ model.name }}.o + $(RM) acados_sim_solver_pyx{{ shared_lib_ext }} + $(RM) acados_sim_solver_pyx.o + {%- endif %} diff --git a/third_party/acados/acados_template/c_templates_tera/acados_sim_solver.in.c b/third_party/acados/acados_template/c_templates_tera/acados_sim_solver.in.c index f2e75058c..0cd098273 100644 --- a/third_party/acados/acados_template/c_templates_tera/acados_sim_solver.in.c +++ b/third_party/acados/acados_template/c_templates_tera/acados_sim_solver.in.c @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * @@ -88,18 +85,19 @@ int {{ model.name }}_acados_sim_create(sim_solver_capsule * capsule) double Tsim = {{ solver_options.Tsim }}; {% if solver_options.integrator_type == "IRK" %} - capsule->sim_impl_dae_fun = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)); - capsule->sim_impl_dae_fun_jac_x_xdot_z = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)); - capsule->sim_impl_dae_jac_x_xdot_u_z = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)); + capsule->sim_impl_dae_fun = (external_function_param_{{ model.dyn_ext_fun_type }} *) malloc(sizeof(external_function_param_{{ model.dyn_ext_fun_type }})); + capsule->sim_impl_dae_fun_jac_x_xdot_z = (external_function_param_{{ model.dyn_ext_fun_type }} *) malloc(sizeof(external_function_param_{{ model.dyn_ext_fun_type }})); + capsule->sim_impl_dae_jac_x_xdot_u_z = (external_function_param_{{ model.dyn_ext_fun_type }} *) malloc(sizeof(external_function_param_{{ model.dyn_ext_fun_type }})); + {%- if model.dyn_ext_fun_type == "casadi" %} // external functions (implicit model) - capsule->sim_impl_dae_fun->casadi_fun = &{{ model.name }}_impl_dae_fun; + capsule->sim_impl_dae_fun->casadi_fun = &{{ model.name }}_impl_dae_fun; capsule->sim_impl_dae_fun->casadi_work = &{{ model.name }}_impl_dae_fun_work; capsule->sim_impl_dae_fun->casadi_sparsity_in = &{{ model.name }}_impl_dae_fun_sparsity_in; capsule->sim_impl_dae_fun->casadi_sparsity_out = &{{ model.name }}_impl_dae_fun_sparsity_out; capsule->sim_impl_dae_fun->casadi_n_in = &{{ model.name }}_impl_dae_fun_n_in; capsule->sim_impl_dae_fun->casadi_n_out = &{{ model.name }}_impl_dae_fun_n_out; - external_function_param_casadi_create(capsule->sim_impl_dae_fun, np); + external_function_param_{{ model.dyn_ext_fun_type }}_create(capsule->sim_impl_dae_fun, np); capsule->sim_impl_dae_fun_jac_x_xdot_z->casadi_fun = &{{ model.name }}_impl_dae_fun_jac_x_xdot_z; capsule->sim_impl_dae_fun_jac_x_xdot_z->casadi_work = &{{ model.name }}_impl_dae_fun_jac_x_xdot_z_work; @@ -107,33 +105,39 @@ int {{ model.name }}_acados_sim_create(sim_solver_capsule * capsule) capsule->sim_impl_dae_fun_jac_x_xdot_z->casadi_sparsity_out = &{{ model.name }}_impl_dae_fun_jac_x_xdot_z_sparsity_out; capsule->sim_impl_dae_fun_jac_x_xdot_z->casadi_n_in = &{{ model.name }}_impl_dae_fun_jac_x_xdot_z_n_in; capsule->sim_impl_dae_fun_jac_x_xdot_z->casadi_n_out = &{{ model.name }}_impl_dae_fun_jac_x_xdot_z_n_out; - external_function_param_casadi_create(capsule->sim_impl_dae_fun_jac_x_xdot_z, np); + external_function_param_{{ model.dyn_ext_fun_type }}_create(capsule->sim_impl_dae_fun_jac_x_xdot_z, np); - // external_function_param_casadi impl_dae_jac_x_xdot_u_z; + // external_function_param_{{ model.dyn_ext_fun_type }} impl_dae_jac_x_xdot_u_z; capsule->sim_impl_dae_jac_x_xdot_u_z->casadi_fun = &{{ model.name }}_impl_dae_jac_x_xdot_u_z; capsule->sim_impl_dae_jac_x_xdot_u_z->casadi_work = &{{ model.name }}_impl_dae_jac_x_xdot_u_z_work; capsule->sim_impl_dae_jac_x_xdot_u_z->casadi_sparsity_in = &{{ model.name }}_impl_dae_jac_x_xdot_u_z_sparsity_in; capsule->sim_impl_dae_jac_x_xdot_u_z->casadi_sparsity_out = &{{ model.name }}_impl_dae_jac_x_xdot_u_z_sparsity_out; capsule->sim_impl_dae_jac_x_xdot_u_z->casadi_n_in = &{{ model.name }}_impl_dae_jac_x_xdot_u_z_n_in; capsule->sim_impl_dae_jac_x_xdot_u_z->casadi_n_out = &{{ model.name }}_impl_dae_jac_x_xdot_u_z_n_out; - external_function_param_casadi_create(capsule->sim_impl_dae_jac_x_xdot_u_z, np); + external_function_param_{{ model.dyn_ext_fun_type }}_create(capsule->sim_impl_dae_jac_x_xdot_u_z, np); + {%- else %} + capsule->sim_impl_dae_fun->fun = &{{ model.dyn_impl_dae_fun }}; + capsule->sim_impl_dae_fun_jac_x_xdot_z->fun = &{{ model.dyn_impl_dae_fun_jac }}; + capsule->sim_impl_dae_jac_x_xdot_u_z->fun = &{{ model.dyn_impl_dae_jac }}; + {%- endif %} {%- if hessian_approx == "EXACT" %} - capsule->sim_impl_dae_hess = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)); - // external_function_param_casadi impl_dae_jac_x_xdot_u_z; + capsule->sim_impl_dae_hess = (external_function_param_{{ model.dyn_ext_fun_type }} *) malloc(sizeof(external_function_param_{{ model.dyn_ext_fun_type }})); + // external_function_param_{{ model.dyn_ext_fun_type }} impl_dae_jac_x_xdot_u_z; capsule->sim_impl_dae_hess->casadi_fun = &{{ model.name }}_impl_dae_hess; capsule->sim_impl_dae_hess->casadi_work = &{{ model.name }}_impl_dae_hess_work; capsule->sim_impl_dae_hess->casadi_sparsity_in = &{{ model.name }}_impl_dae_hess_sparsity_in; capsule->sim_impl_dae_hess->casadi_sparsity_out = &{{ model.name }}_impl_dae_hess_sparsity_out; capsule->sim_impl_dae_hess->casadi_n_in = &{{ model.name }}_impl_dae_hess_n_in; capsule->sim_impl_dae_hess->casadi_n_out = &{{ model.name }}_impl_dae_hess_n_out; - external_function_param_casadi_create(capsule->sim_impl_dae_hess, np); + external_function_param_{{ model.dyn_ext_fun_type }}_create(capsule->sim_impl_dae_hess, np); {%- endif %} {% elif solver_options.integrator_type == "ERK" %} // explicit ode - capsule->sim_forw_vde_casadi = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)); - capsule->sim_expl_ode_fun_casadi = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)); + capsule->sim_forw_vde_casadi = (external_function_param_{{ model.dyn_ext_fun_type }} *) malloc(sizeof(external_function_param_{{ model.dyn_ext_fun_type }})); + capsule->sim_vde_adj_casadi = (external_function_param_{{ model.dyn_ext_fun_type }} *) malloc(sizeof(external_function_param_{{ model.dyn_ext_fun_type }})); + capsule->sim_expl_ode_fun_casadi = (external_function_param_{{ model.dyn_ext_fun_type }} *) malloc(sizeof(external_function_param_{{ model.dyn_ext_fun_type }})); capsule->sim_forw_vde_casadi->casadi_fun = &{{ model.name }}_expl_vde_forw; capsule->sim_forw_vde_casadi->casadi_n_in = &{{ model.name }}_expl_vde_forw_n_in; @@ -141,7 +145,15 @@ int {{ model.name }}_acados_sim_create(sim_solver_capsule * capsule) capsule->sim_forw_vde_casadi->casadi_sparsity_in = &{{ model.name }}_expl_vde_forw_sparsity_in; capsule->sim_forw_vde_casadi->casadi_sparsity_out = &{{ model.name }}_expl_vde_forw_sparsity_out; capsule->sim_forw_vde_casadi->casadi_work = &{{ model.name }}_expl_vde_forw_work; - external_function_param_casadi_create(capsule->sim_forw_vde_casadi, np); + external_function_param_{{ model.dyn_ext_fun_type }}_create(capsule->sim_forw_vde_casadi, np); + + capsule->sim_vde_adj_casadi->casadi_fun = &{{ model.name }}_expl_vde_adj; + capsule->sim_vde_adj_casadi->casadi_n_in = &{{ model.name }}_expl_vde_adj_n_in; + capsule->sim_vde_adj_casadi->casadi_n_out = &{{ model.name }}_expl_vde_adj_n_out; + capsule->sim_vde_adj_casadi->casadi_sparsity_in = &{{ model.name }}_expl_vde_adj_sparsity_in; + capsule->sim_vde_adj_casadi->casadi_sparsity_out = &{{ model.name }}_expl_vde_adj_sparsity_out; + capsule->sim_vde_adj_casadi->casadi_work = &{{ model.name }}_expl_vde_adj_work; + external_function_param_{{ model.dyn_ext_fun_type }}_create(capsule->sim_vde_adj_casadi, np); capsule->sim_expl_ode_fun_casadi->casadi_fun = &{{ model.name }}_expl_ode_fun; capsule->sim_expl_ode_fun_casadi->casadi_n_in = &{{ model.name }}_expl_ode_fun_n_in; @@ -149,30 +161,30 @@ int {{ model.name }}_acados_sim_create(sim_solver_capsule * capsule) capsule->sim_expl_ode_fun_casadi->casadi_sparsity_in = &{{ model.name }}_expl_ode_fun_sparsity_in; capsule->sim_expl_ode_fun_casadi->casadi_sparsity_out = &{{ model.name }}_expl_ode_fun_sparsity_out; capsule->sim_expl_ode_fun_casadi->casadi_work = &{{ model.name }}_expl_ode_fun_work; - external_function_param_casadi_create(capsule->sim_expl_ode_fun_casadi, np); + external_function_param_{{ model.dyn_ext_fun_type }}_create(capsule->sim_expl_ode_fun_casadi, np); {%- if hessian_approx == "EXACT" %} - capsule->sim_expl_ode_hess = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)); - // external_function_param_casadi impl_dae_jac_x_xdot_u_z; + capsule->sim_expl_ode_hess = (external_function_param_{{ model.dyn_ext_fun_type }} *) malloc(sizeof(external_function_param_{{ model.dyn_ext_fun_type }})); + // external_function_param_{{ model.dyn_ext_fun_type }} impl_dae_jac_x_xdot_u_z; capsule->sim_expl_ode_hess->casadi_fun = &{{ model.name }}_expl_ode_hess; capsule->sim_expl_ode_hess->casadi_work = &{{ model.name }}_expl_ode_hess_work; capsule->sim_expl_ode_hess->casadi_sparsity_in = &{{ model.name }}_expl_ode_hess_sparsity_in; capsule->sim_expl_ode_hess->casadi_sparsity_out = &{{ model.name }}_expl_ode_hess_sparsity_out; capsule->sim_expl_ode_hess->casadi_n_in = &{{ model.name }}_expl_ode_hess_n_in; capsule->sim_expl_ode_hess->casadi_n_out = &{{ model.name }}_expl_ode_hess_n_out; - external_function_param_casadi_create(capsule->sim_expl_ode_hess, np); + external_function_param_{{ model.dyn_ext_fun_type }}_create(capsule->sim_expl_ode_hess, np); {%- endif %} {% elif solver_options.integrator_type == "GNSF" -%} {% if model.gnsf.purely_linear != 1 %} - capsule->sim_gnsf_phi_fun = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)); - capsule->sim_gnsf_phi_fun_jac_y = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)); - capsule->sim_gnsf_phi_jac_y_uhat = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)); + capsule->sim_gnsf_phi_fun = (external_function_param_{{ model.dyn_ext_fun_type }} *) malloc(sizeof(external_function_param_{{ model.dyn_ext_fun_type }})); + capsule->sim_gnsf_phi_fun_jac_y = (external_function_param_{{ model.dyn_ext_fun_type }} *) malloc(sizeof(external_function_param_{{ model.dyn_ext_fun_type }})); + capsule->sim_gnsf_phi_jac_y_uhat = (external_function_param_{{ model.dyn_ext_fun_type }} *) malloc(sizeof(external_function_param_{{ model.dyn_ext_fun_type }})); {% if model.gnsf.nontrivial_f_LO == 1 %} - capsule->sim_gnsf_f_lo_jac_x1_x1dot_u_z = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)); + capsule->sim_gnsf_f_lo_jac_x1_x1dot_u_z = (external_function_param_{{ model.dyn_ext_fun_type }} *) malloc(sizeof(external_function_param_{{ model.dyn_ext_fun_type }})); {%- endif %} {%- endif %} - capsule->sim_gnsf_get_matrices_fun = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)); + capsule->sim_gnsf_get_matrices_fun = (external_function_param_{{ model.dyn_ext_fun_type }} *) malloc(sizeof(external_function_param_{{ model.dyn_ext_fun_type }})); {% if model.gnsf.purely_linear != 1 %} capsule->sim_gnsf_phi_fun->casadi_fun = &{{ model.name }}_gnsf_phi_fun; @@ -181,7 +193,7 @@ int {{ model.name }}_acados_sim_create(sim_solver_capsule * capsule) capsule->sim_gnsf_phi_fun->casadi_sparsity_in = &{{ model.name }}_gnsf_phi_fun_sparsity_in; capsule->sim_gnsf_phi_fun->casadi_sparsity_out = &{{ model.name }}_gnsf_phi_fun_sparsity_out; capsule->sim_gnsf_phi_fun->casadi_work = &{{ model.name }}_gnsf_phi_fun_work; - external_function_param_casadi_create(capsule->sim_gnsf_phi_fun, np); + external_function_param_{{ model.dyn_ext_fun_type }}_create(capsule->sim_gnsf_phi_fun, np); capsule->sim_gnsf_phi_fun_jac_y->casadi_fun = &{{ model.name }}_gnsf_phi_fun_jac_y; capsule->sim_gnsf_phi_fun_jac_y->casadi_n_in = &{{ model.name }}_gnsf_phi_fun_jac_y_n_in; @@ -189,7 +201,7 @@ int {{ model.name }}_acados_sim_create(sim_solver_capsule * capsule) capsule->sim_gnsf_phi_fun_jac_y->casadi_sparsity_in = &{{ model.name }}_gnsf_phi_fun_jac_y_sparsity_in; capsule->sim_gnsf_phi_fun_jac_y->casadi_sparsity_out = &{{ model.name }}_gnsf_phi_fun_jac_y_sparsity_out; capsule->sim_gnsf_phi_fun_jac_y->casadi_work = &{{ model.name }}_gnsf_phi_fun_jac_y_work; - external_function_param_casadi_create(capsule->sim_gnsf_phi_fun_jac_y, np); + external_function_param_{{ model.dyn_ext_fun_type }}_create(capsule->sim_gnsf_phi_fun_jac_y, np); capsule->sim_gnsf_phi_jac_y_uhat->casadi_fun = &{{ model.name }}_gnsf_phi_jac_y_uhat; capsule->sim_gnsf_phi_jac_y_uhat->casadi_n_in = &{{ model.name }}_gnsf_phi_jac_y_uhat_n_in; @@ -197,7 +209,7 @@ int {{ model.name }}_acados_sim_create(sim_solver_capsule * capsule) capsule->sim_gnsf_phi_jac_y_uhat->casadi_sparsity_in = &{{ model.name }}_gnsf_phi_jac_y_uhat_sparsity_in; capsule->sim_gnsf_phi_jac_y_uhat->casadi_sparsity_out = &{{ model.name }}_gnsf_phi_jac_y_uhat_sparsity_out; capsule->sim_gnsf_phi_jac_y_uhat->casadi_work = &{{ model.name }}_gnsf_phi_jac_y_uhat_work; - external_function_param_casadi_create(capsule->sim_gnsf_phi_jac_y_uhat, np); + external_function_param_{{ model.dyn_ext_fun_type }}_create(capsule->sim_gnsf_phi_jac_y_uhat, np); {% if model.gnsf.nontrivial_f_LO == 1 %} capsule->sim_gnsf_f_lo_jac_x1_x1dot_u_z->casadi_fun = &{{ model.name }}_gnsf_f_lo_fun_jac_x1k1uz; @@ -206,7 +218,7 @@ int {{ model.name }}_acados_sim_create(sim_solver_capsule * capsule) capsule->sim_gnsf_f_lo_jac_x1_x1dot_u_z->casadi_sparsity_in = &{{ model.name }}_gnsf_f_lo_fun_jac_x1k1uz_sparsity_in; capsule->sim_gnsf_f_lo_jac_x1_x1dot_u_z->casadi_sparsity_out = &{{ model.name }}_gnsf_f_lo_fun_jac_x1k1uz_sparsity_out; capsule->sim_gnsf_f_lo_jac_x1_x1dot_u_z->casadi_work = &{{ model.name }}_gnsf_f_lo_fun_jac_x1k1uz_work; - external_function_param_casadi_create(capsule->sim_gnsf_f_lo_jac_x1_x1dot_u_z, np); + external_function_param_{{ model.dyn_ext_fun_type }}_create(capsule->sim_gnsf_f_lo_jac_x1_x1dot_u_z, np); {%- endif %} {%- endif %} @@ -216,7 +228,7 @@ int {{ model.name }}_acados_sim_create(sim_solver_capsule * capsule) capsule->sim_gnsf_get_matrices_fun->casadi_sparsity_in = &{{ model.name }}_gnsf_get_matrices_fun_sparsity_in; capsule->sim_gnsf_get_matrices_fun->casadi_sparsity_out = &{{ model.name }}_gnsf_get_matrices_fun_sparsity_out; capsule->sim_gnsf_get_matrices_fun->casadi_work = &{{ model.name }}_gnsf_get_matrices_fun_work; - external_function_param_casadi_create(capsule->sim_gnsf_get_matrices_fun, np); + external_function_param_{{ model.dyn_ext_fun_type }}_create(capsule->sim_gnsf_get_matrices_fun, np); {% endif %} // sim plan & config @@ -252,6 +264,8 @@ int {{ model.name }}_acados_sim_create(sim_solver_capsule * capsule) capsule->acados_sim_opts = {{ model.name }}_sim_opts; int tmp_int = {{ solver_options.sim_method_newton_iter }}; sim_opts_set({{ model.name }}_sim_config, {{ model.name }}_sim_opts, "newton_iter", &tmp_int); + double tmp_double = {{ solver_options.sim_method_newton_tol }}; + sim_opts_set({{ model.name }}_sim_config, {{ model.name }}_sim_opts, "newton_tol", &tmp_double); sim_collocation_type collocation_type = {{ solver_options.collocation_type }}; sim_opts_set({{ model.name }}_sim_config, {{ model.name }}_sim_opts, "collocation_type", &collocation_type); @@ -307,7 +321,9 @@ int {{ model.name }}_acados_sim_create(sim_solver_capsule * capsule) {%- elif solver_options.integrator_type == "ERK" %} {{ model.name }}_sim_config->model_set({{ model.name }}_sim_in->model, - "expl_vde_for", capsule->sim_forw_vde_casadi); + "expl_vde_forw", capsule->sim_forw_vde_casadi); + {{ model.name }}_sim_config->model_set({{ model.name }}_sim_in->model, + "expl_vde_adj", capsule->sim_vde_adj_casadi); {{ model.name }}_sim_config->model_set({{ model.name }}_sim_in->model, "expl_ode_fun", capsule->sim_expl_ode_fun_casadi); {%- if hessian_approx == "EXACT" %} @@ -408,28 +424,29 @@ int {{ model.name }}_acados_sim_free(sim_solver_capsule *capsule) // free external function {%- if solver_options.integrator_type == "IRK" %} - external_function_param_casadi_free(capsule->sim_impl_dae_fun); - external_function_param_casadi_free(capsule->sim_impl_dae_fun_jac_x_xdot_z); - external_function_param_casadi_free(capsule->sim_impl_dae_jac_x_xdot_u_z); + external_function_param_{{ model.dyn_ext_fun_type }}_free(capsule->sim_impl_dae_fun); + external_function_param_{{ model.dyn_ext_fun_type }}_free(capsule->sim_impl_dae_fun_jac_x_xdot_z); + external_function_param_{{ model.dyn_ext_fun_type }}_free(capsule->sim_impl_dae_jac_x_xdot_u_z); {%- if hessian_approx == "EXACT" %} - external_function_param_casadi_free(capsule->sim_impl_dae_hess); + external_function_param_{{ model.dyn_ext_fun_type }}_free(capsule->sim_impl_dae_hess); {%- endif %} {%- elif solver_options.integrator_type == "ERK" %} - external_function_param_casadi_free(capsule->sim_forw_vde_casadi); - external_function_param_casadi_free(capsule->sim_expl_ode_fun_casadi); + external_function_param_{{ model.dyn_ext_fun_type }}_free(capsule->sim_forw_vde_casadi); + external_function_param_{{ model.dyn_ext_fun_type }}_free(capsule->sim_vde_adj_casadi); + external_function_param_{{ model.dyn_ext_fun_type }}_free(capsule->sim_expl_ode_fun_casadi); {%- if hessian_approx == "EXACT" %} - external_function_param_casadi_free(capsule->sim_expl_ode_hess); + external_function_param_{{ model.dyn_ext_fun_type }}_free(capsule->sim_expl_ode_hess); {%- endif %} {%- elif solver_options.integrator_type == "GNSF" %} {% if model.gnsf.purely_linear != 1 %} - external_function_param_casadi_free(capsule->sim_gnsf_phi_fun); - external_function_param_casadi_free(capsule->sim_gnsf_phi_fun_jac_y); - external_function_param_casadi_free(capsule->sim_gnsf_phi_jac_y_uhat); + external_function_param_{{ model.dyn_ext_fun_type }}_free(capsule->sim_gnsf_phi_fun); + external_function_param_{{ model.dyn_ext_fun_type }}_free(capsule->sim_gnsf_phi_fun_jac_y); + external_function_param_{{ model.dyn_ext_fun_type }}_free(capsule->sim_gnsf_phi_jac_y_uhat); {% if model.gnsf.nontrivial_f_LO == 1 %} - external_function_param_casadi_free(capsule->sim_gnsf_f_lo_jac_x1_x1dot_u_z); + external_function_param_{{ model.dyn_ext_fun_type }}_free(capsule->sim_gnsf_f_lo_jac_x1_x1dot_u_z); {%- endif %} {%- endif %} - external_function_param_casadi_free(capsule->sim_gnsf_get_matrices_fun); + external_function_param_{{ model.dyn_ext_fun_type }}_free(capsule->sim_gnsf_get_matrices_fun); {% endif %} return 0; @@ -449,6 +466,7 @@ int {{ model.name }}_acados_sim_update_params(sim_solver_capsule *capsule, doubl {%- if solver_options.integrator_type == "ERK" %} capsule->sim_forw_vde_casadi[0].set_param(capsule->sim_forw_vde_casadi, p); + capsule->sim_vde_adj_casadi[0].set_param(capsule->sim_vde_adj_casadi, p); capsule->sim_expl_ode_fun_casadi[0].set_param(capsule->sim_expl_ode_fun_casadi, p); {%- if hessian_approx == "EXACT" %} capsule->sim_expl_ode_hess[0].set_param(capsule->sim_expl_ode_hess, p); diff --git a/third_party/acados/acados_template/c_templates_tera/acados_sim_solver.in.h b/third_party/acados/acados_template/c_templates_tera/acados_sim_solver.in.h index 7306491ba..59aee62f4 100644 --- a/third_party/acados/acados_template/c_templates_tera/acados_sim_solver.in.h +++ b/third_party/acados/acados_template/c_templates_tera/acados_sim_solver.in.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * @@ -60,22 +57,23 @@ typedef struct sim_solver_capsule /* external functions */ // ERK - external_function_param_casadi * sim_forw_vde_casadi; - external_function_param_casadi * sim_expl_ode_fun_casadi; - external_function_param_casadi * sim_expl_ode_hess; + external_function_param_{{ model.dyn_ext_fun_type }} * sim_forw_vde_casadi; + external_function_param_{{ model.dyn_ext_fun_type }} * sim_vde_adj_casadi; + external_function_param_{{ model.dyn_ext_fun_type }} * sim_expl_ode_fun_casadi; + external_function_param_{{ model.dyn_ext_fun_type }} * sim_expl_ode_hess; // IRK - external_function_param_casadi * sim_impl_dae_fun; - external_function_param_casadi * sim_impl_dae_fun_jac_x_xdot_z; - external_function_param_casadi * sim_impl_dae_jac_x_xdot_u_z; - external_function_param_casadi * sim_impl_dae_hess; + external_function_param_{{ model.dyn_ext_fun_type }} * sim_impl_dae_fun; + external_function_param_{{ model.dyn_ext_fun_type }} * sim_impl_dae_fun_jac_x_xdot_z; + external_function_param_{{ model.dyn_ext_fun_type }} * sim_impl_dae_jac_x_xdot_u_z; + external_function_param_{{ model.dyn_ext_fun_type }} * sim_impl_dae_hess; // GNSF - external_function_param_casadi * sim_gnsf_phi_fun; - external_function_param_casadi * sim_gnsf_phi_fun_jac_y; - external_function_param_casadi * sim_gnsf_phi_jac_y_uhat; - external_function_param_casadi * sim_gnsf_f_lo_jac_x1_x1dot_u_z; - external_function_param_casadi * sim_gnsf_get_matrices_fun; + external_function_param_{{ model.dyn_ext_fun_type }} * sim_gnsf_phi_fun; + external_function_param_{{ model.dyn_ext_fun_type }} * sim_gnsf_phi_fun_jac_y; + external_function_param_{{ model.dyn_ext_fun_type }} * sim_gnsf_phi_jac_y_uhat; + external_function_param_{{ model.dyn_ext_fun_type }} * sim_gnsf_f_lo_jac_x1_x1dot_u_z; + external_function_param_{{ model.dyn_ext_fun_type }} * sim_gnsf_get_matrices_fun; } sim_solver_capsule; diff --git a/third_party/acados/acados_template/c_templates_tera/acados_sim_solver.in.pxd b/third_party/acados/acados_template/c_templates_tera/acados_sim_solver.in.pxd new file mode 100644 index 000000000..153f98d13 --- /dev/null +++ b/third_party/acados/acados_template/c_templates_tera/acados_sim_solver.in.pxd @@ -0,0 +1,51 @@ +# +# Copyright (c) The acados authors. +# +# This file is part of acados. +# +# 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 HOLDER 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.; +# + +cimport acados_sim_solver_common + +cdef extern from "acados_sim_solver_{{ model.name }}.h": + ctypedef struct sim_solver_capsule "sim_solver_capsule": + pass + + sim_solver_capsule * acados_sim_solver_create_capsule "{{ model.name }}_acados_sim_solver_create_capsule"() + int acados_sim_solver_free_capsule "{{ model.name }}_acados_sim_solver_free_capsule"(sim_solver_capsule *capsule) + + int acados_sim_create "{{ model.name }}_acados_sim_create"(sim_solver_capsule * capsule) + int acados_sim_solve "{{ model.name }}_acados_sim_solve"(sim_solver_capsule * capsule) + int acados_sim_free "{{ model.name }}_acados_sim_free"(sim_solver_capsule * capsule) + int acados_sim_update_params "{{ model.name }}_acados_sim_update_params"(sim_solver_capsule * capsule, double *value, int np_) + # int acados_sim_update_params_sparse "{{ model.name }}_acados_sim_update_params_sparse"(sim_solver_capsule * capsule, int stage, int *idx, double *p, int n_update) + + acados_sim_solver_common.sim_in *acados_get_sim_in "{{ model.name }}_acados_get_sim_in"(sim_solver_capsule * capsule) + acados_sim_solver_common.sim_out *acados_get_sim_out "{{ model.name }}_acados_get_sim_out"(sim_solver_capsule * capsule) + acados_sim_solver_common.sim_solver *acados_get_sim_solver "{{ model.name }}_acados_get_sim_solver"(sim_solver_capsule * capsule) + acados_sim_solver_common.sim_config *acados_get_sim_config "{{ model.name }}_acados_get_sim_config"(sim_solver_capsule * capsule) + acados_sim_solver_common.sim_opts *acados_get_sim_opts "{{ model.name }}_acados_get_sim_opts"(sim_solver_capsule * capsule) + void *acados_get_sim_dims "{{ model.name }}_acados_get_sim_dims"(sim_solver_capsule * capsule) diff --git a/third_party/acados/acados_template/c_templates_tera/acados_solver.in.c b/third_party/acados/acados_template/c_templates_tera/acados_solver.in.c index 0af812770..5e36a53d1 100644 --- a/third_party/acados/acados_template/c_templates_tera/acados_solver.in.c +++ b/third_party/acados/acados_template/c_templates_tera/acados_solver.in.c @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * @@ -42,33 +39,26 @@ // example specific #include "{{ model.name }}_model/{{ model.name }}_model.h" -{% if constraints.constr_type == "BGP" and dims.nphi %} -#include "{{ model.name }}_constraints/{{ model.name }}_phi_constraint.h" -{% endif %} -{% if constraints.constr_type_e == "BGP" and dims.nphi_e > 0 %} -#include "{{ model.name }}_constraints/{{ model.name }}_phi_e_constraint.h" -{% endif %} -{% if constraints.constr_type == "BGH" and dims.nh > 0 %} -#include "{{ model.name }}_constraints/{{ model.name }}_h_constraint.h" -{% endif %} -{% if constraints.constr_type_e == "BGH" and dims.nh_e > 0 %} -#include "{{ model.name }}_constraints/{{ model.name }}_h_e_constraint.h" -{% endif %} -{%- if cost.cost_type == "NONLINEAR_LS" %} -#include "{{ model.name }}_cost/{{ model.name }}_cost_y_fun.h" -{%- elif cost.cost_type == "EXTERNAL" %} -#include "{{ model.name }}_cost/{{ model.name }}_external_cost.h" +#include "{{ model.name }}_constraints/{{ model.name }}_constraints.h" + +{%- if cost.cost_type != "LINEAR_LS" or cost.cost_type_e != "LINEAR_LS" or cost.cost_type_0 != "LINEAR_LS" %} +#include "{{ model.name }}_cost/{{ model.name }}_cost.h" {%- endif %} -{%- if cost.cost_type_0 == "NONLINEAR_LS" %} -#include "{{ model.name }}_cost/{{ model.name }}_cost_y_0_fun.h" -{%- elif cost.cost_type_0 == "EXTERNAL" %} -#include "{{ model.name }}_cost/{{ model.name }}_external_cost_0.h" + +{%- if not solver_options.custom_update_filename %} + {%- set custom_update_filename = "" %} +{% else %} + {%- set custom_update_filename = solver_options.custom_update_filename %} {%- endif %} -{%- if cost.cost_type_e == "NONLINEAR_LS" %} -#include "{{ model.name }}_cost/{{ model.name }}_cost_y_e_fun.h" -{%- elif cost.cost_type_e == "EXTERNAL" %} -#include "{{ model.name }}_cost/{{ model.name }}_external_cost_e.h" +{%- if not solver_options.custom_update_header_filename %} + {%- set custom_update_header_filename = "" %} +{% else %} + {%- set custom_update_header_filename = solver_options.custom_update_header_filename %} {%- endif %} +{%- if custom_update_header_filename != "" %} +#include "{{ custom_update_header_filename }}" +{%- endif %} + #include "acados_solver_{{ model.name }}.h" @@ -205,7 +195,6 @@ void {{ model.name }}_acados_create_1_set_plan(ocp_nlp_plan_t* nlp_solver_plan, nlp_solver_plan->nlp_constraints[N] = BGH; {%- endif %} -{%- if solver_options.hessian_approx == "EXACT" %} {%- if solver_options.regularize_method == "NO_REGULARIZE" %} nlp_solver_plan->regularization = NO_REGULARIZE; {%- elif solver_options.regularize_method == "MIRROR" %} @@ -217,7 +206,6 @@ void {{ model.name }}_acados_create_1_set_plan(ocp_nlp_plan_t* nlp_solver_plan, {%- elif solver_options.regularize_method == "CONVEXIFY" %} nlp_solver_plan->regularization = CONVEXIFY; {%- endif %} -{%- endif %} } @@ -324,11 +312,11 @@ ocp_nlp_dims* {{ model.name }}_acados_create_2_create_and_set_dimensions({{ mode ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, i, "nbxe", &nbxe[i]); } -{%- if cost.cost_type_0 == "NONLINEAR_LS" or cost.cost_type_0 == "LINEAR_LS" %} +{%- if cost.cost_type_0 == "NONLINEAR_LS" or cost.cost_type_0 == "LINEAR_LS" or cost.cost_type_0 == "CONVEX_OVER_NONLINEAR"%} ocp_nlp_dims_set_cost(nlp_config, nlp_dims, 0, "ny", &ny[0]); {%- endif %} -{%- if cost.cost_type == "NONLINEAR_LS" or cost.cost_type == "LINEAR_LS" %} +{%- if cost.cost_type == "NONLINEAR_LS" or cost.cost_type == "LINEAR_LS" or cost.cost_type == "CONVEX_OVER_NONLINEAR"%} for (int i = 1; i < N; i++) ocp_nlp_dims_set_cost(nlp_config, nlp_dims, i, "ny", &ny[i]); {%- endif %} @@ -353,7 +341,7 @@ ocp_nlp_dims* {{ model.name }}_acados_create_2_create_and_set_dimensions({{ mode ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, N, "nphi", &nphi[N]); ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, N, "nsphi", &nsphi[N]); {%- endif %} -{%- if cost.cost_type_e == "NONLINEAR_LS" or cost.cost_type_e == "LINEAR_LS" %} +{%- if cost.cost_type_e == "NONLINEAR_LS" or cost.cost_type_e == "LINEAR_LS" or cost.cost_type_e == "CONVEX_OVER_NONLINEAR"%} ocp_nlp_dims_set_cost(nlp_config, nlp_dims, N, "ny", &ny[N]); {%- endif %} free(intNp1mem); @@ -388,7 +376,6 @@ return nlp_dims; void {{ model.name }}_acados_create_3_create_and_set_functions({{ model.name }}_solver_capsule* capsule) { const int N = capsule->nlp_solver_plan->N; - ocp_nlp_config* nlp_config = capsule->nlp_config; /************************************************ * external functions @@ -468,35 +455,50 @@ void {{ model.name }}_acados_create_3_create_and_set_functions({{ model.name }}_ {% elif solver_options.integrator_type == "IRK" %} // implicit dae - capsule->impl_dae_fun = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); + capsule->impl_dae_fun = (external_function_param_{{ model.dyn_ext_fun_type }} *) malloc(sizeof(external_function_param_{{ model.dyn_ext_fun_type }})*N); for (int i = 0; i < N; i++) { + {%- if model.dyn_ext_fun_type == "casadi" %} MAP_CASADI_FNC(impl_dae_fun[i], {{ model.name }}_impl_dae_fun); + {%- else %} + capsule->impl_dae_fun[i].fun = &{{ model.dyn_impl_dae_fun }}; + external_function_param_{{ model.dyn_ext_fun_type }}_create(&capsule->impl_dae_fun[i], {{ dims.np }}); + {%- endif %} } - capsule->impl_dae_fun_jac_x_xdot_z = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); + capsule->impl_dae_fun_jac_x_xdot_z = (external_function_param_{{ model.dyn_ext_fun_type }} *) malloc(sizeof(external_function_param_{{ model.dyn_ext_fun_type }})*N); for (int i = 0; i < N; i++) { + {%- if model.dyn_ext_fun_type == "casadi" %} MAP_CASADI_FNC(impl_dae_fun_jac_x_xdot_z[i], {{ model.name }}_impl_dae_fun_jac_x_xdot_z); + {%- else %} + capsule->impl_dae_fun_jac_x_xdot_z[i].fun = &{{ model.dyn_impl_dae_fun_jac }}; + external_function_param_{{ model.dyn_ext_fun_type }}_create(&capsule->impl_dae_fun_jac_x_xdot_z[i], {{ dims.np }}); + {%- endif %} } - capsule->impl_dae_jac_x_xdot_u_z = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); + capsule->impl_dae_jac_x_xdot_u_z = (external_function_param_{{ model.dyn_ext_fun_type }} *) malloc(sizeof(external_function_param_{{ model.dyn_ext_fun_type }})*N); for (int i = 0; i < N; i++) { + {%- if model.dyn_ext_fun_type == "casadi" %} MAP_CASADI_FNC(impl_dae_jac_x_xdot_u_z[i], {{ model.name }}_impl_dae_jac_x_xdot_u_z); + {%- else %} + capsule->impl_dae_jac_x_xdot_u_z[i].fun = &{{ model.dyn_impl_dae_jac }}; + external_function_param_{{ model.dyn_ext_fun_type }}_create(&capsule->impl_dae_jac_x_xdot_u_z[i], {{ dims.np }}); + {%- endif %} } {%- if solver_options.hessian_approx == "EXACT" %} - capsule->impl_dae_hess = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); + capsule->impl_dae_hess = (external_function_param_{{ model.dyn_ext_fun_type }} *) malloc(sizeof(external_function_param_{{ model.dyn_ext_fun_type }})*N); for (int i = 0; i < N; i++) { MAP_CASADI_FNC(impl_dae_hess[i], {{ model.name }}_impl_dae_hess); } {%- endif %} {% elif solver_options.integrator_type == "LIFTED_IRK" %} // external functions (implicit model) - capsule->impl_dae_fun = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); + capsule->impl_dae_fun = (external_function_param_{{ model.dyn_ext_fun_type }} *) malloc(sizeof(external_function_param_{{ model.dyn_ext_fun_type }})*N); for (int i = 0; i < N; i++) { MAP_CASADI_FNC(impl_dae_fun[i], {{ model.name }}_impl_dae_fun); } - capsule->impl_dae_fun_jac_x_xdot_u = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); + capsule->impl_dae_fun_jac_x_xdot_u = (external_function_param_{{ model.dyn_ext_fun_type }} *) malloc(sizeof(external_function_param_{{ model.dyn_ext_fun_type }})*N); for (int i = 0; i < N; i++) { MAP_CASADI_FNC(impl_dae_fun_jac_x_xdot_u[i], {{ model.name }}_impl_dae_fun_jac_x_xdot_u); } @@ -574,6 +576,11 @@ void {{ model.name }}_acados_create_3_create_and_set_functions({{ model.name }}_ MAP_CASADI_FNC(cost_y_0_fun_jac_ut_xt, {{ model.name }}_cost_y_0_fun_jac_ut_xt); MAP_CASADI_FNC(cost_y_0_hess, {{ model.name }}_cost_y_0_hess); +{%- elif cost.cost_type_0 == "CONVEX_OVER_NONLINEAR" %} + // convex-over-nonlinear cost + MAP_CASADI_FNC(conl_cost_0_fun, {{ model.name }}_conl_cost_0_fun); + MAP_CASADI_FNC(conl_cost_0_fun_jac_hess, {{ model.name }}_conl_cost_0_fun_jac_hess); + {%- elif cost.cost_type_0 == "EXTERNAL" %} // external cost {%- if cost.cost_ext_fun_type_0 == "casadi" %} @@ -619,6 +626,20 @@ void {{ model.name }}_acados_create_3_create_and_set_functions({{ model.name }}_ { MAP_CASADI_FNC(cost_y_hess[i], {{ model.name }}_cost_y_hess); } + +{%- elif cost.cost_type_0 == "CONVEX_OVER_NONLINEAR" %} + // convex-over-nonlinear cost + capsule->conl_cost_fun = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); + for (int i = 0; i < N-1; i++) + { + MAP_CASADI_FNC(conl_cost_fun[i], {{ model.name }}_conl_cost_fun); + } + capsule->conl_cost_fun_jac_hess = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); + for (int i = 0; i < N-1; i++) + { + MAP_CASADI_FNC(conl_cost_fun_jac_hess[i], {{ model.name }}_conl_cost_fun_jac_hess); + } + {%- elif cost.cost_type == "EXTERNAL" %} // external cost capsule->ext_cost_fun = (external_function_param_{{ cost.cost_ext_fun_type }} *) malloc(sizeof(external_function_param_{{ cost.cost_ext_fun_type }})*N); @@ -660,6 +681,12 @@ void {{ model.name }}_acados_create_3_create_and_set_functions({{ model.name }}_ MAP_CASADI_FNC(cost_y_e_fun, {{ model.name }}_cost_y_e_fun); MAP_CASADI_FNC(cost_y_e_fun_jac_ut_xt, {{ model.name }}_cost_y_e_fun_jac_ut_xt); MAP_CASADI_FNC(cost_y_e_hess, {{ model.name }}_cost_y_e_hess); + +{%- elif cost.cost_type_e == "CONVEX_OVER_NONLINEAR" %} + // convex-over-nonlinear cost + MAP_CASADI_FNC(conl_cost_e_fun, {{ model.name }}_conl_cost_e_fun); + MAP_CASADI_FNC(conl_cost_e_fun_jac_hess, {{ model.name }}_conl_cost_e_fun_jac_hess); + {%- elif cost.cost_type_e == "EXTERNAL" %} // external cost - function {%- if cost.cost_ext_fun_type_e == "casadi" %} @@ -808,20 +835,9 @@ void {{ model.name }}_acados_create_5_set_nlp_in({{ model.name }}_solver_capsule } /**** Cost ****/ -{%- if cost.cost_type_0 == "NONLINEAR_LS" or cost.cost_type_0 == "LINEAR_LS" %} - {%- if dims.ny_0 > 0 %} - double* W_0 = calloc(NY0*NY0, sizeof(double)); - // change only the non-zero elements: - {%- for j in range(end=dims.ny_0) %} - {%- for k in range(end=dims.ny_0) %} - {%- if cost.W_0[j][k] != 0 %} - W_0[{{ j }}+(NY0) * {{ k }}] = {{ cost.W_0[j][k] }}; - {%- endif %} - {%- endfor %} - {%- endfor %} - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "W", W_0); - free(W_0); +{%- if dims.ny_0 == 0 %} +{%- elif cost.cost_type_0 == "NONLINEAR_LS" or cost.cost_type_0 == "LINEAR_LS" or cost.cost_type_0 == "CONVEX_OVER_NONLINEAR" %} double* yref_0 = calloc(NY0, sizeof(double)); // change only the non-zero elements: {%- for j in range(end=dims.ny_0) %} @@ -831,21 +847,11 @@ void {{ model.name }}_acados_create_5_set_nlp_in({{ model.name }}_solver_capsule {%- endfor %} ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "yref", yref_0); free(yref_0); - {%- endif %} {%- endif %} -{%- if cost.cost_type == "NONLINEAR_LS" or cost.cost_type == "LINEAR_LS" %} - {%- if dims.ny > 0 %} - double* W = calloc(NY*NY, sizeof(double)); - // change only the non-zero elements: - {%- for j in range(end=dims.ny) %} - {%- for k in range(end=dims.ny) %} - {%- if cost.W[j][k] != 0 %} - W[{{ j }}+(NY) * {{ k }}] = {{ cost.W[j][k] }}; - {%- endif %} - {%- endfor %} - {%- endfor %} +{%- if dims.ny == 0 %} +{%- elif cost.cost_type == "NONLINEAR_LS" or cost.cost_type == "LINEAR_LS" or cost.cost_type == "CONVEX_OVER_NONLINEAR" %} double* yref = calloc(NY, sizeof(double)); // change only the non-zero elements: {%- for j in range(end=dims.ny) %} @@ -856,15 +862,76 @@ void {{ model.name }}_acados_create_5_set_nlp_in({{ model.name }}_solver_capsule for (int i = 1; i < N; i++) { - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "W", W); ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "yref", yref); } - free(W); free(yref); - {%- endif %} {%- endif %} -{%- if cost.cost_type_0 == "LINEAR_LS" %} + +{%- if dims.ny_e == 0 %} +{%- elif cost.cost_type_e == "NONLINEAR_LS" or cost.cost_type_e == "LINEAR_LS" or cost.cost_type_e == "CONVEX_OVER_NONLINEAR" %} + double* yref_e = calloc(NYN, sizeof(double)); + // change only the non-zero elements: + {%- for j in range(end=dims.ny_e) %} + {%- if cost.yref_e[j] != 0 %} + yref_e[{{ j }}] = {{ cost.yref_e[j] }}; + {%- endif %} + {%- endfor %} + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "yref", yref_e); + free(yref_e); +{%- endif %} + +{%- if dims.ny_0 == 0 %} +{%- elif cost.cost_type_0 == "NONLINEAR_LS" or cost.cost_type_0 == "LINEAR_LS" %} + double* W_0 = calloc(NY0*NY0, sizeof(double)); + // change only the non-zero elements: + {%- for j in range(end=dims.ny_0) %} + {%- for k in range(end=dims.ny_0) %} + {%- if cost.W_0[j][k] != 0 %} + W_0[{{ j }}+(NY0) * {{ k }}] = {{ cost.W_0[j][k] }}; + {%- endif %} + {%- endfor %} + {%- endfor %} + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "W", W_0); + free(W_0); +{%- endif %} + +{%- if dims.ny == 0 %} +{%- elif cost.cost_type == "NONLINEAR_LS" or cost.cost_type == "LINEAR_LS" %} + double* W = calloc(NY*NY, sizeof(double)); + // change only the non-zero elements: + {%- for j in range(end=dims.ny) %} + {%- for k in range(end=dims.ny) %} + {%- if cost.W[j][k] != 0 %} + W[{{ j }}+(NY) * {{ k }}] = {{ cost.W[j][k] }}; + {%- endif %} + {%- endfor %} + {%- endfor %} + + for (int i = 1; i < N; i++) + { + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "W", W); + } + free(W); +{%- endif %} + +{%- if dims.ny_e == 0 %} +{%- elif cost.cost_type_e == "NONLINEAR_LS" or cost.cost_type_e == "LINEAR_LS" %} + double* W_e = calloc(NYN*NYN, sizeof(double)); + // change only the non-zero elements: + {%- for j in range(end=dims.ny_e) %} + {%- for k in range(end=dims.ny_e) %} + {%- if cost.W_e[j][k] != 0 %} + W_e[{{ j }}+(NYN) * {{ k }}] = {{ cost.W_e[j][k] }}; + {%- endif %} + {%- endfor %} + {%- endfor %} + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "W", W_e); + free(W_e); +{%- endif %} + +{%- if dims.ny_0 == 0 %} +{%- elif cost.cost_type_0 == "LINEAR_LS" %} double* Vx_0 = calloc(NY0*NX, sizeof(double)); // change only the non-zero elements: {%- for j in range(end=dims.ny_0) %} @@ -877,7 +944,7 @@ void {{ model.name }}_acados_create_5_set_nlp_in({{ model.name }}_solver_capsule ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "Vx", Vx_0); free(Vx_0); - {%- if dims.ny_0 > 0 and dims.nu > 0 %} + {%- if dims.nu > 0 %} double* Vu_0 = calloc(NY0*NU, sizeof(double)); // change only the non-zero elements: {%- for j in range(end=dims.ny_0) %} @@ -891,7 +958,7 @@ void {{ model.name }}_acados_create_5_set_nlp_in({{ model.name }}_solver_capsule free(Vu_0); {%- endif %} - {%- if dims.ny_0 > 0 and dims.nz > 0 %} + {%- if dims.nz > 0 %} double* Vz_0 = calloc(NY0*NZ, sizeof(double)); // change only the non-zero elements: {% for j in range(end=dims.ny_0) %} @@ -904,10 +971,10 @@ void {{ model.name }}_acados_create_5_set_nlp_in({{ model.name }}_solver_capsule ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "Vz", Vz_0); free(Vz_0); {%- endif %} -{%- endif %}{# LINEAR LS #} +{%- endif %} - -{%- if cost.cost_type == "LINEAR_LS" %} +{%- if dims.ny == 0 %} +{%- elif cost.cost_type == "LINEAR_LS" %} double* Vx = calloc(NY*NX, sizeof(double)); // change only the non-zero elements: {%- for j in range(end=dims.ny) %} @@ -923,7 +990,7 @@ void {{ model.name }}_acados_create_5_set_nlp_in({{ model.name }}_solver_capsule } free(Vx); - {% if dims.ny > 0 and dims.nu > 0 %} + {% if dims.nu > 0 %} double* Vu = calloc(NY*NU, sizeof(double)); // change only the non-zero elements: {% for j in range(end=dims.ny) %} @@ -941,7 +1008,7 @@ void {{ model.name }}_acados_create_5_set_nlp_in({{ model.name }}_solver_capsule free(Vu); {%- endif %} - {%- if dims.ny > 0 and dims.nz > 0 %} + {%- if dims.nz > 0 %} double* Vz = calloc(NY*NZ, sizeof(double)); // change only the non-zero elements: {% for j in range(end=dims.ny) %} @@ -960,11 +1027,28 @@ void {{ model.name }}_acados_create_5_set_nlp_in({{ model.name }}_solver_capsule {%- endif %} {%- endif %}{# LINEAR LS #} +{%- if dims.ny_e == 0 %} +{%- elif cost.cost_type_e == "LINEAR_LS" %} + double* Vx_e = calloc(NYN*NX, sizeof(double)); + // change only the non-zero elements: + {% for j in range(end=dims.ny_e) %} + {%- for k in range(end=dims.nx) %} + {%- if cost.Vx_e[j][k] != 0 %} + Vx_e[{{ j }}+(NYN) * {{ k }}] = {{ cost.Vx_e[j][k] }}; + {%- endif %} + {%- endfor %} + {%- endfor %} + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "Vx", Vx_e); + free(Vx_e); +{%- endif %} {%- if cost.cost_type_0 == "NONLINEAR_LS" %} ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "nls_y_fun", &capsule->cost_y_0_fun); ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "nls_y_fun_jac", &capsule->cost_y_0_fun_jac_ut_xt); ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "nls_y_hess", &capsule->cost_y_0_hess); +{%- elif cost.cost_type_0 == "CONVEX_OVER_NONLINEAR" %} + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "conl_cost_fun", &capsule->conl_cost_0_fun); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "conl_cost_fun_jac_hess", &capsule->conl_cost_0_fun_jac_hess); {%- elif cost.cost_type_0 == "EXTERNAL" %} ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "ext_cost_fun", &capsule->ext_cost_0_fun); ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "ext_cost_fun_jac", &capsule->ext_cost_0_fun_jac); @@ -978,6 +1062,12 @@ void {{ model.name }}_acados_create_5_set_nlp_in({{ model.name }}_solver_capsule ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "nls_y_fun_jac", &capsule->cost_y_fun_jac_ut_xt[i-1]); ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "nls_y_hess", &capsule->cost_y_hess[i-1]); } +{%- elif cost.cost_type == "CONVEX_OVER_NONLINEAR" %} + for (int i = 1; i < N; i++) + { + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "conl_cost_fun", &capsule->conl_cost_fun[i-1]); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "conl_cost_fun_jac_hess", &capsule->conl_cost_fun_jac_hess[i-1]); + } {%- elif cost.cost_type == "EXTERNAL" %} for (int i = 1; i < N; i++) { @@ -987,7 +1077,25 @@ void {{ model.name }}_acados_create_5_set_nlp_in({{ model.name }}_solver_capsule } {%- endif %} +{%- if cost.cost_type_e == "NONLINEAR_LS" %} + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "nls_y_fun", &capsule->cost_y_e_fun); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "nls_y_fun_jac", &capsule->cost_y_e_fun_jac_ut_xt); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "nls_y_hess", &capsule->cost_y_e_hess); + +{%- elif cost.cost_type_e == "CONVEX_OVER_NONLINEAR" %} + + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "conl_cost_fun", &capsule->conl_cost_e_fun); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "conl_cost_fun_jac_hess", &capsule->conl_cost_e_fun_jac_hess); + +{%- elif cost.cost_type_e == "EXTERNAL" %} + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "ext_cost_fun", &capsule->ext_cost_e_fun); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "ext_cost_fun_jac", &capsule->ext_cost_e_fun_jac); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "ext_cost_fun_jac_hess", &capsule->ext_cost_e_fun_jac_hess); +{%- endif %} + + {%- if dims.ns > 0 %} + // slacks double* zlumem = calloc(4*NS, sizeof(double)); double* Zl = zlumem+NS*0; double* Zu = zlumem+NS*1; @@ -1028,59 +1136,8 @@ void {{ model.name }}_acados_create_5_set_nlp_in({{ model.name }}_solver_capsule free(zlumem); {%- endif %} - // terminal cost -{%- if cost.cost_type_e == "LINEAR_LS" or cost.cost_type_e == "NONLINEAR_LS" %} - {%- if dims.ny_e > 0 %} - double* yref_e = calloc(NYN, sizeof(double)); - // change only the non-zero elements: - {%- for j in range(end=dims.ny_e) %} - {%- if cost.yref_e[j] != 0 %} - yref_e[{{ j }}] = {{ cost.yref_e[j] }}; - {%- endif %} - {%- endfor %} - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "yref", yref_e); - free(yref_e); - - double* W_e = calloc(NYN*NYN, sizeof(double)); - // change only the non-zero elements: - {%- for j in range(end=dims.ny_e) %} - {%- for k in range(end=dims.ny_e) %} - {%- if cost.W_e[j][k] != 0 %} - W_e[{{ j }}+(NYN) * {{ k }}] = {{ cost.W_e[j][k] }}; - {%- endif %} - {%- endfor %} - {%- endfor %} - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "W", W_e); - free(W_e); - - {%- if cost.cost_type_e == "LINEAR_LS" %} - double* Vx_e = calloc(NYN*NX, sizeof(double)); - // change only the non-zero elements: - {% for j in range(end=dims.ny_e) %} - {%- for k in range(end=dims.nx) %} - {%- if cost.Vx_e[j][k] != 0 %} - Vx_e[{{ j }}+(NYN) * {{ k }}] = {{ cost.Vx_e[j][k] }}; - {%- endif %} - {%- endfor %} - {%- endfor %} - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "Vx", Vx_e); - free(Vx_e); - {%- endif %} - - {%- if cost.cost_type_e == "NONLINEAR_LS" %} - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "nls_y_fun", &capsule->cost_y_e_fun); - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "nls_y_fun_jac", &capsule->cost_y_e_fun_jac_ut_xt); - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "nls_y_hess", &capsule->cost_y_e_hess); - {%- endif %} - {%- endif %}{# ny_e > 0 #} - -{%- elif cost.cost_type_e == "EXTERNAL" %} - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "ext_cost_fun", &capsule->ext_cost_e_fun); - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "ext_cost_fun_jac", &capsule->ext_cost_e_fun_jac); - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "ext_cost_fun_jac_hess", &capsule->ext_cost_e_fun_jac_hess); -{%- endif %} - {% if dims.ns_e > 0 %} + // slacks terminal double* zluemem = calloc(4*NSN, sizeof(double)); double* Zl_e = zluemem+NSN*0; double* Zu_e = zluemem+NSN*1; @@ -1185,7 +1242,7 @@ void {{ model.name }}_acados_create_5_set_nlp_in({{ model.name }}_solver_capsule {%- endfor %} for (int i = 1; i < N; i++) - { + { ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "idxsbx", idxsbx); ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "lsbx", lsbx); ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "usbx", usbx); @@ -1363,7 +1420,7 @@ void {{ model.name }}_acados_create_5_set_nlp_in({{ model.name }}_solver_capsule {%- endif %} {% if dims.ng > 0 %} - // set up general constraints for stage 0 to N-1 + // set up general constraints for stage 0 to N-1 double* D = calloc(NG*NU, sizeof(double)); double* C = calloc(NG*NX, sizeof(double)); double* lug = calloc(2*NG, sizeof(double)); @@ -1427,7 +1484,7 @@ void {{ model.name }}_acados_create_5_set_nlp_in({{ model.name }}_solver_capsule uh[{{ i }}] = {{ constraints.uh[i] }}; {%- endif %} {%- endfor %} - + for (int i = 0; i < N; i++) { // nonlinear constraints for stages 0 to N-1 @@ -1599,16 +1656,16 @@ void {{ model.name }}_acados_create_5_set_nlp_in({{ model.name }}_solver_capsule {% endif %} {% if dims.ng_e > 0 %} - // set up general constraints for last stage + // set up general constraints for last stage double* C_e = calloc(NGN*NX, sizeof(double)); double* lug_e = calloc(2*NGN, sizeof(double)); double* lg_e = lug_e; double* ug_e = lug_e + NGN; - {% for j in range(end=dims.ng) %} + {% for j in range(end=dims.ng_e) %} {%- for k in range(end=dims.nx) %} {%- if constraints.C_e[j][k] != 0 %} - C_e[{{ j }}+NG * {{ k }}] = {{ constraints.C_e[j][k] }}; + C_e[{{ j }}+NGN * {{ k }}] = {{ constraints.C_e[j][k] }}; {%- endif %} {%- endfor %} {%- endfor %} @@ -1658,7 +1715,7 @@ void {{ model.name }}_acados_create_5_set_nlp_in({{ model.name }}_solver_capsule {%- endif %} {% if dims.nphi_e > 0 and constraints.constr_type_e == "BGP" %} - // set up convex-over-nonlinear constraints for last stage + // set up convex-over-nonlinear constraints for last stage double* luphi_e = calloc(2*NPHIN, sizeof(double)); double* lphi_e = luphi_e; double* uphi_e = luphi_e + NPHIN; @@ -1687,7 +1744,6 @@ void {{ model.name }}_acados_create_6_set_opts({{ model.name }}_solver_capsule* { const int N = capsule->nlp_solver_plan->N; ocp_nlp_config* nlp_config = capsule->nlp_config; - ocp_nlp_dims* nlp_dims = capsule->nlp_dims; void *nlp_opts = capsule->nlp_opts; /************************************************ @@ -1695,12 +1751,9 @@ void {{ model.name }}_acados_create_6_set_opts({{ model.name }}_solver_capsule* ************************************************/ {% if solver_options.hessian_approx == "EXACT" %} - bool nlp_solver_exact_hessian = true; - // TODO: this if should not be needed! however, calling the setter with false leads to weird behavior. Investigate! - if (nlp_solver_exact_hessian) - { - ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "exact_hess", &nlp_solver_exact_hessian); - } + int nlp_solver_exact_hessian = 1; + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "exact_hess", &nlp_solver_exact_hessian); + int exact_hess_dyn = {{ solver_options.exact_hess_dyn }}; ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "exact_hess_dyn", &exact_hess_dyn); @@ -1861,6 +1914,8 @@ void {{ model.name }}_acados_create_6_set_opts({{ model.name }}_solver_capsule* ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "qp_cond_N", &qp_solver_cond_N); {%- endif %} + int nlp_solver_ext_qp_res = {{ solver_options.nlp_solver_ext_qp_res }}; + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "ext_qp_res", &nlp_solver_ext_qp_res); {%- if solver_options.qp_solver is containing("HPIPM") %} // set HPIPM mode: should be done before setting other QP solver options @@ -1920,6 +1975,15 @@ void {{ model.name }}_acados_create_6_set_opts({{ model.name }}_solver_capsule* int print_level = {{ solver_options.print_level }}; ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "print_level", &print_level); +{%- if solver_options.qp_solver is containing('PARTIAL_CONDENSING') %} + int qp_solver_cond_ric_alg = {{ solver_options.qp_solver_cond_ric_alg }}; + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "qp_cond_ric_alg", &qp_solver_cond_ric_alg); +{% endif %} + +{%- if solver_options.qp_solver == 'PARTIAL_CONDENSING_HPIPM' %} + int qp_solver_ric_alg = {{ solver_options.qp_solver_ric_alg }}; + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "qp_ric_alg", &qp_solver_ric_alg); +{% endif %} int ext_cost_num_hess = {{ solver_options.ext_cost_num_hess }}; {%- if cost.cost_type == "EXTERNAL" %} @@ -2042,6 +2106,12 @@ int {{ model.name }}_acados_create_with_discretization({{ model.name }}_solver_c // 9) do precomputations int status = {{ model.name }}_acados_create_9_precompute(capsule); + + {%- if custom_update_filename != "" %} + // Initialize custom update function + custom_update_init_function(capsule); + {%- endif %} + return status; } @@ -2076,7 +2146,7 @@ int {{ model.name }}_acados_update_qp_solver_cond_N({{ model.name }}_solver_caps } -int {{ model.name }}_acados_reset({{ model.name }}_solver_capsule* capsule) +int {{ model.name }}_acados_reset({{ model.name }}_solver_capsule* capsule, int reset_qp_solver_mem) { // set initialization to all zeros @@ -2088,8 +2158,6 @@ int {{ model.name }}_acados_reset({{ model.name }}_solver_capsule* capsule) ocp_nlp_in* nlp_in = capsule->nlp_in; ocp_nlp_solver* nlp_solver = capsule->nlp_solver; - int nx, nu, nv, ns, nz, ni, dim; - double* buffer = calloc(NX+NU+NZ+2*NS+2*NSN+NBX+NBU+NG+NH+NPHI+NBX0+NBXN+NHN+NPHIN+NGN, sizeof(double)); for(int i=0; i reset memory int qp_status; ocp_nlp_get(capsule->nlp_config, capsule->nlp_solver, "qp_status", &qp_status); - if (qp_status == 3) + if (reset_qp_solver_mem || (qp_status == 3)) { // printf("\nin reset qp_status %d -> resetting QP memory\n", qp_status); ocp_nlp_solver_reset_qp_memory(nlp_solver, nlp_in, nlp_out); @@ -2144,7 +2212,6 @@ int {{ model.name }}_acados_update_params({{ model.name }}_solver_capsule* capsu exit(1); } -{%- if dims.np > 0 %} const int N = capsule->nlp_solver_plan->N; if (stage < N && stage >= 0) { @@ -2201,6 +2268,9 @@ int {{ model.name }}_acados_update_params({{ model.name }}_solver_capsule* capsu capsule->cost_y_0_fun.set_param(&capsule->cost_y_0_fun, p); capsule->cost_y_0_fun_jac_ut_xt.set_param(&capsule->cost_y_0_fun_jac_ut_xt, p); capsule->cost_y_0_hess.set_param(&capsule->cost_y_0_hess, p); + {%- elif cost.cost_type_0 == "CONVEX_OVER_NONLINEAR" %} + capsule->conl_cost_0_fun.set_param(&capsule->conl_cost_0_fun, p); + capsule->conl_cost_0_fun_jac_hess.set_param(&capsule->conl_cost_0_fun_jac_hess, p); {%- elif cost.cost_type_0 == "EXTERNAL" %} capsule->ext_cost_0_fun.set_param(&capsule->ext_cost_0_fun, p); capsule->ext_cost_0_fun_jac.set_param(&capsule->ext_cost_0_fun_jac, p); @@ -2213,6 +2283,9 @@ int {{ model.name }}_acados_update_params({{ model.name }}_solver_capsule* capsu capsule->cost_y_fun[stage-1].set_param(capsule->cost_y_fun+stage-1, p); capsule->cost_y_fun_jac_ut_xt[stage-1].set_param(capsule->cost_y_fun_jac_ut_xt+stage-1, p); capsule->cost_y_hess[stage-1].set_param(capsule->cost_y_hess+stage-1, p); + {%- elif cost.cost_type == "CONVEX_OVER_NONLINEAR" %} + capsule->conl_cost_fun[stage-1].set_param(capsule->conl_cost_fun+stage-1, p); + capsule->conl_cost_fun_jac_hess[stage-1].set_param(capsule->conl_cost_fun_jac_hess+stage-1, p); {%- elif cost.cost_type == "EXTERNAL" %} capsule->ext_cost_fun[stage-1].set_param(capsule->ext_cost_fun+stage-1, p); capsule->ext_cost_fun_jac[stage-1].set_param(capsule->ext_cost_fun_jac+stage-1, p); @@ -2229,6 +2302,9 @@ int {{ model.name }}_acados_update_params({{ model.name }}_solver_capsule* capsu capsule->cost_y_e_fun.set_param(&capsule->cost_y_e_fun, p); capsule->cost_y_e_fun_jac_ut_xt.set_param(&capsule->cost_y_e_fun_jac_ut_xt, p); capsule->cost_y_e_hess.set_param(&capsule->cost_y_e_hess, p); + {%- elif cost.cost_type_e == "CONVEX_OVER_NONLINEAR" %} + capsule->conl_cost_e_fun.set_param(&capsule->conl_cost_e_fun, p); + capsule->conl_cost_e_fun_jac_hess.set_param(&capsule->conl_cost_e_fun_jac_hess, p); {%- elif cost.cost_type_e == "EXTERNAL" %} capsule->ext_cost_e_fun.set_param(&capsule->ext_cost_e_fun, p); capsule->ext_cost_e_fun_jac.set_param(&capsule->ext_cost_e_fun_jac, p); @@ -2245,16 +2321,149 @@ int {{ model.name }}_acados_update_params({{ model.name }}_solver_capsule* capsu {%- endif %} {% endif %} } -{% endif %}{# if dims.np #} return solver_status; } +int {{ model.name }}_acados_update_params_sparse({{ model.name }}_solver_capsule * capsule, int stage, int *idx, double *p, int n_update) +{ + int solver_status = 0; + + int casadi_np = {{ dims.np }}; + if (casadi_np < n_update) { + printf("{{ model.name }}_acados_update_params_sparse: trying to set %d parameters for external functions." + " External function has %d parameters. Exiting.\n", n_update, casadi_np); + exit(1); + } + // for (int i = 0; i < n_update; i++) + // { + // if (idx[i] > casadi_np) { + // printf("{{ model.name }}_acados_update_params_sparse: attempt to set parameters with index %d, while" + // " external functions only has %d parameters. Exiting.\n", idx[i], casadi_np); + // exit(1); + // } + // printf("param %d value %e\n", idx[i], p[i]); + // } + +{%- if dims.np > 0 %} + const int N = capsule->nlp_solver_plan->N; + if (stage < N && stage >= 0) + { + {%- if solver_options.integrator_type == "IRK" %} + capsule->impl_dae_fun[stage].set_param_sparse(capsule->impl_dae_fun+stage, n_update, idx, p); + capsule->impl_dae_fun_jac_x_xdot_z[stage].set_param_sparse(capsule->impl_dae_fun_jac_x_xdot_z+stage, n_update, idx, p); + capsule->impl_dae_jac_x_xdot_u_z[stage].set_param_sparse(capsule->impl_dae_jac_x_xdot_u_z+stage, n_update, idx, p); + + {%- if solver_options.hessian_approx == "EXACT" %} + capsule->impl_dae_hess[stage].set_param_sparse(capsule->impl_dae_hess+stage, n_update, idx, p); + {%- endif %} + {% elif solver_options.integrator_type == "LIFTED_IRK" %} + capsule->impl_dae_fun[stage].set_param_sparse(capsule->impl_dae_fun+stage, n_update, idx, p); + capsule->impl_dae_fun_jac_x_xdot_u[stage].set_param_sparse(capsule->impl_dae_fun_jac_x_xdot_u+stage, n_update, idx, p); + {% elif solver_options.integrator_type == "ERK" %} + capsule->forw_vde_casadi[stage].set_param_sparse(capsule->forw_vde_casadi+stage, n_update, idx, p); + capsule->expl_ode_fun[stage].set_param_sparse(capsule->expl_ode_fun+stage, n_update, idx, p); + + {%- if solver_options.hessian_approx == "EXACT" %} + capsule->hess_vde_casadi[stage].set_param_sparse(capsule->hess_vde_casadi+stage, n_update, idx, p); + {%- endif %} + {% elif solver_options.integrator_type == "GNSF" %} + {% if model.gnsf.purely_linear != 1 %} + capsule->gnsf_phi_fun[stage].set_param_sparse(capsule->gnsf_phi_fun+stage, n_update, idx, p); + capsule->gnsf_phi_fun_jac_y[stage].set_param_sparse(capsule->gnsf_phi_fun_jac_y+stage, n_update, idx, p); + capsule->gnsf_phi_jac_y_uhat[stage].set_param_sparse(capsule->gnsf_phi_jac_y_uhat+stage, n_update, idx, p); + {% if model.gnsf.nontrivial_f_LO == 1 %} + capsule->gnsf_f_lo_jac_x1_x1dot_u_z[stage].set_param_sparse(capsule->gnsf_f_lo_jac_x1_x1dot_u_z+stage, n_update, idx, p); + {%- endif %} + {%- endif %} + {% elif solver_options.integrator_type == "DISCRETE" %} + capsule->discr_dyn_phi_fun[stage].set_param_sparse(capsule->discr_dyn_phi_fun+stage, n_update, idx, p); + capsule->discr_dyn_phi_fun_jac_ut_xt[stage].set_param_sparse(capsule->discr_dyn_phi_fun_jac_ut_xt+stage, n_update, idx, p); + {%- if solver_options.hessian_approx == "EXACT" %} + capsule->discr_dyn_phi_fun_jac_ut_xt_hess[stage].set_param_sparse(capsule->discr_dyn_phi_fun_jac_ut_xt_hess+stage, n_update, idx, p); + {% endif %} + {%- endif %}{# integrator_type #} + + // constraints + {% if constraints.constr_type == "BGP" %} + capsule->phi_constraint[stage].set_param_sparse(capsule->phi_constraint+stage, n_update, idx, p); + {% elif constraints.constr_type == "BGH" and dims.nh > 0 %} + capsule->nl_constr_h_fun_jac[stage].set_param_sparse(capsule->nl_constr_h_fun_jac+stage, n_update, idx, p); + capsule->nl_constr_h_fun[stage].set_param_sparse(capsule->nl_constr_h_fun+stage, n_update, idx, p); + {%- if solver_options.hessian_approx == "EXACT" %} + capsule->nl_constr_h_fun_jac_hess[stage].set_param_sparse(capsule->nl_constr_h_fun_jac_hess+stage, n_update, idx, p); + {%- endif %} + {%- endif %} + + // cost + if (stage == 0) + { + {%- if cost.cost_type_0 == "NONLINEAR_LS" %} + capsule->cost_y_0_fun.set_param_sparse(&capsule->cost_y_0_fun, n_update, idx, p); + capsule->cost_y_0_fun_jac_ut_xt.set_param_sparse(&capsule->cost_y_0_fun_jac_ut_xt, n_update, idx, p); + capsule->cost_y_0_hess.set_param_sparse(&capsule->cost_y_0_hess, n_update, idx, p); + {%- elif cost.cost_type_0 == "CONVEX_OVER_NONLINEAR" %} + capsule->conl_cost_0_fun.set_param_sparse(&capsule->conl_cost_0_fun, n_update, idx, p); + capsule->conl_cost_0_fun_jac_hess.set_param_sparse(&capsule->conl_cost_0_fun_jac_hess, n_update, idx, p); + {%- elif cost.cost_type_0 == "EXTERNAL" %} + capsule->ext_cost_0_fun.set_param_sparse(&capsule->ext_cost_0_fun, n_update, idx, p); + capsule->ext_cost_0_fun_jac.set_param_sparse(&capsule->ext_cost_0_fun_jac, n_update, idx, p); + capsule->ext_cost_0_fun_jac_hess.set_param_sparse(&capsule->ext_cost_0_fun_jac_hess, n_update, idx, p); + {% endif %} + } + else // 0 < stage < N + { + {%- if cost.cost_type == "NONLINEAR_LS" %} + capsule->cost_y_fun[stage-1].set_param_sparse(capsule->cost_y_fun+stage-1, n_update, idx, p); + capsule->cost_y_fun_jac_ut_xt[stage-1].set_param_sparse(capsule->cost_y_fun_jac_ut_xt+stage-1, n_update, idx, p); + capsule->cost_y_hess[stage-1].set_param_sparse(capsule->cost_y_hess+stage-1, n_update, idx, p); + {%- elif cost.cost_type == "CONVEX_OVER_NONLINEAR" %} + capsule->conl_cost_fun[stage-1].set_param_sparse(capsule->conl_cost_fun+stage-1, n_update, idx, p); + capsule->conl_cost_fun_jac_hess[stage-1].set_param_sparse(capsule->conl_cost_fun_jac_hess+stage-1, n_update, idx, p); + {%- elif cost.cost_type == "EXTERNAL" %} + capsule->ext_cost_fun[stage-1].set_param_sparse(capsule->ext_cost_fun+stage-1, n_update, idx, p); + capsule->ext_cost_fun_jac[stage-1].set_param_sparse(capsule->ext_cost_fun_jac+stage-1, n_update, idx, p); + capsule->ext_cost_fun_jac_hess[stage-1].set_param_sparse(capsule->ext_cost_fun_jac_hess+stage-1, n_update, idx, p); + {%- endif %} + } + } + + else // stage == N + { + // terminal shooting node has no dynamics + // cost + {%- if cost.cost_type_e == "NONLINEAR_LS" %} + capsule->cost_y_e_fun.set_param_sparse(&capsule->cost_y_e_fun, n_update, idx, p); + capsule->cost_y_e_fun_jac_ut_xt.set_param_sparse(&capsule->cost_y_e_fun_jac_ut_xt, n_update, idx, p); + capsule->cost_y_e_hess.set_param_sparse(&capsule->cost_y_e_hess, n_update, idx, p); + {%- elif cost.cost_type_e == "CONVEX_OVER_NONLINEAR" %} + capsule->conl_cost_e_fun.set_param_sparse(&capsule->conl_cost_e_fun, n_update, idx, p); + capsule->conl_cost_e_fun_jac_hess.set_param_sparse(&capsule->conl_cost_e_fun_jac_hess, n_update, idx, p); + {%- elif cost.cost_type_e == "EXTERNAL" %} + capsule->ext_cost_e_fun.set_param_sparse(&capsule->ext_cost_e_fun, n_update, idx, p); + capsule->ext_cost_e_fun_jac.set_param_sparse(&capsule->ext_cost_e_fun_jac, n_update, idx, p); + capsule->ext_cost_e_fun_jac_hess.set_param_sparse(&capsule->ext_cost_e_fun_jac_hess, n_update, idx, p); + {% endif %} + // constraints + {% if constraints.constr_type_e == "BGP" %} + capsule->phi_e_constraint.set_param_sparse(&capsule->phi_e_constraint, n_update, idx, p); + {% elif constraints.constr_type_e == "BGH" and dims.nh_e > 0 %} + capsule->nl_constr_h_e_fun_jac.set_param_sparse(&capsule->nl_constr_h_e_fun_jac, n_update, idx, p); + capsule->nl_constr_h_e_fun.set_param_sparse(&capsule->nl_constr_h_e_fun, n_update, idx, p); + {%- if solver_options.hessian_approx == "EXACT" %} + capsule->nl_constr_h_e_fun_jac_hess.set_param_sparse(&capsule->nl_constr_h_e_fun_jac_hess, n_update, idx, p); + {%- endif %} + {% endif %} + } +{% endif %}{# if dims.np #} + + return solver_status; +} int {{ model.name }}_acados_solve({{ model.name }}_solver_capsule* capsule) { - // solve NLP + // solve NLP int solver_status = ocp_nlp_solve(capsule->nlp_solver, capsule->nlp_in, capsule->nlp_out); return solver_status; @@ -2265,6 +2474,9 @@ int {{ model.name }}_acados_free({{ model.name }}_solver_capsule* capsule) { // before destroying, keep some info const int N = capsule->nlp_solver_plan->N; + {%- if custom_update_filename != "" %} + custom_update_terminate_function(capsule); + {%- endif %} // free memory ocp_nlp_solver_opts_destroy(capsule->nlp_opts); ocp_nlp_in_destroy(capsule->nlp_in); @@ -2280,11 +2492,11 @@ int {{ model.name }}_acados_free({{ model.name }}_solver_capsule* capsule) {%- if solver_options.integrator_type == "IRK" %} for (int i = 0; i < N; i++) { - external_function_param_casadi_free(&capsule->impl_dae_fun[i]); - external_function_param_casadi_free(&capsule->impl_dae_fun_jac_x_xdot_z[i]); - external_function_param_casadi_free(&capsule->impl_dae_jac_x_xdot_u_z[i]); + external_function_param_{{ model.dyn_ext_fun_type }}_free(&capsule->impl_dae_fun[i]); + external_function_param_{{ model.dyn_ext_fun_type }}_free(&capsule->impl_dae_fun_jac_x_xdot_z[i]); + external_function_param_{{ model.dyn_ext_fun_type }}_free(&capsule->impl_dae_jac_x_xdot_u_z[i]); {%- if solver_options.hessian_approx == "EXACT" %} - external_function_param_casadi_free(&capsule->impl_dae_hess[i]); + external_function_param_{{ model.dyn_ext_fun_type }}_free(&capsule->impl_dae_hess[i]); {%- endif %} } free(capsule->impl_dae_fun); @@ -2297,8 +2509,8 @@ int {{ model.name }}_acados_free({{ model.name }}_solver_capsule* capsule) {%- elif solver_options.integrator_type == "LIFTED_IRK" %} for (int i = 0; i < N; i++) { - external_function_param_casadi_free(&capsule->impl_dae_fun[i]); - external_function_param_casadi_free(&capsule->impl_dae_fun_jac_x_xdot_u[i]); + external_function_param_{{ model.dyn_ext_fun_type }}_free(&capsule->impl_dae_fun[i]); + external_function_param_{{ model.dyn_ext_fun_type }}_free(&capsule->impl_dae_fun_jac_x_xdot_u[i]); } free(capsule->impl_dae_fun); free(capsule->impl_dae_fun_jac_x_xdot_u); @@ -2354,7 +2566,7 @@ int {{ model.name }}_acados_free({{ model.name }}_solver_capsule* capsule) {%- if solver_options.hessian_approx == "EXACT" %} free(capsule->discr_dyn_phi_fun_jac_ut_xt_hess); {%- endif %} - + {%- endif %} // cost @@ -2362,6 +2574,9 @@ int {{ model.name }}_acados_free({{ model.name }}_solver_capsule* capsule) external_function_param_casadi_free(&capsule->cost_y_0_fun); external_function_param_casadi_free(&capsule->cost_y_0_fun_jac_ut_xt); external_function_param_casadi_free(&capsule->cost_y_0_hess); +{%- elif cost.cost_type_0 == "CONVEX_OVER_NONLINEAR" %} + external_function_param_casadi_free(&capsule->conl_cost_0_fun); + external_function_param_casadi_free(&capsule->conl_cost_0_fun_jac_hess); {%- elif cost.cost_type_0 == "EXTERNAL" %} external_function_param_{{ cost.cost_ext_fun_type_0 }}_free(&capsule->ext_cost_0_fun); external_function_param_{{ cost.cost_ext_fun_type_0 }}_free(&capsule->ext_cost_0_fun_jac); @@ -2377,6 +2592,14 @@ int {{ model.name }}_acados_free({{ model.name }}_solver_capsule* capsule) free(capsule->cost_y_fun); free(capsule->cost_y_fun_jac_ut_xt); free(capsule->cost_y_hess); +{%- elif cost.cost_type == "CONVEX_OVER_NONLINEAR" %} + for (int i = 0; i < N - 1; i++) + { + external_function_param_casadi_free(&capsule->conl_cost_fun[i]); + external_function_param_casadi_free(&capsule->conl_cost_fun_jac_hess[i]); + } + free(capsule->conl_cost_fun); + free(capsule->conl_cost_fun_jac_hess); {%- elif cost.cost_type == "EXTERNAL" %} for (int i = 0; i < N - 1; i++) { @@ -2392,6 +2615,9 @@ int {{ model.name }}_acados_free({{ model.name }}_solver_capsule* capsule) external_function_param_casadi_free(&capsule->cost_y_e_fun); external_function_param_casadi_free(&capsule->cost_y_e_fun_jac_ut_xt); external_function_param_casadi_free(&capsule->cost_y_e_hess); +{%- elif cost.cost_type_e == "CONVEX_OVER_NONLINEAR" %} + external_function_param_casadi_free(&capsule->conl_cost_e_fun); + external_function_param_casadi_free(&capsule->conl_cost_e_fun_jac_hess); {%- elif cost.cost_type_e == "EXTERNAL" %} external_function_param_{{ cost.cost_ext_fun_type_e }}_free(&capsule->ext_cost_e_fun); external_function_param_{{ cost.cost_ext_fun_type_e }}_free(&capsule->ext_cost_e_fun_jac); @@ -2438,15 +2664,6 @@ int {{ model.name }}_acados_free({{ model.name }}_solver_capsule* capsule) return 0; } -ocp_nlp_in *{{ model.name }}_acados_get_nlp_in({{ model.name }}_solver_capsule* capsule) { return capsule->nlp_in; } -ocp_nlp_out *{{ model.name }}_acados_get_nlp_out({{ model.name }}_solver_capsule* capsule) { return capsule->nlp_out; } -ocp_nlp_out *{{ model.name }}_acados_get_sens_out({{ model.name }}_solver_capsule* capsule) { return capsule->sens_out; } -ocp_nlp_solver *{{ model.name }}_acados_get_nlp_solver({{ model.name }}_solver_capsule* capsule) { return capsule->nlp_solver; } -ocp_nlp_config *{{ model.name }}_acados_get_nlp_config({{ model.name }}_solver_capsule* capsule) { return capsule->nlp_config; } -void *{{ model.name }}_acados_get_nlp_opts({{ model.name }}_solver_capsule* capsule) { return capsule->nlp_opts; } -ocp_nlp_dims *{{ model.name }}_acados_get_nlp_dims({{ model.name }}_solver_capsule* capsule) { return capsule->nlp_dims; } -ocp_nlp_plan_t *{{ model.name }}_acados_get_nlp_plan({{ model.name }}_solver_capsule* capsule) { return capsule->nlp_solver_plan; } - void {{ model.name }}_acados_print_stats({{ model.name }}_solver_capsule* capsule) { @@ -2461,8 +2678,13 @@ void {{ model.name }}_acados_print_stats({{ model.name }}_solver_capsule* capsul int nrow = sqp_iter+1 < stat_m ? sqp_iter+1 : stat_m; + printf("iter\tres_stat\tres_eq\t\tres_ineq\tres_comp\tqp_stat\tqp_iter\talpha"); + if (stat_n > 8) + printf("\t\tqp_res_stat\tqp_res_eq\tqp_res_ineq\tqp_res_comp"); + printf("\n"); + {%- if solver_options.nlp_solver_type == "SQP" %} - printf("iter\tres_stat\tres_eq\t\tres_ineq\tres_comp\tqp_stat\tqp_iter\talpha\n"); + for (int i = 0; i < nrow; i++) { for (int j = 0; j < stat_n + 1; j++) @@ -2493,3 +2715,27 @@ void {{ model.name }}_acados_print_stats({{ model.name }}_solver_capsule* capsul {%- endif %} } +int {{ model.name }}_acados_custom_update({{ model.name }}_solver_capsule* capsule, double* data, int data_len) +{ +{%- if custom_update_filename == "" %} + (void)capsule; + (void)data; + (void)data_len; + printf("\ndummy function that can be called in between solver calls to update parameters or numerical data efficiently in C.\n"); + printf("nothing set yet..\n"); + return 1; +{% else %} + custom_update_function(capsule, data, data_len); +{%- endif %} +} + + + +ocp_nlp_in *{{ model.name }}_acados_get_nlp_in({{ model.name }}_solver_capsule* capsule) { return capsule->nlp_in; } +ocp_nlp_out *{{ model.name }}_acados_get_nlp_out({{ model.name }}_solver_capsule* capsule) { return capsule->nlp_out; } +ocp_nlp_out *{{ model.name }}_acados_get_sens_out({{ model.name }}_solver_capsule* capsule) { return capsule->sens_out; } +ocp_nlp_solver *{{ model.name }}_acados_get_nlp_solver({{ model.name }}_solver_capsule* capsule) { return capsule->nlp_solver; } +ocp_nlp_config *{{ model.name }}_acados_get_nlp_config({{ model.name }}_solver_capsule* capsule) { return capsule->nlp_config; } +void *{{ model.name }}_acados_get_nlp_opts({{ model.name }}_solver_capsule* capsule) { return capsule->nlp_opts; } +ocp_nlp_dims *{{ model.name }}_acados_get_nlp_dims({{ model.name }}_solver_capsule* capsule) { return capsule->nlp_dims; } +ocp_nlp_plan_t *{{ model.name }}_acados_get_nlp_plan({{ model.name }}_solver_capsule* capsule) { return capsule->nlp_solver_plan; } diff --git a/third_party/acados/acados_template/c_templates_tera/acados_solver.in.h b/third_party/acados/acados_template/c_templates_tera/acados_solver.in.h index 1c82ef3ba..5cf38aa8c 100644 --- a/third_party/acados/acados_template/c_templates_tera/acados_solver.in.h +++ b/third_party/acados/acados_template/c_templates_tera/acados_solver.in.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * @@ -74,6 +71,12 @@ extern "C" { #endif +{%- if not solver_options.custom_update_filename %} + {%- set custom_update_filename = "" %} +{% else %} + {%- set custom_update_filename = solver_options.custom_update_filename %} +{%- endif %} + // ** capsule for solver data ** typedef struct {{ model.name }}_solver_capsule { @@ -99,15 +102,15 @@ typedef struct {{ model.name }}_solver_capsule external_function_param_casadi *hess_vde_casadi; {%- endif %} {% elif solver_options.integrator_type == "IRK" %} - external_function_param_casadi *impl_dae_fun; - external_function_param_casadi *impl_dae_fun_jac_x_xdot_z; - external_function_param_casadi *impl_dae_jac_x_xdot_u_z; + external_function_param_{{ model.dyn_ext_fun_type }} *impl_dae_fun; + external_function_param_{{ model.dyn_ext_fun_type }} *impl_dae_fun_jac_x_xdot_z; + external_function_param_{{ model.dyn_ext_fun_type }} *impl_dae_jac_x_xdot_u_z; {% if solver_options.hessian_approx == "EXACT" %} - external_function_param_casadi *impl_dae_hess; + external_function_param_{{ model.dyn_ext_fun_type }} *impl_dae_hess; {%- endif %} {% elif solver_options.integrator_type == "LIFTED_IRK" %} - external_function_param_casadi *impl_dae_fun; - external_function_param_casadi *impl_dae_fun_jac_x_xdot_u; + external_function_param_{{ model.dyn_ext_fun_type }} *impl_dae_fun; + external_function_param_{{ model.dyn_ext_fun_type }} *impl_dae_fun_jac_x_xdot_u; {% elif solver_options.integrator_type == "GNSF" %} external_function_param_casadi *gnsf_phi_fun; external_function_param_casadi *gnsf_phi_fun_jac_y; @@ -128,6 +131,9 @@ typedef struct {{ model.name }}_solver_capsule external_function_param_casadi *cost_y_fun; external_function_param_casadi *cost_y_fun_jac_ut_xt; external_function_param_casadi *cost_y_hess; +{% elif cost.cost_type == "CONVEX_OVER_NONLINEAR" %} + external_function_param_casadi *conl_cost_fun; + external_function_param_casadi *conl_cost_fun_jac_hess; {%- elif cost.cost_type == "EXTERNAL" %} external_function_param_{{ cost.cost_ext_fun_type }} *ext_cost_fun; external_function_param_{{ cost.cost_ext_fun_type }} *ext_cost_fun_jac; @@ -138,6 +144,9 @@ typedef struct {{ model.name }}_solver_capsule external_function_param_casadi cost_y_0_fun; external_function_param_casadi cost_y_0_fun_jac_ut_xt; external_function_param_casadi cost_y_0_hess; +{% elif cost.cost_type_0 == "CONVEX_OVER_NONLINEAR" %} + external_function_param_casadi conl_cost_0_fun; + external_function_param_casadi conl_cost_0_fun_jac_hess; {% elif cost.cost_type_0 == "EXTERNAL" %} external_function_param_{{ cost.cost_ext_fun_type_0 }} ext_cost_0_fun; external_function_param_{{ cost.cost_ext_fun_type_0 }} ext_cost_0_fun_jac; @@ -148,6 +157,9 @@ typedef struct {{ model.name }}_solver_capsule external_function_param_casadi cost_y_e_fun; external_function_param_casadi cost_y_e_fun_jac_ut_xt; external_function_param_casadi cost_y_e_hess; +{% elif cost.cost_type_e == "CONVEX_OVER_NONLINEAR" %} + external_function_param_casadi conl_cost_e_fun; + external_function_param_casadi conl_cost_e_fun_jac_hess; {% elif cost.cost_type_e == "EXTERNAL" %} external_function_param_{{ cost.cost_ext_fun_type_e }} ext_cost_e_fun; external_function_param_{{ cost.cost_ext_fun_type_e }} ext_cost_e_fun_jac; @@ -160,8 +172,10 @@ typedef struct {{ model.name }}_solver_capsule {% elif constraints.constr_type == "BGH" and dims.nh > 0 %} external_function_param_casadi *nl_constr_h_fun_jac; external_function_param_casadi *nl_constr_h_fun; +{%- if solver_options.hessian_approx == "EXACT" %} external_function_param_casadi *nl_constr_h_fun_jac_hess; {%- endif %} +{%- endif %} {% if constraints.constr_type_e == "BGP" %} @@ -169,8 +183,14 @@ typedef struct {{ model.name }}_solver_capsule {% elif constraints.constr_type_e == "BGH" and dims.nh_e > 0 %} external_function_param_casadi nl_constr_h_e_fun_jac; external_function_param_casadi nl_constr_h_e_fun; +{%- if solver_options.hessian_approx == "EXACT" %} external_function_param_casadi nl_constr_h_e_fun_jac_hess; {%- endif %} +{%- endif %} + +{%- if custom_update_filename != "" %} + void * custom_update_memory; +{%- endif %} } {{ model.name }}_solver_capsule; @@ -179,7 +199,7 @@ ACADOS_SYMBOL_EXPORT int {{ model.name }}_acados_free_capsule({{ model.name }}_s ACADOS_SYMBOL_EXPORT int {{ model.name }}_acados_create({{ model.name }}_solver_capsule * capsule); -ACADOS_SYMBOL_EXPORT int {{ model.name }}_acados_reset({{ model.name }}_solver_capsule* capsule); +ACADOS_SYMBOL_EXPORT int {{ model.name }}_acados_reset({{ model.name }}_solver_capsule* capsule, int reset_qp_solver_mem); /** * Generic version of {{ model.name }}_acados_create which allows to use a different number of shooting intervals than @@ -197,10 +217,14 @@ ACADOS_SYMBOL_EXPORT int {{ model.name }}_acados_update_time_steps({{ model.name */ ACADOS_SYMBOL_EXPORT int {{ model.name }}_acados_update_qp_solver_cond_N({{ model.name }}_solver_capsule * capsule, int qp_solver_cond_N); ACADOS_SYMBOL_EXPORT int {{ model.name }}_acados_update_params({{ model.name }}_solver_capsule * capsule, int stage, double *value, int np); +ACADOS_SYMBOL_EXPORT int {{ model.name }}_acados_update_params_sparse({{ model.name }}_solver_capsule * capsule, int stage, int *idx, double *p, int n_update); + ACADOS_SYMBOL_EXPORT int {{ model.name }}_acados_solve({{ model.name }}_solver_capsule * capsule); ACADOS_SYMBOL_EXPORT int {{ model.name }}_acados_free({{ model.name }}_solver_capsule * capsule); ACADOS_SYMBOL_EXPORT void {{ model.name }}_acados_print_stats({{ model.name }}_solver_capsule * capsule); - +ACADOS_SYMBOL_EXPORT int {{ model.name }}_acados_custom_update({{ model.name }}_solver_capsule* capsule, double* data, int data_len); + + ACADOS_SYMBOL_EXPORT ocp_nlp_in *{{ model.name }}_acados_get_nlp_in({{ model.name }}_solver_capsule * capsule); ACADOS_SYMBOL_EXPORT ocp_nlp_out *{{ model.name }}_acados_get_nlp_out({{ model.name }}_solver_capsule * capsule); ACADOS_SYMBOL_EXPORT ocp_nlp_out *{{ model.name }}_acados_get_sens_out({{ model.name }}_solver_capsule * capsule); diff --git a/third_party/acados/acados_template/c_templates_tera/acados_solver.in.pxd b/third_party/acados/acados_template/c_templates_tera/acados_solver.in.pxd index 09f8755cb..233e3f79d 100644 --- a/third_party/acados/acados_template/c_templates_tera/acados_solver.in.pxd +++ b/third_party/acados/acados_template/c_templates_tera/acados_solver.in.pxd @@ -1,8 +1,5 @@ # -# Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, -# Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, -# Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, -# Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl +# Copyright (c) The acados authors. # # This file is part of acados. # @@ -47,11 +44,14 @@ cdef extern from "acados_solver_{{ model.name }}.h": int acados_update_qp_solver_cond_N "{{ model.name }}_acados_update_qp_solver_cond_N"(nlp_solver_capsule * capsule, int qp_solver_cond_N) int acados_update_params "{{ model.name }}_acados_update_params"(nlp_solver_capsule * capsule, int stage, double *value, int np_) + int acados_update_params_sparse "{{ model.name }}_acados_update_params_sparse"(nlp_solver_capsule * capsule, int stage, int *idx, double *p, int n_update) int acados_solve "{{ model.name }}_acados_solve"(nlp_solver_capsule * capsule) - int acados_reset "{{ model.name }}_acados_reset"(nlp_solver_capsule * capsule) + int acados_reset "{{ model.name }}_acados_reset"(nlp_solver_capsule * capsule, int reset_qp_solver_mem) int acados_free "{{ model.name }}_acados_free"(nlp_solver_capsule * capsule) void acados_print_stats "{{ model.name }}_acados_print_stats"(nlp_solver_capsule * capsule) + int acados_custom_update "{{ model.name }}_acados_custom_update"(nlp_solver_capsule* capsule, double * data, int data_len) + acados_solver_common.ocp_nlp_in *acados_get_nlp_in "{{ model.name }}_acados_get_nlp_in"(nlp_solver_capsule * capsule) acados_solver_common.ocp_nlp_out *acados_get_nlp_out "{{ model.name }}_acados_get_nlp_out"(nlp_solver_capsule * capsule) acados_solver_common.ocp_nlp_out *acados_get_sens_out "{{ model.name }}_acados_get_sens_out"(nlp_solver_capsule * capsule) diff --git a/third_party/acados/acados_template/c_templates_tera/h_e_constraint.in.h b/third_party/acados/acados_template/c_templates_tera/constraints.in.h similarity index 54% rename from third_party/acados/acados_template/c_templates_tera/h_e_constraint.in.h rename to third_party/acados/acados_template/c_templates_tera/constraints.in.h index a5dd71164..d71ce5cc2 100644 --- a/third_party/acados/acados_template/c_templates_tera/h_e_constraint.in.h +++ b/third_party/acados/acados_template/c_templates_tera/constraints.in.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * @@ -31,14 +28,56 @@ * POSSIBILITY OF SUCH DAMAGE.; */ - -#ifndef {{ model.name }}_H_E_CONSTRAINT -#define {{ model.name }}_H_E_CONSTRAINT +#ifndef {{ model.name }}_CONSTRAINTS +#define {{ model.name }}_CONSTRAINTS #ifdef __cplusplus extern "C" { #endif +{% if dims.nphi > 0 %} +int {{ model.name }}_phi_constraint(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); +int {{ model.name }}_phi_constraint_work(int *, int *, int *, int *); +const int *{{ model.name }}_phi_constraint_sparsity_in(int); +const int *{{ model.name }}_phi_constraint_sparsity_out(int); +int {{ model.name }}_phi_constraint_n_in(void); +int {{ model.name }}_phi_constraint_n_out(void); +{% endif %} + +{% if dims.nphi_e > 0 %} +int {{ model.name }}_phi_e_constraint(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); +int {{ model.name }}_phi_e_constraint_work(int *, int *, int *, int *); +const int *{{ model.name }}_phi_e_constraint_sparsity_in(int); +const int *{{ model.name }}_phi_e_constraint_sparsity_out(int); +int {{ model.name }}_phi_e_constraint_n_in(void); +int {{ model.name }}_phi_e_constraint_n_out(void); +{% endif %} + +{% if dims.nh > 0 %} +int {{ model.name }}_constr_h_fun_jac_uxt_zt(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); +int {{ model.name }}_constr_h_fun_jac_uxt_zt_work(int *, int *, int *, int *); +const int *{{ model.name }}_constr_h_fun_jac_uxt_zt_sparsity_in(int); +const int *{{ model.name }}_constr_h_fun_jac_uxt_zt_sparsity_out(int); +int {{ model.name }}_constr_h_fun_jac_uxt_zt_n_in(void); +int {{ model.name }}_constr_h_fun_jac_uxt_zt_n_out(void); + +int {{ model.name }}_constr_h_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); +int {{ model.name }}_constr_h_fun_work(int *, int *, int *, int *); +const int *{{ model.name }}_constr_h_fun_sparsity_in(int); +const int *{{ model.name }}_constr_h_fun_sparsity_out(int); +int {{ model.name }}_constr_h_fun_n_in(void); +int {{ model.name }}_constr_h_fun_n_out(void); + +{% if solver_options.hessian_approx == "EXACT" -%} +int {{ model.name }}_constr_h_fun_jac_uxt_zt_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); +int {{ model.name }}_constr_h_fun_jac_uxt_zt_hess_work(int *, int *, int *, int *); +const int *{{ model.name }}_constr_h_fun_jac_uxt_zt_hess_sparsity_in(int); +const int *{{ model.name }}_constr_h_fun_jac_uxt_zt_hess_sparsity_out(int); +int {{ model.name }}_constr_h_fun_jac_uxt_zt_hess_n_in(void); +int {{ model.name }}_constr_h_fun_jac_uxt_zt_hess_n_out(void); +{% endif %} +{% endif %} + {% if dims.nh_e > 0 %} int {{ model.name }}_constr_h_e_fun_jac_uxt_zt(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); int {{ model.name }}_constr_h_e_fun_jac_uxt_zt_work(int *, int *, int *, int *); @@ -68,4 +107,4 @@ int {{ model.name }}_constr_h_e_fun_jac_uxt_zt_hess_n_out(void); } /* extern "C" */ #endif -#endif // {{ model.name }}_H_E_CONSTRAINT +#endif // {{ model.name }}_CONSTRAINTS diff --git a/third_party/acados/acados_template/c_templates_tera/cost.in.h b/third_party/acados/acados_template/c_templates_tera/cost.in.h new file mode 100644 index 000000000..45eb09c12 --- /dev/null +++ b/third_party/acados/acados_template/c_templates_tera/cost.in.h @@ -0,0 +1,238 @@ +/* + * Copyright (c) The acados authors. + * + * This file is part of acados. + * + * 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 HOLDER 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.; + */ + + +#ifndef {{ model.name }}_COST +#define {{ model.name }}_COST + +#ifdef __cplusplus +extern "C" { +#endif + + +// Cost at initial shooting node +{% if cost.cost_type_0 == "NONLINEAR_LS" %} +int {{ model.name }}_cost_y_0_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); +int {{ model.name }}_cost_y_0_fun_work(int *, int *, int *, int *); +const int *{{ model.name }}_cost_y_0_fun_sparsity_in(int); +const int *{{ model.name }}_cost_y_0_fun_sparsity_out(int); +int {{ model.name }}_cost_y_0_fun_n_in(void); +int {{ model.name }}_cost_y_0_fun_n_out(void); + +int {{ model.name }}_cost_y_0_fun_jac_ut_xt(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); +int {{ model.name }}_cost_y_0_fun_jac_ut_xt_work(int *, int *, int *, int *); +const int *{{ model.name }}_cost_y_0_fun_jac_ut_xt_sparsity_in(int); +const int *{{ model.name }}_cost_y_0_fun_jac_ut_xt_sparsity_out(int); +int {{ model.name }}_cost_y_0_fun_jac_ut_xt_n_in(void); +int {{ model.name }}_cost_y_0_fun_jac_ut_xt_n_out(void); + +int {{ model.name }}_cost_y_0_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); +int {{ model.name }}_cost_y_0_hess_work(int *, int *, int *, int *); +const int *{{ model.name }}_cost_y_0_hess_sparsity_in(int); +const int *{{ model.name }}_cost_y_0_hess_sparsity_out(int); +int {{ model.name }}_cost_y_0_hess_n_in(void); +int {{ model.name }}_cost_y_0_hess_n_out(void); +{% elif cost.cost_type_0 == "CONVEX_OVER_NONLINEAR" %} + +int {{ model.name }}_conl_cost_0_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); +int {{ model.name }}_conl_cost_0_fun_work(int *, int *, int *, int *); +const int *{{ model.name }}_conl_cost_0_fun_sparsity_in(int); +const int *{{ model.name }}_conl_cost_0_fun_sparsity_out(int); +int {{ model.name }}_conl_cost_0_fun_n_in(void); +int {{ model.name }}_conl_cost_0_fun_n_out(void); + +int {{ model.name }}_conl_cost_0_fun_jac_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); +int {{ model.name }}_conl_cost_0_fun_jac_hess_work(int *, int *, int *, int *); +const int *{{ model.name }}_conl_cost_0_fun_jac_hess_sparsity_in(int); +const int *{{ model.name }}_conl_cost_0_fun_jac_hess_sparsity_out(int); +int {{ model.name }}_conl_cost_0_fun_jac_hess_n_in(void); +int {{ model.name }}_conl_cost_0_fun_jac_hess_n_out(void); + +{% elif cost.cost_type_0 == "EXTERNAL" %} + {%- if cost.cost_ext_fun_type_0 == "casadi" %} +int {{ model.name }}_cost_ext_cost_0_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); +int {{ model.name }}_cost_ext_cost_0_fun_work(int *, int *, int *, int *); +const int *{{ model.name }}_cost_ext_cost_0_fun_sparsity_in(int); +const int *{{ model.name }}_cost_ext_cost_0_fun_sparsity_out(int); +int {{ model.name }}_cost_ext_cost_0_fun_n_in(void); +int {{ model.name }}_cost_ext_cost_0_fun_n_out(void); + +int {{ model.name }}_cost_ext_cost_0_fun_jac_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); +int {{ model.name }}_cost_ext_cost_0_fun_jac_hess_work(int *, int *, int *, int *); +const int *{{ model.name }}_cost_ext_cost_0_fun_jac_hess_sparsity_in(int); +const int *{{ model.name }}_cost_ext_cost_0_fun_jac_hess_sparsity_out(int); +int {{ model.name }}_cost_ext_cost_0_fun_jac_hess_n_in(void); +int {{ model.name }}_cost_ext_cost_0_fun_jac_hess_n_out(void); + +int {{ model.name }}_cost_ext_cost_0_fun_jac(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); +int {{ model.name }}_cost_ext_cost_0_fun_jac_work(int *, int *, int *, int *); +const int *{{ model.name }}_cost_ext_cost_0_fun_jac_sparsity_in(int); +const int *{{ model.name }}_cost_ext_cost_0_fun_jac_sparsity_out(int); +int {{ model.name }}_cost_ext_cost_0_fun_jac_n_in(void); +int {{ model.name }}_cost_ext_cost_0_fun_jac_n_out(void); + {%- else %} +int {{ cost.cost_function_ext_cost_0 }}(void **, void **, void *); + {%- endif %} +{% endif %} + + +// Cost at path shooting node +{% if cost.cost_type == "NONLINEAR_LS" %} +int {{ model.name }}_cost_y_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); +int {{ model.name }}_cost_y_fun_work(int *, int *, int *, int *); +const int *{{ model.name }}_cost_y_fun_sparsity_in(int); +const int *{{ model.name }}_cost_y_fun_sparsity_out(int); +int {{ model.name }}_cost_y_fun_n_in(void); +int {{ model.name }}_cost_y_fun_n_out(void); + +int {{ model.name }}_cost_y_fun_jac_ut_xt(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); +int {{ model.name }}_cost_y_fun_jac_ut_xt_work(int *, int *, int *, int *); +const int *{{ model.name }}_cost_y_fun_jac_ut_xt_sparsity_in(int); +const int *{{ model.name }}_cost_y_fun_jac_ut_xt_sparsity_out(int); +int {{ model.name }}_cost_y_fun_jac_ut_xt_n_in(void); +int {{ model.name }}_cost_y_fun_jac_ut_xt_n_out(void); + +int {{ model.name }}_cost_y_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); +int {{ model.name }}_cost_y_hess_work(int *, int *, int *, int *); +const int *{{ model.name }}_cost_y_hess_sparsity_in(int); +const int *{{ model.name }}_cost_y_hess_sparsity_out(int); +int {{ model.name }}_cost_y_hess_n_in(void); +int {{ model.name }}_cost_y_hess_n_out(void); + +{% elif cost.cost_type == "CONVEX_OVER_NONLINEAR" %} +int {{ model.name }}_conl_cost_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); +int {{ model.name }}_conl_cost_fun_work(int *, int *, int *, int *); +const int *{{ model.name }}_conl_cost_fun_sparsity_in(int); +const int *{{ model.name }}_conl_cost_fun_sparsity_out(int); +int {{ model.name }}_conl_cost_fun_n_in(void); +int {{ model.name }}_conl_cost_fun_n_out(void); + +int {{ model.name }}_conl_cost_fun_jac_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); +int {{ model.name }}_conl_cost_fun_jac_hess_work(int *, int *, int *, int *); +const int *{{ model.name }}_conl_cost_fun_jac_hess_sparsity_in(int); +const int *{{ model.name }}_conl_cost_fun_jac_hess_sparsity_out(int); +int {{ model.name }}_conl_cost_fun_jac_hess_n_in(void); +int {{ model.name }}_conl_cost_fun_jac_hess_n_out(void); +{% elif cost.cost_type == "EXTERNAL" %} + {%- if cost.cost_ext_fun_type == "casadi" %} +int {{ model.name }}_cost_ext_cost_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); +int {{ model.name }}_cost_ext_cost_fun_work(int *, int *, int *, int *); +const int *{{ model.name }}_cost_ext_cost_fun_sparsity_in(int); +const int *{{ model.name }}_cost_ext_cost_fun_sparsity_out(int); +int {{ model.name }}_cost_ext_cost_fun_n_in(void); +int {{ model.name }}_cost_ext_cost_fun_n_out(void); + +int {{ model.name }}_cost_ext_cost_fun_jac_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); +int {{ model.name }}_cost_ext_cost_fun_jac_hess_work(int *, int *, int *, int *); +const int *{{ model.name }}_cost_ext_cost_fun_jac_hess_sparsity_in(int); +const int *{{ model.name }}_cost_ext_cost_fun_jac_hess_sparsity_out(int); +int {{ model.name }}_cost_ext_cost_fun_jac_hess_n_in(void); +int {{ model.name }}_cost_ext_cost_fun_jac_hess_n_out(void); + +int {{ model.name }}_cost_ext_cost_fun_jac(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); +int {{ model.name }}_cost_ext_cost_fun_jac_work(int *, int *, int *, int *); +const int *{{ model.name }}_cost_ext_cost_fun_jac_sparsity_in(int); +const int *{{ model.name }}_cost_ext_cost_fun_jac_sparsity_out(int); +int {{ model.name }}_cost_ext_cost_fun_jac_n_in(void); +int {{ model.name }}_cost_ext_cost_fun_jac_n_out(void); + {%- else %} +int {{ cost.cost_function_ext_cost }}(void **, void **, void *); + {%- endif %} +{% endif %} + +// Cost at terminal shooting node +{% if cost.cost_type_e == "NONLINEAR_LS" %} +int {{ model.name }}_cost_y_e_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); +int {{ model.name }}_cost_y_e_fun_work(int *, int *, int *, int *); +const int *{{ model.name }}_cost_y_e_fun_sparsity_in(int); +const int *{{ model.name }}_cost_y_e_fun_sparsity_out(int); +int {{ model.name }}_cost_y_e_fun_n_in(void); +int {{ model.name }}_cost_y_e_fun_n_out(void); + +int {{ model.name }}_cost_y_e_fun_jac_ut_xt(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); +int {{ model.name }}_cost_y_e_fun_jac_ut_xt_work(int *, int *, int *, int *); +const int *{{ model.name }}_cost_y_e_fun_jac_ut_xt_sparsity_in(int); +const int *{{ model.name }}_cost_y_e_fun_jac_ut_xt_sparsity_out(int); +int {{ model.name }}_cost_y_e_fun_jac_ut_xt_n_in(void); +int {{ model.name }}_cost_y_e_fun_jac_ut_xt_n_out(void); + +int {{ model.name }}_cost_y_e_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); +int {{ model.name }}_cost_y_e_hess_work(int *, int *, int *, int *); +const int *{{ model.name }}_cost_y_e_hess_sparsity_in(int); +const int *{{ model.name }}_cost_y_e_hess_sparsity_out(int); +int {{ model.name }}_cost_y_e_hess_n_in(void); +int {{ model.name }}_cost_y_e_hess_n_out(void); +{% elif cost.cost_type_e == "CONVEX_OVER_NONLINEAR" %} +int {{ model.name }}_conl_cost_e_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); +int {{ model.name }}_conl_cost_e_fun_work(int *, int *, int *, int *); +const int *{{ model.name }}_conl_cost_e_fun_sparsity_in(int); +const int *{{ model.name }}_conl_cost_e_fun_sparsity_out(int); +int {{ model.name }}_conl_cost_e_fun_n_in(void); +int {{ model.name }}_conl_cost_e_fun_n_out(void); + +int {{ model.name }}_conl_cost_e_fun_jac_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); +int {{ model.name }}_conl_cost_e_fun_jac_hess_work(int *, int *, int *, int *); +const int *{{ model.name }}_conl_cost_e_fun_jac_hess_sparsity_in(int); +const int *{{ model.name }}_conl_cost_e_fun_jac_hess_sparsity_out(int); +int {{ model.name }}_conl_cost_e_fun_jac_hess_n_in(void); +int {{ model.name }}_conl_cost_e_fun_jac_hess_n_out(void); +{% elif cost.cost_type_e == "EXTERNAL" %} + {%- if cost.cost_ext_fun_type_e == "casadi" %} +int {{ model.name }}_cost_ext_cost_e_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); +int {{ model.name }}_cost_ext_cost_e_fun_work(int *, int *, int *, int *); +const int *{{ model.name }}_cost_ext_cost_e_fun_sparsity_in(int); +const int *{{ model.name }}_cost_ext_cost_e_fun_sparsity_out(int); +int {{ model.name }}_cost_ext_cost_e_fun_n_in(void); +int {{ model.name }}_cost_ext_cost_e_fun_n_out(void); + +int {{ model.name }}_cost_ext_cost_e_fun_jac_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); +int {{ model.name }}_cost_ext_cost_e_fun_jac_hess_work(int *, int *, int *, int *); +const int *{{ model.name }}_cost_ext_cost_e_fun_jac_hess_sparsity_in(int); +const int *{{ model.name }}_cost_ext_cost_e_fun_jac_hess_sparsity_out(int); +int {{ model.name }}_cost_ext_cost_e_fun_jac_hess_n_in(void); +int {{ model.name }}_cost_ext_cost_e_fun_jac_hess_n_out(void); + +int {{ model.name }}_cost_ext_cost_e_fun_jac(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); +int {{ model.name }}_cost_ext_cost_e_fun_jac_work(int *, int *, int *, int *); +const int *{{ model.name }}_cost_ext_cost_e_fun_jac_sparsity_in(int); +const int *{{ model.name }}_cost_ext_cost_e_fun_jac_sparsity_out(int); +int {{ model.name }}_cost_ext_cost_e_fun_jac_n_in(void); +int {{ model.name }}_cost_ext_cost_e_fun_jac_n_out(void); + {%- else %} +int {{ cost.cost_function_ext_cost_e }}(void **, void **, void *); + {%- endif %} +{% endif %} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif + +#endif // {{ model.name }}_COST diff --git a/third_party/acados/acados_template/c_templates_tera/cost_y_0_fun.in.h b/third_party/acados/acados_template/c_templates_tera/cost_y_0_fun.in.h deleted file mode 100644 index 347446e3f..000000000 --- a/third_party/acados/acados_template/c_templates_tera/cost_y_0_fun.in.h +++ /dev/null @@ -1,69 +0,0 @@ -/* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl - * - * This file is part of acados. - * - * 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 HOLDER 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.; - */ - - -#ifndef {{ model.name }}_Y_0_COST -#define {{ model.name }}_Y_0_COST - -#ifdef __cplusplus -extern "C" { -#endif - -{% if cost.cost_type_0 == "NONLINEAR_LS" %} -int {{ model.name }}_cost_y_0_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_y_0_fun_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_y_0_fun_sparsity_in(int); -const int *{{ model.name }}_cost_y_0_fun_sparsity_out(int); -int {{ model.name }}_cost_y_0_fun_n_in(void); -int {{ model.name }}_cost_y_0_fun_n_out(void); - -int {{ model.name }}_cost_y_0_fun_jac_ut_xt(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_y_0_fun_jac_ut_xt_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_y_0_fun_jac_ut_xt_sparsity_in(int); -const int *{{ model.name }}_cost_y_0_fun_jac_ut_xt_sparsity_out(int); -int {{ model.name }}_cost_y_0_fun_jac_ut_xt_n_in(void); -int {{ model.name }}_cost_y_0_fun_jac_ut_xt_n_out(void); - -int {{ model.name }}_cost_y_0_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_y_0_hess_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_y_0_hess_sparsity_in(int); -const int *{{ model.name }}_cost_y_0_hess_sparsity_out(int); -int {{ model.name }}_cost_y_0_hess_n_in(void); -int {{ model.name }}_cost_y_0_hess_n_out(void); -{% endif %} - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // {{ model.name }}_Y_0_COST diff --git a/third_party/acados/acados_template/c_templates_tera/cost_y_e_fun.in.h b/third_party/acados/acados_template/c_templates_tera/cost_y_e_fun.in.h deleted file mode 100644 index acc99009f..000000000 --- a/third_party/acados/acados_template/c_templates_tera/cost_y_e_fun.in.h +++ /dev/null @@ -1,69 +0,0 @@ -/* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl - * - * This file is part of acados. - * - * 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 HOLDER 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.; - */ - - -#ifndef {{ model.name }}_Y_E_COST -#define {{ model.name }}_Y_E_COST - -#ifdef __cplusplus -extern "C" { -#endif - -{% if cost.cost_type_e == "NONLINEAR_LS" %} -int {{ model.name }}_cost_y_e_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_y_e_fun_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_y_e_fun_sparsity_in(int); -const int *{{ model.name }}_cost_y_e_fun_sparsity_out(int); -int {{ model.name }}_cost_y_e_fun_n_in(void); -int {{ model.name }}_cost_y_e_fun_n_out(void); - -int {{ model.name }}_cost_y_e_fun_jac_ut_xt(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_y_e_fun_jac_ut_xt_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_y_e_fun_jac_ut_xt_sparsity_in(int); -const int *{{ model.name }}_cost_y_e_fun_jac_ut_xt_sparsity_out(int); -int {{ model.name }}_cost_y_e_fun_jac_ut_xt_n_in(void); -int {{ model.name }}_cost_y_e_fun_jac_ut_xt_n_out(void); - -int {{ model.name }}_cost_y_e_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_y_e_hess_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_y_e_hess_sparsity_in(int); -const int *{{ model.name }}_cost_y_e_hess_sparsity_out(int); -int {{ model.name }}_cost_y_e_hess_n_in(void); -int {{ model.name }}_cost_y_e_hess_n_out(void); -{% endif %} - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // {{ model.name }}_Y_E_COST diff --git a/third_party/acados/acados_template/c_templates_tera/cost_y_fun.in.h b/third_party/acados/acados_template/c_templates_tera/cost_y_fun.in.h deleted file mode 100644 index 1e03780cc..000000000 --- a/third_party/acados/acados_template/c_templates_tera/cost_y_fun.in.h +++ /dev/null @@ -1,69 +0,0 @@ -/* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl - * - * This file is part of acados. - * - * 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 HOLDER 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.; - */ - - -#ifndef {{ model.name }}_Y_COST -#define {{ model.name }}_Y_COST - -#ifdef __cplusplus -extern "C" { -#endif - -{% if cost.cost_type == "NONLINEAR_LS" %} -int {{ model.name }}_cost_y_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_y_fun_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_y_fun_sparsity_in(int); -const int *{{ model.name }}_cost_y_fun_sparsity_out(int); -int {{ model.name }}_cost_y_fun_n_in(void); -int {{ model.name }}_cost_y_fun_n_out(void); - -int {{ model.name }}_cost_y_fun_jac_ut_xt(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_y_fun_jac_ut_xt_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_y_fun_jac_ut_xt_sparsity_in(int); -const int *{{ model.name }}_cost_y_fun_jac_ut_xt_sparsity_out(int); -int {{ model.name }}_cost_y_fun_jac_ut_xt_n_in(void); -int {{ model.name }}_cost_y_fun_jac_ut_xt_n_out(void); - -int {{ model.name }}_cost_y_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_y_hess_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_y_hess_sparsity_in(int); -const int *{{ model.name }}_cost_y_hess_sparsity_out(int); -int {{ model.name }}_cost_y_hess_n_in(void); -int {{ model.name }}_cost_y_hess_n_out(void); -{% endif %} - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // {{ model.name }}_Y_COST diff --git a/third_party/acados/acados_template/c_templates_tera/external_cost.in.h b/third_party/acados/acados_template/c_templates_tera/external_cost.in.h deleted file mode 100644 index d200dba45..000000000 --- a/third_party/acados/acados_template/c_templates_tera/external_cost.in.h +++ /dev/null @@ -1,74 +0,0 @@ -/* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl - * - * This file is part of acados. - * - * 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 HOLDER 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.; - */ - - -#ifndef {{ model.name }}_EXT_COST -#define {{ model.name }}_EXT_COST - -#ifdef __cplusplus -extern "C" { -#endif - -{% if cost.cost_ext_fun_type == "casadi" %} -{% if cost.cost_type == "EXTERNAL" %} -int {{ model.name }}_cost_ext_cost_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_ext_cost_fun_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_ext_cost_fun_sparsity_in(int); -const int *{{ model.name }}_cost_ext_cost_fun_sparsity_out(int); -int {{ model.name }}_cost_ext_cost_fun_n_in(void); -int {{ model.name }}_cost_ext_cost_fun_n_out(void); - -int {{ model.name }}_cost_ext_cost_fun_jac_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_ext_cost_fun_jac_hess_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_ext_cost_fun_jac_hess_sparsity_in(int); -const int *{{ model.name }}_cost_ext_cost_fun_jac_hess_sparsity_out(int); -int {{ model.name }}_cost_ext_cost_fun_jac_hess_n_in(void); -int {{ model.name }}_cost_ext_cost_fun_jac_hess_n_out(void); - -int {{ model.name }}_cost_ext_cost_fun_jac(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_ext_cost_fun_jac_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_ext_cost_fun_jac_sparsity_in(int); -const int *{{ model.name }}_cost_ext_cost_fun_jac_sparsity_out(int); -int {{ model.name }}_cost_ext_cost_fun_jac_n_in(void); -int {{ model.name }}_cost_ext_cost_fun_jac_n_out(void); -{% endif %} - -{% else %} -int {{ cost.cost_function_ext_cost }}(void **, void **, void *); -{% endif %} - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // {{ model.name }}_EXT_COST diff --git a/third_party/acados/acados_template/c_templates_tera/external_cost_0.in.h b/third_party/acados/acados_template/c_templates_tera/external_cost_0.in.h deleted file mode 100644 index 8152447e5..000000000 --- a/third_party/acados/acados_template/c_templates_tera/external_cost_0.in.h +++ /dev/null @@ -1,75 +0,0 @@ -/* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl - * - * This file is part of acados. - * - * 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 HOLDER 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.; - */ - - -#ifndef {{ model.name }}_EXT_COST_0 -#define {{ model.name }}_EXT_COST_0 - -#ifdef __cplusplus -extern "C" { -#endif - -{% if cost.cost_ext_fun_type_0 == "casadi" %} - -{% if cost.cost_type_0 == "EXTERNAL" %} -int {{ model.name }}_cost_ext_cost_0_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_ext_cost_0_fun_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_ext_cost_0_fun_sparsity_in(int); -const int *{{ model.name }}_cost_ext_cost_0_fun_sparsity_out(int); -int {{ model.name }}_cost_ext_cost_0_fun_n_in(void); -int {{ model.name }}_cost_ext_cost_0_fun_n_out(void); - -int {{ model.name }}_cost_ext_cost_0_fun_jac_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_ext_cost_0_fun_jac_hess_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_ext_cost_0_fun_jac_hess_sparsity_in(int); -const int *{{ model.name }}_cost_ext_cost_0_fun_jac_hess_sparsity_out(int); -int {{ model.name }}_cost_ext_cost_0_fun_jac_hess_n_in(void); -int {{ model.name }}_cost_ext_cost_0_fun_jac_hess_n_out(void); - -int {{ model.name }}_cost_ext_cost_0_fun_jac(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_ext_cost_0_fun_jac_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_ext_cost_0_fun_jac_sparsity_in(int); -const int *{{ model.name }}_cost_ext_cost_0_fun_jac_sparsity_out(int); -int {{ model.name }}_cost_ext_cost_0_fun_jac_n_in(void); -int {{ model.name }}_cost_ext_cost_0_fun_jac_n_out(void); -{% endif %} - -{% else %} -int {{ cost.cost_function_ext_cost_0 }}(void **, void **, void *); -{% endif %} - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // {{ model.name }}_EXT_COST_0 diff --git a/third_party/acados/acados_template/c_templates_tera/external_cost_e.in.h b/third_party/acados/acados_template/c_templates_tera/external_cost_e.in.h deleted file mode 100644 index 56485db4c..000000000 --- a/third_party/acados/acados_template/c_templates_tera/external_cost_e.in.h +++ /dev/null @@ -1,74 +0,0 @@ -/* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl - * - * This file is part of acados. - * - * 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 HOLDER 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.; - */ - - -#ifndef {{ model.name }}_EXT_COST_E -#define {{ model.name }}_EXT_COST_E - -#ifdef __cplusplus -extern "C" { -#endif - -{% if cost.cost_ext_fun_type_e == "casadi" %} -{% if cost.cost_type_e == "EXTERNAL" %} -int {{ model.name }}_cost_ext_cost_e_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_ext_cost_e_fun_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_ext_cost_e_fun_sparsity_in(int); -const int *{{ model.name }}_cost_ext_cost_e_fun_sparsity_out(int); -int {{ model.name }}_cost_ext_cost_e_fun_n_in(void); -int {{ model.name }}_cost_ext_cost_e_fun_n_out(void); - -int {{ model.name }}_cost_ext_cost_e_fun_jac_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_ext_cost_e_fun_jac_hess_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_ext_cost_e_fun_jac_hess_sparsity_in(int); -const int *{{ model.name }}_cost_ext_cost_e_fun_jac_hess_sparsity_out(int); -int {{ model.name }}_cost_ext_cost_e_fun_jac_hess_n_in(void); -int {{ model.name }}_cost_ext_cost_e_fun_jac_hess_n_out(void); - -int {{ model.name }}_cost_ext_cost_e_fun_jac(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_ext_cost_e_fun_jac_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_ext_cost_e_fun_jac_sparsity_in(int); -const int *{{ model.name }}_cost_ext_cost_e_fun_jac_sparsity_out(int); -int {{ model.name }}_cost_ext_cost_e_fun_jac_n_in(void); -int {{ model.name }}_cost_ext_cost_e_fun_jac_n_out(void); -{% endif %} - -{% else %} -int {{ cost.cost_function_ext_cost_e }}(void **, void **, void *); -{% endif %} - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // {{ model.name }}_EXT_COST_E diff --git a/third_party/acados/acados_template/c_templates_tera/h_constraint.in.h b/third_party/acados/acados_template/c_templates_tera/h_constraint.in.h deleted file mode 100644 index e49176c6e..000000000 --- a/third_party/acados/acados_template/c_templates_tera/h_constraint.in.h +++ /dev/null @@ -1,70 +0,0 @@ -/* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl - * - * This file is part of acados. - * - * 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 HOLDER 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.; - */ - -#ifndef {{ model.name }}_H_CONSTRAINT -#define {{ model.name }}_H_CONSTRAINT - -#ifdef __cplusplus -extern "C" { -#endif - -{% if dims.nh > 0 %} -int {{ model.name }}_constr_h_fun_jac_uxt_zt(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_constr_h_fun_jac_uxt_zt_work(int *, int *, int *, int *); -const int *{{ model.name }}_constr_h_fun_jac_uxt_zt_sparsity_in(int); -const int *{{ model.name }}_constr_h_fun_jac_uxt_zt_sparsity_out(int); -int {{ model.name }}_constr_h_fun_jac_uxt_zt_n_in(void); -int {{ model.name }}_constr_h_fun_jac_uxt_zt_n_out(void); - -int {{ model.name }}_constr_h_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_constr_h_fun_work(int *, int *, int *, int *); -const int *{{ model.name }}_constr_h_fun_sparsity_in(int); -const int *{{ model.name }}_constr_h_fun_sparsity_out(int); -int {{ model.name }}_constr_h_fun_n_in(void); -int {{ model.name }}_constr_h_fun_n_out(void); - -{% if solver_options.hessian_approx == "EXACT" -%} -int {{ model.name }}_constr_h_fun_jac_uxt_zt_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_constr_h_fun_jac_uxt_zt_hess_work(int *, int *, int *, int *); -const int *{{ model.name }}_constr_h_fun_jac_uxt_zt_hess_sparsity_in(int); -const int *{{ model.name }}_constr_h_fun_jac_uxt_zt_hess_sparsity_out(int); -int {{ model.name }}_constr_h_fun_jac_uxt_zt_hess_n_in(void); -int {{ model.name }}_constr_h_fun_jac_uxt_zt_hess_n_out(void); -{% endif %} -{% endif %} - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // {{ model.name }}_H_CONSTRAINT diff --git a/third_party/acados/acados_template/c_templates_tera/main.in.c b/third_party/acados/acados_template/c_templates_tera/main.in.c index 99c4f13be..92a8b33ea 100644 --- a/third_party/acados/acados_template/c_templates_tera/main.in.c +++ b/third_party/acados/acados_template/c_templates_tera/main.in.c @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * @@ -31,6 +28,11 @@ * POSSIBILITY OF SUCH DAMAGE.; */ +{%- if not solver_options.custom_update_filename %} + {%- set custom_update_filename = "" %} +{% else %} + {%- set custom_update_filename = solver_options.custom_update_filename %} +{%- endif %} // standard #include @@ -42,6 +44,9 @@ #include "acados_c/external_function_interface.h" #include "acados_solver_{{ model.name }}.h" +// blasfeo +#include "blasfeo/include/blasfeo_d_aux_ext_dep.h" + #define NX {{ model.name | upper }}_NX #define NZ {{ model.name | upper }}_NZ #define NU {{ model.name | upper }}_NU @@ -191,6 +196,11 @@ int main() printf("{{ model.name }}_acados_solve() failed with status %d.\n", status); } + +{%- if custom_update_filename != "" %} + {{ model.name }}_acados_custom_update(acados_ocp_capsule, xtraj, NX*(N+1)); +{%- endif %} + // get solution ocp_nlp_out_get(nlp_config, nlp_dims, nlp_out, 0, "kkt_norm_inf", &kkt_norm_inf); ocp_nlp_get(nlp_config, nlp_solver, "sqp_iter", &sqp_iter); diff --git a/third_party/acados/acados_template/c_templates_tera/main_sim.in.c b/third_party/acados/acados_template/c_templates_tera/main_sim.in.c index 743e81d59..8960aa003 100644 --- a/third_party/acados/acados_template/c_templates_tera/main_sim.in.c +++ b/third_party/acados/acados_template/c_templates_tera/main_sim.in.c @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * diff --git a/third_party/acados/acados_template/c_templates_tera/acados_mex_create.in.c b/third_party/acados/acados_template/c_templates_tera/matlab_templates/acados_mex_create.in.c similarity index 98% rename from third_party/acados/acados_template/c_templates_tera/acados_mex_create.in.c rename to third_party/acados/acados_template/c_templates_tera/matlab_templates/acados_mex_create.in.c index e67a51567..24ae94ac2 100644 --- a/third_party/acados/acados_template/c_templates_tera/acados_mex_create.in.c +++ b/third_party/acados/acados_template/c_templates_tera/matlab_templates/acados_mex_create.in.c @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * diff --git a/third_party/acados/acados_template/c_templates_tera/acados_mex_free.in.c b/third_party/acados/acados_template/c_templates_tera/matlab_templates/acados_mex_free.in.c similarity index 88% rename from third_party/acados/acados_template/c_templates_tera/acados_mex_free.in.c rename to third_party/acados/acados_template/c_templates_tera/matlab_templates/acados_mex_free.in.c index 560adb0b9..bd457969b 100644 --- a/third_party/acados/acados_template/c_templates_tera/acados_mex_free.in.c +++ b/third_party/acados/acados_template/c_templates_tera/matlab_templates/acados_mex_free.in.c @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * diff --git a/third_party/acados/acados_template/c_templates_tera/acados_mex_set.in.c b/third_party/acados/acados_template/c_templates_tera/matlab_templates/acados_mex_set.in.c similarity index 76% rename from third_party/acados/acados_template/c_templates_tera/acados_mex_set.in.c rename to third_party/acados/acados_template/c_templates_tera/matlab_templates/acados_mex_set.in.c index f8e1e5e44..78a308df4 100644 --- a/third_party/acados/acados_template/c_templates_tera/acados_mex_set.in.c +++ b/third_party/acados/acados_template/c_templates_tera/matlab_templates/acados_mex_set.in.c @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * @@ -59,9 +56,6 @@ void mexFunction(int nlhs, mxArray *plhs[], int nrhs, const mxArray *prhs[]) /* RHS */ int min_nrhs = 6; - char *ext_fun_type = mxArrayToString( prhs[0] ); - char *ext_fun_type_e = mxArrayToString( prhs[1] ); - // C ocp const mxArray *C_ocp = prhs[2]; // capsule @@ -378,45 +372,63 @@ void mexFunction(int nlhs, mxArray *plhs[], int nrhs, const mxArray *prhs[]) // } // } // initializations - else if (!strcmp(field, "init_x")) + else if (!strcmp(field, "init_x") || !strcmp(field, "x")) { - if (nrhs!=min_nrhs) - MEX_SETTER_NO_STAGE_SUPPORT(fun_name, field) - - acados_size = (N+1) * nx; - MEX_DIM_CHECK_VEC(fun_name, field, matlab_size, acados_size); - for (int ii=0; ii<=N; ii++) + if (nrhs == min_nrhs) { - ocp_nlp_out_set(config, dims, out, ii, "x", value+ii*nx); + acados_size = (N+1) * nx; + MEX_DIM_CHECK_VEC(fun_name, field, matlab_size, acados_size); + for (int ii=0; ii<=N; ii++) + { + ocp_nlp_out_set(config, dims, out, ii, "x", value+ii*nx); + } + } + else // (nrhs == min_nrhs + 1) + { + acados_size = nx; + MEX_DIM_CHECK_VEC(fun_name, field, matlab_size, acados_size); + ocp_nlp_out_set(config, dims, out, s0, "x", value); } } - else if (!strcmp(field, "init_u")) + else if (!strcmp(field, "init_u") || !strcmp(field, "u")) { - if (nrhs!=min_nrhs) - MEX_SETTER_NO_STAGE_SUPPORT(fun_name, field) - - acados_size = N*nu; - MEX_DIM_CHECK_VEC(fun_name, field, matlab_size, acados_size); - for (int ii=0; iisim_solver_plan[0]; sim_solver_t type = sim_plan.sim_solver; if (type == IRK) { int nz = ocp_nlp_dims_get_from_attr(config, dims, out, 0, "z"); - if (nrhs!=min_nrhs) - MEX_SETTER_NO_STAGE_SUPPORT(fun_name, field) - - acados_size = N*nz; - MEX_DIM_CHECK_VEC(fun_name, field, matlab_size, acados_size); - for (int ii=0; iisim_solver_plan[0]; sim_solver_t type = sim_plan.sim_solver; if (type == IRK) { int nx = ocp_nlp_dims_get_from_attr(config, dims, out, 0, "x"); - if (nrhs!=min_nrhs) - MEX_SETTER_NO_STAGE_SUPPORT(fun_name, field) - - acados_size = N*nx; - MEX_DIM_CHECK_VEC(fun_name, field, matlab_size, acados_size); - for (int ii=0; iisim_solver_plan[0]; sim_solver_t type = sim_plan.sim_solver; @@ -454,14 +472,20 @@ void mexFunction(int nlhs, mxArray *plhs[], int nrhs, const mxArray *prhs[]) { int nout = ocp_nlp_dims_get_from_attr(config, dims, out, 0, "init_gnsf_phi"); - if (nrhs!=min_nrhs) - MEX_SETTER_NO_STAGE_SUPPORT(fun_name, field) - - acados_size = N*nout; - MEX_DIM_CHECK_VEC(fun_name, field, matlab_size, acados_size); - for (int ii=0; ii 0 and simulink_opts.inputs.uh -%} {#- uh #} {%- set n_inputs = n_inputs + 1 -%} {%- endif -%} + {%- if dims.nh_e > 0 and simulink_opts.inputs.lh_e -%} {#- lh_e #} + {%- set n_inputs = n_inputs + 1 -%} + {%- endif -%} + {%- if dims.nh_e > 0 and simulink_opts.inputs.uh_e -%} {#- uh_e #} + {%- set n_inputs = n_inputs + 1 -%} + {%- endif -%} {%- for key, val in simulink_opts.inputs -%} {%- if val != 0 and val != 1 -%} @@ -177,7 +182,7 @@ static void mdlInitializeSizes (SimStruct *S) {%- if dims.np > 0 and simulink_opts.inputs.parameter_traj -%} {#- parameter_traj #} {%- set i_input = i_input + 1 %} // parameters - ssSetInputPortVectorDimension(S, {{ i_input }}, ({{ dims.N }}+1) * {{ dims.np }}); + ssSetInputPortVectorDimension(S, {{ i_input }}, (N+1) * {{ dims.np }}); {%- endif %} {%- if dims.ny > 0 and simulink_opts.inputs.y_ref_0 %} @@ -235,23 +240,34 @@ static void mdlInitializeSizes (SimStruct *S) {%- if dims.ng > 0 and simulink_opts.inputs.lg -%} {#- lg #} {%- set i_input = i_input + 1 %} // lg - ssSetInputPortVectorDimension(S, {{ i_input }}, {{ dims.ng }}); + ssSetInputPortVectorDimension(S, {{ i_input }}, {{ dims.N*dims.ng }}); {%- endif -%} {%- if dims.ng > 0 and simulink_opts.inputs.ug -%} {#- ug #} {%- set i_input = i_input + 1 %} // ug - ssSetInputPortVectorDimension(S, {{ i_input }}, {{ dims.ng }}); + ssSetInputPortVectorDimension(S, {{ i_input }}, {{ dims.N*dims.ng }}); {%- endif -%} {%- if dims.nh > 0 and simulink_opts.inputs.lh -%} {#- lh #} {%- set i_input = i_input + 1 %} // lh - ssSetInputPortVectorDimension(S, {{ i_input }}, {{ dims.nh }}); + ssSetInputPortVectorDimension(S, {{ i_input }}, {{ dims.N*dims.nh }}); {%- endif -%} {%- if dims.nh > 0 and simulink_opts.inputs.uh -%} {#- uh #} {%- set i_input = i_input + 1 %} // uh - ssSetInputPortVectorDimension(S, {{ i_input }}, {{ dims.nh }}); + ssSetInputPortVectorDimension(S, {{ i_input }}, {{ dims.N*dims.nh }}); + {%- endif -%} + + {%- if dims.nh_e > 0 and simulink_opts.inputs.lh_e -%} {#- lh_e #} + {%- set i_input = i_input + 1 %} + // lh_e + ssSetInputPortVectorDimension(S, {{ i_input }}, {{ dims.nh_e }}); + {%- endif -%} + {%- if dims.nh_e > 0 and simulink_opts.inputs.uh_e -%} {#- uh_e #} + {%- set i_input = i_input + 1 %} + // uh_e + ssSetInputPortVectorDimension(S, {{ i_input }}, {{ dims.nh_e }}); {%- endif -%} {%- if dims.ny_0 > 0 and simulink_opts.inputs.cost_W_0 %} {#- cost_W_0 #} @@ -312,11 +328,21 @@ static void mdlInitializeSizes (SimStruct *S) ssSetOutputPortVectorDimension(S, {{ i_output }}, 1 ); {%- endif %} + {%- if simulink_opts.outputs.cost_value == 1 %} + {%- set i_output = i_output + 1 %} + ssSetOutputPortVectorDimension(S, {{ i_output }}, 1 ); + {%- endif %} + {%- if simulink_opts.outputs.KKT_residual == 1 %} {%- set i_output = i_output + 1 %} ssSetOutputPortVectorDimension(S, {{ i_output }}, 1 ); {%- endif %} + {%- if simulink_opts.outputs.KKT_residuals == 1 %} + {%- set i_output = i_output + 1 %} + ssSetOutputPortVectorDimension(S, {{ i_output }}, 4 ); + {%- endif %} + {%- if dims.N > 0 and simulink_opts.outputs.x1 == 1 %} {%- set i_output = i_output + 1 %} ssSetOutputPortVectorDimension(S, {{ i_output }}, {{ dims.nx }} ); // state at shooting node 1 @@ -404,7 +430,9 @@ static void mdlOutputs(SimStruct *S, int_T tid) InputRealPtrsType in_sign; - {%- set buffer_sizes = [dims.nbx_0, dims.np, dims.nbx, dims.nbu, dims.ng, dims.nh, dims.nx] -%} + int N = {{ model.name | upper }}_N; + + {%- set buffer_sizes = [dims.nbx_0, dims.np, dims.nbx, dims.nbx_e, dims.nbu, dims.ng, dims.nh, dims.ng_e, dims.nh_e] -%} {%- if dims.ny_0 > 0 and simulink_opts.inputs.y_ref_0 %} {# y_ref_0 #} {%- set buffer_sizes = buffer_sizes | concat(with=(dims.ny_0)) %} @@ -457,7 +485,7 @@ static void mdlOutputs(SimStruct *S, int_T tid) in_sign = ssGetInputPortRealSignalPtrs(S, {{ i_input }}); // update value of parameters - for (int ii = 0; ii <= {{ dims.N }}; ii++) + for (int ii = 0; ii <= N; ii++) { for (int jj = 0; jj < {{ dims.np }}; jj++) buffer[jj] = (double)(*in_sign[ii*{{dims.np}}+jj]); @@ -481,7 +509,7 @@ static void mdlOutputs(SimStruct *S, int_T tid) {%- set i_input = i_input + 1 %} in_sign = ssGetInputPortRealSignalPtrs(S, {{ i_input }}); - for (int ii = 1; ii < {{ dims.N }}; ii++) + for (int ii = 1; ii < N; ii++) { for (int jj = 0; jj < {{ dims.ny }}; jj++) buffer[jj] = (double)(*in_sign[(ii-1)*{{ dims.ny }}+jj]); @@ -497,14 +525,14 @@ static void mdlOutputs(SimStruct *S, int_T tid) for (int i = 0; i < {{ dims.ny_e }}; i++) buffer[i] = (double)(*in_sign[i]); - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, {{ dims.N }}, "yref", (void *) buffer); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "yref", (void *) buffer); {%- endif %} {%- if dims.nbx > 0 and dims.N > 1 and simulink_opts.inputs.lbx -%} {#- lbx #} // lbx {%- set i_input = i_input + 1 %} in_sign = ssGetInputPortRealSignalPtrs(S, {{ i_input }}); - for (int ii = 1; ii < {{ dims.N }}; ii++) + for (int ii = 1; ii < N; ii++) { for (int jj = 0; jj < {{ dims.nbx }}; jj++) buffer[jj] = (double)(*in_sign[(ii-1)*{{ dims.nbx }}+jj]); @@ -515,7 +543,7 @@ static void mdlOutputs(SimStruct *S, int_T tid) // ubx {%- set i_input = i_input + 1 %} in_sign = ssGetInputPortRealSignalPtrs(S, {{ i_input }}); - for (int ii = 1; ii < {{ dims.N }}; ii++) + for (int ii = 1; ii < N; ii++) { for (int jj = 0; jj < {{ dims.nbx }}; jj++) buffer[jj] = (double)(*in_sign[(ii-1)*{{ dims.nbx }}+jj]); @@ -531,7 +559,7 @@ static void mdlOutputs(SimStruct *S, int_T tid) for (int i = 0; i < {{ dims.nbx_e }}; i++) buffer[i] = (double)(*in_sign[i]); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, {{ dims.N }}, "lbx", buffer); + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, N, "lbx", buffer); {%- endif %} {%- if dims.nbx_e > 0 and dims.N > 0 and simulink_opts.inputs.ubx_e -%} {#- ubx_e #} // ubx_e @@ -540,7 +568,7 @@ static void mdlOutputs(SimStruct *S, int_T tid) for (int i = 0; i < {{ dims.nbx_e }}; i++) buffer[i] = (double)(*in_sign[i]); - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, {{ dims.N }}, "ubx", buffer); + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, N, "ubx", buffer); {%- endif %} @@ -548,7 +576,7 @@ static void mdlOutputs(SimStruct *S, int_T tid) // lbu {%- set i_input = i_input + 1 %} in_sign = ssGetInputPortRealSignalPtrs(S, {{ i_input }}); - for (int ii = 0; ii < {{ dims.N }}; ii++) + for (int ii = 0; ii < N; ii++) { for (int jj = 0; jj < {{ dims.nbu }}; jj++) buffer[jj] = (double)(*in_sign[ii*{{ dims.nbu }}+jj]); @@ -559,7 +587,7 @@ static void mdlOutputs(SimStruct *S, int_T tid) // ubu {%- set i_input = i_input + 1 %} in_sign = ssGetInputPortRealSignalPtrs(S, {{ i_input }}); - for (int ii = 0; ii < {{ dims.N }}; ii++) + for (int ii = 0; ii < N; ii++) { for (int jj = 0; jj < {{ dims.nbu }}; jj++) buffer[jj] = (double)(*in_sign[ii*{{ dims.nbu }}+jj]); @@ -572,44 +600,67 @@ static void mdlOutputs(SimStruct *S, int_T tid) {%- set i_input = i_input + 1 %} in_sign = ssGetInputPortRealSignalPtrs(S, {{ i_input }}); - for (int i = 0; i < {{ dims.ng }}; i++) - buffer[i] = (double)(*in_sign[i]); - - for (int ii = 0; ii < {{ dims.N }}; ii++) - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, ii, "lg", buffer); + for (int ii = 0; ii < N; ii++) + { + for (int jj = 0; jj < {{ dims.ng }}; jj++) + buffer[jj] = (double)(*in_sign[ii*{{ dims.ng }}+jj]); + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, ii, "lg", (void *) buffer); + } {%- endif -%} {%- if dims.ng > 0 and simulink_opts.inputs.ug -%} {#- ug #} // ug {%- set i_input = i_input + 1 %} in_sign = ssGetInputPortRealSignalPtrs(S, {{ i_input }}); - for (int i = 0; i < {{ dims.ng }}; i++) - buffer[i] = (double)(*in_sign[i]); - - for (int ii = 0; ii < {{ dims.N }}; ii++) - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, ii, "ug", buffer); + for (int ii = 0; ii < N; ii++) + { + for (int jj = 0; jj < {{ dims.ng }}; jj++) + buffer[jj] = (double)(*in_sign[ii*{{ dims.ng }}+jj]); + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, ii, "ug", (void *) buffer); + } {%- endif -%} + {%- if dims.nh > 0 and simulink_opts.inputs.lh -%} {#- lh #} // lh {%- set i_input = i_input + 1 %} in_sign = ssGetInputPortRealSignalPtrs(S, {{ i_input }}); - for (int i = 0; i < {{ dims.nh }}; i++) - buffer[i] = (double)(*in_sign[i]); - - for (int ii = 0; ii < {{ dims.N }}; ii++) - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, ii, "lh", buffer); + for (int ii = 0; ii < N; ii++) + { + for (int jj = 0; jj < {{ dims.nh }}; jj++) + buffer[jj] = (double)(*in_sign[ii*{{ dims.nh }}+jj]); + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, ii, "lh", (void *) buffer); + } {%- endif -%} {%- if dims.nh > 0 and simulink_opts.inputs.uh -%} {#- uh #} // uh {%- set i_input = i_input + 1 %} in_sign = ssGetInputPortRealSignalPtrs(S, {{ i_input }}); - for (int i = 0; i < {{ dims.nh }}; i++) - buffer[i] = (double)(*in_sign[i]); + for (int ii = 0; ii < N; ii++) + { + for (int jj = 0; jj < {{ dims.nh }}; jj++) + buffer[jj] = (double)(*in_sign[ii*{{ dims.nh }}+jj]); + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, ii, "uh", (void *) buffer); + } + {%- endif -%} - for (int ii = 0; ii < {{ dims.N }}; ii++) - ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, ii, "uh", buffer); + + {%- if dims.nh_e > 0 and simulink_opts.inputs.lh_e -%} {#- lh_e #} + // lh_e + {%- set i_input = i_input + 1 %} + in_sign = ssGetInputPortRealSignalPtrs(S, {{ i_input }}); + for (int i = 0; i < {{ dims.nh_e }}; i++) + buffer[i] = (double)(*in_sign[i]); + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, N, "lh", buffer); + {%- endif -%} + {%- if dims.nh_e > 0 and simulink_opts.inputs.uh_e -%} {#- uh_e #} + // uh_e + {%- set i_input = i_input + 1 %} + in_sign = ssGetInputPortRealSignalPtrs(S, {{ i_input }}); + for (int i = 0; i < {{ dims.nh_e }}; i++) + buffer[i] = (double)(*in_sign[i]); + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, N, "uh", buffer); {%- endif -%} {%- if dims.ny_0 > 0 and simulink_opts.inputs.cost_W_0 %} {#- cost_W_0 #} @@ -629,7 +680,7 @@ static void mdlOutputs(SimStruct *S, int_T tid) for (int i = 0; i < {{ dims.ny * dims.ny }}; i++) buffer[i] = (double)(*in_sign[i]); - for (int ii = 1; ii < {{ dims.N }}; ii++) + for (int ii = 1; ii < N; ii++) ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, ii, "W", buffer); {%- endif %} @@ -640,7 +691,7 @@ static void mdlOutputs(SimStruct *S, int_T tid) for (int i = 0; i < {{ dims.ny_e * dims.ny_e }}; i++) buffer[i] = (double)(*in_sign[i]); - ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, {{ dims.N }}, "W", buffer); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "W", buffer); {%- endif %} {%- if simulink_opts.inputs.reset_solver %} {#- reset_solver #} @@ -650,7 +701,7 @@ static void mdlOutputs(SimStruct *S, int_T tid) double reset = (double)(*in_sign[0]); if (reset) { - {{ model.name }}_acados_reset(capsule); + {{ model.name }}_acados_reset(capsule, 1); } {%- endif %} @@ -670,7 +721,7 @@ static void mdlOutputs(SimStruct *S, int_T tid) // u_init {%- set i_input = i_input + 1 %} in_sign = ssGetInputPortRealSignalPtrs(S, {{ i_input }}); - for (int ii = 0; ii < {{ dims.N }}; ii++) + for (int ii = 0; ii < N; ii++) { for (int jj = 0; jj < {{ dims.nu }}; jj++) buffer[jj] = (double)(*in_sign[(ii)*{{ dims.nu }}+jj]); @@ -686,7 +737,7 @@ static void mdlOutputs(SimStruct *S, int_T tid) /* set outputs */ // assign pointers to output signals - real_t *out_u0, *out_utraj, *out_xtraj, *out_status, *out_sqp_iter, *out_KKT_res, *out_x1, *out_cpu_time, *out_cpu_time_sim, *out_cpu_time_qp, *out_cpu_time_lin; + real_t *out_u0, *out_utraj, *out_xtraj, *out_status, *out_sqp_iter, *out_KKT_res, *out_KKT_residuals, *out_x1, *out_cpu_time, *out_cpu_time_sim, *out_cpu_time_qp, *out_cpu_time_lin, *out_cost_value; int tmp_int; {%- set i_output = -1 -%}{# note here i_output is 0-based #} @@ -699,7 +750,7 @@ static void mdlOutputs(SimStruct *S, int_T tid) {%- if simulink_opts.outputs.utraj == 1 %} {%- set i_output = i_output + 1 %} out_utraj = ssGetOutputPortRealSignal(S, {{ i_output }}); - for (int ii = 0; ii < {{ dims.N }}; ii++) + for (int ii = 0; ii < N; ii++) ocp_nlp_out_get(nlp_config, nlp_dims, nlp_out, ii, "u", (void *) (out_utraj + ii * {{ dims.nu }})); {%- endif %} @@ -719,12 +770,32 @@ static void mdlOutputs(SimStruct *S, int_T tid) *out_status = (real_t) acados_status; {%- endif %} + {%- if simulink_opts.outputs.cost_value == 1 %} + {%- set i_output = i_output + 1 %} + out_cost_value = ssGetOutputPortRealSignal(S, {{ i_output }}); + ocp_nlp_eval_cost(capsule->nlp_solver, nlp_in, nlp_out); + ocp_nlp_get(nlp_config, capsule->nlp_solver, "cost_value", (void *) out_cost_value); + {%- endif %} + {%- if simulink_opts.outputs.KKT_residual == 1 %} {%- set i_output = i_output + 1 %} out_KKT_res = ssGetOutputPortRealSignal(S, {{ i_output }}); *out_KKT_res = (real_t) nlp_out->inf_norm_res; {%- endif %} + {%- if simulink_opts.outputs.KKT_residuals == 1 %} + {%- set i_output = i_output + 1 %} + out_KKT_residuals = ssGetOutputPortRealSignal(S, {{ i_output }}); + + {%- if solver_options.nlp_solver_type == "SQP_RTI" %} + ocp_nlp_eval_residuals(capsule->nlp_solver, nlp_in, nlp_out); + {%- endif %} + ocp_nlp_get(nlp_config, capsule->nlp_solver, "res_stat", (void *) &out_KKT_residuals[0]); + ocp_nlp_get(nlp_config, capsule->nlp_solver, "res_eq", (void *) &out_KKT_residuals[1]); + ocp_nlp_get(nlp_config, capsule->nlp_solver, "res_ineq", (void *) &out_KKT_residuals[2]); + ocp_nlp_get(nlp_config, capsule->nlp_solver, "res_comp", (void *) &out_KKT_residuals[3]); + {%- endif %} + {%- if dims.N > 0 and simulink_opts.outputs.x1 == 1 %} {%- set i_output = i_output + 1 %} out_x1 = ssGetOutputPortRealSignal(S, {{ i_output }}); diff --git a/third_party/acados/acados_template/c_templates_tera/main_mex.in.c b/third_party/acados/acados_template/c_templates_tera/matlab_templates/main_mex.in.c similarity index 95% rename from third_party/acados/acados_template/c_templates_tera/main_mex.in.c rename to third_party/acados/acados_template/c_templates_tera/matlab_templates/main_mex.in.c index 8da5db29a..851a3cc04 100644 --- a/third_party/acados/acados_template/c_templates_tera/main_mex.in.c +++ b/third_party/acados/acados_template/c_templates_tera/matlab_templates/main_mex.in.c @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * diff --git a/third_party/acados/acados_template/c_templates_tera/make_main_mex.in.m b/third_party/acados/acados_template/c_templates_tera/matlab_templates/make_main_mex.in.m similarity index 93% rename from third_party/acados/acados_template/c_templates_tera/make_main_mex.in.m rename to third_party/acados/acados_template/c_templates_tera/matlab_templates/make_main_mex.in.m index 9188686a0..d21794845 100644 --- a/third_party/acados/acados_template/c_templates_tera/make_main_mex.in.m +++ b/third_party/acados/acados_template/c_templates_tera/matlab_templates/make_main_mex.in.m @@ -1,8 +1,5 @@ % -% Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, -% Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, -% Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, -% Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl +% Copyright (c) The acados authors. % % This file is part of acados. % @@ -29,6 +26,7 @@ % 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.; + % function make_main_mex_{{ model.name }}() diff --git a/third_party/acados/acados_template/c_templates_tera/make_mex.in.m b/third_party/acados/acados_template/c_templates_tera/matlab_templates/make_mex.in.m similarity index 81% rename from third_party/acados/acados_template/c_templates_tera/make_mex.in.m rename to third_party/acados/acados_template/c_templates_tera/matlab_templates/make_mex.in.m index cde30f6f4..5e3582713 100644 --- a/third_party/acados/acados_template/c_templates_tera/make_mex.in.m +++ b/third_party/acados/acados_template/c_templates_tera/matlab_templates/make_mex.in.m @@ -1,8 +1,5 @@ % -% Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, -% Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, -% Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, -% Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl +% Copyright (c) The acados authors. % % This file is part of acados. % @@ -29,6 +26,7 @@ % 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.; + % function make_mex_{{ model.name }}() @@ -48,6 +46,23 @@ function make_mex_{{ model.name }}() blasfeo_include = ['-I', fullfile(acados_folder, 'external', 'blasfeo', 'include')]; hpipm_include = ['-I', fullfile(acados_folder, 'external', 'hpipm', 'include')]; + % load linking information of compiled acados + link_libs_core_filename = fullfile(acados_folder, 'lib', 'link_libs.json'); + addpath(fullfile(acados_folder, 'external', 'jsonlab')); + link_libs = loadjson(link_libs_core_filename); + + % add necessary link instructs + acados_lib_extra = {}; + lib_names = fieldnames(link_libs); + for idx = 1 : numel(lib_names) + lib_name = lib_names{idx}; + link_arg = link_libs.(lib_name); + if ~isempty(link_arg) + acados_lib_extra = [acados_lib_extra, link_arg]; + end + end + + mex_include = ['-I', fullfile(acados_folder, 'interfaces', 'acados_matlab_octave')]; mex_names = { ... @@ -94,7 +109,8 @@ function make_mex_{{ model.name }}() if is_octave() % mkoctfile -p CFLAGS mex(acados_include, template_lib_include, external_include, blasfeo_include, hpipm_include,... - acados_lib_path, template_lib_path, mex_include, '-lacados', '-lhpipm', '-lblasfeo', mex_files{ii}) + template_lib_path, mex_include, acados_lib_path, '-lacados', '-lhpipm', '-lblasfeo',... + acados_lib_extra{:}, mex_files{ii}) else if ismac() FLAGS = 'CFLAGS=$CFLAGS -std=c99'; @@ -102,7 +118,8 @@ function make_mex_{{ model.name }}() FLAGS = 'CFLAGS=$CFLAGS -std=c99 -fopenmp'; end mex(FLAGS, acados_include, template_lib_include, external_include, blasfeo_include, hpipm_include,... - acados_lib_path, template_lib_path, mex_include, '-lacados', '-lhpipm', '-lblasfeo', mex_files{ii}) + template_lib_path, mex_include, acados_lib_path, '-lacados', '-lhpipm', '-lblasfeo',... + acados_lib_extra{:}, mex_files{ii}) end end diff --git a/third_party/acados/acados_template/c_templates_tera/make_sfun.in.m b/third_party/acados/acados_template/c_templates_tera/matlab_templates/make_sfun.in.m similarity index 74% rename from third_party/acados/acados_template/c_templates_tera/make_sfun.in.m rename to third_party/acados/acados_template/c_templates_tera/matlab_templates/make_sfun.in.m index 77603a78f..5d74c523f 100644 --- a/third_party/acados/acados_template/c_templates_tera/make_sfun.in.m +++ b/third_party/acados/acados_template/c_templates_tera/matlab_templates/make_sfun.in.m @@ -1,8 +1,5 @@ % -% Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, -% Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, -% Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, -% Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl +% Copyright (c) The acados authors. % % This file is part of acados. % @@ -29,6 +26,7 @@ % 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.; + % SOURCES = { ... @@ -133,6 +131,9 @@ COMPDEFINES = [ COMPDEFINES, ' -DACADOS_WITH_OSQP ' ]; {%- elif solver_options.qp_solver is containing("QPDUNES") %} CFLAGS = [ CFLAGS, ' -DACADOS_WITH_QPDUNES ' ]; COMPDEFINES = [ COMPDEFINES, ' -DACADOS_WITH_QPDUNES ' ]; +{%- elif solver_options.qp_solver is containing("DAQP") %} +CFLAGS = [ CFLAGS, ' -DACADOS_WITH_DAQP' ]; +COMPDEFINES = [ COMPDEFINES, ' -DACADOS_WITH_DAQP' ]; {%- elif solver_options.qp_solver is containing("HPMPC") %} CFLAGS = [ CFLAGS, ' -DACADOS_WITH_HPMPC ' ]; COMPDEFINES = [ COMPDEFINES, ' -DACADOS_WITH_HPMPC ' ]; @@ -153,129 +154,176 @@ LIBS{end+1} = '{{ acados_link_libs.osqp }}'; {% if solver_options.qp_solver is containing("QPOASES") %} LIBS{end+1} = '-lqpOASES_e'; {% endif %} + {% if solver_options.qp_solver is containing("DAQP") %} +LIBS{end+1} = '-ldaqp'; + {% endif %} {%- endif %} -mex('-v', '-O', CFLAGS, LDFLAGS, COMPFLAGS, COMPDEFINES, INCS{:}, ... - LIB_PATH, LIBS{:}, SOURCES{:}, ... - '-output', 'acados_solver_sfunction_{{ model.name }}' ); + +try + % mex('-v', '-O', CFLAGS, LDFLAGS, COMPFLAGS, COMPDEFINES, INCS{:}, ... + mex('-O', CFLAGS, LDFLAGS, COMPFLAGS, COMPDEFINES, INCS{:}, ... + LIB_PATH, LIBS{:}, SOURCES{:}, ... + '-output', 'acados_solver_sfunction_{{ model.name }}' ); +catch exception + disp('make_sfun failed with the following exception:') + disp(exception); + disp('Try adding -v to the mex command above to get more information.') + keyboard +end fprintf( [ '\n\nSuccessfully created sfunction:\nacados_solver_sfunction_{{ model.name }}', '.', ... eval('mexext')] ); -%% print note on usage of s-function +%% print note on usage of s-function, and create I/O port names vectors fprintf('\n\nNote: Usage of Sfunction is as follows:\n') input_note = 'Inputs are:\n'; i_in = 1; +global sfun_input_names +sfun_input_names = {}; {%- if dims.nbx_0 > 0 and simulink_opts.inputs.lbx_0 -%} {#- lbx_0 #} input_note = strcat(input_note, num2str(i_in), ') lbx_0 - lower bound on x for stage 0,',... ' size [{{ dims.nbx_0 }}]\n '); +sfun_input_names = [sfun_input_names; 'lbx_0 [{{ dims.nbx_0 }}]']; i_in = i_in + 1; {%- endif %} {%- if dims.nbx_0 > 0 and simulink_opts.inputs.ubx_0 -%} {#- ubx_0 #} input_note = strcat(input_note, num2str(i_in), ') ubx_0 - upper bound on x for stage 0,',... ' size [{{ dims.nbx_0 }}]\n '); +sfun_input_names = [sfun_input_names; 'ubx_0 [{{ dims.nbx_0 }}]']; i_in = i_in + 1; {%- endif %} {%- if dims.np > 0 and simulink_opts.inputs.parameter_traj -%} {#- parameter_traj #} -input_note = strcat(input_note, num2str(i_in), ') parameters - concatenated for all shooting nodes 0 to N+1,',... +input_note = strcat(input_note, num2str(i_in), ') parameters - concatenated for all shooting nodes 0 to N,',... ' size [{{ (dims.N+1)*dims.np }}]\n '); +sfun_input_names = [sfun_input_names; 'parameter_traj [{{ (dims.N+1)*dims.np }}]']; i_in = i_in + 1; {%- endif %} {%- if dims.ny_0 > 0 and simulink_opts.inputs.y_ref_0 %} input_note = strcat(input_note, num2str(i_in), ') y_ref_0, size [{{ dims.ny_0 }}]\n '); +sfun_input_names = [sfun_input_names; 'y_ref_0 [{{ dims.ny_0 }}]']; i_in = i_in + 1; {%- endif %} {%- if dims.ny > 0 and dims.N > 1 and simulink_opts.inputs.y_ref %} input_note = strcat(input_note, num2str(i_in), ') y_ref - concatenated for shooting nodes 1 to N-1,',... ' size [{{ (dims.N-1) * dims.ny }}]\n '); +sfun_input_names = [sfun_input_names; 'y_ref [{{ (dims.N-1) * dims.ny }}]']; i_in = i_in + 1; {%- endif %} {%- if dims.ny_e > 0 and dims.N > 0 and simulink_opts.inputs.y_ref_e %} input_note = strcat(input_note, num2str(i_in), ') y_ref_e, size [{{ dims.ny_e }}]\n '); +sfun_input_names = [sfun_input_names; 'y_ref_e [{{ dims.ny_e }}]']; i_in = i_in + 1; {%- endif %} {%- if dims.nbx > 0 and dims.N > 1 and simulink_opts.inputs.lbx -%} {#- lbx #} input_note = strcat(input_note, num2str(i_in), ') lbx for shooting nodes 1 to N-1, size [{{ (dims.N-1) * dims.nbx }}]\n '); +sfun_input_names = [sfun_input_names; 'lbx [{{ (dims.N-1) * dims.nbx }}]']; i_in = i_in + 1; {%- endif %} {%- if dims.nbx > 0 and dims.N > 1 and simulink_opts.inputs.ubx -%} {#- ubx #} input_note = strcat(input_note, num2str(i_in), ') ubx for shooting nodes 1 to N-1, size [{{ (dims.N-1) * dims.nbx }}]\n '); +sfun_input_names = [sfun_input_names; 'ubx [{{ (dims.N-1) * dims.nbx }}]']; i_in = i_in + 1; {%- endif %} {%- if dims.nbx_e > 0 and dims.N > 0 and simulink_opts.inputs.lbx_e -%} {#- lbx_e #} input_note = strcat(input_note, num2str(i_in), ') lbx_e (lbx at shooting node N), size [{{ dims.nbx_e }}]\n '); +sfun_input_names = [sfun_input_names; 'lbx_e [{{ dims.nbx_e }}]']; i_in = i_in + 1; {%- endif %} {%- if dims.nbx_e > 0 and dims.N > 0 and simulink_opts.inputs.ubx_e -%} {#- ubx_e #} input_note = strcat(input_note, num2str(i_in), ') ubx_e (ubx at shooting node N), size [{{ dims.nbx_e }}]\n '); +sfun_input_names = [sfun_input_names; 'ubx_e [{{ dims.nbx_e }}]']; i_in = i_in + 1; {%- endif %} {%- if dims.nbu > 0 and dims.N > 0 and simulink_opts.inputs.lbu -%} {#- lbu #} input_note = strcat(input_note, num2str(i_in), ') lbu for shooting nodes 0 to N-1, size [{{ dims.N*dims.nbu }}]\n '); +sfun_input_names = [sfun_input_names; 'lbu [{{ dims.N*dims.nbu }}]']; i_in = i_in + 1; {%- endif -%} {%- if dims.nbu > 0 and dims.N > 0 and simulink_opts.inputs.ubu -%} {#- ubu #} input_note = strcat(input_note, num2str(i_in), ') ubu for shooting nodes 0 to N-1, size [{{ dims.N*dims.nbu }}]\n '); +sfun_input_names = [sfun_input_names; 'ubu [{{ dims.N*dims.nbu }}]']; i_in = i_in + 1; {%- endif -%} {%- if dims.ng > 0 and simulink_opts.inputs.lg -%} {#- lg #} -input_note = strcat(input_note, num2str(i_in), ') lg, size [{{ dims.ng }}]\n '); +input_note = strcat(input_note, num2str(i_in), ') lg for shooting nodes 0 to N-1, size [{{ dims.N*dims.ng }}]\n '); +sfun_input_names = [sfun_input_names; 'lg [{{ dims.N*dims.ng }}]']; i_in = i_in + 1; {%- endif %} {%- if dims.ng > 0 and simulink_opts.inputs.ug -%} {#- ug #} -input_note = strcat(input_note, num2str(i_in), ') ug, size [{{ dims.ng }}]\n '); +input_note = strcat(input_note, num2str(i_in), ') ug for shooting nodes 0 to N-1, size [{{ dims.N*dims.ng }}]\n '); +sfun_input_names = [sfun_input_names; 'ug [{{ dims.N*dims.ng }}]']; i_in = i_in + 1; {%- endif %} {%- if dims.nh > 0 and simulink_opts.inputs.lh -%} {#- lh #} -input_note = strcat(input_note, num2str(i_in), ') lh, size [{{ dims.nh }}]\n '); +input_note = strcat(input_note, num2str(i_in), ') lh for shooting nodes 0 to N-1, size [{{ dims.N*dims.nh }}]\n '); +sfun_input_names = [sfun_input_names; 'lh [{{ dims.N*dims.nh }}]']; i_in = i_in + 1; {%- endif %} {%- if dims.nh > 0 and simulink_opts.inputs.uh -%} {#- uh #} -input_note = strcat(input_note, num2str(i_in), ') uh, size [{{ dims.nh }}]\n '); +input_note = strcat(input_note, num2str(i_in), ') uh for shooting nodes 0 to N-1, size [{{ dims.N*dims.nh }}]\n '); +sfun_input_names = [sfun_input_names; 'uh [{{ dims.N*dims.nh }}]']; +i_in = i_in + 1; +{%- endif %} + +{%- if dims.nh_e > 0 and simulink_opts.inputs.lh_e -%} {#- lh_e #} +input_note = strcat(input_note, num2str(i_in), ') lh_e, size [{{ dims.nh_e }}]\n '); +sfun_input_names = [sfun_input_names; 'lh_e [{{ dims.nh_e }}]']; +i_in = i_in + 1; +{%- endif %} +{%- if dims.nh_e > 0 and simulink_opts.inputs.uh_e -%} {#- uh_e #} +input_note = strcat(input_note, num2str(i_in), ') uh_e, size [{{ dims.nh_e }}]\n '); +sfun_input_names = [sfun_input_names; 'uh_e [{{ dims.nh_e }}]']; i_in = i_in + 1; {%- endif %} {%- if dims.ny_0 > 0 and simulink_opts.inputs.cost_W_0 %} {#- cost_W_0 #} input_note = strcat(input_note, num2str(i_in), ') cost_W_0 in column-major format, size [{{ dims.ny_0 * dims.ny_0 }}]\n '); +sfun_input_names = [sfun_input_names; 'cost_W_0 [{{ dims.ny_0 * dims.ny_0 }}]']; i_in = i_in + 1; {%- endif %} {%- if dims.ny > 0 and simulink_opts.inputs.cost_W %} {#- cost_W #} input_note = strcat(input_note, num2str(i_in), ') cost_W in column-major format, that is set for all intermediate shooting nodes: 1 to N-1, size [{{ dims.ny * dims.ny }}]\n '); +sfun_input_names = [sfun_input_names; 'cost_W [{{ dims.ny * dims.ny }}]']; i_in = i_in + 1; {%- endif %} {%- if dims.ny_e > 0 and simulink_opts.inputs.cost_W_e %} {#- cost_W_e #} input_note = strcat(input_note, num2str(i_in), ') cost_W_e in column-major format, size [{{ dims.ny_e * dims.ny_e }}]\n '); +sfun_input_names = [sfun_input_names; 'cost_W_e [{{ dims.ny_e * dims.ny_e }}]']; i_in = i_in + 1; {%- endif %} {%- if simulink_opts.inputs.reset_solver %} {#- reset_solver #} input_note = strcat(input_note, num2str(i_in), ') reset_solver determines if iterate is set to all zeros before other initializations (x_init, u_init) are set and before solver is called, size [1]\n '); +sfun_input_names = [sfun_input_names; 'reset_solver [1]']; i_in = i_in + 1; {%- endif %} {%- if simulink_opts.inputs.x_init %} {#- x_init #} input_note = strcat(input_note, num2str(i_in), ') initialization of x for all shooting nodes, size [{{ dims.nx * (dims.N+1) }}]\n '); +sfun_input_names = [sfun_input_names; 'x_init [{{ dims.nx * (dims.N+1) }}]']; i_in = i_in + 1; {%- endif %} {%- if simulink_opts.inputs.u_init %} {#- u_init #} input_note = strcat(input_note, num2str(i_in), ') initialization of u for shooting nodes 0 to N-1, size [{{ dims.nu * (dims.N) }}]\n '); +sfun_input_names = [sfun_input_names; 'u_init [{{ dims.nu * (dims.N) }}]']; i_in = i_in + 1; {%- endif %} @@ -286,59 +334,99 @@ disp(' ') output_note = 'Outputs are:\n'; i_out = 0; +global sfun_output_names +sfun_output_names = {}; + {%- if dims.nu > 0 and simulink_opts.outputs.u0 == 1 %} i_out = i_out + 1; output_note = strcat(output_note, num2str(i_out), ') u0, control input at node 0, size [{{ dims.nu }}]\n '); +sfun_output_names = [sfun_output_names; 'u0 [{{ dims.nu }}]']; {%- endif %} {%- if simulink_opts.outputs.utraj == 1 %} i_out = i_out + 1; output_note = strcat(output_note, num2str(i_out), ') utraj, control input concatenated for nodes 0 to N-1, size [{{ dims.nu * dims.N }}]\n '); +sfun_output_names = [sfun_output_names; 'utraj [{{ dims.nu * dims.N }}]']; {%- endif %} {%- if simulink_opts.outputs.xtraj == 1 %} i_out = i_out + 1; output_note = strcat(output_note, num2str(i_out), ') xtraj, state concatenated for nodes 0 to N, size [{{ dims.nx * (dims.N + 1) }}]\n '); +sfun_output_names = [sfun_output_names; 'xtraj [{{ dims.nx * (dims.N + 1) }}]']; {%- endif %} {%- if simulink_opts.outputs.solver_status == 1 %} i_out = i_out + 1; output_note = strcat(output_note, num2str(i_out), ') acados solver status (0 = SUCCESS)\n '); +sfun_output_names = [sfun_output_names; 'solver_status']; {%- endif %} +{%- if simulink_opts.outputs.cost_value == 1 %} +i_out = i_out + 1; +output_note = strcat(output_note, num2str(i_out), ') cost function value\n '); +sfun_output_names = [sfun_output_names; 'cost_value']; +{%- endif %} + + {%- if simulink_opts.outputs.KKT_residual == 1 %} i_out = i_out + 1; output_note = strcat(output_note, num2str(i_out), ') KKT residual\n '); +sfun_output_names = [sfun_output_names; 'KKT_residual']; +{%- endif %} + +{%- if simulink_opts.outputs.KKT_residuals == 1 %} +i_out = i_out + 1; +output_note = strcat(output_note, num2str(i_out), ') KKT residuals, size [4] (stat, eq, ineq, comp)\n '); +sfun_output_names = [sfun_output_names; 'KKT_residuals [4]']; {%- endif %} {%- if dims.N > 0 and simulink_opts.outputs.x1 == 1 %} i_out = i_out + 1; output_note = strcat(output_note, num2str(i_out), ') x1, state at node 1\n '); +sfun_output_names = [sfun_output_names; 'x1']; {%- endif %} {%- if simulink_opts.outputs.CPU_time == 1 %} i_out = i_out + 1; output_note = strcat(output_note, num2str(i_out), ') CPU time\n '); +sfun_output_names = [sfun_output_names; 'CPU_time']; {%- endif %} {%- if simulink_opts.outputs.CPU_time_sim == 1 %} i_out = i_out + 1; output_note = strcat(output_note, num2str(i_out), ') CPU time integrator\n '); +sfun_output_names = [sfun_output_names; 'CPU_time_sim']; {%- endif %} {%- if simulink_opts.outputs.CPU_time_qp == 1 %} i_out = i_out + 1; output_note = strcat(output_note, num2str(i_out), ') CPU time QP solution\n '); +sfun_output_names = [sfun_output_names; 'CPU_time_qp']; {%- endif %} {%- if simulink_opts.outputs.CPU_time_lin == 1 %} i_out = i_out + 1; output_note = strcat(output_note, num2str(i_out), ') CPU time linearization (including integrator)\n '); +sfun_output_names = [sfun_output_names; 'CPU_time_lin']; {%- endif %} {%- if simulink_opts.outputs.sqp_iter == 1 %} i_out = i_out + 1; output_note = strcat(output_note, num2str(i_out), ') SQP iterations\n '); +sfun_output_names = [sfun_output_names; 'sqp_iter']; {%- endif %} fprintf(output_note) + +% The mask drawing command is: +% --- +% global sfun_input_names sfun_output_names +% for i = 1:length(sfun_input_names) +% port_label('input', i, sfun_input_names{i}) +% end +% for i = 1:length(sfun_output_names) +% port_label('output', i, sfun_output_names{i}) +% end +% --- +% It can be used by copying it in sfunction/Mask/Edit mask/Icon drawing commands +% (you can access it wirth ctrl+M on the s-function) \ No newline at end of file diff --git a/third_party/acados/acados_template/c_templates_tera/make_sfun_sim.in.m b/third_party/acados/acados_template/c_templates_tera/matlab_templates/make_sfun_sim.in.m similarity index 70% rename from third_party/acados/acados_template/c_templates_tera/make_sfun_sim.in.m rename to third_party/acados/acados_template/c_templates_tera/matlab_templates/make_sfun_sim.in.m index a0c503e41..e4c32a8c1 100644 --- a/third_party/acados/acados_template/c_templates_tera/make_sfun_sim.in.m +++ b/third_party/acados/acados_template/c_templates_tera/matlab_templates/make_sfun_sim.in.m @@ -1,8 +1,5 @@ % -% Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, -% Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, -% Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, -% Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl +% Copyright (c) The acados authors. % % This file is part of acados. % @@ -29,17 +26,19 @@ % 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.; + % SOURCES = [ 'acados_sim_solver_sfunction_{{ model.name }}.c ', ... 'acados_sim_solver_{{ model.name }}.c ', ... {%- if solver_options.integrator_type == 'ERK' %} - '{{ model.name }}_model/{{ model.name }}_expl_ode_fun.c ', ... + '{{ model.name }}_model/{{ model.name }}_expl_ode_fun.c ',... '{{ model.name }}_model/{{ model.name }}_expl_vde_forw.c ',... + '{{ model.name }}_model/{{ model.name }}_expl_vde_adj.c ',... {%- if solver_options.hessian_approx == 'EXACT' %} '{{ model.name }}_model/{{ model.name }}_expl_ode_hess.c ',... {%- endif %} - {%- elif solver_options.integrator_type == "IRK" %} + {%- elif solver_options.integrator_type == "IRK" %} '{{ model.name }}_model/{{ model.name }}_impl_dae_fun.c ', ... '{{ model.name }}_model/{{ model.name }}_impl_dae_fun_jac_x_xdot_z.c ', ... '{{ model.name }}_model/{{ model.name }}_impl_dae_jac_x_xdot_u_z.c ', ... @@ -47,15 +46,15 @@ SOURCES = [ 'acados_sim_solver_sfunction_{{ model.name }}.c ', ... '{{ model.name }}_model/{{ model.name }}_impl_dae_hess.c ',... {%- endif %} {%- elif solver_options.integrator_type == "GNSF" %} - {% if model.gnsf.purely_linear != 1 %} - '{{ model.name }}_model/{{ model.name }}_gnsf_phi_fun.c ' - '{{ model.name }}_model/{{ model.name }}_gnsf_phi_fun_jac_y.c ' - '{{ model.name }}_model/{{ model.name }}_gnsf_phi_jac_y_uhat.c ' - {% if model.gnsf.nontrivial_f_LO == 1 %} - '{{ model.name }}_model/{{ model.name }}_gnsf_f_lo_fun_jac_x1k1uz.c ' + {%- if model.gnsf.purely_linear != 1 %} + '{{ model.name }}_model/{{ model.name }}_gnsf_phi_fun.c ',... + '{{ model.name }}_model/{{ model.name }}_gnsf_phi_fun_jac_y.c ',... + '{{ model.name }}_model/{{ model.name }}_gnsf_phi_jac_y_uhat.c ',... + {%- if model.gnsf.nontrivial_f_LO == 1 %} + '{{ model.name }}_model/{{ model.name }}_gnsf_f_lo_fun_jac_x1k1uz.c ',... {%- endif %} {%- endif %} - '{{ model.name }}_model/{{ model.name }}_gnsf_get_matrices_fun.c ' + '{{ model.name }}_model/{{ model.name }}_gnsf_get_matrices_fun.c ',... {%- endif %} ]; @@ -71,25 +70,42 @@ LIB_PATH = '{{ acados_lib_path }}'; LIBS = '-lacados -lblasfeo -lhpipm'; -eval( [ 'mex -v -output acados_sim_solver_sfunction_{{ model.name }} ', ... - CFLAGS, INCS, ' ', SOURCES, ' -L', LIB_PATH, ' ', LIBS ]); +try + % eval( [ 'mex -v -output acados_sim_solver_sfunction_{{ model.name }} ', ... + eval( [ 'mex -output acados_sim_solver_sfunction_{{ model.name }} ', ... + CFLAGS, INCS, ' ', SOURCES, ' -L', LIB_PATH, ' ', LIBS ]); + +catch exception + disp('make_sfun failed with the following exception:') + disp(exception); + disp('Try adding -v to the mex command above to get more information.') + keyboard +end + fprintf( [ '\n\nSuccessfully created sfunction:\nacados_sim_solver_sfunction_{{ model.name }}', '.', ... eval('mexext')] ); +global sfun_sim_input_names +sfun_sim_input_names = {}; + %% print note on usage of s-function fprintf('\n\nNote: Usage of Sfunction is as follows:\n') input_note = 'Inputs are:\n1) x0, initial state, size [{{ dims.nx }}]\n '; i_in = 2; +sfun_sim_input_names = [sfun_sim_input_names; 'x0 [{{ dims.nx }}]']; + {%- if dims.nu > 0 %} input_note = strcat(input_note, num2str(i_in), ') u, size [{{ dims.nu }}]\n '); i_in = i_in + 1; +sfun_sim_input_names = [sfun_sim_input_names; 'u [{{ dims.nu }}]']; {%- endif %} {%- if dims.np > 0 %} input_note = strcat(input_note, num2str(i_in), ') parameters, size [{{ dims.np }}]\n '); i_in = i_in + 1; +sfun_sim_input_names = [sfun_sim_input_names; 'p [{{ dims.np }}]']; {%- endif %} @@ -97,7 +113,25 @@ fprintf(input_note) disp(' ') +global sfun_sim_output_names +sfun_sim_output_names = {}; + output_note = strcat('Outputs are:\n', ... '1) x1 - simulated state, size [{{ dims.nx }}]\n'); +sfun_sim_output_names = [sfun_sim_output_names; 'x1 [{{ dims.nx }}]']; fprintf(output_note) + + +% The mask drawing command is: +% --- +% global sfun_sim_input_names sfun_sim_output_names +% for i = 1:length(sfun_sim_input_names) +% port_label('input', i, sfun_sim_input_names{i}) +% end +% for i = 1:length(sfun_sim_output_names) +% port_label('output', i, sfun_sim_output_names{i}) +% end +% --- +% It can be used by copying it in sfunction/Mask/Edit mask/Icon drawing commands +% (you can access it wirth ctrl+M on the s-function) \ No newline at end of file diff --git a/third_party/acados/acados_template/c_templates_tera/mex_solver.in.m b/third_party/acados/acados_template/c_templates_tera/matlab_templates/mex_solver.in.m similarity index 61% rename from third_party/acados/acados_template/c_templates_tera/mex_solver.in.m rename to third_party/acados/acados_template/c_templates_tera/matlab_templates/mex_solver.in.m index 278e0a605..374321283 100644 --- a/third_party/acados/acados_template/c_templates_tera/mex_solver.in.m +++ b/third_party/acados/acados_template/c_templates_tera/matlab_templates/mex_solver.in.m @@ -1,8 +1,5 @@ % -% Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, -% Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, -% Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, -% Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl +% Copyright (c) The acados authors. % % This file is part of acados. % @@ -29,6 +26,7 @@ % 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.; + % classdef {{ model.name }}_mex_solver < handle @@ -38,6 +36,9 @@ classdef {{ model.name }}_mex_solver < handle C_ocp_ext_fun cost_ext_fun_type cost_ext_fun_type_e + N + name + code_gen_dir end % properties @@ -52,13 +53,21 @@ classdef {{ model.name }}_mex_solver < handle addpath('.') obj.cost_ext_fun_type = '{{ cost.cost_ext_fun_type }}'; obj.cost_ext_fun_type_e = '{{ cost.cost_ext_fun_type_e }}'; + obj.N = {{ dims.N }}; + obj.name = '{{ model.name }}'; + obj.code_gen_dir = pwd(); end % destructor function delete(obj) + disp("delete template..."); + return_dir = pwd(); + cd(obj.code_gen_dir); if ~isempty(obj.C_ocp) acados_mex_free_{{ model.name }}(obj.C_ocp); end + cd(return_dir); + disp("done."); end % solve @@ -112,6 +121,101 @@ classdef {{ model.name }}_mex_solver < handle end + function [] = store_iterate(varargin) + %%% Stores the current iterate of the ocp solver in a json file. + %%% param1: filename: if not set, use model_name + timestamp + '.json' + %%% param2: overwrite: if false and filename exists add timestamp to filename + + obj = varargin{1}; + filename = ''; + overwrite = false; + + if nargin>=2 + filename = varargin{2}; + if ~isa(filename, 'char') + error('filename must be a char vector, use '' '''); + end + end + + if nargin==3 + overwrite = varargin{3}; + end + + if nargin > 3 + disp('acados_ocp.get: wrong number of input arguments (1 or 2 allowed)'); + end + + if strcmp(filename,'') + filename = [obj.name '_iterate.json']; + end + if ~overwrite + % append timestamp + if exist(filename, 'file') + filename = filename(1:end-5); + filename = [filename '_' datestr(now,'yyyy-mm-dd-HH:MM:SS') '.json']; + end + end + filename = fullfile(pwd, filename); + + % get iterate: + solution = struct(); + for i=0:obj.N + solution.(['x_' num2str(i)]) = obj.get('x', i); + solution.(['lam_' num2str(i)]) = obj.get('lam', i); + solution.(['t_' num2str(i)]) = obj.get('t', i); + solution.(['sl_' num2str(i)]) = obj.get('sl', i); + solution.(['su_' num2str(i)]) = obj.get('su', i); + end + for i=0:obj.N-1 + solution.(['z_' num2str(i)]) = obj.get('z', i); + solution.(['u_' num2str(i)]) = obj.get('u', i); + solution.(['pi_' num2str(i)]) = obj.get('pi', i); + end + + acados_folder = getenv('ACADOS_INSTALL_DIR'); + addpath(fullfile(acados_folder, 'external', 'jsonlab')); + savejson('', solution, filename); + + json_string = savejson('', solution, 'ForceRootName', 0); + + fid = fopen(filename, 'w'); + if fid == -1, error('store_iterate: Cannot create JSON file'); end + fwrite(fid, json_string, 'char'); + fclose(fid); + + disp(['stored current iterate in ' filename]); + end + + + function [] = load_iterate(obj, filename) + %%% Loads the iterate stored in json file with filename into the ocp solver. + acados_folder = getenv('ACADOS_INSTALL_DIR'); + addpath(fullfile(acados_folder, 'external', 'jsonlab')); + filename = fullfile(pwd, filename); + + if ~exist(filename, 'file') + error(['load_iterate: failed, file does not exist: ' filename]) + end + + solution = loadjson(filename); + keys = fieldnames(solution); + + for k = 1:numel(keys) + key = keys{k}; + key_parts = strsplit(key, '_'); + field = key_parts{1}; + stage = key_parts{2}; + + val = solution.(key); + + % check if array is empty (can happen for z) + if numel(val) > 0 + obj.set(field, val, str2num(stage)) + end + end + end + + % print function print(varargin) if nargin < 2 diff --git a/third_party/acados/acados_template/c_templates_tera/model.in.h b/third_party/acados/acados_template/c_templates_tera/model.in.h index 918e2bc29..e5059df9f 100644 --- a/third_party/acados/acados_template/c_templates_tera/model.in.h +++ b/third_party/acados/acados_template/c_templates_tera/model.in.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * @@ -47,7 +44,8 @@ extern "C" { {%- endif %} {% if solver_options.integrator_type == "IRK" or solver_options.integrator_type == "LIFTED_IRK" %} -// implicit ODE + {% if model.dyn_ext_fun_type == "casadi" %} +// implicit ODE: function int {{ model.name }}_impl_dae_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); int {{ model.name }}_impl_dae_fun_work(int *, int *, int *, int *); const int *{{ model.name }}_impl_dae_fun_sparsity_in(int); @@ -55,7 +53,7 @@ const int *{{ model.name }}_impl_dae_fun_sparsity_out(int); int {{ model.name }}_impl_dae_fun_n_in(void); int {{ model.name }}_impl_dae_fun_n_out(void); -// implicit ODE +// implicit ODE: function + jacobians int {{ model.name }}_impl_dae_fun_jac_x_xdot_z(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); int {{ model.name }}_impl_dae_fun_jac_x_xdot_z_work(int *, int *, int *, int *); const int *{{ model.name }}_impl_dae_fun_jac_x_xdot_z_sparsity_in(int); @@ -63,7 +61,7 @@ const int *{{ model.name }}_impl_dae_fun_jac_x_xdot_z_sparsity_out(int); int {{ model.name }}_impl_dae_fun_jac_x_xdot_z_n_in(void); int {{ model.name }}_impl_dae_fun_jac_x_xdot_z_n_out(void); -// implicit ODE +// implicit ODE: jacobians only int {{ model.name }}_impl_dae_jac_x_xdot_u_z(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); int {{ model.name }}_impl_dae_jac_x_xdot_u_z_work(int *, int *, int *, int *); const int *{{ model.name }}_impl_dae_jac_x_xdot_u_z_sparsity_in(int); @@ -79,14 +77,23 @@ const int *{{ model.name }}_impl_dae_fun_jac_x_xdot_u_sparsity_out(int); int {{ model.name }}_impl_dae_fun_jac_x_xdot_u_n_in(void); int {{ model.name }}_impl_dae_fun_jac_x_xdot_u_n_out(void); -{%- if hessian_approx == "EXACT" %} + {%- if hessian_approx == "EXACT" %} +// implicit ODE - hessian int {{ model.name }}_impl_dae_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); int {{ model.name }}_impl_dae_hess_work(int *, int *, int *, int *); const int *{{ model.name }}_impl_dae_hess_sparsity_in(int); const int *{{ model.name }}_impl_dae_hess_sparsity_out(int); int {{ model.name }}_impl_dae_hess_n_in(void); int {{ model.name }}_impl_dae_hess_n_out(void); -{%- endif %} + {% endif %} + {% else %}{# ext_fun_type #} + {%- if hessian_approx == "EXACT" %} +int {{ model.dyn_impl_dae_hess }}(void **, void **, void *); + {% endif %} +int {{ model.dyn_impl_dae_fun_jac }}(void **, void **, void *); +int {{ model.dyn_impl_dae_jac }}(void **, void **, void *); +int {{ model.dyn_impl_dae_fun }}(void **, void **, void *); + {% endif %}{# ext_fun_type #} {% elif solver_options.integrator_type == "GNSF" %} /* GNSF Functions */ diff --git a/third_party/acados/acados_template/c_templates_tera/phi_e_constraint.in.h b/third_party/acados/acados_template/c_templates_tera/phi_e_constraint.in.h deleted file mode 100644 index dc8e293ad..000000000 --- a/third_party/acados/acados_template/c_templates_tera/phi_e_constraint.in.h +++ /dev/null @@ -1,21 +0,0 @@ -#ifndef {{ model.name }}_PHI_E_CONSTRAINT -#define {{ model.name }}_PHI_E_CONSTRAINT - -#ifdef __cplusplus -extern "C" { -#endif - -{% if dims.nphi_e > 0 %} -int {{ model.name }}_phi_e_constraint(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_phi_e_constraint_work(int *, int *, int *, int *); -const int *{{ model.name }}_phi_e_constraint_sparsity_in(int); -const int *{{ model.name }}_phi_e_constraint_sparsity_out(int); -int {{ model.name }}_phi_e_constraint_n_in(void); -int {{ model.name }}_phi_e_constraint_n_out(void); -{% endif %} - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // {{ model.name }}_PHI_E_CONSTRAINT diff --git a/third_party/acados/acados_template/casadi_function_generation.py b/third_party/acados/acados_template/casadi_function_generation.py new file mode 100644 index 000000000..6373a2809 --- /dev/null +++ b/third_party/acados/acados_template/casadi_function_generation.py @@ -0,0 +1,708 @@ +# +# Copyright (c) The acados authors. +# +# This file is part of acados. +# +# 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 HOLDER 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.; +# + +import os +import casadi as ca +from .utils import is_empty, casadi_length + + +def get_casadi_symbol(x): + if isinstance(x, ca.MX): + return ca.MX.sym + elif isinstance(x, ca.SX): + return ca.SX.sym + else: + raise TypeError("Expected casadi SX or MX.") + +################ +# Dynamics +################ + + +def generate_c_code_discrete_dynamics( model, opts ): + + casadi_codegen_opts = dict(mex=False, casadi_int='int', casadi_real='double') + + # load model + x = model.x + u = model.u + p = model.p + phi = model.disc_dyn_expr + model_name = model.name + nx = casadi_length(x) + + symbol = get_casadi_symbol(x) + # assume nx1 = nx !!! + lam = symbol('lam', nx, 1) + + # generate jacobians + ux = ca.vertcat(u,x) + jac_ux = ca.jacobian(phi, ux) + # generate adjoint + adj_ux = ca.jtimes(phi, ux, lam, True) + # generate hessian + hess_ux = ca.jacobian(adj_ux, ux) + + # change directory + cwd = os.getcwd() + model_dir = os.path.abspath(os.path.join(opts["code_export_directory"], f'{model_name}_model')) + if not os.path.exists(model_dir): + os.makedirs(model_dir) + os.chdir(model_dir) + + # set up & generate ca.Functions + fun_name = model_name + '_dyn_disc_phi_fun' + phi_fun = ca.Function(fun_name, [x, u, p], [phi]) + phi_fun.generate(fun_name, casadi_codegen_opts) + + fun_name = model_name + '_dyn_disc_phi_fun_jac' + phi_fun_jac_ut_xt = ca.Function(fun_name, [x, u, p], [phi, jac_ux.T]) + phi_fun_jac_ut_xt.generate(fun_name, casadi_codegen_opts) + + fun_name = model_name + '_dyn_disc_phi_fun_jac_hess' + phi_fun_jac_ut_xt_hess = ca.Function(fun_name, [x, u, lam, p], [phi, jac_ux.T, hess_ux]) + phi_fun_jac_ut_xt_hess.generate(fun_name, casadi_codegen_opts) + + os.chdir(cwd) + return + + + +def generate_c_code_explicit_ode( model, opts ): + + casadi_codegen_opts = dict(mex=False, casadi_int='int', casadi_real='double') + + generate_hess = opts["generate_hess"] + + # load model + x = model.x + u = model.u + p = model.p + f_expl = model.f_expl_expr + model_name = model.name + + ## get model dimensions + nx = x.size()[0] + nu = u.size()[0] + + symbol = get_casadi_symbol(x) + + ## set up functions to be exported + Sx = symbol('Sx', nx, nx) + Sp = symbol('Sp', nx, nu) + lambdaX = symbol('lambdaX', nx, 1) + + fun_name = model_name + '_expl_ode_fun' + + ## Set up functions + expl_ode_fun = ca.Function(fun_name, [x, u, p], [f_expl]) + + vdeX = ca.jtimes(f_expl,x,Sx) + vdeP = ca.jacobian(f_expl,u) + ca.jtimes(f_expl,x,Sp) + + fun_name = model_name + '_expl_vde_forw' + + expl_vde_forw = ca.Function(fun_name, [x, Sx, Sp, u, p], [f_expl, vdeX, vdeP]) + + adj = ca.jtimes(f_expl, ca.vertcat(x, u), lambdaX, True) + + fun_name = model_name + '_expl_vde_adj' + expl_vde_adj = ca.Function(fun_name, [x, lambdaX, u, p], [adj]) + + if generate_hess: + S_forw = ca.vertcat(ca.horzcat(Sx, Sp), ca.horzcat(ca.DM.zeros(nu,nx), ca.DM.eye(nu))) + hess = ca.mtimes(ca.transpose(S_forw),ca.jtimes(adj, ca.vertcat(x,u), S_forw)) + hess2 = [] + for j in range(nx+nu): + for i in range(j,nx+nu): + hess2 = ca.vertcat(hess2, hess[i,j]) + + fun_name = model_name + '_expl_ode_hess' + expl_ode_hess = ca.Function(fun_name, [x, Sx, Sp, lambdaX, u, p], [adj, hess2]) + + # change directory + cwd = os.getcwd() + model_dir = os.path.abspath(os.path.join(opts["code_export_directory"], f'{model_name}_model')) + if not os.path.exists(model_dir): + os.makedirs(model_dir) + os.chdir(model_dir) + + # generate C code + fun_name = model_name + '_expl_ode_fun' + expl_ode_fun.generate(fun_name, casadi_codegen_opts) + + fun_name = model_name + '_expl_vde_forw' + expl_vde_forw.generate(fun_name, casadi_codegen_opts) + + fun_name = model_name + '_expl_vde_adj' + expl_vde_adj.generate(fun_name, casadi_codegen_opts) + + if generate_hess: + fun_name = model_name + '_expl_ode_hess' + expl_ode_hess.generate(fun_name, casadi_codegen_opts) + os.chdir(cwd) + + return + + +def generate_c_code_implicit_ode( model, opts ): + + casadi_codegen_opts = dict(mex=False, casadi_int='int', casadi_real='double') + + # load model + x = model.x + xdot = model.xdot + u = model.u + z = model.z + p = model.p + f_impl = model.f_impl_expr + model_name = model.name + + # get model dimensions + nx = casadi_length(x) + nz = casadi_length(z) + + # generate jacobians + jac_x = ca.jacobian(f_impl, x) + jac_xdot = ca.jacobian(f_impl, xdot) + jac_u = ca.jacobian(f_impl, u) + jac_z = ca.jacobian(f_impl, z) + + # Set up functions + p = model.p + fun_name = model_name + '_impl_dae_fun' + impl_dae_fun = ca.Function(fun_name, [x, xdot, u, z, p], [f_impl]) + + fun_name = model_name + '_impl_dae_fun_jac_x_xdot_z' + impl_dae_fun_jac_x_xdot_z = ca.Function(fun_name, [x, xdot, u, z, p], [f_impl, jac_x, jac_xdot, jac_z]) + + fun_name = model_name + '_impl_dae_fun_jac_x_xdot_u_z' + impl_dae_fun_jac_x_xdot_u_z = ca.Function(fun_name, [x, xdot, u, z, p], [f_impl, jac_x, jac_xdot, jac_u, jac_z]) + + fun_name = model_name + '_impl_dae_fun_jac_x_xdot_u' + impl_dae_fun_jac_x_xdot_u = ca.Function(fun_name, [x, xdot, u, z, p], [f_impl, jac_x, jac_xdot, jac_u]) + + fun_name = model_name + '_impl_dae_jac_x_xdot_u_z' + impl_dae_jac_x_xdot_u_z = ca.Function(fun_name, [x, xdot, u, z, p], [jac_x, jac_xdot, jac_u, jac_z]) + + if opts["generate_hess"]: + x_xdot_z_u = ca.vertcat(x, xdot, z, u) + symbol = get_casadi_symbol(x) + multiplier = symbol('multiplier', nx + nz) + ADJ = ca.jtimes(f_impl, x_xdot_z_u, multiplier, True) + HESS = ca.jacobian(ADJ, x_xdot_z_u) + fun_name = model_name + '_impl_dae_hess' + impl_dae_hess = ca.Function(fun_name, [x, xdot, u, z, multiplier, p], [HESS]) + + # change directory + cwd = os.getcwd() + model_dir = os.path.abspath(os.path.join(opts["code_export_directory"], f'{model_name}_model')) + if not os.path.exists(model_dir): + os.makedirs(model_dir) + os.chdir(model_dir) + + # generate C code + fun_name = model_name + '_impl_dae_fun' + impl_dae_fun.generate(fun_name, casadi_codegen_opts) + + fun_name = model_name + '_impl_dae_fun_jac_x_xdot_z' + impl_dae_fun_jac_x_xdot_z.generate(fun_name, casadi_codegen_opts) + + fun_name = model_name + '_impl_dae_jac_x_xdot_u_z' + impl_dae_jac_x_xdot_u_z.generate(fun_name, casadi_codegen_opts) + + fun_name = model_name + '_impl_dae_fun_jac_x_xdot_u_z' + impl_dae_fun_jac_x_xdot_u_z.generate(fun_name, casadi_codegen_opts) + + fun_name = model_name + '_impl_dae_fun_jac_x_xdot_u' + impl_dae_fun_jac_x_xdot_u.generate(fun_name, casadi_codegen_opts) + + if opts["generate_hess"]: + fun_name = model_name + '_impl_dae_hess' + impl_dae_hess.generate(fun_name, casadi_codegen_opts) + + os.chdir(cwd) + return + + +def generate_c_code_gnsf( model, opts ): + + casadi_codegen_opts = dict(mex=False, casadi_int='int', casadi_real='double') + + model_name = model.name + + # set up directory + cwd = os.getcwd() + model_dir = os.path.abspath(os.path.join(opts["code_export_directory"], f'{model_name}_model')) + if not os.path.exists(model_dir): + os.makedirs(model_dir) + os.chdir(model_dir) + + # obtain gnsf dimensions + get_matrices_fun = model.get_matrices_fun + phi_fun = model.phi_fun + + size_gnsf_A = get_matrices_fun.size_out(0) + gnsf_nx1 = size_gnsf_A[1] + gnsf_nz1 = size_gnsf_A[0] - size_gnsf_A[1] + gnsf_nuhat = max(phi_fun.size_in(1)) + gnsf_ny = max(phi_fun.size_in(0)) + gnsf_nout = max(phi_fun.size_out(0)) + + # set up expressions + # if the model uses ca.MX because of cost/constraints + # the DAE can be exported as ca.SX -> detect GNSF in Matlab + # -> evaluated ca.SX GNSF functions with ca.MX. + u = model.u + symbol = get_casadi_symbol(u) + + y = symbol("y", gnsf_ny, 1) + uhat = symbol("uhat", gnsf_nuhat, 1) + p = model.p + x1 = symbol("gnsf_x1", gnsf_nx1, 1) + x1dot = symbol("gnsf_x1dot", gnsf_nx1, 1) + z1 = symbol("gnsf_z1", gnsf_nz1, 1) + dummy = symbol("gnsf_dummy", 1, 1) + empty_var = symbol("gnsf_empty_var", 0, 0) + + ## generate C code + fun_name = model_name + '_gnsf_phi_fun' + phi_fun_ = ca.Function(fun_name, [y, uhat, p], [phi_fun(y, uhat, p)]) + phi_fun_.generate(fun_name, casadi_codegen_opts) + + fun_name = model_name + '_gnsf_phi_fun_jac_y' + phi_fun_jac_y = model.phi_fun_jac_y + phi_fun_jac_y_ = ca.Function(fun_name, [y, uhat, p], phi_fun_jac_y(y, uhat, p)) + phi_fun_jac_y_.generate(fun_name, casadi_codegen_opts) + + fun_name = model_name + '_gnsf_phi_jac_y_uhat' + phi_jac_y_uhat = model.phi_jac_y_uhat + phi_jac_y_uhat_ = ca.Function(fun_name, [y, uhat, p], phi_jac_y_uhat(y, uhat, p)) + phi_jac_y_uhat_.generate(fun_name, casadi_codegen_opts) + + fun_name = model_name + '_gnsf_f_lo_fun_jac_x1k1uz' + f_lo_fun_jac_x1k1uz = model.f_lo_fun_jac_x1k1uz + f_lo_fun_jac_x1k1uz_eval = f_lo_fun_jac_x1k1uz(x1, x1dot, z1, u, p) + + # avoid codegeneration issue + if not isinstance(f_lo_fun_jac_x1k1uz_eval, tuple) and is_empty(f_lo_fun_jac_x1k1uz_eval): + f_lo_fun_jac_x1k1uz_eval = [empty_var] + + f_lo_fun_jac_x1k1uz_ = ca.Function(fun_name, [x1, x1dot, z1, u, p], + f_lo_fun_jac_x1k1uz_eval) + f_lo_fun_jac_x1k1uz_.generate(fun_name, casadi_codegen_opts) + + fun_name = model_name + '_gnsf_get_matrices_fun' + get_matrices_fun_ = ca.Function(fun_name, [dummy], get_matrices_fun(1)) + get_matrices_fun_.generate(fun_name, casadi_codegen_opts) + + # remove fields for json dump + del model.phi_fun + del model.phi_fun_jac_y + del model.phi_jac_y_uhat + del model.f_lo_fun_jac_x1k1uz + del model.get_matrices_fun + + os.chdir(cwd) + + return + + +################ +# Cost +################ + +def generate_c_code_external_cost(model, stage_type, opts): + + casadi_codegen_opts = dict(mex=False, casadi_int='int', casadi_real='double') + + x = model.x + p = model.p + u = model.u + z = model.z + symbol = get_casadi_symbol(x) + + if stage_type == 'terminal': + suffix_name = "_cost_ext_cost_e_fun" + suffix_name_hess = "_cost_ext_cost_e_fun_jac_hess" + suffix_name_jac = "_cost_ext_cost_e_fun_jac" + ext_cost = model.cost_expr_ext_cost_e + custom_hess = model.cost_expr_ext_cost_custom_hess_e + # Last stage cannot depend on u and z + u = symbol("u", 0, 0) + z = symbol("z", 0, 0) + + elif stage_type == 'path': + suffix_name = "_cost_ext_cost_fun" + suffix_name_hess = "_cost_ext_cost_fun_jac_hess" + suffix_name_jac = "_cost_ext_cost_fun_jac" + ext_cost = model.cost_expr_ext_cost + custom_hess = model.cost_expr_ext_cost_custom_hess + + elif stage_type == 'initial': + suffix_name = "_cost_ext_cost_0_fun" + suffix_name_hess = "_cost_ext_cost_0_fun_jac_hess" + suffix_name_jac = "_cost_ext_cost_0_fun_jac" + ext_cost = model.cost_expr_ext_cost_0 + custom_hess = model.cost_expr_ext_cost_custom_hess_0 + + nunx = x.shape[0] + u.shape[0] + + # set up functions to be exported + fun_name = model.name + suffix_name + fun_name_hess = model.name + suffix_name_hess + fun_name_jac = model.name + suffix_name_jac + + # generate expression for full gradient and Hessian + hess_uxz, grad_uxz = ca.hessian(ext_cost, ca.vertcat(u, x, z)) + + hess_ux = hess_uxz[:nunx, :nunx] + hess_z = hess_uxz[nunx:, nunx:] + hess_z_ux = hess_uxz[nunx:, :nunx] + + if custom_hess is not None: + hess_ux = custom_hess + + ext_cost_fun = ca.Function(fun_name, [x, u, z, p], [ext_cost]) + + ext_cost_fun_jac_hess = ca.Function( + fun_name_hess, [x, u, z, p], [ext_cost, grad_uxz, hess_ux, hess_z, hess_z_ux] + ) + ext_cost_fun_jac = ca.Function( + fun_name_jac, [x, u, z, p], [ext_cost, grad_uxz] + ) + + # change directory + cwd = os.getcwd() + cost_dir = os.path.abspath(os.path.join(opts["code_export_directory"], f'{model.name}_cost')) + if not os.path.exists(cost_dir): + os.makedirs(cost_dir) + os.chdir(cost_dir) + + ext_cost_fun.generate(fun_name, casadi_codegen_opts) + ext_cost_fun_jac_hess.generate(fun_name_hess, casadi_codegen_opts) + ext_cost_fun_jac.generate(fun_name_jac, casadi_codegen_opts) + + os.chdir(cwd) + return + + +def generate_c_code_nls_cost( model, cost_name, stage_type, opts ): + + casadi_codegen_opts = dict(mex=False, casadi_int='int', casadi_real='double') + + x = model.x + z = model.z + p = model.p + u = model.u + + symbol = get_casadi_symbol(x) + + if stage_type == 'terminal': + middle_name = '_cost_y_e' + u = symbol('u', 0, 0) + y_expr = model.cost_y_expr_e + + elif stage_type == 'initial': + middle_name = '_cost_y_0' + y_expr = model.cost_y_expr_0 + + elif stage_type == 'path': + middle_name = '_cost_y' + y_expr = model.cost_y_expr + + # change directory + cwd = os.getcwd() + cost_dir = os.path.abspath(os.path.join(opts["code_export_directory"], f'{model.name}_cost')) + if not os.path.exists(cost_dir): + os.makedirs(cost_dir) + os.chdir(cost_dir) + + # set up expressions + cost_jac_expr = ca.transpose(ca.jacobian(y_expr, ca.vertcat(u, x))) + dy_dz = ca.jacobian(y_expr, z) + ny = casadi_length(y_expr) + + y = symbol('y', ny, 1) + + y_adj = ca.jtimes(y_expr, ca.vertcat(u, x), y, True) + y_hess = ca.jacobian(y_adj, ca.vertcat(u, x)) + + ## generate C code + suffix_name = '_fun' + fun_name = cost_name + middle_name + suffix_name + y_fun = ca.Function( fun_name, [x, u, z, p], [ y_expr ]) + y_fun.generate( fun_name, casadi_codegen_opts ) + + suffix_name = '_fun_jac_ut_xt' + fun_name = cost_name + middle_name + suffix_name + y_fun_jac_ut_xt = ca.Function(fun_name, [x, u, z, p], [ y_expr, cost_jac_expr, dy_dz ]) + y_fun_jac_ut_xt.generate( fun_name, casadi_codegen_opts ) + + suffix_name = '_hess' + fun_name = cost_name + middle_name + suffix_name + y_hess = ca.Function(fun_name, [x, u, z, y, p], [ y_hess ]) + y_hess.generate( fun_name, casadi_codegen_opts ) + + os.chdir(cwd) + + return + + + +def generate_c_code_conl_cost(model, cost_name, stage_type, opts): + + casadi_codegen_opts = dict(mex=False, casadi_int='int', casadi_real='double') + + x = model.x + z = model.z + p = model.p + + symbol = get_casadi_symbol(x) + + if stage_type == 'terminal': + u = symbol('u', 0, 0) + + yref = model.cost_r_in_psi_expr_e + inner_expr = model.cost_y_expr_e - yref + outer_expr = model.cost_psi_expr_e + res_expr = model.cost_r_in_psi_expr_e + + suffix_name_fun = '_conl_cost_e_fun' + suffix_name_fun_jac_hess = '_conl_cost_e_fun_jac_hess' + + custom_hess = model.cost_conl_custom_outer_hess_e + + elif stage_type == 'initial': + u = model.u + + yref = model.cost_r_in_psi_expr_0 + inner_expr = model.cost_y_expr_0 - yref + outer_expr = model.cost_psi_expr_0 + res_expr = model.cost_r_in_psi_expr_0 + + suffix_name_fun = '_conl_cost_0_fun' + suffix_name_fun_jac_hess = '_conl_cost_0_fun_jac_hess' + + custom_hess = model.cost_conl_custom_outer_hess_0 + + elif stage_type == 'path': + u = model.u + + yref = model.cost_r_in_psi_expr + inner_expr = model.cost_y_expr - yref + outer_expr = model.cost_psi_expr + res_expr = model.cost_r_in_psi_expr + + suffix_name_fun = '_conl_cost_fun' + suffix_name_fun_jac_hess = '_conl_cost_fun_jac_hess' + + custom_hess = model.cost_conl_custom_outer_hess + + # set up function names + fun_name_cost_fun = model.name + suffix_name_fun + fun_name_cost_fun_jac_hess = model.name + suffix_name_fun_jac_hess + + # set up functions to be exported + outer_loss_fun = ca.Function('psi', [res_expr, p], [outer_expr]) + cost_expr = outer_loss_fun(inner_expr, p) + + outer_loss_grad_fun = ca.Function('outer_loss_grad', [res_expr, p], [ca.jacobian(outer_expr, res_expr).T]) + + if custom_hess is None: + outer_hess_fun = ca.Function('inner_hess', [res_expr, p], [ca.hessian(outer_loss_fun(res_expr, p), res_expr)[0]]) + else: + outer_hess_fun = ca.Function('inner_hess', [res_expr, p], [custom_hess]) + + Jt_ux_expr = ca.jacobian(inner_expr, ca.vertcat(u, x)).T + Jt_z_expr = ca.jacobian(inner_expr, z).T + + cost_fun = ca.Function( + fun_name_cost_fun, + [x, u, z, yref, p], + [cost_expr]) + + cost_fun_jac_hess = ca.Function( + fun_name_cost_fun_jac_hess, + [x, u, z, yref, p], + [cost_expr, outer_loss_grad_fun(inner_expr, p), Jt_ux_expr, Jt_z_expr, outer_hess_fun(inner_expr, p)] + ) + # change directory + cwd = os.getcwd() + cost_dir = os.path.abspath(os.path.join(opts["code_export_directory"], f'{model.name}_cost')) + if not os.path.exists(cost_dir): + os.makedirs(cost_dir) + os.chdir(cost_dir) + + # generate C code + cost_fun.generate(fun_name_cost_fun, casadi_codegen_opts) + cost_fun_jac_hess.generate(fun_name_cost_fun_jac_hess, casadi_codegen_opts) + + os.chdir(cwd) + + return + + +################ +# Constraints +################ +def generate_c_code_constraint( model, con_name, is_terminal, opts ): + + casadi_codegen_opts = dict(mex=False, casadi_int='int', casadi_real='double') + + # load constraint variables and expression + x = model.x + p = model.p + + symbol = get_casadi_symbol(x) + + if is_terminal: + con_h_expr = model.con_h_expr_e + con_phi_expr = model.con_phi_expr_e + # create dummy u, z + u = symbol('u', 0, 0) + z = symbol('z', 0, 0) + else: + con_h_expr = model.con_h_expr + con_phi_expr = model.con_phi_expr + u = model.u + z = model.z + + if (not is_empty(con_h_expr)) and (not is_empty(con_phi_expr)): + raise Exception("acados: you can either have constraint_h, or constraint_phi, not both.") + + if (is_empty(con_h_expr) and is_empty(con_phi_expr)): + # both empty -> nothing to generate + return + + if is_empty(con_h_expr): + constr_type = 'BGP' + else: + constr_type = 'BGH' + + if is_empty(p): + p = symbol('p', 0, 0) + + if is_empty(z): + z = symbol('z', 0, 0) + + if not (is_empty(con_h_expr)) and opts['generate_hess']: + # multipliers for hessian + nh = casadi_length(con_h_expr) + lam_h = symbol('lam_h', nh, 1) + + # set up & change directory + cwd = os.getcwd() + constraints_dir = os.path.abspath(os.path.join(opts["code_export_directory"], f'{model.name}_constraints')) + if not os.path.exists(constraints_dir): + os.makedirs(constraints_dir) + os.chdir(constraints_dir) + + # export casadi functions + if constr_type == 'BGH': + if is_terminal: + fun_name = con_name + '_constr_h_e_fun_jac_uxt_zt' + else: + fun_name = con_name + '_constr_h_fun_jac_uxt_zt' + + jac_ux_t = ca.transpose(ca.jacobian(con_h_expr, ca.vertcat(u,x))) + jac_z_t = ca.jacobian(con_h_expr, z) + constraint_fun_jac_tran = ca.Function(fun_name, [x, u, z, p], \ + [con_h_expr, jac_ux_t, jac_z_t]) + + constraint_fun_jac_tran.generate(fun_name, casadi_codegen_opts) + if opts['generate_hess']: + + if is_terminal: + fun_name = con_name + '_constr_h_e_fun_jac_uxt_zt_hess' + else: + fun_name = con_name + '_constr_h_fun_jac_uxt_zt_hess' + + # adjoint + adj_ux = ca.jtimes(con_h_expr, ca.vertcat(u, x), lam_h, True) + # hessian + hess_ux = ca.jacobian(adj_ux, ca.vertcat(u, x)) + + adj_z = ca.jtimes(con_h_expr, z, lam_h, True) + hess_z = ca.jacobian(adj_z, z) + + # set up functions + constraint_fun_jac_tran_hess = \ + ca.Function(fun_name, [x, u, lam_h, z, p], \ + [con_h_expr, jac_ux_t, hess_ux, jac_z_t, hess_z]) + + # generate C code + constraint_fun_jac_tran_hess.generate(fun_name, casadi_codegen_opts) + + if is_terminal: + fun_name = con_name + '_constr_h_e_fun' + else: + fun_name = con_name + '_constr_h_fun' + h_fun = ca.Function(fun_name, [x, u, z, p], [con_h_expr]) + h_fun.generate(fun_name, casadi_codegen_opts) + + else: # BGP constraint + if is_terminal: + fun_name = con_name + '_phi_e_constraint' + r = model.con_r_in_phi_e + con_r_expr = model.con_r_expr_e + else: + fun_name = con_name + '_phi_constraint' + r = model.con_r_in_phi + con_r_expr = model.con_r_expr + + nphi = casadi_length(con_phi_expr) + con_phi_expr_x_u_z = ca.substitute(con_phi_expr, r, con_r_expr) + phi_jac_u = ca.jacobian(con_phi_expr_x_u_z, u) + phi_jac_x = ca.jacobian(con_phi_expr_x_u_z, x) + phi_jac_z = ca.jacobian(con_phi_expr_x_u_z, z) + + hess = ca.hessian(con_phi_expr[0], r)[0] + for i in range(1, nphi): + hess = ca.vertcat(hess, ca.hessian(con_phi_expr[i], r)[0]) + + r_jac_u = ca.jacobian(con_r_expr, u) + r_jac_x = ca.jacobian(con_r_expr, x) + + constraint_phi = \ + ca.Function(fun_name, [x, u, z, p], \ + [con_phi_expr_x_u_z, \ + ca.vertcat(ca.transpose(phi_jac_u), ca.transpose(phi_jac_x)), \ + ca.transpose(phi_jac_z), \ + hess, + ca.vertcat(ca.transpose(r_jac_u), ca.transpose(r_jac_x))]) + + constraint_phi.generate(fun_name, casadi_codegen_opts) + + # change directory back + os.chdir(cwd) + + return + diff --git a/third_party/acados/acados_template/custom_update_templates/custom_update_function_zoro_template.in.c b/third_party/acados/acados_template/custom_update_templates/custom_update_function_zoro_template.in.c new file mode 100644 index 000000000..b39ff2e23 --- /dev/null +++ b/third_party/acados/acados_template/custom_update_templates/custom_update_function_zoro_template.in.c @@ -0,0 +1,819 @@ +/* + * Copyright (c) The acados authors. + * + * This file is part of acados. + * + * 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 HOLDER 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.; + */ + +// This is a template based custom_update function +#include +#include +#include +#include + +#include "custom_update_function.h" +#include "acados_solver_{{ model.name }}.h" +#include "acados_c/ocp_nlp_interface.h" +#include "acados/utils/mem.h" + +#include "blasfeo/include/blasfeo_d_aux_ext_dep.h" +#include "blasfeo/include/blasfeo_d_blasfeo_api.h" + + +typedef struct custom_memory +{ + // covariance matrics + struct blasfeo_dmat *uncertainty_matrix_buffer; // shape = (N+1, nx, nx) + // covariance matrix of the additive disturbance + struct blasfeo_dmat W_mat; // shape = (nw, nw) + struct blasfeo_dmat unc_jac_G_mat; // shape = (nx, nw) + struct blasfeo_dmat temp_GW_mat; // shape = (nx, nw) + struct blasfeo_dmat GWG_mat; // shape = (nx, nx) + // sensitivity matrices + struct blasfeo_dmat A_mat; // shape = (nx, nx) + struct blasfeo_dmat B_mat; // shape = (nx, nu) + // matrix in linear constraints + struct blasfeo_dmat Cg_mat; // shape = (ng, nx) + struct blasfeo_dmat Dg_mat; // shape = (ng, nu) + struct blasfeo_dmat Cg_e_mat; // shape = (ng_e, nx) + struct blasfeo_dmat dummy_Dgh_e_mat; // shape = (ngh_e_max, nu) + // matrix in nonlinear constraints + struct blasfeo_dmat Ch_mat; // shape = (nh, nx) + struct blasfeo_dmat Dh_mat; // shape = (nh, nu) + struct blasfeo_dmat Ch_e_mat; // shape = (nh_e, nx) + // feedback gain matrix + struct blasfeo_dmat K_mat; // shape = (nu, nx) + // AK = A - B@K + struct blasfeo_dmat AK_mat; // shape = (nx, nx) + // A@P_k + struct blasfeo_dmat temp_AP_mat; // shape = (nx, nx) + // K@P_k, K@P_k@K^T + struct blasfeo_dmat temp_KP_mat; // shape = (nu, nx) + struct blasfeo_dmat temp_KPK_mat; // shape = (nu, nu) + // C + D @ K, (C + D @ K) @ P_k + struct blasfeo_dmat temp_CaDK_mat; // shape = (ngh_me_max, nx) + struct blasfeo_dmat temp_CaDKmP_mat; // shape = (ngh_me_max, nx) + struct blasfeo_dmat temp_beta_mat; // shape = (ngh_me_max, ngh_me_max) + + double *d_A_mat; // shape = (nx, nx) + double *d_B_mat; // shape = (nx, nu) + double *d_Cg_mat; // shape = (ng, nx) + double *d_Dg_mat; // shape = (ng, nu) + double *d_Cg_e_mat; // shape = (ng_e, nx) + double *d_Cgh_mat; // shape = (ng+nh, nx) + double *d_Dgh_mat; // shape = (ng+nh, nu) + double *d_Cgh_e_mat; // shape = (ng_e+nh_e, nx) + double *d_state_vec; + // upper and lower bounds on state variables + double *d_lbx; // shape = (nbx,) + double *d_ubx; // shape = (nbx,) + double *d_lbx_e; // shape = (nbx_e,) + double *d_ubx_e; // shape = (nbx_e,) + // tightened upper and lower bounds on state variables + double *d_lbx_tightened; // shape = (nbx,) + double *d_ubx_tightened; // shape = (nbx,) + double *d_lbx_e_tightened; // shape = (nbx_e,) + double *d_ubx_e_tightened; // shape = (nbx_e,) + // upper and lower bounds on control inputs + double *d_lbu; // shape = (nbu,) + double *d_ubu; // shape = (nbu,) + // tightened upper and lower bounds on control inputs + double *d_lbu_tightened; // shape = (nbu,) + double *d_ubu_tightened; // shape = (nbu,) + // upper and lower bounds on polytopic constraints + double *d_lg; // shape = (ng,) + double *d_ug; // shape = (ng,) + double *d_lg_e; // shape = (ng_e,) + double *d_ug_e; // shape = (ng_e,) + // tightened lower bounds on polytopic constraints + double *d_lg_tightened; // shape = (ng,) + double *d_ug_tightened; // shape = (ng,) + double *d_lg_e_tightened; // shape = (ng_e,) + double *d_ug_e_tightened; // shape = (ng_e,) + // upper and lower bounds on nonlinear constraints + double *d_lh; // shape = (nh,) + double *d_uh; // shape = (nh,) + double *d_lh_e; // shape = (nh_e,) + double *d_uh_e; // shape = (nh_e,) + // tightened upper and lower bounds on nonlinear constraints + double *d_lh_tightened; // shape = (nh,) + double *d_uh_tightened; // shape = (nh,) + double *d_lh_e_tightened; // shape = (nh_e,) + double *d_uh_e_tightened; // shape = (nh_e,) + + int *idxbx; // shape = (nbx,) + int *idxbu; // shape = (nbu,) + int *idxbx_e; // shape = (nbx_e,) + + void *raw_memory; // Pointer to allocated memory, to be used for freeing +} custom_memory; + +static int int_max(int num1, int num2) +{ + return (num1 > num2 ) ? num1 : num2; +} + + +static int custom_memory_calculate_size(ocp_nlp_config *nlp_config, ocp_nlp_dims *nlp_dims) +{ + int N = nlp_dims->N; + int nx = {{ dims.nx }}; + int nu = {{ dims.nu }}; + int nw = {{ zoro_description.nw }}; + + int ng = {{ dims.ng }}; + int nh = {{ dims.nh }}; + int nbx = {{ dims.nbx }}; + int nbu = {{ dims.nbu }}; + + int ng_e = {{ dims.ng_e }}; + int nh_e = {{ dims.nh_e }}; + int ngh_e_max = int_max(ng_e, nh_e); + int ngh_me_max = int_max(ngh_e_max, int_max(ng, nh)); + int nbx_e = {{ dims.nbx_e }}; + + assert({{zoro_description.nlbx_t}} <= nbx); + assert({{zoro_description.nubx_t}} <= nbx); + assert({{zoro_description.nlbu_t}} <= nbu); + assert({{zoro_description.nubu_t}} <= nbu); + assert({{zoro_description.nlg_t}} <= ng); + assert({{zoro_description.nug_t}} <= ng); + assert({{zoro_description.nlh_t}} <= nh); + assert({{zoro_description.nuh_t}} <= nh); + assert({{zoro_description.nlbx_e_t}} <= nbx_e); + assert({{zoro_description.nubx_e_t}} <= nbx_e); + assert({{zoro_description.nlg_e_t}} <= ng_e); + assert({{zoro_description.nug_e_t}} <= ng_e); + assert({{zoro_description.nlh_e_t}} <= nh_e); + assert({{zoro_description.nuh_e_t}} <= nh_e); + + acados_size_t size = sizeof(custom_memory); + size += nbx * sizeof(int); + /* blasfeo structs */ + size += (N + 1) * sizeof(struct blasfeo_dmat); + /* blasfeo mem: mat */ + size += (N + 1) * blasfeo_memsize_dmat(nx, nx); // uncertainty_matrix_buffer + size += blasfeo_memsize_dmat(nw, nw); // W_mat + size += 2 * blasfeo_memsize_dmat(nx, nw); // unc_jac_G_mat, temp_GW_mat + size += 4 * blasfeo_memsize_dmat(nx, nx); // GWG_mat, A_mat, AK_mat, temp_AP_mat + size += blasfeo_memsize_dmat(nx, nu); // B_mat + size += 2 * blasfeo_memsize_dmat(nu, nx); // K_mat, temp_KP_mat + size += blasfeo_memsize_dmat(nu, nu); // temp_KPK_mat + size += blasfeo_memsize_dmat(ng, nx); // Cg_mat + size += blasfeo_memsize_dmat(ng, nu); // Dg_mat + size += blasfeo_memsize_dmat(ng_e, nx); // Cg_e_mat + size += blasfeo_memsize_dmat(ngh_e_max, nu); // dummy_Dgh_e_mat + size += blasfeo_memsize_dmat(nh, nx); // Ch_mat + size += blasfeo_memsize_dmat(nh, nu); // Dh_mat + size += blasfeo_memsize_dmat(nh_e, nx); // Ch_e_mat + size += 2 * blasfeo_memsize_dmat(ngh_me_max, nx); // temp_CaDK_mat, temp_CaDKmP_mat + size += blasfeo_memsize_dmat(ngh_me_max, ngh_me_max); // temp_beta_mat + /* blasfeo mem: vec */ + /* Arrays */ + size += nx*nx *sizeof(double); // d_A_mat + size += nx*nu *sizeof(double); // d_B_mat + size += (ng + ng_e) * nx * sizeof(double); // d_Cg_mat, d_Cg_e_mat + size += (ng) * nu * sizeof(double); // d_Dg_mat + size += (nh + nh_e + ng + ng_e) * nx * sizeof(double); // d_Cgh_mat, d_Cgh_e_mat + size += (nh + ng) * nu * sizeof(double); // d_Dgh_mat + // d_state_vec + size += nx *sizeof(double); + // constraints and tightened constraints + size += 4 * (nbx + nbu + ng + nh)*sizeof(double); + size += 4 * (nbx_e + ng_e + nh_e)*sizeof(double); + size += (nbx + nbu + nbx_e)*sizeof(int); // idxbx, idxbu, idxbx_e + + size += 1 * 8; // initial alignment + make_int_multiple_of(64, &size); + size += 1 * 64; + + return size; +} + + +static custom_memory *custom_memory_assign(ocp_nlp_config *nlp_config, ocp_nlp_dims *nlp_dims, void *raw_memory) +{ + int N = nlp_dims->N; + int nx = {{ dims.nx }}; + int nu = {{ dims.nu }}; + int nw = {{ zoro_description.nw }}; + + int ng = {{ dims.ng }}; + int nh = {{ dims.nh }}; + int nbx = {{ dims.nbx }}; + int nbu = {{ dims.nbu }}; + + int ng_e = {{ dims.ng_e }}; + int nh_e = {{ dims.nh_e }}; + int ngh_e_max = int_max(ng_e, nh_e); + int ngh_me_max = int_max(ngh_e_max, int_max(ng, nh)); + int nbx_e = {{ dims.nbx_e }}; + + char *c_ptr = (char *) raw_memory; + custom_memory *mem = (custom_memory *) c_ptr; + c_ptr += sizeof(custom_memory); + + align_char_to(8, &c_ptr); + assign_and_advance_blasfeo_dmat_structs(N+1, &mem->uncertainty_matrix_buffer, &c_ptr); + + align_char_to(64, &c_ptr); + + for (int ii = 0; ii <= N; ii++) + { + assign_and_advance_blasfeo_dmat_mem(nx, nx, &mem->uncertainty_matrix_buffer[ii], &c_ptr); + } + // Disturbance Dynamics + assign_and_advance_blasfeo_dmat_mem(nw, nw, &mem->W_mat, &c_ptr); + assign_and_advance_blasfeo_dmat_mem(nx, nw, &mem->unc_jac_G_mat, &c_ptr); + assign_and_advance_blasfeo_dmat_mem(nx, nw, &mem->temp_GW_mat, &c_ptr); + assign_and_advance_blasfeo_dmat_mem(nx, nx, &mem->GWG_mat, &c_ptr); + // System Dynamics + assign_and_advance_blasfeo_dmat_mem(nx, nx, &mem->A_mat, &c_ptr); + assign_and_advance_blasfeo_dmat_mem(nx, nu, &mem->B_mat, &c_ptr); + assign_and_advance_blasfeo_dmat_mem(ng, nx, &mem->Cg_mat, &c_ptr); + assign_and_advance_blasfeo_dmat_mem(ng, nu, &mem->Dg_mat, &c_ptr); + assign_and_advance_blasfeo_dmat_mem(ng_e, nx, &mem->Cg_e_mat, &c_ptr); + assign_and_advance_blasfeo_dmat_mem(ngh_e_max, nu, &mem->dummy_Dgh_e_mat, &c_ptr); + assign_and_advance_blasfeo_dmat_mem(nh, nx, &mem->Ch_mat, &c_ptr); + assign_and_advance_blasfeo_dmat_mem(nh, nu, &mem->Dh_mat, &c_ptr); + assign_and_advance_blasfeo_dmat_mem(nh_e, nx, &mem->Ch_e_mat, &c_ptr); + assign_and_advance_blasfeo_dmat_mem(nu, nx, &mem->K_mat, &c_ptr); + assign_and_advance_blasfeo_dmat_mem(nx, nx, &mem->AK_mat, &c_ptr); + assign_and_advance_blasfeo_dmat_mem(nx, nx, &mem->temp_AP_mat, &c_ptr); + assign_and_advance_blasfeo_dmat_mem(nu, nx, &mem->temp_KP_mat, &c_ptr); + assign_and_advance_blasfeo_dmat_mem(nu, nu, &mem->temp_KPK_mat, &c_ptr); + assign_and_advance_blasfeo_dmat_mem(ngh_me_max, nx, &mem->temp_CaDK_mat, &c_ptr); + assign_and_advance_blasfeo_dmat_mem(ngh_me_max, nx, &mem->temp_CaDKmP_mat, &c_ptr); + assign_and_advance_blasfeo_dmat_mem(ngh_me_max, ngh_me_max, &mem->temp_beta_mat, &c_ptr); + + assign_and_advance_double(nx*nx, &mem->d_A_mat, &c_ptr); + assign_and_advance_double(nx*nu, &mem->d_B_mat, &c_ptr); + assign_and_advance_double(ng*nx, &mem->d_Cg_mat, &c_ptr); + assign_and_advance_double(ng*nu, &mem->d_Dg_mat, &c_ptr); + assign_and_advance_double(ng_e*nx, &mem->d_Cg_e_mat, &c_ptr); + assign_and_advance_double((ng + nh)*nx, &mem->d_Cgh_mat, &c_ptr); + assign_and_advance_double((ng + nh)*nu, &mem->d_Dgh_mat, &c_ptr); + assign_and_advance_double((ng_e + nh_e)*nx, &mem->d_Cgh_e_mat, &c_ptr); + assign_and_advance_double(nx, &mem->d_state_vec, &c_ptr); + assign_and_advance_double(nbx, &mem->d_lbx, &c_ptr); + assign_and_advance_double(nbx, &mem->d_ubx, &c_ptr); + assign_and_advance_double(nbx_e, &mem->d_lbx_e, &c_ptr); + assign_and_advance_double(nbx_e, &mem->d_ubx_e, &c_ptr); + assign_and_advance_double(nbx, &mem->d_lbx_tightened, &c_ptr); + assign_and_advance_double(nbx, &mem->d_ubx_tightened, &c_ptr); + assign_and_advance_double(nbx_e, &mem->d_lbx_e_tightened, &c_ptr); + assign_and_advance_double(nbx_e, &mem->d_ubx_e_tightened, &c_ptr); + assign_and_advance_double(nbu, &mem->d_lbu, &c_ptr); + assign_and_advance_double(nbu, &mem->d_ubu, &c_ptr); + assign_and_advance_double(nbu, &mem->d_lbu_tightened, &c_ptr); + assign_and_advance_double(nbu, &mem->d_ubu_tightened, &c_ptr); + assign_and_advance_double(ng, &mem->d_lg, &c_ptr); + assign_and_advance_double(ng, &mem->d_ug, &c_ptr); + assign_and_advance_double(ng_e, &mem->d_lg_e, &c_ptr); + assign_and_advance_double(ng_e, &mem->d_ug_e, &c_ptr); + assign_and_advance_double(ng, &mem->d_lg_tightened, &c_ptr); + assign_and_advance_double(ng, &mem->d_ug_tightened, &c_ptr); + assign_and_advance_double(ng_e, &mem->d_lg_e_tightened, &c_ptr); + assign_and_advance_double(ng_e, &mem->d_ug_e_tightened, &c_ptr); + assign_and_advance_double(nh, &mem->d_lh, &c_ptr); + assign_and_advance_double(nh, &mem->d_uh, &c_ptr); + assign_and_advance_double(nh_e, &mem->d_lh_e, &c_ptr); + assign_and_advance_double(nh_e, &mem->d_uh_e, &c_ptr); + assign_and_advance_double(nh, &mem->d_lh_tightened, &c_ptr); + assign_and_advance_double(nh, &mem->d_uh_tightened, &c_ptr); + assign_and_advance_double(nh_e, &mem->d_lh_e_tightened, &c_ptr); + assign_and_advance_double(nh_e, &mem->d_uh_e_tightened, &c_ptr); + + assign_and_advance_int(nbx, &mem->idxbx, &c_ptr); + assign_and_advance_int(nbu, &mem->idxbu, &c_ptr); + assign_and_advance_int(nbx_e, &mem->idxbx_e, &c_ptr); + + assert((char *) raw_memory + custom_memory_calculate_size(nlp_config, nlp_dims) >= c_ptr); + mem->raw_memory = raw_memory; + + return mem; +} + + + +static void *custom_memory_create({{ model.name }}_solver_capsule* capsule) +{ + printf("\nin custom_memory_create_function\n"); + + ocp_nlp_dims *nlp_dims = {{ model.name }}_acados_get_nlp_dims(capsule); + ocp_nlp_config *nlp_config = {{ model.name }}_acados_get_nlp_config(capsule); + acados_size_t bytes = custom_memory_calculate_size(nlp_config, nlp_dims); + + void *ptr = acados_calloc(1, bytes); + + custom_memory *custom_mem = custom_memory_assign(nlp_config, nlp_dims, ptr); + custom_mem->raw_memory = ptr; + + return custom_mem; +} + + +static void custom_val_init_function(ocp_nlp_dims *nlp_dims, ocp_nlp_in *nlp_in, ocp_nlp_solver *nlp_solver, custom_memory *custom_mem) +{ + int N = nlp_dims->N; + int nx = {{ dims.nx }}; + int nu = {{ dims.nu }}; + int nw = {{ zoro_description.nw }}; + + int ng = {{ dims.ng }}; + int nh = {{ dims.nh }}; + int nbx = {{ dims.nbx }}; + int nbu = {{ dims.nbu }}; + + int ng_e = {{ dims.ng_e }}; + int nh_e = {{ dims.nh_e }}; + int ngh_e_max = int_max(ng_e, nh_e); + int nbx_e = {{ dims.nbx_e }}; + + /* Get the state constraint bounds */ + ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, 1, "idxbx", custom_mem->idxbx); + ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, N, "idxbx", custom_mem->idxbx_e); + ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, 1, "lbx", custom_mem->d_lbx); + ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, 1, "ubx", custom_mem->d_ubx); + ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, N, "lbx", custom_mem->d_lbx_e); + ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, N, "ubx", custom_mem->d_ubx_e); + ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, 1, "idxbu", custom_mem->idxbu); + ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, 1, "lbu", custom_mem->d_lbu); + ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, 1, "ubu", custom_mem->d_ubu); + // Get the Jacobians and the bounds of the linear constraints + ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, 1, "lg", custom_mem->d_lg); + ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, 1, "ug", custom_mem->d_ug); + ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, N, "lg", custom_mem->d_lg_e); + ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, N, "ug", custom_mem->d_ug_e); + ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, 1, "C", custom_mem->d_Cg_mat); + ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, 1, "D", custom_mem->d_Dg_mat); + ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, N, "C", custom_mem->d_Cg_e_mat); + blasfeo_pack_dmat(ng, nx, custom_mem->d_Cg_mat, ng, &custom_mem->Cg_mat, 0, 0); + blasfeo_pack_dmat(ng, nu, custom_mem->d_Dg_mat, ng, &custom_mem->Dg_mat, 0, 0); + blasfeo_pack_dmat(ng_e, nx, custom_mem->d_Cg_e_mat, ng_e, &custom_mem->Cg_e_mat, 0, 0); + blasfeo_dgese(ngh_e_max, nu, 0., &custom_mem->dummy_Dgh_e_mat, 0, 0); //fill with zeros + // NOTE: fixed lower and upper bounds of nonlinear constraints + ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, 1, "lh", custom_mem->d_lh); + ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, 1, "uh", custom_mem->d_uh); + ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, N, "lh", custom_mem->d_lh_e); + ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, N, "uh", custom_mem->d_uh_e); + + /* Initilize tightened constraints*/ + // NOTE: tightened constraints are only initialized once + ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, 1, "lbx", custom_mem->d_lbx_tightened); + ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, 1, "ubx", custom_mem->d_ubx_tightened); + ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, N, "lbx", custom_mem->d_lbx_e_tightened); + ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, N, "ubx", custom_mem->d_ubx_e_tightened); + ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, 1, "lbu", custom_mem->d_lbu_tightened); + ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, 1, "ubu", custom_mem->d_ubu_tightened); + ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, 1, "lg", custom_mem->d_lg_tightened); + ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, 1, "ug", custom_mem->d_ug_tightened); + ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, N, "lg", custom_mem->d_lg_e_tightened); + ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, N, "ug", custom_mem->d_ug_e_tightened); + ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, 1, "lh", custom_mem->d_lh_tightened); + ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, 1, "uh", custom_mem->d_uh_tightened); + ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, N, "lh", custom_mem->d_lh_e_tightened); + ocp_nlp_constraints_model_get(nlp_solver->config, nlp_dims, nlp_in, N, "uh", custom_mem->d_uh_e_tightened); + + /* Initialize the W matrix */ + // blasfeo_dgese(nw, nw, 0., &custom_mem->W_mat, 0, 0); +{%- for ir in range(end=zoro_description.nw) %} + {%- for ic in range(end=zoro_description.nw) %} + blasfeo_dgein1({{zoro_description.W_mat[ir][ic]}}, &custom_mem->W_mat, {{ir}}, {{ic}}); + {%- endfor %} +{%- endfor %} + +{%- for ir in range(end=dims.nx) %} + {%- for ic in range(end=zoro_description.nw) %} + blasfeo_dgein1({{zoro_description.unc_jac_G_mat[ir][ic]}}, &custom_mem->unc_jac_G_mat, {{ir}}, {{ic}}); + {%- endfor %} +{%- endfor %} + + // NOTE: if G is changing this is not in init! + // temp_GW_mat = unc_jac_G_mat * W_mat + blasfeo_dgemm_nn(nx, nw, nw, 1.0, &custom_mem->unc_jac_G_mat, 0, 0, + &custom_mem->W_mat, 0, 0, 0.0, + &custom_mem->temp_GW_mat, 0, 0, &custom_mem->temp_GW_mat, 0, 0); + // GWG_mat = temp_GW_mat * unc_jac_G_mat^T + blasfeo_dgemm_nt(nx, nx, nw, 1.0, &custom_mem->temp_GW_mat, 0, 0, + &custom_mem->unc_jac_G_mat, 0, 0, 0.0, + &custom_mem->GWG_mat, 0, 0, &custom_mem->GWG_mat, 0, 0); + + /* Initialize the uncertainty_matrix_buffer[0] */ +{%- for ir in range(end=dims.nx) %} + {%- for ic in range(end=dims.nx) %} + blasfeo_dgein1({{zoro_description.P0_mat[ir][ic]}}, &custom_mem->uncertainty_matrix_buffer[0], {{ir}}, {{ic}}); + {%- endfor %} +{%- endfor %} + + /* Initialize the feedback gain matrix */ +{%- for ir in range(end=dims.nu) %} + {%- for ic in range(end=dims.nx) %} + blasfeo_dgein1({{zoro_description.fdbk_K_mat[ir][ic]}}, &custom_mem->K_mat, {{ir}}, {{ic}}); + {%- endfor %} +{%- endfor %} +} + + +int custom_update_init_function({{ model.name }}_solver_capsule* capsule) +{ + capsule->custom_update_memory = custom_memory_create(capsule); + ocp_nlp_in *nlp_in = {{ model.name }}_acados_get_nlp_in(capsule); + + ocp_nlp_dims *nlp_dims = {{ model.name }}_acados_get_nlp_dims(capsule); + ocp_nlp_solver *nlp_solver = {{ model.name }}_acados_get_nlp_solver(capsule); + custom_val_init_function(nlp_dims, nlp_in, nlp_solver, capsule->custom_update_memory); + return 1; +} + +static void compute_gh_beta(struct blasfeo_dmat* K_mat, struct blasfeo_dmat* C_mat, + struct blasfeo_dmat* D_mat, struct blasfeo_dmat* CaDK_mat, + struct blasfeo_dmat* CaDKmP_mat, struct blasfeo_dmat* beta_mat, + struct blasfeo_dmat* P_mat, + int n_cstr, int nx, int nu) +{ + // (C+DK)@P@(C^T+K^TD^T) + // CaDK_mat = C_mat + D_mat @ K_mat + blasfeo_dgemm_nn(n_cstr, nx, nu, 1.0, D_mat, 0, 0, + K_mat, 0, 0, 1.0, + C_mat, 0, 0, CaDK_mat, 0, 0); + // CaDKmP_mat = CaDK_mat @ P_mat + blasfeo_dgemm_nn(n_cstr, nx, nx, 1.0, CaDK_mat, 0, 0, + P_mat, 0, 0, 0.0, + CaDKmP_mat, 0, 0, CaDKmP_mat, 0, 0); + // beta_mat = CaDKmP_mat @ CaDK_mat^T + blasfeo_dgemm_nt(n_cstr, n_cstr, nx, 1.0, CaDKmP_mat, 0, 0, + CaDK_mat, 0, 0, 0.0, + beta_mat, 0, 0, beta_mat, 0, 0); +} + +static void compute_KPK(struct blasfeo_dmat* K_mat, struct blasfeo_dmat* temp_KP_mat, + struct blasfeo_dmat* temp_KPK_mat, struct blasfeo_dmat* P_mat, + int nx, int nu) +{ + // K @ P_k @ K^T + // temp_KP_mat = K_mat @ P_mat + blasfeo_dgemm_nn(nu, nx, nx, 1.0, K_mat, 0, 0, + P_mat, 0, 0, 0.0, + temp_KP_mat, 0, 0, temp_KP_mat, 0, 0); + // temp_KPK_mat = temp_KP_mat @ K_mat^T + blasfeo_dgemm_nt(nu, nu, nx, 1.0, temp_KP_mat, 0, 0, + K_mat, 0, 0, 0.0, + temp_KPK_mat, 0, 0, temp_KPK_mat, 0, 0); +} + +static void compute_next_P_matrix(struct blasfeo_dmat* P_mat, struct blasfeo_dmat* P_next_mat, + struct blasfeo_dmat* A_mat, struct blasfeo_dmat* B_mat, + struct blasfeo_dmat* K_mat, struct blasfeo_dmat* W_mat, + struct blasfeo_dmat* AK_mat, struct blasfeo_dmat* temp_AP_mat, int nx, int nu) +{ + // AK_mat = -B@K + A + blasfeo_dgemm_nn(nx, nx, nu, -1.0, B_mat, 0, 0, K_mat, 0, 0, + 1.0, A_mat, 0, 0, AK_mat, 0, 0); + // temp_AP_mat = AK_mat @ P_k + blasfeo_dgemm_nn(nx, nx, nx, 1.0, AK_mat, 0, 0, + P_mat, 0, 0, 0.0, + temp_AP_mat, 0, 0, temp_AP_mat, 0, 0); + // P_{k+1} = temp_AP_mat @ AK_mat^T + GWG_mat + blasfeo_dgemm_nt(nx, nx, nx, 1.0, temp_AP_mat, 0, 0, + AK_mat, 0, 0, 1.0, + W_mat, 0, 0, P_next_mat, 0, 0); +} + +static void reset_P0_matrix(ocp_nlp_dims *nlp_dims, struct blasfeo_dmat* P_mat, double* data) +{ + int nx = nlp_dims->nx[0]; + blasfeo_pack_dmat(nx, nx, data, nx, P_mat, 0, 0); +} + +static void uncertainty_propagate_and_update(ocp_nlp_solver *solver, ocp_nlp_in *nlp_in, ocp_nlp_out *nlp_out, custom_memory *custom_mem) +{ + ocp_nlp_config *nlp_config = solver->config; + ocp_nlp_dims *nlp_dims = solver->dims; + + int N = nlp_dims->N; + int nx = nlp_dims->nx[0]; + int nu = nlp_dims->nu[0]; + int nx_sqr = nx*nx; + int nbx = {{ dims.nbx }}; + int nbu = {{ dims.nbu }}; + int ng = {{ dims.ng }}; + int nh = {{ dims.nh }}; + int ng_e = {{ dims.ng_e }}; + int nh_e = {{ dims.nh_e }}; + int nbx_e = {{ dims.nbx_e }}; + double backoff_scaling_gamma = {{ zoro_description.backoff_scaling_gamma }}; + + // First Stage + // NOTE: lbx_0 and ubx_0 should not be tightened. + // NOTE: lg_0 and ug_0 are not tightened. + // NOTE: lh_0 and uh_0 are not tightened. +{%- if zoro_description.nlbu_t + zoro_description.nubu_t > 0 %} + compute_KPK(&custom_mem->K_mat, &custom_mem->temp_KP_mat, + &custom_mem->temp_KPK_mat, &(custom_mem->uncertainty_matrix_buffer[0]), nx, nu); + +{%- if zoro_description.nlbu_t > 0 %} + // backoff lbu + {%- for it in zoro_description.idx_lbu_t %} + custom_mem->d_lbu_tightened[{{it}}] + = custom_mem->d_lbu[{{it}}] + + backoff_scaling_gamma * sqrt(blasfeo_dgeex1(&custom_mem->temp_KPK_mat, + custom_mem->idxbu[{{it}}],custom_mem->idxbu[{{it}}])); + {%- endfor %} + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "lbu", custom_mem->d_lbu_tightened); +{%- endif %} +{%- if zoro_description.nubu_t > 0 %} + // backoff ubu + {%- for it in zoro_description.idx_ubu_t %} + custom_mem->d_ubu_tightened[{{it}}] + = custom_mem->d_ubu[{{it}}] + - backoff_scaling_gamma * sqrt(blasfeo_dgeex1(&custom_mem->temp_KPK_mat, + custom_mem->idxbu[{{it}}],custom_mem->idxbu[{{it}}])); + {%- endfor %} + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "ubu", custom_mem->d_ubu_tightened); +{%- endif %} +{%- endif %} + // Middle Stages + // constraint tightening: for next stage based on dynamics of ii stage + // P[ii+1] = (A-B@K) @ P[ii] @ (A-B@K).T + G@W@G.T + for (int ii = 0; ii < N-1; ii++) + { + // get and pack: A, B + ocp_nlp_get_at_stage(nlp_config, nlp_dims, solver, ii, "A", custom_mem->d_A_mat); + blasfeo_pack_dmat(nx, nx, custom_mem->d_A_mat, nx, &custom_mem->A_mat, 0, 0); + ocp_nlp_get_at_stage(nlp_config, nlp_dims, solver, ii, "B", custom_mem->d_B_mat); + blasfeo_pack_dmat(nx, nu, custom_mem->d_B_mat, nx, &custom_mem->B_mat, 0, 0); + + compute_next_P_matrix(&(custom_mem->uncertainty_matrix_buffer[ii]), + &(custom_mem->uncertainty_matrix_buffer[ii+1]), + &custom_mem->A_mat, &custom_mem->B_mat, + &custom_mem->K_mat, &custom_mem->GWG_mat, + &custom_mem->AK_mat, &custom_mem->temp_AP_mat, nx, nu); + + // state constraints +{%- if zoro_description.nlbx_t + zoro_description.nubx_t> 0 %} + {%- if zoro_description.nlbx_t > 0 %} + // lbx + {%- for it in zoro_description.idx_lbx_t %} + custom_mem->d_lbx_tightened[{{it}}] + = custom_mem->d_lbx[{{it}}] + + backoff_scaling_gamma * sqrt(blasfeo_dgeex1(&custom_mem->uncertainty_matrix_buffer[ii+1], + custom_mem->idxbx[{{it}}],custom_mem->idxbx[{{it}}])); + {%- endfor %} + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, ii+1, "lbx", custom_mem->d_lbx_tightened); + {%- endif %} + {% if zoro_description.nubx_t > 0 %} + // ubx + {%- for it in zoro_description.idx_ubx_t %} + custom_mem->d_ubx_tightened[{{it}}] = custom_mem->d_ubx[{{it}}] + - backoff_scaling_gamma * sqrt(blasfeo_dgeex1(&custom_mem->uncertainty_matrix_buffer[ii+1], + custom_mem->idxbx[{{it}}],custom_mem->idxbx[{{it}}])); + {%- endfor %} + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, ii+1, "ubx", custom_mem->d_ubx_tightened); + {%- endif %} +{%- endif %} + +{%- if zoro_description.nlbu_t + zoro_description.nubu_t > 0 %} + // input constraints + compute_KPK(&custom_mem->K_mat, &custom_mem->temp_KP_mat, + &custom_mem->temp_KPK_mat, &(custom_mem->uncertainty_matrix_buffer[ii+1]), nx, nu); + + {%- if zoro_description.nlbu_t > 0 %} + {%- for it in zoro_description.idx_lbu_t %} + custom_mem->d_lbu_tightened[{{it}}] = custom_mem->d_lbu[{{it}}] + + backoff_scaling_gamma * sqrt(blasfeo_dgeex1(&custom_mem->temp_KPK_mat, + custom_mem->idxbu[{{it}}], custom_mem->idxbu[{{it}}])); + {%- endfor %} + + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, ii+1, "lbu", custom_mem->d_lbu_tightened); + {%- endif %} + {%- if zoro_description.nubu_t > 0 %} + {%- for it in zoro_description.idx_ubu_t %} + custom_mem->d_ubu_tightened[{{it}}] = custom_mem->d_ubu[{{it}}] + - backoff_scaling_gamma * sqrt(blasfeo_dgeex1(&custom_mem->temp_KPK_mat, + custom_mem->idxbu[{{it}}], custom_mem->idxbu[{{it}}])); + {%- endfor %} + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, ii+1, "ubu", custom_mem->d_ubu_tightened); + {%- endif %} +{%- endif %} + +{%- if zoro_description.nlg_t + zoro_description.nug_t > 0 %} + // Linear constraints: g + compute_gh_beta(&custom_mem->K_mat, &custom_mem->Cg_mat, + &custom_mem->Dg_mat, &custom_mem->temp_CaDK_mat, + &custom_mem->temp_CaDKmP_mat, &custom_mem->temp_beta_mat, + &custom_mem->uncertainty_matrix_buffer[ii+1], ng, nx, nu); + + {%- if zoro_description.nlg_t > 0 %} + {%- for it in zoro_description.idx_lg_t %} + custom_mem->d_lg_tightened[{{it}}] + = custom_mem->d_lg[{{it}}] + + backoff_scaling_gamma * sqrt(blasfeo_dgeex1(&custom_mem->temp_beta_mat, {{it}}, {{it}})); + {%- endfor %} + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, ii+1, "lg", custom_mem->d_lg_tightened); + {%- endif %} + {%- if zoro_description.nug_t > 0 %} + {%- for it in zoro_description.idx_ug_t %} + custom_mem->d_ug_tightened[{{it}}] + = custom_mem->d_ug[{{it}}] + - backoff_scaling_gamma * sqrt(blasfeo_dgeex1(&custom_mem->temp_beta_mat, {{it}}, {{it}})); + {%- endfor %} + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, ii+1, "ug", custom_mem->d_ug_tightened); + {%- endif %} +{%- endif %} + + +{%- if zoro_description.nlh_t + zoro_description.nuh_t > 0 %} + // nonlinear constraints: h + // Get C_{k+1} and D_{k+1} + ocp_nlp_get_at_stage(solver->config, nlp_dims, solver, ii+1, "C", custom_mem->d_Cgh_mat); + ocp_nlp_get_at_stage(solver->config, nlp_dims, solver, ii+1, "D", custom_mem->d_Dgh_mat); + // NOTE: the d_Cgh_mat is column-major, the first ng rows are the Jacobians of the linear constraints + blasfeo_pack_dmat(nh, nx, custom_mem->d_Cgh_mat+ng, ng+nh, &custom_mem->Ch_mat, 0, 0); + blasfeo_pack_dmat(nh, nu, custom_mem->d_Dgh_mat+ng, ng+nh, &custom_mem->Dh_mat, 0, 0); + + compute_gh_beta(&custom_mem->K_mat, &custom_mem->Ch_mat, + &custom_mem->Dh_mat, &custom_mem->temp_CaDK_mat, + &custom_mem->temp_CaDKmP_mat, &custom_mem->temp_beta_mat, + &custom_mem->uncertainty_matrix_buffer[ii+1], nh, nx, nu); + + {%- if zoro_description.nlh_t > 0 %} + {%- for it in zoro_description.idx_lh_t %} + custom_mem->d_lh_tightened[{{it}}] + = custom_mem->d_lh[{{it}}] + + backoff_scaling_gamma * sqrt(blasfeo_dgeex1(&custom_mem->temp_beta_mat, {{it}}, {{it}})); + {%- endfor %} + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, ii+1, "lh", custom_mem->d_lh_tightened); + {%- endif %} + {%- if zoro_description.nuh_t > 0 %} + {%- for it in zoro_description.idx_uh_t %} + custom_mem->d_uh_tightened[{{it}}] = custom_mem->d_uh[{{it}}] + - backoff_scaling_gamma * sqrt(blasfeo_dgeex1(&custom_mem->temp_beta_mat, {{it}}, {{it}})); + {%- endfor %} + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, ii+1, "uh", custom_mem->d_uh_tightened); + {%- endif %} +{%- endif %} + } + + // Last stage + // get and pack: A, B + ocp_nlp_get_at_stage(nlp_config, nlp_dims, solver, N-1, "A", custom_mem->d_A_mat); + blasfeo_pack_dmat(nx, nx, custom_mem->d_A_mat, nx, &custom_mem->A_mat, 0, 0); + ocp_nlp_get_at_stage(nlp_config, nlp_dims, solver, N-1, "B", custom_mem->d_B_mat); + blasfeo_pack_dmat(nx, nu, custom_mem->d_B_mat, nx, &custom_mem->B_mat, 0, 0); + // AK_mat = -B*K + A + compute_next_P_matrix(&(custom_mem->uncertainty_matrix_buffer[N-1]), + &(custom_mem->uncertainty_matrix_buffer[N]), + &custom_mem->A_mat, &custom_mem->B_mat, + &custom_mem->K_mat, &custom_mem->GWG_mat, + &custom_mem->AK_mat, &custom_mem->temp_AP_mat, nx, nu); + + // state constraints nlbx_e_t +{%- if zoro_description.nlbx_e_t + zoro_description.nubx_e_t> 0 %} +{%- if zoro_description.nlbx_e_t > 0 %} + // lbx_e + {%- for it in zoro_description.idx_lbx_e_t %} + custom_mem->d_lbx_e_tightened[{{it}}] + = custom_mem->d_lbx_e[{{it}}] + + backoff_scaling_gamma * sqrt(blasfeo_dgeex1(&custom_mem->uncertainty_matrix_buffer[N], + custom_mem->idxbx_e[{{it}}],custom_mem->idxbx_e[{{it}}])); + {%- endfor %} + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, N, "lbx", custom_mem->d_lbx_e_tightened); +{%- endif %} +{% if zoro_description.nubx_e_t > 0 %} + // ubx_e + {%- for it in zoro_description.idx_ubx_e_t %} + custom_mem->d_ubx_e_tightened[{{it}}] = custom_mem->d_ubx_e[{{it}}] + - backoff_scaling_gamma * sqrt(blasfeo_dgeex1(&custom_mem->uncertainty_matrix_buffer[N], + custom_mem->idxbx_e[{{it}}],custom_mem->idxbx_e[{{it}}])); + {%- endfor %} + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, N, "ubx", custom_mem->d_ubx_e_tightened); +{%- endif %} +{%- endif %} + +{%- if zoro_description.nlg_e_t + zoro_description.nug_e_t > 0 %} + // Linear constraints: g + compute_gh_beta(&custom_mem->K_mat, &custom_mem->Cg_mat, + &custom_mem->dummy_Dgh_e_mat, &custom_mem->temp_CaDK_mat, + &custom_mem->temp_CaDKmP_mat, &custom_mem->temp_beta_mat, + &custom_mem->uncertainty_matrix_buffer[N], ng, nx, nu); + +{%- if zoro_description.nlg_e_t > 0 %} + {%- for it in zoro_description.idx_lg_e_t %} + custom_mem->d_lg_e_tightened[{{it}}] + = custom_mem->d_lg_e[{{it}}] + + backoff_scaling_gamma * sqrt(blasfeo_dgeex1(&custom_mem->temp_beta_mat, {{it}}, {{it}})); + {%- endfor %} + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, N, "lg", custom_mem->d_lg_e_tightened); +{%- endif %} +{%- if zoro_description.nug_e_t > 0 %} + {%- for it in zoro_description.idx_ug_e_t %} + custom_mem->d_ug_e_tightened[{{it}}] + = custom_mem->d_ug_e[{{it}}] + - backoff_scaling_gamma * sqrt(blasfeo_dgeex1(&custom_mem->temp_beta_mat, {{it}}, {{it}})); + {%- endfor %} + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, N, "ug", custom_mem->d_ug_e_tightened); +{%- endif %} +{%- endif %} + + +{%- if zoro_description.nlh_e_t + zoro_description.nuh_e_t > 0 %} + // nonlinear constraints: h + // Get C_{k+1} and D_{k+1} + ocp_nlp_get_at_stage(solver->config, nlp_dims, solver, N, "C", custom_mem->d_Cgh_mat); + // NOTE: the d_Cgh_mat is column-major, the first ng rows are the Jacobians of the linear constraints + blasfeo_pack_dmat(nh, nx, custom_mem->d_Cgh_mat+ng, ng+nh, &custom_mem->Ch_mat, 0, 0); + + compute_gh_beta(&custom_mem->K_mat, &custom_mem->Ch_mat, + &custom_mem->dummy_Dgh_e_mat, &custom_mem->temp_CaDK_mat, + &custom_mem->temp_CaDKmP_mat, &custom_mem->temp_beta_mat, + &custom_mem->uncertainty_matrix_buffer[N], nh, nx, nu); + + {%- if zoro_description.nlh_e_t > 0 %} + {%- for it in zoro_description.idx_lh_e_t %} + custom_mem->d_lh_e_tightened[{{it}}] + = custom_mem->d_lh_e[{{it}}] + + backoff_scaling_gamma * sqrt(blasfeo_dgeex1(&custom_mem->temp_beta_mat, {{it}}, {{it}})); + {%- endfor %} + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, N, "lh", custom_mem->d_lh_e_tightened); + {%- endif %} + {%- if zoro_description.nuh_e_t > 0 %} + {%- for it in zoro_description.idx_uh_e_t %} + custom_mem->d_uh_e_tightened[{{it}}] = custom_mem->d_uh_e[{{it}}] + - backoff_scaling_gamma * sqrt(blasfeo_dgeex1(&custom_mem->temp_beta_mat, {{it}}, {{it}})); + {%- endfor %} + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, N, "uh", custom_mem->d_uh_e_tightened); + {%- endif %} +{%- endif %} + +} + + +int custom_update_function({{ model.name }}_solver_capsule* capsule, double* data, int data_len) +{ + custom_memory *custom_mem = (custom_memory *) capsule->custom_update_memory; + ocp_nlp_config *nlp_config = {{ model.name }}_acados_get_nlp_config(capsule); + ocp_nlp_dims *nlp_dims = {{ model.name }}_acados_get_nlp_dims(capsule); + ocp_nlp_in *nlp_in = {{ model.name }}_acados_get_nlp_in(capsule); + ocp_nlp_out *nlp_out = {{ model.name }}_acados_get_nlp_out(capsule); + ocp_nlp_solver *nlp_solver = {{ model.name }}_acados_get_nlp_solver(capsule); + void *nlp_opts = {{ model.name }}_acados_get_nlp_opts(capsule); + + if (data_len > 0) + { + reset_P0_matrix(nlp_dims, &custom_mem->uncertainty_matrix_buffer[0], data); + } + uncertainty_propagate_and_update(nlp_solver, nlp_in, nlp_out, custom_mem); + + return 1; +} + + +int custom_update_terminate_function({{ model.name }}_solver_capsule* capsule) +{ + custom_memory *mem = capsule->custom_update_memory; + + free(mem->raw_memory); + return 1; +} + +// useful prints for debugging + +/* +printf("A_mat:\n"); +blasfeo_print_exp_dmat(nx, nx, &custom_mem->A_mat, 0, 0); +printf("B_mat:\n"); +blasfeo_print_exp_dmat(nx, nu, &custom_mem->B_mat, 0, 0); +printf("K_mat:\n"); +blasfeo_print_exp_dmat(nu, nx, &custom_mem->K_mat, 0, 0); +printf("AK_mat:\n"); +blasfeo_print_exp_dmat(nx, nx, &custom_mem->AK_mat, 0, 0); +printf("temp_AP_mat:\n"); +blasfeo_print_exp_dmat(nx, nx, &custom_mem->temp_AP_mat, 0, 0); +printf("W_mat:\n"); +blasfeo_print_exp_dmat(nx, nx, &custom_mem->W_mat, 0, 0); +printf("P_k+1:\n"); +blasfeo_print_exp_dmat(nx, nx, &(custom_mem->uncertainty_matrix_buffer[ii+1]), 0, 0);*/ \ No newline at end of file diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_fun.h b/third_party/acados/acados_template/custom_update_templates/custom_update_function_zoro_template.in.h similarity index 50% rename from selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_fun.h rename to third_party/acados/acados_template/custom_update_templates/custom_update_function_zoro_template.in.h index 0d475171f..9611ea210 100644 --- a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_fun.h +++ b/third_party/acados/acados_template/custom_update_templates/custom_update_function_zoro_template.in.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * @@ -31,39 +28,17 @@ * POSSIBILITY OF SUCH DAMAGE.; */ +#include "acados_solver_{{ model.name }}.h" -#ifndef lat_Y_COST -#define lat_Y_COST - -#ifdef __cplusplus -extern "C" { -#endif +// Called at the end of solver creation. +// This is allowed to allocate memory and store the pointer to it into capsule->custom_update_memory. +int custom_update_init_function({{ model.name }}_solver_capsule* capsule); -int lat_cost_y_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int lat_cost_y_fun_work(int *, int *, int *, int *); -const int *lat_cost_y_fun_sparsity_in(int); -const int *lat_cost_y_fun_sparsity_out(int); -int lat_cost_y_fun_n_in(void); -int lat_cost_y_fun_n_out(void); - -int lat_cost_y_fun_jac_ut_xt(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int lat_cost_y_fun_jac_ut_xt_work(int *, int *, int *, int *); -const int *lat_cost_y_fun_jac_ut_xt_sparsity_in(int); -const int *lat_cost_y_fun_jac_ut_xt_sparsity_out(int); -int lat_cost_y_fun_jac_ut_xt_n_in(void); -int lat_cost_y_fun_jac_ut_xt_n_out(void); - -int lat_cost_y_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int lat_cost_y_hess_work(int *, int *, int *, int *); -const int *lat_cost_y_hess_sparsity_in(int); -const int *lat_cost_y_hess_sparsity_out(int); -int lat_cost_y_hess_n_in(void); -int lat_cost_y_hess_n_out(void); +// Custom update function that can be called between solver calls +int custom_update_function({{ model.name }}_solver_capsule* capsule, double* data, int data_len); -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // lat_Y_COST +// Called just before destroying the solver. +// Responsible to free allocated memory, stored at capsule->custom_update_memory. +int custom_update_terminate_function({{ model.name }}_solver_capsule* capsule); diff --git a/third_party/acados/acados_template/generate_c_code_constraint.py b/third_party/acados/acados_template/generate_c_code_constraint.py deleted file mode 100644 index c79ddc129..000000000 --- a/third_party/acados/acados_template/generate_c_code_constraint.py +++ /dev/null @@ -1,180 +0,0 @@ -# -# Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, -# Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, -# Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, -# Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl -# -# This file is part of acados. -# -# 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 HOLDER 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.; -# - -import os -from casadi import * -from .utils import ALLOWED_CASADI_VERSIONS, is_empty, casadi_length, casadi_version_warning - -def generate_c_code_constraint( model, con_name, is_terminal, opts ): - - casadi_version = CasadiMeta.version() - casadi_opts = dict(mex=False, casadi_int='int', casadi_real='double') - - if casadi_version not in (ALLOWED_CASADI_VERSIONS): - casadi_version_warning(casadi_version) - - # load constraint variables and expression - x = model.x - p = model.p - - if isinstance(x, casadi.MX): - symbol = MX.sym - else: - symbol = SX.sym - - if is_terminal: - con_h_expr = model.con_h_expr_e - con_phi_expr = model.con_phi_expr_e - # create dummy u, z - u = symbol('u', 0, 0) - z = symbol('z', 0, 0) - else: - con_h_expr = model.con_h_expr - con_phi_expr = model.con_phi_expr - u = model.u - z = model.z - - if (not is_empty(con_h_expr)) and (not is_empty(con_phi_expr)): - raise Exception("acados: you can either have constraint_h, or constraint_phi, not both.") - - if not (is_empty(con_h_expr) and is_empty(con_phi_expr)): - if is_empty(con_h_expr): - constr_type = 'BGP' - else: - constr_type = 'BGH' - - if is_empty(p): - p = symbol('p', 0, 0) - - if is_empty(z): - z = symbol('z', 0, 0) - - if not (is_empty(con_h_expr)) and opts['generate_hess']: - # multipliers for hessian - nh = casadi_length(con_h_expr) - lam_h = symbol('lam_h', nh, 1) - - # set up & change directory - code_export_dir = opts["code_export_directory"] - if not os.path.exists(code_export_dir): - os.makedirs(code_export_dir) - - cwd = os.getcwd() - os.chdir(code_export_dir) - gen_dir = con_name + '_constraints' - if not os.path.exists(gen_dir): - os.mkdir(gen_dir) - gen_dir_location = os.path.join('.', gen_dir) - os.chdir(gen_dir_location) - - # export casadi functions - if constr_type == 'BGH': - if is_terminal: - fun_name = con_name + '_constr_h_e_fun_jac_uxt_zt' - else: - fun_name = con_name + '_constr_h_fun_jac_uxt_zt' - - jac_ux_t = transpose(jacobian(con_h_expr, vertcat(u,x))) - jac_z_t = jacobian(con_h_expr, z) - constraint_fun_jac_tran = Function(fun_name, [x, u, z, p], \ - [con_h_expr, jac_ux_t, jac_z_t]) - - constraint_fun_jac_tran.generate(fun_name, casadi_opts) - if opts['generate_hess']: - - if is_terminal: - fun_name = con_name + '_constr_h_e_fun_jac_uxt_zt_hess' - else: - fun_name = con_name + '_constr_h_fun_jac_uxt_zt_hess' - - # adjoint - adj_ux = jtimes(con_h_expr, vertcat(u, x), lam_h, True) - # hessian - hess_ux = jacobian(adj_ux, vertcat(u, x)) - - adj_z = jtimes(con_h_expr, z, lam_h, True) - hess_z = jacobian(adj_z, z) - - # set up functions - constraint_fun_jac_tran_hess = \ - Function(fun_name, [x, u, lam_h, z, p], \ - [con_h_expr, jac_ux_t, hess_ux, jac_z_t, hess_z]) - - # generate C code - constraint_fun_jac_tran_hess.generate(fun_name, casadi_opts) - - if is_terminal: - fun_name = con_name + '_constr_h_e_fun' - else: - fun_name = con_name + '_constr_h_fun' - h_fun = Function(fun_name, [x, u, z, p], [con_h_expr]) - h_fun.generate(fun_name, casadi_opts) - - else: # BGP constraint - if is_terminal: - fun_name = con_name + '_phi_e_constraint' - r = model.con_r_in_phi_e - con_r_expr = model.con_r_expr_e - else: - fun_name = con_name + '_phi_constraint' - r = model.con_r_in_phi - con_r_expr = model.con_r_expr - - nphi = casadi_length(con_phi_expr) - con_phi_expr_x_u_z = substitute(con_phi_expr, r, con_r_expr) - phi_jac_u = jacobian(con_phi_expr_x_u_z, u) - phi_jac_x = jacobian(con_phi_expr_x_u_z, x) - phi_jac_z = jacobian(con_phi_expr_x_u_z, z) - - hess = hessian(con_phi_expr[0], r)[0] - for i in range(1, nphi): - hess = vertcat(hess, hessian(con_phi_expr[i], r)[0]) - - r_jac_u = jacobian(con_r_expr, u) - r_jac_x = jacobian(con_r_expr, x) - - constraint_phi = \ - Function(fun_name, [x, u, z, p], \ - [con_phi_expr_x_u_z, \ - vertcat(transpose(phi_jac_u), \ - transpose(phi_jac_x)), \ - transpose(phi_jac_z), \ - hess, vertcat(transpose(r_jac_u), \ - transpose(r_jac_x))]) - - constraint_phi.generate(fun_name, casadi_opts) - - # change directory back - os.chdir(cwd) - - return diff --git a/third_party/acados/acados_template/generate_c_code_discrete_dynamics.py b/third_party/acados/acados_template/generate_c_code_discrete_dynamics.py deleted file mode 100644 index c6a245ff8..000000000 --- a/third_party/acados/acados_template/generate_c_code_discrete_dynamics.py +++ /dev/null @@ -1,98 +0,0 @@ -# -# Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, -# Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, -# Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, -# Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl -# -# This file is part of acados. -# -# 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 HOLDER 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. -# - -import os -import casadi as ca -from .utils import ALLOWED_CASADI_VERSIONS, casadi_length, casadi_version_warning - -def generate_c_code_discrete_dynamics( model, opts ): - - casadi_version = ca.CasadiMeta.version() - casadi_opts = dict(mex=False, casadi_int='int', casadi_real='double') - - if casadi_version not in (ALLOWED_CASADI_VERSIONS): - casadi_version_warning(casadi_version) - - # load model - x = model.x - u = model.u - p = model.p - phi = model.disc_dyn_expr - model_name = model.name - nx = casadi_length(x) - - if isinstance(phi, ca.MX): - symbol = ca.MX.sym - elif isinstance(phi, ca.SX): - symbol = ca.SX.sym - else: - Exception("generate_c_code_disc_dyn: disc_dyn_expr must be a CasADi expression, you have type: {}".format(type(phi))) - - # assume nx1 = nx !!! - lam = symbol('lam', nx, 1) - - # generate jacobians - ux = ca.vertcat(u,x) - jac_ux = ca.jacobian(phi, ux) - # generate adjoint - adj_ux = ca.jtimes(phi, ux, lam, True) - # generate hessian - hess_ux = ca.jacobian(adj_ux, ux) - - ## change directory - code_export_dir = opts["code_export_directory"] - if not os.path.exists(code_export_dir): - os.makedirs(code_export_dir) - - cwd = os.getcwd() - os.chdir(code_export_dir) - model_dir = model_name + '_model' - if not os.path.exists(model_dir): - os.mkdir(model_dir) - model_dir_location = os.path.join('.', model_dir) - os.chdir(model_dir_location) - - # set up & generate Functions - fun_name = model_name + '_dyn_disc_phi_fun' - phi_fun = ca.Function(fun_name, [x, u, p], [phi]) - phi_fun.generate(fun_name, casadi_opts) - - fun_name = model_name + '_dyn_disc_phi_fun_jac' - phi_fun_jac_ut_xt = ca.Function(fun_name, [x, u, p], [phi, jac_ux.T]) - phi_fun_jac_ut_xt.generate(fun_name, casadi_opts) - - fun_name = model_name + '_dyn_disc_phi_fun_jac_hess' - phi_fun_jac_ut_xt_hess = ca.Function(fun_name, [x, u, lam, p], [phi, jac_ux.T, hess_ux]) - phi_fun_jac_ut_xt_hess.generate(fun_name, casadi_opts) - - os.chdir(cwd) diff --git a/third_party/acados/acados_template/generate_c_code_explicit_ode.py b/third_party/acados/acados_template/generate_c_code_explicit_ode.py deleted file mode 100644 index 76e640053..000000000 --- a/third_party/acados/acados_template/generate_c_code_explicit_ode.py +++ /dev/null @@ -1,124 +0,0 @@ -# -# Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, -# Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, -# Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, -# Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl -# -# This file is part of acados. -# -# 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 HOLDER 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.; -# - -import os -from casadi import * -from .utils import ALLOWED_CASADI_VERSIONS, is_empty, casadi_version_warning - -def generate_c_code_explicit_ode( model, opts ): - - casadi_version = CasadiMeta.version() - casadi_opts = dict(mex=False, casadi_int='int', casadi_real='double') - if casadi_version not in (ALLOWED_CASADI_VERSIONS): - casadi_version_warning(casadi_version) - - - generate_hess = opts["generate_hess"] - code_export_dir = opts["code_export_directory"] - - # load model - x = model.x - u = model.u - p = model.p - f_expl = model.f_expl_expr - model_name = model.name - - ## get model dimensions - nx = x.size()[0] - nu = u.size()[0] - - if isinstance(f_expl, casadi.MX): - symbol = MX.sym - elif isinstance(f_expl, casadi.SX): - symbol = SX.sym - else: - raise Exception("Invalid type for f_expl! Possible types are 'SX' and 'MX'. Exiting.") - ## set up functions to be exported - Sx = symbol('Sx', nx, nx) - Sp = symbol('Sp', nx, nu) - lambdaX = symbol('lambdaX', nx, 1) - - fun_name = model_name + '_expl_ode_fun' - - ## Set up functions - expl_ode_fun = Function(fun_name, [x, u, p], [f_expl]) - - vdeX = jtimes(f_expl,x,Sx) - vdeP = jacobian(f_expl,u) + jtimes(f_expl,x,Sp) - - fun_name = model_name + '_expl_vde_forw' - - expl_vde_forw = Function(fun_name, [x, Sx, Sp, u, p], [f_expl, vdeX, vdeP]) - - adj = jtimes(f_expl, vertcat(x, u), lambdaX, True) - - fun_name = model_name + '_expl_vde_adj' - expl_vde_adj = Function(fun_name, [x, lambdaX, u, p], [adj]) - - if generate_hess: - S_forw = vertcat(horzcat(Sx, Sp), horzcat(DM.zeros(nu,nx), DM.eye(nu))) - hess = mtimes(transpose(S_forw),jtimes(adj, vertcat(x,u), S_forw)) - hess2 = [] - for j in range(nx+nu): - for i in range(j,nx+nu): - hess2 = vertcat(hess2, hess[i,j]) - - fun_name = model_name + '_expl_ode_hess' - expl_ode_hess = Function(fun_name, [x, Sx, Sp, lambdaX, u, p], [adj, hess2]) - - ## generate C code - if not os.path.exists(code_export_dir): - os.makedirs(code_export_dir) - - cwd = os.getcwd() - os.chdir(code_export_dir) - model_dir = model_name + '_model' - if not os.path.exists(model_dir): - os.mkdir(model_dir) - model_dir_location = os.path.join('.', model_dir) - os.chdir(model_dir_location) - fun_name = model_name + '_expl_ode_fun' - expl_ode_fun.generate(fun_name, casadi_opts) - - fun_name = model_name + '_expl_vde_forw' - expl_vde_forw.generate(fun_name, casadi_opts) - - fun_name = model_name + '_expl_vde_adj' - expl_vde_adj.generate(fun_name, casadi_opts) - - if generate_hess: - fun_name = model_name + '_expl_ode_hess' - expl_ode_hess.generate(fun_name, casadi_opts) - os.chdir(cwd) - - return diff --git a/third_party/acados/acados_template/generate_c_code_external_cost.py b/third_party/acados/acados_template/generate_c_code_external_cost.py deleted file mode 100644 index 839652261..000000000 --- a/third_party/acados/acados_template/generate_c_code_external_cost.py +++ /dev/null @@ -1,116 +0,0 @@ -# -# Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, -# Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, -# Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, -# Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl -# -# This file is part of acados. -# -# 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 HOLDER 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.; -# - -import os -from casadi import SX, MX, Function, transpose, vertcat, horzcat, hessian, CasadiMeta -from .utils import ALLOWED_CASADI_VERSIONS, casadi_version_warning - - -def generate_c_code_external_cost(model, stage_type, opts): - - casadi_version = CasadiMeta.version() - casadi_opts = dict(mex=False, casadi_int="int", casadi_real="double") - - if casadi_version not in (ALLOWED_CASADI_VERSIONS): - casadi_version_warning(casadi_version) - - x = model.x - p = model.p - - if isinstance(x, MX): - symbol = MX.sym - else: - symbol = SX.sym - - if stage_type == 'terminal': - suffix_name = "_cost_ext_cost_e_fun" - suffix_name_hess = "_cost_ext_cost_e_fun_jac_hess" - suffix_name_jac = "_cost_ext_cost_e_fun_jac" - u = symbol("u", 0, 0) - ext_cost = model.cost_expr_ext_cost_e - custom_hess = model.cost_expr_ext_cost_custom_hess_e - - elif stage_type == 'path': - suffix_name = "_cost_ext_cost_fun" - suffix_name_hess = "_cost_ext_cost_fun_jac_hess" - suffix_name_jac = "_cost_ext_cost_fun_jac" - u = model.u - ext_cost = model.cost_expr_ext_cost - custom_hess = model.cost_expr_ext_cost_custom_hess - - elif stage_type == 'initial': - suffix_name = "_cost_ext_cost_0_fun" - suffix_name_hess = "_cost_ext_cost_0_fun_jac_hess" - suffix_name_jac = "_cost_ext_cost_0_fun_jac" - u = model.u - ext_cost = model.cost_expr_ext_cost_0 - custom_hess = model.cost_expr_ext_cost_custom_hess_0 - - # set up functions to be exported - fun_name = model.name + suffix_name - fun_name_hess = model.name + suffix_name_hess - fun_name_jac = model.name + suffix_name_jac - - # generate expression for full gradient and Hessian - full_hess, grad = hessian(ext_cost, vertcat(u, x)) - - if custom_hess is not None: - full_hess = custom_hess - - ext_cost_fun = Function(fun_name, [x, u, p], [ext_cost]) - ext_cost_fun_jac_hess = Function( - fun_name_hess, [x, u, p], [ext_cost, grad, full_hess] - ) - ext_cost_fun_jac = Function( - fun_name_jac, [x, u, p], [ext_cost, grad] - ) - - # generate C code - code_export_dir = opts["code_export_directory"] - if not os.path.exists(code_export_dir): - os.makedirs(code_export_dir) - - cwd = os.getcwd() - os.chdir(code_export_dir) - gen_dir = model.name + '_cost' - if not os.path.exists(gen_dir): - os.mkdir(gen_dir) - gen_dir_location = "./" + gen_dir - os.chdir(gen_dir_location) - - ext_cost_fun.generate(fun_name, casadi_opts) - ext_cost_fun_jac_hess.generate(fun_name_hess, casadi_opts) - ext_cost_fun_jac.generate(fun_name_jac, casadi_opts) - - os.chdir(cwd) - return diff --git a/third_party/acados/acados_template/generate_c_code_gnsf.py b/third_party/acados/acados_template/generate_c_code_gnsf.py deleted file mode 100644 index 97acb8e33..000000000 --- a/third_party/acados/acados_template/generate_c_code_gnsf.py +++ /dev/null @@ -1,131 +0,0 @@ -# -# Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, -# Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, -# Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, -# Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl -# -# This file is part of acados. -# -# 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 HOLDER 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.; -# - -import os -from casadi import * -from .utils import ALLOWED_CASADI_VERSIONS, is_empty, casadi_version_warning - -def generate_c_code_gnsf( model, opts ): - - casadi_version = CasadiMeta.version() - casadi_opts = dict(mex=False, casadi_int='int', casadi_real='double') - if casadi_version not in (ALLOWED_CASADI_VERSIONS): - casadi_version_warning(casadi_version) - - model_name = model.name - code_export_dir = opts["code_export_directory"] - - # set up directory - if not os.path.exists(code_export_dir): - os.makedirs(code_export_dir) - - cwd = os.getcwd() - os.chdir(code_export_dir) - model_dir = model_name + '_model' - if not os.path.exists(model_dir): - os.mkdir(model_dir) - model_dir_location = os.path.join('.', model_dir) - os.chdir(model_dir_location) - - # obtain gnsf dimensions - get_matrices_fun = model.get_matrices_fun - phi_fun = model.phi_fun - - size_gnsf_A = get_matrices_fun.size_out(0) - gnsf_nx1 = size_gnsf_A[1] - gnsf_nz1 = size_gnsf_A[0] - size_gnsf_A[1] - gnsf_nuhat = max(phi_fun.size_in(1)) - gnsf_ny = max(phi_fun.size_in(0)) - gnsf_nout = max(phi_fun.size_out(0)) - - # set up expressions - # if the model uses MX because of cost/constraints - # the DAE can be exported as SX -> detect GNSF in Matlab - # -> evaluated SX GNSF functions with MX. - u = model.u - - if isinstance(u, casadi.MX): - symbol = MX.sym - else: - symbol = SX.sym - - y = symbol("y", gnsf_ny, 1) - uhat = symbol("uhat", gnsf_nuhat, 1) - p = model.p - x1 = symbol("gnsf_x1", gnsf_nx1, 1) - x1dot = symbol("gnsf_x1dot", gnsf_nx1, 1) - z1 = symbol("gnsf_z1", gnsf_nz1, 1) - dummy = symbol("gnsf_dummy", 1, 1) - empty_var = symbol("gnsf_empty_var", 0, 0) - - ## generate C code - fun_name = model_name + '_gnsf_phi_fun' - phi_fun_ = Function(fun_name, [y, uhat, p], [phi_fun(y, uhat, p)]) - phi_fun_.generate(fun_name, casadi_opts) - - fun_name = model_name + '_gnsf_phi_fun_jac_y' - phi_fun_jac_y = model.phi_fun_jac_y - phi_fun_jac_y_ = Function(fun_name, [y, uhat, p], phi_fun_jac_y(y, uhat, p)) - phi_fun_jac_y_.generate(fun_name, casadi_opts) - - fun_name = model_name + '_gnsf_phi_jac_y_uhat' - phi_jac_y_uhat = model.phi_jac_y_uhat - phi_jac_y_uhat_ = Function(fun_name, [y, uhat, p], phi_jac_y_uhat(y, uhat, p)) - phi_jac_y_uhat_.generate(fun_name, casadi_opts) - - fun_name = model_name + '_gnsf_f_lo_fun_jac_x1k1uz' - f_lo_fun_jac_x1k1uz = model.f_lo_fun_jac_x1k1uz - f_lo_fun_jac_x1k1uz_eval = f_lo_fun_jac_x1k1uz(x1, x1dot, z1, u, p) - - # avoid codegeneration issue - if not isinstance(f_lo_fun_jac_x1k1uz_eval, tuple) and is_empty(f_lo_fun_jac_x1k1uz_eval): - f_lo_fun_jac_x1k1uz_eval = [empty_var] - - f_lo_fun_jac_x1k1uz_ = Function(fun_name, [x1, x1dot, z1, u, p], - f_lo_fun_jac_x1k1uz_eval) - f_lo_fun_jac_x1k1uz_.generate(fun_name, casadi_opts) - - fun_name = model_name + '_gnsf_get_matrices_fun' - get_matrices_fun_ = Function(fun_name, [dummy], get_matrices_fun(1)) - get_matrices_fun_.generate(fun_name, casadi_opts) - - # remove fields for json dump - del model.phi_fun - del model.phi_fun_jac_y - del model.phi_jac_y_uhat - del model.f_lo_fun_jac_x1k1uz - del model.get_matrices_fun - - os.chdir(cwd) - - return diff --git a/third_party/acados/acados_template/generate_c_code_implicit_ode.py b/third_party/acados/acados_template/generate_c_code_implicit_ode.py deleted file mode 100644 index f2d50b43a..000000000 --- a/third_party/acados/acados_template/generate_c_code_implicit_ode.py +++ /dev/null @@ -1,139 +0,0 @@ -# -# Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, -# Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, -# Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, -# Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl -# -# This file is part of acados. -# -# 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 HOLDER 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.; -# - -import os -from casadi import * -from .utils import ALLOWED_CASADI_VERSIONS, is_empty, casadi_length, casadi_version_warning - -def generate_c_code_implicit_ode( model, opts ): - - casadi_version = CasadiMeta.version() - casadi_opts = dict(mex=False, casadi_int='int', casadi_real='double') - if casadi_version not in (ALLOWED_CASADI_VERSIONS): - casadi_version_warning(casadi_version) - - generate_hess = opts["generate_hess"] - code_export_dir = opts["code_export_directory"] - - ## load model - x = model.x - xdot = model.xdot - u = model.u - z = model.z - p = model.p - f_impl = model.f_impl_expr - model_name = model.name - - ## get model dimensions - nx = casadi_length(x) - nu = casadi_length(u) - nz = casadi_length(z) - - ## generate jacobians - jac_x = jacobian(f_impl, x) - jac_xdot = jacobian(f_impl, xdot) - jac_u = jacobian(f_impl, u) - jac_z = jacobian(f_impl, z) - - ## generate hessian - x_xdot_z_u = vertcat(x, xdot, z, u) - - if isinstance(x, casadi.MX): - symbol = MX.sym - else: - symbol = SX.sym - - multiplier = symbol('multiplier', nx + nz) - - ADJ = jtimes(f_impl, x_xdot_z_u, multiplier, True) - HESS = jacobian(ADJ, x_xdot_z_u) - - ## Set up functions - p = model.p - fun_name = model_name + '_impl_dae_fun' - impl_dae_fun = Function(fun_name, [x, xdot, u, z, p], [f_impl]) - - fun_name = model_name + '_impl_dae_fun_jac_x_xdot_z' - impl_dae_fun_jac_x_xdot_z = Function(fun_name, [x, xdot, u, z, p], [f_impl, jac_x, jac_xdot, jac_z]) - - # fun_name = model_name + '_impl_dae_fun_jac_x_xdot_z' - # impl_dae_fun_jac_x_xdot = Function(fun_name, [x, xdot, u, z, p], [f_impl, jac_x, jac_xdot, jac_z]) - - # fun_name = model_name + '_impl_dae_jac_x_xdot_u' - # impl_dae_jac_x_xdot_u = Function(fun_name, [x, xdot, u, z, p], [jac_x, jac_xdot, jac_u, jac_z]) - - fun_name = model_name + '_impl_dae_fun_jac_x_xdot_u_z' - impl_dae_fun_jac_x_xdot_u_z = Function(fun_name, [x, xdot, u, z, p], [f_impl, jac_x, jac_xdot, jac_u, jac_z]) - - fun_name = model_name + '_impl_dae_fun_jac_x_xdot_u' - impl_dae_fun_jac_x_xdot_u = Function(fun_name, [x, xdot, u, z, p], [f_impl, jac_x, jac_xdot, jac_u]) - - fun_name = model_name + '_impl_dae_jac_x_xdot_u_z' - impl_dae_jac_x_xdot_u_z = Function(fun_name, [x, xdot, u, z, p], [jac_x, jac_xdot, jac_u, jac_z]) - - - fun_name = model_name + '_impl_dae_hess' - impl_dae_hess = Function(fun_name, [x, xdot, u, z, multiplier, p], [HESS]) - - # generate C code - if not os.path.exists(code_export_dir): - os.makedirs(code_export_dir) - - cwd = os.getcwd() - os.chdir(code_export_dir) - model_dir = model_name + '_model' - if not os.path.exists(model_dir): - os.mkdir(model_dir) - model_dir_location = os.path.join('.', model_dir) - os.chdir(model_dir_location) - - fun_name = model_name + '_impl_dae_fun' - impl_dae_fun.generate(fun_name, casadi_opts) - - fun_name = model_name + '_impl_dae_fun_jac_x_xdot_z' - impl_dae_fun_jac_x_xdot_z.generate(fun_name, casadi_opts) - - fun_name = model_name + '_impl_dae_jac_x_xdot_u_z' - impl_dae_jac_x_xdot_u_z.generate(fun_name, casadi_opts) - - fun_name = model_name + '_impl_dae_fun_jac_x_xdot_u_z' - impl_dae_fun_jac_x_xdot_u_z.generate(fun_name, casadi_opts) - - fun_name = model_name + '_impl_dae_fun_jac_x_xdot_u' - impl_dae_fun_jac_x_xdot_u.generate(fun_name, casadi_opts) - - if generate_hess: - fun_name = model_name + '_impl_dae_hess' - impl_dae_hess.generate(fun_name, casadi_opts) - - os.chdir(cwd) diff --git a/third_party/acados/acados_template/generate_c_code_nls_cost.py b/third_party/acados/acados_template/generate_c_code_nls_cost.py deleted file mode 100644 index ffcd78ca7..000000000 --- a/third_party/acados/acados_template/generate_c_code_nls_cost.py +++ /dev/null @@ -1,113 +0,0 @@ -# -# Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, -# Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, -# Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, -# Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl -# -# This file is part of acados. -# -# 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 HOLDER 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.; -# - -import os -from casadi import * -from .utils import ALLOWED_CASADI_VERSIONS, casadi_length, casadi_version_warning - -def generate_c_code_nls_cost( model, cost_name, stage_type, opts ): - - casadi_version = CasadiMeta.version() - casadi_opts = dict(mex=False, casadi_int='int', casadi_real='double') - - if casadi_version not in (ALLOWED_CASADI_VERSIONS): - casadi_version_warning(casadi_version) - - x = model.x - p = model.p - - if isinstance(x, casadi.MX): - symbol = MX.sym - else: - symbol = SX.sym - - if stage_type == 'terminal': - middle_name = '_cost_y_e' - u = symbol('u', 0, 0) - cost_expr = model.cost_y_expr_e - - elif stage_type == 'initial': - middle_name = '_cost_y_0' - u = model.u - cost_expr = model.cost_y_expr_0 - - elif stage_type == 'path': - middle_name = '_cost_y' - u = model.u - cost_expr = model.cost_y_expr - - # set up directory - code_export_dir = opts["code_export_directory"] - if not os.path.exists(code_export_dir): - os.makedirs(code_export_dir) - - cwd = os.getcwd() - os.chdir(code_export_dir) - gen_dir = cost_name + '_cost' - if not os.path.exists(gen_dir): - os.mkdir(gen_dir) - gen_dir_location = os.path.join('.', gen_dir) - os.chdir(gen_dir_location) - - # set up expressions - cost_jac_expr = transpose(jacobian(cost_expr, vertcat(u, x))) - - ny = casadi_length(cost_expr) - - y = symbol('y', ny, 1) - - y_adj = jtimes(cost_expr, vertcat(u, x), y, True) - y_hess = jacobian(y_adj, vertcat(u, x)) - - ## generate C code - suffix_name = '_fun' - fun_name = cost_name + middle_name + suffix_name - y_fun = Function( fun_name, [x, u, p], \ - [ cost_expr ]) - y_fun.generate( fun_name, casadi_opts ) - - suffix_name = '_fun_jac_ut_xt' - fun_name = cost_name + middle_name + suffix_name - y_fun_jac_ut_xt = Function(fun_name, [x, u, p], \ - [ cost_expr, cost_jac_expr ]) - y_fun_jac_ut_xt.generate( fun_name, casadi_opts ) - - suffix_name = '_hess' - fun_name = cost_name + middle_name + suffix_name - y_hess = Function(fun_name, [x, u, y, p], [ y_hess ]) - y_hess.generate( fun_name, casadi_opts ) - - os.chdir(cwd) - - return - diff --git a/third_party/acados/acados_template/gnsf/__init__.py b/third_party/acados/acados_template/gnsf/__init__.py new file mode 100644 index 000000000..8b1378917 --- /dev/null +++ b/third_party/acados/acados_template/gnsf/__init__.py @@ -0,0 +1 @@ + diff --git a/third_party/acados/acados_template/gnsf/__pycache__/__init__.cpython-311.pyc b/third_party/acados/acados_template/gnsf/__pycache__/__init__.cpython-311.pyc new file mode 100644 index 000000000..ad109a788 Binary files /dev/null and b/third_party/acados/acados_template/gnsf/__pycache__/__init__.cpython-311.pyc differ diff --git a/third_party/acados/acados_template/gnsf/__pycache__/check_reformulation.cpython-311.pyc b/third_party/acados/acados_template/gnsf/__pycache__/check_reformulation.cpython-311.pyc new file mode 100644 index 000000000..6fb6f87dd Binary files /dev/null and b/third_party/acados/acados_template/gnsf/__pycache__/check_reformulation.cpython-311.pyc differ diff --git a/third_party/acados/acados_template/gnsf/__pycache__/detect_affine_terms_reduce_nonlinearity.cpython-311.pyc b/third_party/acados/acados_template/gnsf/__pycache__/detect_affine_terms_reduce_nonlinearity.cpython-311.pyc new file mode 100644 index 000000000..b67adb8a2 Binary files /dev/null and b/third_party/acados/acados_template/gnsf/__pycache__/detect_affine_terms_reduce_nonlinearity.cpython-311.pyc differ diff --git a/third_party/acados/acados_template/gnsf/__pycache__/detect_gnsf_structure.cpython-311.pyc b/third_party/acados/acados_template/gnsf/__pycache__/detect_gnsf_structure.cpython-311.pyc new file mode 100644 index 000000000..196641a44 Binary files /dev/null and b/third_party/acados/acados_template/gnsf/__pycache__/detect_gnsf_structure.cpython-311.pyc differ diff --git a/third_party/acados/acados_template/gnsf/__pycache__/determine_input_nonlinearity_function.cpython-311.pyc b/third_party/acados/acados_template/gnsf/__pycache__/determine_input_nonlinearity_function.cpython-311.pyc new file mode 100644 index 000000000..1e68a4178 Binary files /dev/null and b/third_party/acados/acados_template/gnsf/__pycache__/determine_input_nonlinearity_function.cpython-311.pyc differ diff --git a/third_party/acados/acados_template/gnsf/__pycache__/determine_trivial_gnsf_transcription.cpython-311.pyc b/third_party/acados/acados_template/gnsf/__pycache__/determine_trivial_gnsf_transcription.cpython-311.pyc new file mode 100644 index 000000000..a39b4d76e Binary files /dev/null and b/third_party/acados/acados_template/gnsf/__pycache__/determine_trivial_gnsf_transcription.cpython-311.pyc differ diff --git a/third_party/acados/acados_template/gnsf/__pycache__/reformulate_with_LOS.cpython-311.pyc b/third_party/acados/acados_template/gnsf/__pycache__/reformulate_with_LOS.cpython-311.pyc new file mode 100644 index 000000000..669bb6f0d Binary files /dev/null and b/third_party/acados/acados_template/gnsf/__pycache__/reformulate_with_LOS.cpython-311.pyc differ diff --git a/third_party/acados/acados_template/gnsf/__pycache__/reformulate_with_invertible_E_mat.cpython-311.pyc b/third_party/acados/acados_template/gnsf/__pycache__/reformulate_with_invertible_E_mat.cpython-311.pyc new file mode 100644 index 000000000..f47e928e1 Binary files /dev/null and b/third_party/acados/acados_template/gnsf/__pycache__/reformulate_with_invertible_E_mat.cpython-311.pyc differ diff --git a/third_party/acados/acados_template/gnsf/__pycache__/structure_detection_print_summary.cpython-311.pyc b/third_party/acados/acados_template/gnsf/__pycache__/structure_detection_print_summary.cpython-311.pyc new file mode 100644 index 000000000..dd1602dd6 Binary files /dev/null and b/third_party/acados/acados_template/gnsf/__pycache__/structure_detection_print_summary.cpython-311.pyc differ diff --git a/third_party/acados/acados_template/gnsf/check_reformulation.py b/third_party/acados/acados_template/gnsf/check_reformulation.py new file mode 100644 index 000000000..2bdfbbc33 --- /dev/null +++ b/third_party/acados/acados_template/gnsf/check_reformulation.py @@ -0,0 +1,216 @@ +# +# Copyright (c) The acados authors. +# +# This file is part of acados. +# +# 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 HOLDER 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.; +# + +from acados_template.utils import casadi_length +from casadi import * +import numpy as np + + +def check_reformulation(model, gnsf, print_info): + + ## Description: + # this function takes the implicit ODE/ index-1 DAE and a gnsf structure + # to evaluate both models at num_eval random points x0, x0dot, z0, u0 + # if for all points the relative error is <= TOL, the function will return:: + # 1, otherwise it will give an error. + + TOL = 1e-14 + num_eval = 10 + + # get dimensions + nx = gnsf["nx"] + nu = gnsf["nu"] + nz = gnsf["nz"] + nx1 = gnsf["nx1"] + nx2 = gnsf["nx2"] + nz1 = gnsf["nz1"] + nz2 = gnsf["nz2"] + n_out = gnsf["n_out"] + + # get model matrices + A = gnsf["A"] + B = gnsf["B"] + C = gnsf["C"] + E = gnsf["E"] + c = gnsf["c"] + + L_x = gnsf["L_x"] + L_xdot = gnsf["L_xdot"] + L_z = gnsf["L_z"] + L_u = gnsf["L_u"] + + A_LO = gnsf["A_LO"] + E_LO = gnsf["E_LO"] + B_LO = gnsf["B_LO"] + c_LO = gnsf["c_LO"] + + I_x1 = range(nx1) + I_x2 = range(nx1, nx) + + I_z1 = range(nz1) + I_z2 = range(nz1, nz) + + idx_perm_f = gnsf["idx_perm_f"] + + # get casadi variables + x = gnsf["x"] + xdot = gnsf["xdot"] + z = gnsf["z"] + u = gnsf["u"] + y = gnsf["y"] + uhat = gnsf["uhat"] + p = gnsf["p"] + + # create functions + impl_dae_fun = Function("impl_dae_fun", [x, xdot, u, z, p], [model.f_impl_expr]) + phi_fun = Function("phi_fun", [y, uhat, p], [gnsf["phi_expr"]]) + f_lo_fun = Function( + "f_lo_fun", [x[range(nx1)], xdot[range(nx1)], z, u, p], [gnsf["f_lo_expr"]] + ) + + # print(gnsf) + # print(gnsf["n_out"]) + + for i_check in range(num_eval): + # generate random values + x0 = np.random.rand(nx, 1) + x0dot = np.random.rand(nx, 1) + z0 = np.random.rand(nz, 1) + u0 = np.random.rand(nu, 1) + + if gnsf["ny"] > 0: + y0 = L_x @ x0[I_x1] + L_xdot @ x0dot[I_x1] + L_z @ z0[I_z1] + else: + y0 = [] + if gnsf["nuhat"] > 0: + uhat0 = L_u @ u0 + else: + uhat0 = [] + + # eval functions + p0 = np.random.rand(gnsf["np"], 1) + f_impl_val = impl_dae_fun(x0, x0dot, u0, z0, p0).full() + phi_val = phi_fun(y0, uhat0, p0) + f_lo_val = f_lo_fun(x0[I_x1], x0dot[I_x1], z0[I_z1], u0, p0) + + f_impl_val = f_impl_val[idx_perm_f] + # eval gnsf + if n_out > 0: + C_phi = C @ phi_val + else: + C_phi = np.zeros((nx1 + nz1, 1)) + try: + gnsf_val1 = ( + A @ x0[I_x1] + B @ u0 + C_phi + c - E @ vertcat(x0dot[I_x1], z0[I_z1]) + ) + # gnsf_1 = (A @ x[I_x1] + B @ u + C_phi + c - E @ vertcat(xdot[I_x1], z[I_z1])) + except: + import pdb + + pdb.set_trace() + + if nx2 > 0: # eval LOS: + gnsf_val2 = ( + A_LO @ x0[I_x2] + + B_LO @ u0 + + c_LO + + f_lo_val + - E_LO @ vertcat(x0dot[I_x2], z0[I_z2]) + ) + gnsf_val = vertcat(gnsf_val1, gnsf_val2).full() + else: + gnsf_val = gnsf_val1.full() + # compute error and check + rel_error = np.linalg.norm(f_impl_val - gnsf_val) / np.linalg.norm(f_impl_val) + + if rel_error > TOL: + print("transcription failed rel_error > TOL") + print("you are in debug mode now: import pdb; pdb.set_trace()") + abs_error = gnsf_val - f_impl_val + # T = table(f_impl_val, gnsf_val, abs_error) + # print(T) + print("abs_error:", abs_error) + # error('transcription failed rel_error > TOL') + # check = 0 + import pdb + + pdb.set_trace() + if print_info: + print(" ") + print("model reformulation checked: relative error <= TOL = ", str(TOL)) + print(" ") + check = 1 + ## helpful for debugging: + # # use in calling function and compare + # # compare f_impl(i) with gnsf_val1(i) + # + + # nx = gnsf['nx'] + # nu = gnsf['nu'] + # nz = gnsf['nz'] + # nx1 = gnsf['nx1'] + # nx2 = gnsf['nx2'] + # + # A = gnsf['A'] + # B = gnsf['B'] + # C = gnsf['C'] + # E = gnsf['E'] + # c = gnsf['c'] + # + # L_x = gnsf['L_x'] + # L_z = gnsf['L_z'] + # L_xdot = gnsf['L_xdot'] + # L_u = gnsf['L_u'] + # + # A_LO = gnsf['A_LO'] + # + # x0 = rand(nx, 1) + # x0dot = rand(nx, 1) + # z0 = rand(nz, 1) + # u0 = rand(nu, 1) + # I_x1 = range(nx1) + # I_x2 = nx1+range(nx) + # + # y0 = L_x @ x0[I_x1] + L_xdot @ x0dot[I_x1] + L_z @ z0 + # uhat0 = L_u @ u0 + # + # gnsf_val1 = (A @ x[I_x1] + B @ u + # C @ phi_current + c) - E @ [xdot[I_x1] z] + # gnsf_val1 = gnsf_val1.simplify() + # + # # gnsf_val2 = A_LO @ x[I_x2] + gnsf['f_lo_fun'](x[I_x1], xdot[I_x1], z, u) - xdot[I_x2] + # gnsf_val2 = A_LO @ x[I_x2] + gnsf['f_lo_fun'](x[I_x1], xdot[I_x1], z, u) - xdot[I_x2] + # + # + # gnsf_val = [gnsf_val1 gnsf_val2] + # gnsf_val = gnsf_val.simplify() + # dyn_expr_f = dyn_expr_f.simplify() + # import pdb; pdb.set_trace() + + return check diff --git a/third_party/acados/acados_template/gnsf/detect_affine_terms_reduce_nonlinearity.py b/third_party/acados/acados_template/gnsf/detect_affine_terms_reduce_nonlinearity.py new file mode 100644 index 000000000..ebf1f373a --- /dev/null +++ b/third_party/acados/acados_template/gnsf/detect_affine_terms_reduce_nonlinearity.py @@ -0,0 +1,278 @@ +# +# Copyright (c) The acados authors. +# +# This file is part of acados. +# +# 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 HOLDER 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.; +# + +from casadi import * +from .check_reformulation import check_reformulation +from .determine_input_nonlinearity_function import determine_input_nonlinearity_function +from ..utils import casadi_length, print_casadi_expression + + +def detect_affine_terms_reduce_nonlinearity(gnsf, acados_ocp, print_info): + + ## Description + # this function takes a gnsf structure with trivial model matrices (A, B, + # E, c are zeros, and C is eye). + # It detects all affine linear terms and sets up an equivalent model in the + # GNSF structure, where all affine linear terms are modeled through the + # matrices A, B, E, c and the linear output system (LOS) is empty. + # NOTE: model is just taken as an argument to check equivalence of the + # models within the function. + + model = acados_ocp.model + if print_info: + print(" ") + print("====================================================================") + print(" ") + print("============ Detect affine-linear dependencies ==================") + print(" ") + print("====================================================================") + print(" ") + # symbolics + x = gnsf["x"] + xdot = gnsf["xdot"] + u = gnsf["u"] + z = gnsf["z"] + + # dimensions + nx = gnsf["nx"] + nu = gnsf["nu"] + nz = gnsf["nz"] + + ny_old = gnsf["ny"] + nuhat_old = gnsf["nuhat"] + + ## Represent all affine dependencies through the model matrices A, B, E, c + ## determine A + n_nodes_current = n_nodes(gnsf["phi_expr"]) + + for ii in range(casadi_length(gnsf["phi_expr"])): + fii = gnsf["phi_expr"][ii] + for ix in range(nx): + var = x[ix] + varname = var.name + # symbolic jacobian of fii w.r.t. xi + jac_fii_xi = jacobian(fii, var) + if jac_fii_xi.is_constant(): + # jacobian value + jac_fii_xi_fun = Function("jac_fii_xi_fun", [x[1]], [jac_fii_xi]) + # x[1] as input just to have a scalar input and call the function as follows: + gnsf["A"][ii, ix] = jac_fii_xi_fun(0).full() + else: + gnsf["A"][ii, ix] = 0 + if print_info: + print( + "phi(", + str(ii), + ") is nonlinear in x(", + str(ix), + ") = ", + varname, + ) + print(fii) + print("-----------------------------------------------------") + f_next = gnsf["phi_expr"] - gnsf["A"] @ x + f_next = simplify(f_next) + n_nodes_next = n_nodes(f_next) + + if print_info: + print("\n") + print(f"determined matrix A:") + print(gnsf["A"]) + print(f"reduced nonlinearity from {n_nodes_current} to {n_nodes_next} nodes") + # assert(n_nodes_current >= n_nodes_next,'n_nodes_current >= n_nodes_next FAILED') + gnsf["phi_expr"] = f_next + + check_reformulation(model, gnsf, print_info) + + ## determine B + n_nodes_current = n_nodes(gnsf["phi_expr"]) + + for ii in range(casadi_length(gnsf["phi_expr"])): + fii = gnsf["phi_expr"][ii] + for iu in range(nu): + var = u[iu] + varname = var.name + # symbolic jacobian of fii w.r.t. ui + jac_fii_ui = jacobian(fii, var) + if jac_fii_ui.is_constant(): # i.e. hessian is structural zero: + # jacobian value + jac_fii_ui_fun = Function("jac_fii_ui_fun", [x[1]], [jac_fii_ui]) + gnsf["B"][ii, iu] = jac_fii_ui_fun(0).full() + else: + gnsf["B"][ii, iu] = 0 + if print_info: + print(f"phi({ii}) is nonlinear in u(", str(iu), ") = ", varname) + print(fii) + print("-----------------------------------------------------") + f_next = gnsf["phi_expr"] - gnsf["B"] @ u + f_next = simplify(f_next) + n_nodes_next = n_nodes(f_next) + + if print_info: + print("\n") + print(f"determined matrix B:") + print(gnsf["B"]) + print(f"reduced nonlinearity from {n_nodes_current} to {n_nodes_next} nodes") + + gnsf["phi_expr"] = f_next + + check_reformulation(model, gnsf, print_info) + + ## determine E + n_nodes_current = n_nodes(gnsf["phi_expr"]) + k = vertcat(xdot, z) + + for ii in range(casadi_length(gnsf["phi_expr"])): + fii = gnsf["phi_expr"][ii] + for ik in range(casadi_length(k)): + # symbolic jacobian of fii w.r.t. ui + var = k[ik] + varname = var.name + jac_fii_ki = jacobian(fii, var) + if jac_fii_ki.is_constant(): + # jacobian value + jac_fii_ki_fun = Function("jac_fii_ki_fun", [x[1]], [jac_fii_ki]) + gnsf["E"][ii, ik] = -jac_fii_ki_fun(0).full() + else: + gnsf["E"][ii, ik] = 0 + if print_info: + print(f"phi( {ii}) is nonlinear in xdot_z({ik}) = ", varname) + print(fii) + print("-----------------------------------------------------") + f_next = gnsf["phi_expr"] + gnsf["E"] @ k + f_next = simplify(f_next) + n_nodes_next = n_nodes(f_next) + + if print_info: + print("\n") + print(f"determined matrix E:") + print(gnsf["E"]) + print(f"reduced nonlinearity from {n_nodes_current} to {n_nodes_next} nodes") + + gnsf["phi_expr"] = f_next + check_reformulation(model, gnsf, print_info) + + ## determine constant term c + + n_nodes_current = n_nodes(gnsf["phi_expr"]) + for ii in range(casadi_length(gnsf["phi_expr"])): + fii = gnsf["phi_expr"][ii] + if fii.is_constant(): + # function value goes into c + fii_fun = Function("fii_fun", [x[1]], [fii]) + gnsf["c"][ii] = fii_fun(0).full() + else: + gnsf["c"][ii] = 0 + if print_info: + print(f"phi(", str(ii), ") is NOT constant") + print(fii) + print("-----------------------------------------------------") + gnsf["phi_expr"] = gnsf["phi_expr"] - gnsf["c"] + gnsf["phi_expr"] = simplify(gnsf["phi_expr"]) + n_nodes_next = n_nodes(gnsf["phi_expr"]) + + if print_info: + print("\n") + print(f"determined vector c:") + print(gnsf["c"]) + print(f"reduced nonlinearity from {n_nodes_current} to {n_nodes_next} nodes") + + check_reformulation(model, gnsf, print_info) + + ## determine nonlinearity & corresponding matrix C + ## Reduce dimension of phi + n_nodes_current = n_nodes(gnsf["phi_expr"]) + ind_non_zero = [] + for ii in range(casadi_length(gnsf["phi_expr"])): + fii = gnsf["phi_expr"][ii] + fii = simplify(fii) + if not fii.is_zero(): + ind_non_zero = list(set.union(set(ind_non_zero), set([ii]))) + gnsf["phi_expr"] = gnsf["phi_expr"][ind_non_zero] + + # C + gnsf["C"] = np.zeros((nx + nz, len(ind_non_zero))) + for ii in range(len(ind_non_zero)): + gnsf["C"][ind_non_zero[ii], ii] = 1 + gnsf = determine_input_nonlinearity_function(gnsf) + n_nodes_next = n_nodes(gnsf["phi_expr"]) + + if print_info: + print(" ") + print("determined matrix C:") + print(gnsf["C"]) + print( + "---------------------------------------------------------------------------------" + ) + print( + "------------- Success: Affine linear terms detected -----------------------------" + ) + print( + "---------------------------------------------------------------------------------" + ) + print( + f'reduced nonlinearity dimension n_out from {nx+nz} to {gnsf["n_out"]}' + ) + print(f"reduced nonlinearity from {n_nodes_current} to {n_nodes_next} nodes") + print(" ") + print("phi now reads as:") + print_casadi_expression(gnsf["phi_expr"]) + + ## determine input of nonlinearity function + check_reformulation(model, gnsf, print_info) + + gnsf["ny"] = casadi_length(gnsf["y"]) + gnsf["nuhat"] = casadi_length(gnsf["uhat"]) + + if print_info: + print( + "-----------------------------------------------------------------------------------" + ) + print(" ") + print( + f"reduced input ny of phi from ", + str(ny_old), + " to ", + str(gnsf["ny"]), + ) + print( + f"reduced input nuhat of phi from ", + str(nuhat_old), + " to ", + str(gnsf["nuhat"]), + ) + print( + "-----------------------------------------------------------------------------------" + ) + + # if print_info: + # print(f"gnsf: {gnsf}") + + return gnsf diff --git a/third_party/acados/acados_template/gnsf/detect_gnsf_structure.py b/third_party/acados/acados_template/gnsf/detect_gnsf_structure.py new file mode 100644 index 000000000..24ffe643b --- /dev/null +++ b/third_party/acados/acados_template/gnsf/detect_gnsf_structure.py @@ -0,0 +1,240 @@ +# +# Copyright (c) The acados authors. +# +# This file is part of acados. +# +# 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 HOLDER 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: Jonathan Frey: jonathanpaulfrey(at)gmail.com + +from casadi import Function, jacobian, SX, vertcat, horzcat + +from .determine_trivial_gnsf_transcription import determine_trivial_gnsf_transcription +from .detect_affine_terms_reduce_nonlinearity import ( + detect_affine_terms_reduce_nonlinearity, +) +from .reformulate_with_LOS import reformulate_with_LOS +from .reformulate_with_invertible_E_mat import reformulate_with_invertible_E_mat +from .structure_detection_print_summary import structure_detection_print_summary +from .check_reformulation import check_reformulation + + +def detect_gnsf_structure(acados_ocp, transcribe_opts=None): + + ## Description + # This function takes a CasADi implicit ODE or index-1 DAE model "model" + # consisting of a CasADi expression f_impl in the symbolic CasADi + # variables x, xdot, u, z, (and possibly parameters p), which are also part + # of the model, as well as a model name. + # It will create a struct "gnsf" containing all information needed to use + # it with the gnsf integrator in acados. + # Additionally it will create the struct "reordered_model" which contains + # the permuted state vector and permuted f_impl, in which additionally some + # functions, which were made part of the linear output system of the gnsf, + # have changed signs. + + # Options: transcribe_opts is a Matlab struct consisting of booleans: + # print_info: if extensive information on how the model is processed + # is printed to the console. + # generate_gnsf_model: if the neccessary C functions to simulate the gnsf + # model with the acados implementation of the GNSF exploiting + # integrator should be generated. + # generate_gnsf_model: if the neccessary C functions to simulate the + # reordered model with the acados implementation of the IRK + # integrator should be generated. + # check_E_invertibility: if the transcription method should check if the + # assumption that the main blocks of the matrix gnsf.E are invertible + # holds. If not, the method will try to reformulate the gnsf model + # with a different model, such that the assumption holds. + + # acados_root_dir = getenv('ACADOS_INSTALL_DIR') + + ## load transcribe_opts + if transcribe_opts is None: + print("WARNING: GNSF structure detection called without transcribe_opts") + print(" using default settings") + print("") + transcribe_opts = dict() + + if "print_info" in transcribe_opts: + print_info = transcribe_opts["print_info"] + else: + print_info = 1 + print("print_info option was not set - default is true") + + if "detect_LOS" in transcribe_opts: + detect_LOS = transcribe_opts["detect_LOS"] + else: + detect_LOS = 1 + if print_info: + print("detect_LOS option was not set - default is true") + + if "check_E_invertibility" in transcribe_opts: + check_E_invertibility = transcribe_opts["check_E_invertibility"] + else: + check_E_invertibility = 1 + if print_info: + print("check_E_invertibility option was not set - default is true") + + ## Reformulate implicit index-1 DAE into GNSF form + # (Generalized nonlinear static feedback) + gnsf = determine_trivial_gnsf_transcription(acados_ocp, print_info) + gnsf = detect_affine_terms_reduce_nonlinearity(gnsf, acados_ocp, print_info) + + if detect_LOS: + gnsf = reformulate_with_LOS(acados_ocp, gnsf, print_info) + + if check_E_invertibility: + gnsf = reformulate_with_invertible_E_mat(gnsf, acados_ocp, print_info) + + # detect purely linear model + if gnsf["nx1"] == 0 and gnsf["nz1"] == 0 and gnsf["nontrivial_f_LO"] == 0: + gnsf["purely_linear"] = 1 + else: + gnsf["purely_linear"] = 0 + + structure_detection_print_summary(gnsf, acados_ocp) + check_reformulation(acados_ocp.model, gnsf, print_info) + + ## copy relevant fields from gnsf to model + acados_ocp.model.get_matrices_fun = Function() + dummy = acados_ocp.model.x[0] + model_name = acados_ocp.model.name + + get_matrices_fun = Function( + f"{model_name}_gnsf_get_matrices_fun", + [dummy], + [ + gnsf["A"], + gnsf["B"], + gnsf["C"], + gnsf["E"], + gnsf["L_x"], + gnsf["L_xdot"], + gnsf["L_z"], + gnsf["L_u"], + gnsf["A_LO"], + gnsf["c"], + gnsf["E_LO"], + gnsf["B_LO"], + gnsf["nontrivial_f_LO"], + gnsf["purely_linear"], + gnsf["ipiv_x"] + 1, + gnsf["ipiv_z"] + 1, + gnsf["c_LO"], + ], + ) + + phi = gnsf["phi_expr"] + y = gnsf["y"] + uhat = gnsf["uhat"] + p = gnsf["p"] + + jac_phi_y = jacobian(phi, y) + jac_phi_uhat = jacobian(phi, uhat) + + phi_fun = Function(f"{model_name}_gnsf_phi_fun", [y, uhat, p], [phi]) + acados_ocp.model.phi_fun = phi_fun + acados_ocp.model.phi_fun_jac_y = Function( + f"{model_name}_gnsf_phi_fun_jac_y", [y, uhat, p], [phi, jac_phi_y] + ) + acados_ocp.model.phi_jac_y_uhat = Function( + f"{model_name}_gnsf_phi_jac_y_uhat", [y, uhat, p], [jac_phi_y, jac_phi_uhat] + ) + + x1 = acados_ocp.model.x[gnsf["idx_perm_x"][: gnsf["nx1"]]] + x1dot = acados_ocp.model.xdot[gnsf["idx_perm_x"][: gnsf["nx1"]]] + if gnsf["nz1"] > 0: + z1 = acados_ocp.model.z[gnsf["idx_perm_z"][: gnsf["nz1"]]] + else: + z1 = SX.sym("z1", 0, 0) + f_lo = gnsf["f_lo_expr"] + u = acados_ocp.model.u + acados_ocp.model.f_lo_fun_jac_x1k1uz = Function( + f"{model_name}_gnsf_f_lo_fun_jac_x1k1uz", + [x1, x1dot, z1, u, p], + [ + f_lo, + horzcat( + jacobian(f_lo, x1), + jacobian(f_lo, x1dot), + jacobian(f_lo, u), + jacobian(f_lo, z1), + ), + ], + ) + + acados_ocp.model.get_matrices_fun = get_matrices_fun + + size_gnsf_A = gnsf["A"].shape + acados_ocp.dims.gnsf_nx1 = size_gnsf_A[1] + acados_ocp.dims.gnsf_nz1 = size_gnsf_A[0] - size_gnsf_A[1] + acados_ocp.dims.gnsf_nuhat = max(phi_fun.size_in(1)) + acados_ocp.dims.gnsf_ny = max(phi_fun.size_in(0)) + acados_ocp.dims.gnsf_nout = max(phi_fun.size_out(0)) + + # # dim + # model['dim_gnsf_nx1'] = gnsf['nx1'] + # model['dim_gnsf_nx2'] = gnsf['nx2'] + # model['dim_gnsf_nz1'] = gnsf['nz1'] + # model['dim_gnsf_nz2'] = gnsf['nz2'] + # model['dim_gnsf_nuhat'] = gnsf['nuhat'] + # model['dim_gnsf_ny'] = gnsf['ny'] + # model['dim_gnsf_nout'] = gnsf['n_out'] + + # # sym + # model['sym_gnsf_y'] = gnsf['y'] + # model['sym_gnsf_uhat'] = gnsf['uhat'] + + # # data + # model['dyn_gnsf_A'] = gnsf['A'] + # model['dyn_gnsf_A_LO'] = gnsf['A_LO'] + # model['dyn_gnsf_B'] = gnsf['B'] + # model['dyn_gnsf_B_LO'] = gnsf['B_LO'] + # model['dyn_gnsf_E'] = gnsf['E'] + # model['dyn_gnsf_E_LO'] = gnsf['E_LO'] + # model['dyn_gnsf_C'] = gnsf['C'] + # model['dyn_gnsf_c'] = gnsf['c'] + # model['dyn_gnsf_c_LO'] = gnsf['c_LO'] + # model['dyn_gnsf_L_x'] = gnsf['L_x'] + # model['dyn_gnsf_L_xdot'] = gnsf['L_xdot'] + # model['dyn_gnsf_L_z'] = gnsf['L_z'] + # model['dyn_gnsf_L_u'] = gnsf['L_u'] + # model['dyn_gnsf_idx_perm_x'] = gnsf['idx_perm_x'] + # model['dyn_gnsf_ipiv_x'] = gnsf['ipiv_x'] + # model['dyn_gnsf_idx_perm_z'] = gnsf['idx_perm_z'] + # model['dyn_gnsf_ipiv_z'] = gnsf['ipiv_z'] + # model['dyn_gnsf_idx_perm_f'] = gnsf['idx_perm_f'] + # model['dyn_gnsf_ipiv_f'] = gnsf['ipiv_f'] + + # # flags + # model['dyn_gnsf_nontrivial_f_LO'] = gnsf['nontrivial_f_LO'] + # model['dyn_gnsf_purely_linear'] = gnsf['purely_linear'] + + # # casadi expr + # model['dyn_gnsf_expr_phi'] = gnsf['phi_expr'] + # model['dyn_gnsf_expr_f_lo'] = gnsf['f_lo_expr'] + + return acados_ocp diff --git a/third_party/acados/acados_template/gnsf/determine_input_nonlinearity_function.py b/third_party/acados/acados_template/gnsf/determine_input_nonlinearity_function.py new file mode 100644 index 000000000..94aa001c7 --- /dev/null +++ b/third_party/acados/acados_template/gnsf/determine_input_nonlinearity_function.py @@ -0,0 +1,110 @@ +# +# Copyright (c) The acados authors. +# +# This file is part of acados. +# +# 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 HOLDER 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: Jonathan Frey: jonathanpaulfrey(at)gmail.com + +from casadi import * +from ..utils import casadi_length, is_empty + + +def determine_input_nonlinearity_function(gnsf): + + ## Description + # this function takes a structure gnsf and updates the matrices L_x, + # L_xdot, L_z, L_u and CasADi vectors y, uhat of this structure as follows: + + # given a CasADi expression phi_expr, which may depend on the variables + # (x1, x1dot, z, u), this function determines a vector y (uhat) consisting + # of all components of (x1, x1dot, z) (respectively u) that enter phi_expr. + # Additionally matrices L_x, L_xdot, L_z, L_u are determined such that + # y = L_x * x + L_xdot * xdot + L_z * z + # uhat = L_u * u + # Furthermore the dimensions ny, nuhat, n_out are updated + + ## y + y = SX.sym('y', 0, 0) + # components of x1 + for ii in range(gnsf["nx1"]): + if which_depends(gnsf["phi_expr"], gnsf["x"][ii])[0]: + y = vertcat(y, gnsf["x"][ii]) + # else: + # x[ii] is not part of y + # components of x1dot + for ii in range(gnsf["nx1"]): + if which_depends(gnsf["phi_expr"], gnsf["xdot"][ii])[0]: + print(gnsf["phi_expr"], "depends on", gnsf["xdot"][ii]) + y = vertcat(y, gnsf["xdot"][ii]) + # else: + # xdot[ii] is not part of y + # components of z + for ii in range(gnsf["nz1"]): + if which_depends(gnsf["phi_expr"], gnsf["z"][ii])[0]: + y = vertcat(y, gnsf["z"][ii]) + # else: + # z[ii] is not part of y + ## uhat + uhat = SX.sym('uhat', 0, 0) + # components of u + for ii in range(gnsf["nu"]): + if which_depends(gnsf["phi_expr"], gnsf["u"][ii])[0]: + uhat = vertcat(uhat, gnsf["u"][ii]) + # else: + # u[ii] is not part of uhat + ## generate gnsf['phi_expr_fun'] + # linear input matrices + if is_empty(y): + gnsf["L_x"] = [] + gnsf["L_xdot"] = [] + gnsf["L_u"] = [] + gnsf["L_z"] = [] + else: + dummy = SX.sym("dummy_input", 0) + L_x_fun = Function( + "L_x_fun", [dummy], [jacobian(y, gnsf["x"][range(gnsf["nx1"])])] + ) + L_xdot_fun = Function( + "L_xdot_fun", [dummy], [jacobian(y, gnsf["xdot"][range(gnsf["nx1"])])] + ) + L_z_fun = Function( + "L_z_fun", [dummy], [jacobian(y, gnsf["z"][range(gnsf["nz1"])])] + ) + L_u_fun = Function("L_u_fun", [dummy], [jacobian(uhat, gnsf["u"])]) + + gnsf["L_x"] = L_x_fun(0).full() + gnsf["L_xdot"] = L_xdot_fun(0).full() + gnsf["L_u"] = L_u_fun(0).full() + gnsf["L_z"] = L_z_fun(0).full() + gnsf["y"] = y + gnsf["uhat"] = uhat + + gnsf["ny"] = casadi_length(y) + gnsf["nuhat"] = casadi_length(uhat) + gnsf["n_out"] = casadi_length(gnsf["phi_expr"]) + + return gnsf diff --git a/third_party/acados/acados_template/gnsf/determine_trivial_gnsf_transcription.py b/third_party/acados/acados_template/gnsf/determine_trivial_gnsf_transcription.py new file mode 100644 index 000000000..23c244053 --- /dev/null +++ b/third_party/acados/acados_template/gnsf/determine_trivial_gnsf_transcription.py @@ -0,0 +1,155 @@ +# +# Copyright (c) The acados authors. +# +# This file is part of acados. +# +# 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 HOLDER 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.; +# + +from casadi import * +import numpy as np +from ..utils import casadi_length, idx_perm_to_ipiv +from .determine_input_nonlinearity_function import determine_input_nonlinearity_function +from .check_reformulation import check_reformulation + + +def determine_trivial_gnsf_transcription(acados_ocp, print_info): + ## Description + # this function takes a model of an implicit ODE/ index-1 DAE and sets up + # an equivalent model in the GNSF structure, with empty linear output + # system and trivial model matrices, i.e. A, B, E, c are zeros, and C is + # eye. - no structure is exploited + + model = acados_ocp.model + # initial print + print("*****************************************************************") + print(" ") + print(f"****** Restructuring {model.name} model ***********") + print(" ") + print("*****************************************************************") + + # load model + f_impl_expr = model.f_impl_expr + + model_name_prefix = model.name + + # x + x = model.x + nx = acados_ocp.dims.nx + # check type + if isinstance(x[0], SX): + isSX = True + else: + print("GNSF detection only works for SX CasADi type!!!") + import pdb + + pdb.set_trace() + # xdot + xdot = model.xdot + # u + nu = acados_ocp.dims.nu + if nu == 0: + u = SX.sym("u", 0, 0) + else: + u = model.u + + nz = acados_ocp.dims.nz + if nz == 0: + z = SX.sym("z", 0, 0) + else: + z = model.z + + p = model.p + nparam = acados_ocp.dims.np + + # avoid SX of size 0x1 + if casadi_length(u) == 0: + u = SX.sym("u", 0, 0) + nu = 0 + ## initialize gnsf struct + # dimensions + gnsf = {"nx": nx, "nu": nu, "nz": nz, "np": nparam} + gnsf["nx1"] = nx + gnsf["nx2"] = 0 + gnsf["nz1"] = nz + gnsf["nz2"] = 0 + gnsf["nuhat"] = nu + gnsf["ny"] = 2 * nx + nz + + gnsf["phi_expr"] = f_impl_expr + gnsf["A"] = np.zeros((nx + nz, nx)) + gnsf["B"] = np.zeros((nx + nz, nu)) + gnsf["E"] = np.zeros((nx + nz, nx + nz)) + gnsf["c"] = np.zeros((nx + nz, 1)) + gnsf["C"] = np.eye(nx + nz) + gnsf["name"] = model_name_prefix + + gnsf["x"] = x + gnsf["xdot"] = xdot + gnsf["z"] = z + gnsf["u"] = u + gnsf["p"] = p + + gnsf = determine_input_nonlinearity_function(gnsf) + + gnsf["A_LO"] = [] + gnsf["E_LO"] = [] + gnsf["B_LO"] = [] + gnsf["c_LO"] = [] + gnsf["f_lo_expr"] = [] + + # permutation + gnsf["idx_perm_x"] = range(nx) # matlab-style) + gnsf["ipiv_x"] = idx_perm_to_ipiv(gnsf["idx_perm_x"]) # blasfeo-style + gnsf["idx_perm_z"] = range(nz) + gnsf["ipiv_z"] = idx_perm_to_ipiv(gnsf["idx_perm_z"]) + gnsf["idx_perm_f"] = range((nx + nz)) + gnsf["ipiv_f"] = idx_perm_to_ipiv(gnsf["idx_perm_f"]) + + gnsf["nontrivial_f_LO"] = 0 + + check_reformulation(model, gnsf, print_info) + if print_info: + print(f"Success: Set up equivalent GNSF model with trivial matrices") + print(" ") + if print_info: + print( + "-----------------------------------------------------------------------------------" + ) + print(" ") + print( + "reduced input ny of phi from ", + str(2 * nx + nz), + " to ", + str(gnsf["ny"]), + ) + print( + "reduced input nuhat of phi from ", str(nu), " to ", str(gnsf["nuhat"]) + ) + print(" ") + print( + "-----------------------------------------------------------------------------------" + ) + return gnsf diff --git a/third_party/acados/acados_template/gnsf/matlab to python.md b/third_party/acados/acados_template/gnsf/matlab to python.md new file mode 100644 index 000000000..53a0ed971 --- /dev/null +++ b/third_party/acados/acados_template/gnsf/matlab to python.md @@ -0,0 +1,43 @@ +# matlab to python + +% -> # + +; -> + +from casadi import * +-> +from casadi import * + + +print\('(.*)'\) +print('$1') + +print\(\['(.*)'\]\) +print(f'$1') + +keyboard +import pdb; pdb.set_trace() + + +range((([^))]*)) +range($1) + +\s*end +-> +nothing + + +if (.*) +if $1: + +else +else: + +num2str +str + +for ([a-z_]*) = +for $1 in + +length\( +len( \ No newline at end of file diff --git a/third_party/acados/acados_template/gnsf/reformulate_with_LOS.py b/third_party/acados/acados_template/gnsf/reformulate_with_LOS.py new file mode 100644 index 000000000..297a56556 --- /dev/null +++ b/third_party/acados/acados_template/gnsf/reformulate_with_LOS.py @@ -0,0 +1,394 @@ +# +# Copyright (c) The acados authors. +# +# This file is part of acados. +# +# 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 HOLDER 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: Jonathan Frey: jonathanpaulfrey(at)gmail.com + +from .determine_input_nonlinearity_function import determine_input_nonlinearity_function +from .check_reformulation import check_reformulation +from casadi import * +from ..utils import casadi_length, idx_perm_to_ipiv, is_empty + + +def reformulate_with_LOS(acados_ocp, gnsf, print_info): + + ## Description: + # This function takes an intitial transcription of the implicit ODE model + # "model" into "gnsf" and reformulates "gnsf" with a linear output system + # (LOS), containing as many states of the model as possible. + # Therefore it might be that the state vector and the implicit function + # vector have to be reordered. This reordered model is part of the output, + # namely reordered_model. + + ## import CasADi and load models + model = acados_ocp.model + + # symbolics + x = gnsf["x"] + xdot = gnsf["xdot"] + u = gnsf["u"] + z = gnsf["z"] + + # dimensions + nx = gnsf["nx"] + nz = gnsf["nz"] + + # get model matrices + A = gnsf["A"] + B = gnsf["B"] + C = gnsf["C"] + E = gnsf["E"] + c = gnsf["c"] + + A_LO = gnsf["A_LO"] + + y = gnsf["y"] + + phi_old = gnsf["phi_expr"] + + if print_info: + print(" ") + print("=================================================================") + print(" ") + print("================ Detect Linear Output System ===============") + print(" ") + print("=================================================================") + print(" ") + ## build initial I_x1 and I_x2_candidates + # I_xrange( all components of x for which either xii or xdot_ii enters y): + # I_LOS_candidates: the remaining components + + I_nsf_components = set() + I_LOS_candidates = set() + + if gnsf["ny"] > 0: + for ii in range(nx): + if which_depends(y, x[ii])[0] or which_depends(y, xdot[ii])[0]: + # i.e. xii or xiidot are part of y, and enter phi_expr + if print_info: + print(f"x_{ii} is part of x1") + I_nsf_components = set.union(I_nsf_components, set([ii])) + else: + # i.e. neither xii nor xiidot are part of y, i.e. enter phi_expr + I_LOS_candidates = set.union(I_LOS_candidates, set([ii])) + if print_info: + print(" ") + for ii in range(nz): + if which_depends(y, z[ii])[0]: + # i.e. xii or xiidot are part of y, and enter phi_expr + if print_info: + print(f"z_{ii} is part of x1") + I_nsf_components = set.union(I_nsf_components, set([ii + nx])) + else: + # i.e. neither xii nor xiidot are part of y, i.e. enter phi_expr + I_LOS_candidates = set.union(I_LOS_candidates, set([ii + nx])) + else: + I_LOS_candidates = set(range((nx + nz))) + if print_info: + print(" ") + print(f"I_LOS_candidates {I_LOS_candidates}") + new_nsf_components = I_nsf_components + I_nsf_eq = set([]) + unsorted_dyn = set(range(nx + nz)) + xdot_z = vertcat(xdot, z) + + ## determine components of Linear Output System + # determine maximal index set I_x2 + # such that the components x(I_x2) can be written as a LOS + Eq_map = [] + while True: + ## find equations corresponding to new_nsf_components + for ii in new_nsf_components: + current_var = xdot_z[ii] + var_name = current_var.name + + # print( unsorted_dyn) + # print("np.nonzero(E[:,ii])[0]",np.nonzero(E[:,ii])[0]) + I_eq = set.intersection(set(np.nonzero(E[:, ii])[0]), unsorted_dyn) + if len(I_eq) == 1: + i_eq = I_eq.pop() + if print_info: + print(f"component {i_eq} is associated with state {ii}") + elif len(I_eq) > 1: # x_ii_dot occurs in more than 1 eq linearly + # find the equation with least linear dependencies on + # I_LOS_cancidates + number_of_eq = 0 + candidate_dependencies = np.zeros(len(I_eq), 1) + I_x2_candidates = set.intersection(I_LOS_candidates, set(range(nx))) + for eq in I_eq: + depending_candidates = set.union( + np.nonzero(E[eq, I_LOS_candidates])[0], + np.nonzero(A[eq, I_x2_candidates])[0], + ) + candidate_dependencies[number_of_eq] = +len(depending_candidates) + number_of_eq += 1 + number_of_eq = np.argmin(candidate_dependencies) + i_eq = I_eq[number_of_eq] + else: ## x_ii_dot does not occur linearly in any of the unsorted dynamics + for j in unsorted_dyn: + phi_eq_j = gnsf["phi_expr"][np.nonzero(C[j, :])[0]] + if which_depends(phi_eq_j, xdot_z(ii))[0]: + I_eq = set.union(I_eq, j) + if is_empty(I_eq): + I_eq = unsorted_dyn + # find the equation with least linear dependencies on I_LOS_cancidates + number_of_eq = 0 + candidate_dependencies = np.zeros(len(I_eq), 1) + I_x2_candidates = set.intersection(I_LOS_candidates, set(range(nx))) + for eq in I_eq: + depending_candidates = set.union( + np.nonzero(E[eq, I_LOS_candidates])[0], + np.nonzero(A[eq, I_x2_candidates])[0], + ) + candidate_dependencies[number_of_eq] = +len(depending_candidates) + number_of_eq += 1 + number_of_eq = np.argmin(candidate_dependencies) + i_eq = I_eq[number_of_eq] + ## add 1 * [xdot,z](ii) to both sides of i_eq + if print_info: + print( + "adding 1 * ", + var_name, + " to both sides of equation ", + i_eq, + ".", + ) + gnsf["E"][i_eq, ii] = 1 + i_phi = np.nonzero(gnsf["C"][i_eq, :]) + if is_empty(i_phi): + i_phi = len(gnsf["phi_expr"]) + 1 + gnsf["C"][i_eq, i_phi] = 1 # add column to C with 1 entry + gnsf["phi_expr"] = vertcat(gnsf["phi_expr"], 0) + gnsf["phi_expr"][i_phi] = ( + gnsf["phi_expr"](i_phi) + + gnsf["E"][i_eq, ii] / gnsf["C"][i_eq, i_phi] * xdot_z[ii] + ) + if print_info: + print( + "detected equation ", + i_eq, + " to correspond to variable ", + var_name, + ) + I_nsf_eq = set.union(I_nsf_eq, {i_eq}) + # remove i_eq from unsorted_dyn + unsorted_dyn.remove(i_eq) + Eq_map.append([ii, i_eq]) + + ## add components to I_x1 + for eq in I_nsf_eq: + I_linear_dependence = set.union( + set(np.nonzero(A[eq, :])[0]), set(np.nonzero(E[eq, :])[0]) + ) + I_nsf_components = set.union(I_linear_dependence, I_nsf_components) + # I_nsf_components = I_nsf_components[:] + + new_nsf_components = set.intersection(I_LOS_candidates, I_nsf_components) + if is_empty(new_nsf_components): + if print_info: + print("new_nsf_components is empty") + break + # remove new_nsf_components from candidates + I_LOS_candidates = set.difference(I_LOS_candidates, new_nsf_components) + if not is_empty(Eq_map): + # [~, new_eq_order] = sort(Eq_map(1,:)) + # I_nsf_eq = Eq_map(2, new_eq_order ) + for count, m in enumerate(Eq_map): + m.append(count) + sorted(Eq_map, key=lambda x: x[1]) + new_eq_order = [m[2] for m in Eq_map] + Eq_map = [Eq_map[i] for i in new_eq_order] + I_nsf_eq = [m[1] for m in Eq_map] + + else: + I_nsf_eq = [] + + I_LOS_components = I_LOS_candidates + I_LOS_eq = sorted(set.difference(set(range(nx + nz)), I_nsf_eq)) + I_nsf_eq = sorted(I_nsf_eq) + + I_x1 = set.intersection(I_nsf_components, set(range(nx))) + I_z1 = set.intersection(I_nsf_components, set(range(nx, nx + nz))) + I_z1 = set([i - nx for i in I_z1]) + + I_x2 = set.intersection(I_LOS_components, set(range(nx))) + I_z2 = set.intersection(I_LOS_components, set(range(nx, nx + nz))) + I_z2 = set([i - nx for i in I_z2]) + + if print_info: + print(f"I_x1 {I_x1}, I_x2 {I_x2}") + + ## permute x, xdot + if is_empty(I_x1): + x1 = [] + x1dot = [] + else: + x1 = x[list(I_x1)] + x1dot = xdot[list(I_x1)] + if is_empty(I_x2): + x2 = [] + x2dot = [] + else: + x2 = x[list(I_x2)] + x2dot = xdot[list(I_x2)] + if is_empty(I_z1): + z1 = [] + else: + z1 = z(I_z1) + if is_empty(I_z2): + z2 = [] + else: + z2 = z[list(I_z2)] + + I_x1 = sorted(I_x1) + I_x2 = sorted(I_x2) + I_z1 = sorted(I_z1) + I_z2 = sorted(I_z2) + gnsf["xdot"] = vertcat(x1dot, x2dot) + gnsf["x"] = vertcat(x1, x2) + gnsf["z"] = vertcat(z1, z2) + gnsf["nx1"] = len(I_x1) + gnsf["nx2"] = len(I_x2) + gnsf["nz1"] = len(I_z1) + gnsf["nz2"] = len(I_z2) + + # store permutations + gnsf["idx_perm_x"] = I_x1 + I_x2 + gnsf["ipiv_x"] = idx_perm_to_ipiv(gnsf["idx_perm_x"]) + gnsf["idx_perm_z"] = I_z1 + I_z2 + gnsf["ipiv_z"] = idx_perm_to_ipiv(gnsf["idx_perm_z"]) + gnsf["idx_perm_f"] = I_nsf_eq + I_LOS_eq + gnsf["ipiv_f"] = idx_perm_to_ipiv(gnsf["idx_perm_f"]) + + f_LO = SX.sym("f_LO", 0, 0) + + ## rewrite I_LOS_eq as LOS + if gnsf["n_out"] == 0: + C_phi = np.zeros(gnsf["nx"] + gnsf["nz"], 1) + else: + C_phi = C @ phi_old + if gnsf["nx1"] == 0: + Ax1 = np.zeros(gnsf["nx"] + gnsf["nz"], 1) + else: + Ax1 = A[:, sorted(I_x1)] @ x1 + if gnsf["nx1"] + gnsf["nz1"] == 0: + lhs_nsf = np.zeros(gnsf["nx"] + gnsf["nz"], 1) + else: + lhs_nsf = E[:, sorted(I_nsf_components)] @ vertcat(x1, z1) + n_LO = len(I_LOS_eq) + B_LO = np.zeros((n_LO, gnsf["nu"])) + A_LO = np.zeros((gnsf["nx2"] + gnsf["nz2"], gnsf["nx2"])) + E_LO = np.zeros((n_LO, n_LO)) + c_LO = np.zeros((n_LO, 1)) + + I_LOS_eq = list(I_LOS_eq) + for eq in I_LOS_eq: + i_LO = I_LOS_eq.index(eq) + f_LO = vertcat(f_LO, Ax1[eq] + C_phi[eq] - lhs_nsf[eq]) + print(f"eq {eq} I_LOS_components {I_LOS_components}, i_LO {i_LO}, f_LO {f_LO}") + E_LO[i_LO, :] = E[eq, sorted(I_LOS_components)] + A_LO[i_LO, :] = A[eq, I_x2] + c_LO[i_LO, :] = c[eq] + B_LO[i_LO, :] = B[eq, :] + if casadi_length(f_LO) == 0: + f_LO = SX.zeros((gnsf["nx2"] + gnsf["nz2"], 1)) + f_LO = simplify(f_LO) + gnsf["A_LO"] = A_LO + gnsf["E_LO"] = E_LO + gnsf["B_LO"] = B_LO + gnsf["c_LO"] = c_LO + gnsf["f_lo_expr"] = f_LO + + ## remove I_LOS_eq from NSF type system + gnsf["A"] = gnsf["A"][np.ix_(sorted(I_nsf_eq), sorted(I_x1))] + gnsf["B"] = gnsf["B"][sorted(I_nsf_eq), :] + gnsf["C"] = gnsf["C"][sorted(I_nsf_eq), :] + gnsf["E"] = gnsf["E"][np.ix_(sorted(I_nsf_eq), sorted(I_nsf_components))] + gnsf["c"] = gnsf["c"][sorted(I_nsf_eq), :] + + ## reduce phi, C + I_nonzero = [] + for ii in range(gnsf["C"].shape[1]): # n_colums of C: + print(f"ii {ii}") + if not all(gnsf["C"][:, ii] == 0): # if column ~= 0 + I_nonzero.append(ii) + gnsf["C"] = gnsf["C"][:, I_nonzero] + gnsf["phi_expr"] = gnsf["phi_expr"][I_nonzero] + + gnsf = determine_input_nonlinearity_function(gnsf) + + check_reformulation(model, gnsf, print_info) + + gnsf["nontrivial_f_LO"] = 0 + if not is_empty(gnsf["f_lo_expr"]): + for ii in range(casadi_length(gnsf["f_lo_expr"])): + fii = gnsf["f_lo_expr"][ii] + if not fii.is_zero(): + gnsf["nontrivial_f_LO"] = 1 + if not gnsf["nontrivial_f_LO"] and print_info: + print("f_LO is fully trivial (== 0)") + check_reformulation(model, gnsf, print_info) + + if print_info: + print("") + print( + "---------------------------------------------------------------------------------" + ) + print( + "------------- Success: Linear Output System (LOS) detected ----------------------" + ) + print( + "---------------------------------------------------------------------------------" + ) + print("") + print( + "==>> moved ", + gnsf["nx2"], + "differential states and ", + gnsf["nz2"], + " algebraic variables to the Linear Output System", + ) + print( + "==>> recuced output dimension of phi from ", + casadi_length(phi_old), + " to ", + casadi_length(gnsf["phi_expr"]), + ) + print(" ") + print("Matrices defining the LOS read as") + print(" ") + print("E_LO =") + print(gnsf["E_LO"]) + print("A_LO =") + print(gnsf["A_LO"]) + print("B_LO =") + print(gnsf["B_LO"]) + print("c_LO =") + print(gnsf["c_LO"]) + + return gnsf diff --git a/third_party/acados/acados_template/gnsf/reformulate_with_invertible_E_mat.py b/third_party/acados/acados_template/gnsf/reformulate_with_invertible_E_mat.py new file mode 100644 index 000000000..21ab8ebfd --- /dev/null +++ b/third_party/acados/acados_template/gnsf/reformulate_with_invertible_E_mat.py @@ -0,0 +1,167 @@ +# +# Copyright (c) The acados authors. +# +# This file is part of acados. +# +# 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 HOLDER 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: Jonathan Frey: jonathanpaulfrey(at)gmail.com + +from casadi import * +from .determine_input_nonlinearity_function import determine_input_nonlinearity_function +from .check_reformulation import check_reformulation + + +def reformulate_with_invertible_E_mat(gnsf, model, print_info): + ## Description + # this function checks that the necessary condition to apply the gnsf + # structure exploiting integrator to a model, namely that the matrices E11, + # E22 are invertible holds. + # if this is not the case, it will make these matrices invertible and add: + # corresponding terms, to the term C * phi, such that the obtained model is + # still equivalent + + # check invertibility of E11, E22 and reformulate if needed: + ind_11 = range(gnsf["nx1"]) + ind_22 = range(gnsf["nx1"], gnsf["nx1"] + gnsf["nz1"]) + + if print_info: + print(" ") + print("----------------------------------------------------") + print("checking rank of E11 and E22") + print("----------------------------------------------------") + ## check if E11, E22 are invertible: + z_check = False + if gnsf["nz1"] > 0: + z_check = ( + np.linalg.matrix_rank(gnsf["E"][np.ix_(ind_22, ind_22)]) != gnsf["nz1"] + ) + + if ( + np.linalg.matrix_rank(gnsf["E"][np.ix_(ind_11, ind_11)]) != gnsf["nx1"] + or z_check + ): + # print warning (always) + print(f"the rank of E11 or E22 is not full after the reformulation") + print("") + print( + f"the script will try to reformulate the model with an invertible matrix instead" + ) + print( + f"NOTE: this feature is based on a heuristic, it should be used with care!!!" + ) + + ## load models + xdot = gnsf["xdot"] + z = gnsf["z"] + + # # GNSF + # get dimensions + nx1 = gnsf["nx1"] + x1dot = xdot[range(nx1)] + + k = vertcat(x1dot, z) + for i in [1, 2]: + if i == 1: + ind = range(gnsf["nx1"]) + else: + ind = range(gnsf["nx1"], gnsf["nx1"] + gnsf["nz1"]) + mat = gnsf["E"][np.ix_(ind, ind)] + import pdb + + pdb.set_trace() + while np.linalg.matrix_rank(mat) < len(ind): + # import pdb; pdb.set_trace() + if print_info: + print(" ") + print(f"the rank of E", str(i), str(i), " is not full") + print( + f"the algorithm will try to reformulate the model with an invertible matrix instead" + ) + print( + f"NOTE: this feature is not super stable and might need more testing!!!!!!" + ) + for sub_max in ind: + sub_ind = range(min(ind), sub_max) + # regard the submatrix mat(sub_ind, sub_ind) + sub_mat = gnsf["E"][sub_ind, sub_ind] + if np.linalg.matrix_rank(sub_mat) < len(sub_ind): + # reformulate the model by adding a 1 to last diagonal + # element and changing rhs respectively. + gnsf["E"][sub_max, sub_max] = gnsf["E"][sub_max, sub_max] + 1 + # this means adding the term 1 * k(sub_max) to the sub_max + # row of the l.h.s + if len(np.nonzero(gnsf["C"][sub_max, :])[0]) == 0: + # if isempty(find(gnsf['C'](sub_max,:), 1)): + # add new nonlinearity entry + gnsf["C"][sub_max, gnsf["n_out"] + 1] = 1 + gnsf["phi_expr"] = vertcat(gnsf["phi_expr"], k[sub_max]) + else: + ind_f = np.nonzero(gnsf["C"][sub_max, :])[0] + if len(ind_f) != 1: + raise Exception("C is assumed to be a selection matrix") + else: + ind_f = ind_f[0] + # add term to corresponding nonlinearity entry + # note: herbey we assume that C is a selection matrix, + # i.e. gnsf['phi_expr'](ind_f) is only entering one equation + + gnsf["phi_expr"][ind_f] = ( + gnsf["phi_expr"][ind_f] + + k[sub_max] / gnsf["C"][sub_max, ind_f] + ) + gnsf = determine_input_nonlinearity_function(gnsf) + check_reformulation(model, gnsf, print_info) + print("successfully reformulated the model with invertible matrices E11, E22") + else: + if print_info: + print(" ") + print( + "the rank of both E11 and E22 is naturally full after the reformulation " + ) + print("==> model reformulation finished") + print(" ") + if (gnsf['nx2'] > 0 or gnsf['nz2'] > 0) and det(gnsf["E_LO"]) == 0: + print( + "_______________________________________________________________________________________________________" + ) + print(" ") + print("TAKE CARE ") + print("E_LO matrix is NOT regular after automatic transcription!") + print("->> this means the model CANNOT be used with the gnsf integrator") + print( + "->> it probably means that one entry (of xdot or z) that was moved to the linear output type system" + ) + print(" does not appear in the model at all (zero column in E_LO)") + print(" OR: the columns of E_LO are linearly dependent ") + print(" ") + print( + " SOLUTIONs: a) go through your model & check equations the method wanted to move to LOS" + ) + print(" b) deactivate the detect_LOS option") + print( + "_______________________________________________________________________________________________________" + ) + return gnsf diff --git a/third_party/acados/acados_template/gnsf/structure_detection_print_summary.py b/third_party/acados/acados_template/gnsf/structure_detection_print_summary.py new file mode 100644 index 000000000..db2d18758 --- /dev/null +++ b/third_party/acados/acados_template/gnsf/structure_detection_print_summary.py @@ -0,0 +1,174 @@ +# +# Copyright (c) The acados authors. +# +# This file is part of acados. +# +# 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 HOLDER 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: Jonathan Frey: jonathanpaulfrey(at)gmail.com + +from casadi import n_nodes +import numpy as np + + +def structure_detection_print_summary(gnsf, acados_ocp): + + ## Description + # this function prints the most important info after determining a GNSF + # reformulation of the implicit model "initial_model" into "gnsf", which is + # equivalent to the "reordered_model". + model = acados_ocp.model + # # GNSF + # get dimensions + nx = gnsf["nx"] + nu = gnsf["nu"] + nz = gnsf["nz"] + + nx1 = gnsf["nx1"] + nx2 = gnsf["nx2"] + + nz1 = gnsf["nz1"] + nz2 = gnsf["nz2"] + + # np = gnsf['np'] + n_out = gnsf["n_out"] + ny = gnsf["ny"] + nuhat = gnsf["nuhat"] + + # + f_impl_expr = model.f_impl_expr + n_nodes_initial = n_nodes(model.f_impl_expr) + # x_old = model.x + # f_impl_old = model.f_impl_expr + + x = gnsf["x"] + z = gnsf["z"] + + phi_current = gnsf["phi_expr"] + + ## PRINT SUMMARY -- STRUCHTRE DETECTION + print(" ") + print( + "*********************************************************************************************" + ) + print(" ") + print( + "****************** SUCCESS: GNSF STRUCTURE DETECTION COMPLETE !!! ***************" + ) + print(" ") + print( + "*********************************************************************************************" + ) + print(" ") + print( + f"========================= STRUCTURE DETECTION SUMMARY ====================================" + ) + print(" ") + print("-------- Nonlinear Static Feedback type system --------") + print(" ") + print(" successfully transcribed dynamic system model into GNSF structure ") + print(" ") + print( + "reduced dimension of nonlinearity phi from ", + str(nx + nz), + " to ", + str(gnsf["n_out"]), + ) + print(" ") + print( + "reduced input dimension of nonlinearity phi from ", + 2 * nx + nz + nu, + " to ", + gnsf["ny"] + gnsf["nuhat"], + ) + print(" ") + print(f"reduced number of nodes in CasADi expression of nonlinearity phi from {n_nodes_initial} to {n_nodes(phi_current)}\n") + print("----------- Linear Output System (LOS) ---------------") + if nx2 + nz2 > 0: + print(" ") + print(f"introduced Linear Output System of size ", str(nx2 + nz2)) + print(" ") + if nx2 > 0: + print("consisting of the states:") + print(" ") + print(x[range(nx1, nx)]) + print(" ") + if nz2 > 0: + print("and algebraic variables:") + print(" ") + print(z[range(nz1, nz)]) + print(" ") + if gnsf["purely_linear"] == 1: + print(" ") + print("Model is fully linear!") + print(" ") + if not all(gnsf["idx_perm_x"] == np.array(range(nx))): + print(" ") + print( + "--------------------------------------------------------------------------------------------------" + ) + print( + "NOTE: permuted differential state vector x, such that x_gnsf = x(idx_perm_x) with idx_perm_x =" + ) + print(" ") + print(gnsf["idx_perm_x"]) + if nz != 0 and not all(gnsf["idx_perm_z"] == np.array(range(nz))): + print(" ") + print( + "--------------------------------------------------------------------------------------------------" + ) + print( + "NOTE: permuted algebraic state vector z, such that z_gnsf = z(idx_perm_z) with idx_perm_z =" + ) + print(" ") + print(gnsf["idx_perm_z"]) + if not all(gnsf["idx_perm_f"] == np.array(range(nx + nz))): + print(" ") + print( + "--------------------------------------------------------------------------------------------------" + ) + print( + "NOTE: permuted rhs expression vector f, such that f_gnsf = f(idx_perm_f) with idx_perm_f =" + ) + print(" ") + print(gnsf["idx_perm_f"]) + ## print GNSF dimensions + print( + "--------------------------------------------------------------------------------------------------------" + ) + print(" ") + print("The dimensions of the GNSF reformulated model read as:") + print(" ") + # T_dim = table(nx, nu, nz, np, nx1, nz1, n_out, ny, nuhat) + # print( T_dim ) + print(f"nx ", {nx}) + print(f"nu ", {nu}) + print(f"nz ", {nz}) + # print(f"np ", {np}) + print(f"nx1 ", {nx1}) + print(f"nz1 ", {nz1}) + print(f"n_out ", {n_out}) + print(f"ny ", {ny}) + print(f"nuhat ", {nuhat}) diff --git a/third_party/acados/acados_template/simulink_default_opts.json b/third_party/acados/acados_template/simulink_default_opts.json index 70c939cb8..5d178fef8 100644 --- a/third_party/acados/acados_template/simulink_default_opts.json +++ b/third_party/acados/acados_template/simulink_default_opts.json @@ -4,7 +4,9 @@ "utraj": 0, "xtraj": 0, "solver_status": 1, + "cost_value": 0, "KKT_residual": 1, + "KKT_residuals": 0, "x1": 1, "CPU_time": 1, "CPU_time_sim": 0, @@ -29,6 +31,8 @@ "ug": 1, "lh": 1, "uh": 1, + "lh_e": 1, + "uh_e": 1, "cost_W_0": 0, "cost_W": 0, "cost_W_e": 0, diff --git a/third_party/acados/acados_template/utils.py b/third_party/acados/acados_template/utils.py index 8f44f61e7..d6f6c02f8 100644 --- a/third_party/acados/acados_template/utils.py +++ b/third_party/acados/acados_template/utils.py @@ -1,9 +1,6 @@ # -*- coding: future_fstrings -*- # -# Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, -# Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, -# Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, -# Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl +# Copyright (c) The acados authors. # # This file is part of acados. # @@ -38,10 +35,17 @@ import shutil import numpy as np from casadi import SX, MX, DM, Function, CasadiMeta -ALLOWED_CASADI_VERSIONS = ('3.5.5', '3.5.4', '3.5.3', '3.5.2', '3.5.1', '3.4.5', '3.4.0') +ALLOWED_CASADI_VERSIONS = ('3.5.6', '3.5.5', '3.5.4', '3.5.3', '3.5.2', '3.5.1', '3.4.5', '3.4.0') TERA_VERSION = "0.0.34" +PLATFORM2TERA = { + "linux": "linux", + "darwin": "osx", + "win32": "windows" +} + + def get_acados_path(): ACADOS_PATH = os.environ.get('ACADOS_SOURCE_DIR') if not ACADOS_PATH: @@ -72,20 +76,17 @@ def get_tera_exec_path(): return TERA_PATH -platform2tera = { - "linux": "linux", - "darwin": "osx", - "win32": "windows" -} - - -def casadi_version_warning(casadi_version): - msg = 'Warning: Please note that the following versions of CasADi are ' - msg += 'officially supported: {}.\n '.format(" or ".join(ALLOWED_CASADI_VERSIONS)) - msg += 'If there is an incompatibility with the CasADi generated code, ' - msg += 'please consider changing your CasADi version.\n' - msg += 'Version {} currently in use.'.format(casadi_version) - print(msg) +def check_casadi_version(): + casadi_version = CasadiMeta.version() + if casadi_version in ALLOWED_CASADI_VERSIONS: + return + else: + msg = 'Warning: Please note that the following versions of CasADi are ' + msg += 'officially supported: {}.\n '.format(" or ".join(ALLOWED_CASADI_VERSIONS)) + msg += 'If there is an incompatibility with the CasADi generated code, ' + msg += 'please consider changing your CasADi version.\n' + msg += 'Version {} currently in use.'.format(casadi_version) + print(msg) def is_column(x): @@ -118,11 +119,16 @@ def is_empty(x): return True else: return False - elif x == None or x == []: + elif x == None: return True + elif isinstance(x, (set, list)): + if len(x)==0: + return True + else: + return False else: raise Exception("is_empty expects one of the following types: casadi.MX, casadi.SX, " - + "None, numpy array empty list. Got: " + str(type(x))) + + "None, numpy array empty list, set. Got: " + str(type(x))) def casadi_length(x): @@ -155,6 +161,14 @@ def make_model_consistent(model): return model +def get_lib_ext(): + lib_ext = '.so' + if sys.platform == 'darwin': + lib_ext = '.dylib' + elif os.name == 'nt': + lib_ext = '' + + return lib_ext def get_tera(): tera_path = get_tera_exec_path() @@ -165,7 +179,7 @@ def get_tera(): repo_url = "https://github.com/acados/tera_renderer/releases" url = "{}/download/v{}/t_renderer-v{}-{}".format( - repo_url, TERA_VERSION, TERA_VERSION, platform2tera[sys.platform]) + repo_url, TERA_VERSION, TERA_VERSION, PLATFORM2TERA[sys.platform]) manual_install = 'For manual installation follow these instructions:\n' manual_install += '1 Download binaries from {}\n'.format(url) @@ -200,18 +214,19 @@ def get_tera(): sys.exit(1) -def render_template(in_file, out_file, template_dir, json_path): +def render_template(in_file, out_file, output_dir, json_path, template_glob=None): + + acados_path = os.path.dirname(os.path.abspath(__file__)) + if template_glob is None: + template_glob = os.path.join(acados_path, 'c_templates_tera', '**', '*') cwd = os.getcwd() - if not os.path.exists(template_dir): - os.mkdir(template_dir) - os.chdir(template_dir) + + if not os.path.exists(output_dir): + os.makedirs(output_dir) + os.chdir(output_dir) tera_path = get_tera() - # setting up loader and environment - acados_path = os.path.dirname(os.path.abspath(__file__)) - template_glob = os.path.join(acados_path, 'c_templates_tera', '*') - # call tera as system cmd os_cmd = f"{tera_path} '{template_glob}' '{in_file}' '{json_path}' '{out_file}'" # Windows cmd.exe can not cope with '...', so use "..." instead: @@ -220,21 +235,24 @@ def render_template(in_file, out_file, template_dir, json_path): status = os.system(os_cmd) if (status != 0): - raise Exception(f'Rendering of {in_file} failed!\n\nAttempted to execute OS command:\n{os_cmd}\n\nExiting.\n') + raise Exception(f'Rendering of {in_file} failed!\n\nAttempted to execute OS command:\n{os_cmd}\n\n') os.chdir(cwd) ## Conversion functions -def np_array_to_list(np_array): - if isinstance(np_array, (np.ndarray)): - return np_array.tolist() - elif isinstance(np_array, (SX)): - return DM(np_array).full() - elif isinstance(np_array, (DM)): - return np_array.full() +def make_object_json_dumpable(input): + if isinstance(input, (np.ndarray)): + return input.tolist() + elif isinstance(input, (SX)): + return input.serialize() + elif isinstance(input, (MX)): + # NOTE: MX expressions can not be serialized, only Functions. + return input.__str__() + elif isinstance(input, (DM)): + return input.full() else: - raise(Exception(f"Cannot convert to list type {type(np_array)}")) + raise TypeError(f"Cannot make input of type {type(input)} dumpable.") def format_class_dict(d): @@ -251,7 +269,7 @@ def format_class_dict(d): return out -def get_ocp_nlp_layout(): +def get_ocp_nlp_layout() -> dict: python_interface_path = get_python_interface_path() abs_path = os.path.join(python_interface_path, 'acados_layout.json') with open(abs_path, 'r') as f: @@ -259,62 +277,12 @@ def get_ocp_nlp_layout(): return ocp_nlp_layout -def ocp_check_against_layout(ocp_nlp, ocp_dims): - """ - Check dimensions against layout - Parameters - --------- - ocp_nlp : dict - dictionary loaded from JSON to be post-processed. - - ocp_dims : instance of AcadosOcpDims - """ - - ocp_nlp_layout = get_ocp_nlp_layout() - - ocp_check_against_layout_recursion(ocp_nlp, ocp_dims, ocp_nlp_layout) - return - - -def ocp_check_against_layout_recursion(ocp_nlp, ocp_dims, layout): - - for key, item in ocp_nlp.items(): - - try: - layout_of_key = layout[key] - except KeyError: - raise Exception("ocp_check_against_layout_recursion: field" \ - " '{0}' is not in layout but in OCP description.".format(key)) - - if isinstance(item, dict): - ocp_check_against_layout_recursion(item, ocp_dims, layout_of_key) - - if 'ndarray' in layout_of_key: - if isinstance(item, int) or isinstance(item, float): - item = np.array([item]) - if isinstance(item, (list, np.ndarray)) and (layout_of_key[0] != 'str'): - dim_layout = [] - dim_names = layout_of_key[1] - - for dim_name in dim_names: - dim_layout.append(ocp_dims[dim_name]) - - dims = tuple(dim_layout) - - item = np.array(item) - item_dims = item.shape - if len(item_dims) != len(dims): - raise Exception('Mismatching dimensions for field {0}. ' \ - 'Expected {1} dimensional array, got {2} dimensional array.' \ - .format(key, len(dims), len(item_dims))) - - if np.prod(item_dims) != 0 or np.prod(dims) != 0: - if dims != item_dims: - raise Exception('acados -- mismatching dimensions for field {0}. ' \ - 'Provided data has dimensions {1}, ' \ - 'while associated dimensions {2} are {3}' \ - .format(key, item_dims, dim_names, dims)) - return +def get_default_simulink_opts() -> dict: + python_interface_path = get_python_interface_path() + abs_path = os.path.join(python_interface_path, 'simulink_default_opts.json') + with open(abs_path, 'r') as f: + simulink_opts = json.load(f) + return simulink_opts def J_to_idx(J): @@ -324,9 +292,9 @@ def J_to_idx(J): this_idx = np.nonzero(J[i,:])[0] if len(this_idx) != 1: raise Exception('Invalid J matrix structure detected, ' \ - 'must contain one nonzero element per row. Exiting.') + 'must contain one nonzero element per row.') if this_idx.size > 0 and J[i,this_idx[0]] != 1: - raise Exception('J matrices can only contain 1s. Exiting.') + raise Exception('J matrices can only contain 1s.') idx[i] = this_idx[0] return idx @@ -342,7 +310,7 @@ def J_to_idx_slack(J): idx[i_idx] = i i_idx = i_idx + 1 elif len(this_idx) > 1: - raise Exception('J_to_idx_slack: Invalid J matrix. Exiting. ' \ + raise Exception('J_to_idx_slack: Invalid J matrix. ' \ 'Found more than one nonzero in row ' + str(i)) if this_idx.size > 0 and J[i,this_idx[0]] != 1: raise Exception('J_to_idx_slack: J matrices can only contain 1s, ' \ @@ -376,13 +344,13 @@ def acados_dae_model_json_dump(model): # dump json_file = model_name + '_acados_dae.json' with open(json_file, 'w') as f: - json.dump(dae_dict, f, default=np_array_to_list, indent=4, sort_keys=True) + json.dump(dae_dict, f, default=make_object_json_dumpable, indent=4, sort_keys=True) print("dumped ", model_name, " dae to file:", json_file, "\n") -def set_up_imported_gnsf_model(acados_formulation): +def set_up_imported_gnsf_model(acados_ocp): - gnsf = acados_formulation.gnsf_model + gnsf = acados_ocp.gnsf_model # check CasADi version # dump_casadi_version = gnsf['casadi_version'] @@ -402,39 +370,66 @@ def set_up_imported_gnsf_model(acados_formulation): # obtain gnsf dimensions size_gnsf_A = get_matrices_fun.size_out(0) - acados_formulation.dims.gnsf_nx1 = size_gnsf_A[1] - acados_formulation.dims.gnsf_nz1 = size_gnsf_A[0] - size_gnsf_A[1] - acados_formulation.dims.gnsf_nuhat = max(phi_fun.size_in(1)) - acados_formulation.dims.gnsf_ny = max(phi_fun.size_in(0)) - acados_formulation.dims.gnsf_nout = max(phi_fun.size_out(0)) + acados_ocp.dims.gnsf_nx1 = size_gnsf_A[1] + acados_ocp.dims.gnsf_nz1 = size_gnsf_A[0] - size_gnsf_A[1] + acados_ocp.dims.gnsf_nuhat = max(phi_fun.size_in(1)) + acados_ocp.dims.gnsf_ny = max(phi_fun.size_in(0)) + acados_ocp.dims.gnsf_nout = max(phi_fun.size_out(0)) # save gnsf functions in model - acados_formulation.model.phi_fun = phi_fun - acados_formulation.model.phi_fun_jac_y = phi_fun_jac_y - acados_formulation.model.phi_jac_y_uhat = phi_jac_y_uhat - acados_formulation.model.get_matrices_fun = get_matrices_fun + acados_ocp.model.phi_fun = phi_fun + acados_ocp.model.phi_fun_jac_y = phi_fun_jac_y + acados_ocp.model.phi_jac_y_uhat = phi_jac_y_uhat + acados_ocp.model.get_matrices_fun = get_matrices_fun # get_matrices_fun = Function([model_name,'_gnsf_get_matrices_fun'], {dummy},... # {A, B, C, E, L_x, L_xdot, L_z, L_u, A_LO, c, E_LO, B_LO,... # nontrivial_f_LO, purely_linear, ipiv_x, ipiv_z, c_LO}); get_matrices_out = get_matrices_fun(0) - acados_formulation.model.gnsf['nontrivial_f_LO'] = int(get_matrices_out[12]) - acados_formulation.model.gnsf['purely_linear'] = int(get_matrices_out[13]) + acados_ocp.model.gnsf['nontrivial_f_LO'] = int(get_matrices_out[12]) + acados_ocp.model.gnsf['purely_linear'] = int(get_matrices_out[13]) if "f_lo_fun_jac_x1k1uz" in gnsf: f_lo_fun_jac_x1k1uz = Function.deserialize(gnsf['f_lo_fun_jac_x1k1uz']) - acados_formulation.model.f_lo_fun_jac_x1k1uz = f_lo_fun_jac_x1k1uz + acados_ocp.model.f_lo_fun_jac_x1k1uz = f_lo_fun_jac_x1k1uz else: - dummy_var_x1 = SX.sym('dummy_var_x1', acados_formulation.dims.gnsf_nx1) - dummy_var_x1dot = SX.sym('dummy_var_x1dot', acados_formulation.dims.gnsf_nx1) - dummy_var_z1 = SX.sym('dummy_var_z1', acados_formulation.dims.gnsf_nz1) - dummy_var_u = SX.sym('dummy_var_z1', acados_formulation.dims.nu) - dummy_var_p = SX.sym('dummy_var_z1', acados_formulation.dims.np) + dummy_var_x1 = SX.sym('dummy_var_x1', acados_ocp.dims.gnsf_nx1) + dummy_var_x1dot = SX.sym('dummy_var_x1dot', acados_ocp.dims.gnsf_nx1) + dummy_var_z1 = SX.sym('dummy_var_z1', acados_ocp.dims.gnsf_nz1) + dummy_var_u = SX.sym('dummy_var_z1', acados_ocp.dims.nu) + dummy_var_p = SX.sym('dummy_var_z1', acados_ocp.dims.np) empty_var = SX.sym('empty_var', 0, 0) empty_fun = Function('empty_fun', \ [dummy_var_x1, dummy_var_x1dot, dummy_var_z1, dummy_var_u, dummy_var_p], [empty_var]) - acados_formulation.model.f_lo_fun_jac_x1k1uz = empty_fun + acados_ocp.model.f_lo_fun_jac_x1k1uz = empty_fun - del acados_formulation.gnsf_model + del acados_ocp.gnsf_model + + +def idx_perm_to_ipiv(idx_perm): + n = len(idx_perm) + vec = list(range(n)) + ipiv = np.zeros(n) + + print(n, idx_perm) + # import pdb; pdb.set_trace() + for ii in range(n): + idx0 = idx_perm[ii] + for jj in range(ii,n): + if vec[jj]==idx0: + idx1 = jj + break + tmp = vec[ii] + vec[ii] = vec[idx1] + vec[idx1] = tmp + ipiv[ii] = idx1 + + ipiv = ipiv-1 # C 0-based indexing + return ipiv + + +def print_casadi_expression(f): + for ii in range(casadi_length(f)): + print(f[ii,:]) diff --git a/third_party/acados/acados_template/zoro_description.py b/third_party/acados/acados_template/zoro_description.py new file mode 100644 index 000000000..4d795c150 --- /dev/null +++ b/third_party/acados/acados_template/zoro_description.py @@ -0,0 +1,78 @@ +# Copyright (c) The acados authors. +# +# This file is part of acados. +# +# 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 HOLDER 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.; + +from dataclasses import dataclass, field +import numpy as np + + +@dataclass +class ZoroDescription: + """ + Zero-Order Robust Optimization scheme. + + For advanced users. + """ + backoff_scaling_gamma: float = 1.0 + fdbk_K_mat: np.ndarray = None + unc_jac_G_mat: np.ndarray = None # default: an identity matrix + P0_mat: np.ndarray = None + W_mat: np.ndarray = None + idx_lbx_t: list = field(default_factory=list) + idx_ubx_t: list = field(default_factory=list) + idx_lbx_e_t: list = field(default_factory=list) + idx_ubx_e_t: list = field(default_factory=list) + idx_lbu_t: list = field(default_factory=list) + idx_ubu_t: list = field(default_factory=list) + idx_lg_t: list = field(default_factory=list) + idx_ug_t: list = field(default_factory=list) + idx_lg_e_t: list = field(default_factory=list) + idx_ug_e_t: list = field(default_factory=list) + idx_lh_t: list = field(default_factory=list) + idx_uh_t: list = field(default_factory=list) + idx_lh_e_t: list = field(default_factory=list) + idx_uh_e_t: list = field(default_factory=list) + +def process_zoro_description(zoro_description: ZoroDescription): + zoro_description.nw, _ = zoro_description.W_mat.shape + if zoro_description.unc_jac_G_mat is None: + zoro_description.unc_jac_G_mat = np.eye(zoro_description.nw) + zoro_description.nlbx_t = len(zoro_description.idx_lbx_t) + zoro_description.nubx_t = len(zoro_description.idx_ubx_t) + zoro_description.nlbx_e_t = len(zoro_description.idx_lbx_e_t) + zoro_description.nubx_e_t = len(zoro_description.idx_ubx_e_t) + zoro_description.nlbu_t = len(zoro_description.idx_lbu_t) + zoro_description.nubu_t = len(zoro_description.idx_ubu_t) + zoro_description.nlg_t = len(zoro_description.idx_lg_t) + zoro_description.nug_t = len(zoro_description.idx_ug_t) + zoro_description.nlg_e_t = len(zoro_description.idx_lg_e_t) + zoro_description.nug_e_t = len(zoro_description.idx_ug_e_t) + zoro_description.nlh_t = len(zoro_description.idx_lh_t) + zoro_description.nuh_t = len(zoro_description.idx_uh_t) + zoro_description.nlh_e_t = len(zoro_description.idx_lh_e_t) + zoro_description.nuh_e_t = len(zoro_description.idx_uh_e_t) + return zoro_description.__dict__ diff --git a/third_party/acados/include/acados/dense_qp/dense_qp_common.h b/third_party/acados/include/acados/dense_qp/dense_qp_common.h index f3809c429..2a9a974f9 100644 --- a/third_party/acados/include/acados/dense_qp/dense_qp_common.h +++ b/third_party/acados/include/acados/dense_qp/dense_qp_common.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * diff --git a/third_party/acados/include/acados/dense_qp/dense_qp_daqp.h b/third_party/acados/include/acados/dense_qp/dense_qp_daqp.h new file mode 100644 index 000000000..b262089b4 --- /dev/null +++ b/third_party/acados/include/acados/dense_qp/dense_qp_daqp.h @@ -0,0 +1,110 @@ +/* + * Copyright (c) The acados authors. + * + * This file is part of acados. + * + * 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 HOLDER 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.; + */ + + +#ifndef ACADOS_DENSE_QP_DENSE_QP_DAQP_H_ +#define ACADOS_DENSE_QP_DENSE_QP_DAQP_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +// blasfeo +#include "blasfeo/include/blasfeo_common.h" + +// daqp +#include "daqp/include/types.h" + +// acados +#include "acados/dense_qp/dense_qp_common.h" +#include "acados/utils/types.h" + + +typedef struct dense_qp_daqp_opts_ +{ + DAQPSettings* daqp_opts; + int warm_start; +} dense_qp_daqp_opts; + + +typedef struct dense_qp_daqp_memory_ +{ + double* lb_tmp; + double* ub_tmp; + int* idxb; + int* idxv_to_idxb; + int* idxs; + int* idxdaqp_to_idxs; + + double* Zl; + double* Zu; + double* zl; + double* zu; + double* d_ls; + double* d_us; + + double time_qp_solver_call; + int iter; + DAQPWorkspace * daqp_work; + +} dense_qp_daqp_memory; + +// opts +acados_size_t dense_qp_daqp_opts_calculate_size(void *config, dense_qp_dims *dims); +// +void *dense_qp_daqp_opts_assign(void *config, dense_qp_dims *dims, void *raw_memory); +// +void dense_qp_daqp_opts_initialize_default(void *config, dense_qp_dims *dims, void *opts_); +// +void dense_qp_daqp_opts_update(void *config, dense_qp_dims *dims, void *opts_); +// +// memory +acados_size_t dense_qp_daqp_workspace_calculate_size(void *config, dense_qp_dims *dims, void *opts_); +// +void *dense_qp_daqp_workspace_assign(void *config, dense_qp_dims *dims, void *raw_memory); +// +acados_size_t dense_qp_daqp_memory_calculate_size(void *config, dense_qp_dims *dims, void *opts_); +// +void *dense_qp_daqp_memory_assign(void *config, dense_qp_dims *dims, void *opts_, void *raw_memory); +// +// functions +int dense_qp_daqp(void *config, dense_qp_in *qp_in, dense_qp_out *qp_out, void *opts_, void *memory_, void *work_); +// +void dense_qp_daqp_eval_sens(void *config_, void *qp_in, void *qp_out, void *opts_, void *mem_, void *work_); +// +void dense_qp_daqp_memory_reset(void *config_, void *qp_in, void *qp_out, void *opts_, void *mem_, void *work_); +// +void dense_qp_daqp_config_initialize_default(void *config_); + +#ifdef __cplusplus +} /* extern "C" */ +#endif + +#endif // ACADOS_DENSE_QP_DENSE_QP_DAQP_H_ diff --git a/third_party/acados/include/acados/dense_qp/dense_qp_hpipm.h b/third_party/acados/include/acados/dense_qp/dense_qp_hpipm.h index 20eedc26a..136279d66 100644 --- a/third_party/acados/include/acados/dense_qp/dense_qp_hpipm.h +++ b/third_party/acados/include/acados/dense_qp/dense_qp_hpipm.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * diff --git a/third_party/acados/include/acados/dense_qp/dense_qp_ooqp.h b/third_party/acados/include/acados/dense_qp/dense_qp_ooqp.h index 646f11f06..d051cb15f 100644 --- a/third_party/acados/include/acados/dense_qp/dense_qp_ooqp.h +++ b/third_party/acados/include/acados/dense_qp/dense_qp_ooqp.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * diff --git a/third_party/acados/include/acados/dense_qp/dense_qp_qore.h b/third_party/acados/include/acados/dense_qp/dense_qp_qore.h index 52606fac5..392e47291 100644 --- a/third_party/acados/include/acados/dense_qp/dense_qp_qore.h +++ b/third_party/acados/include/acados/dense_qp/dense_qp_qore.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * diff --git a/third_party/acados/include/acados/dense_qp/dense_qp_qpoases.h b/third_party/acados/include/acados/dense_qp/dense_qp_qpoases.h index 9f0bb1af6..0e13d3ef6 100644 --- a/third_party/acados/include/acados/dense_qp/dense_qp_qpoases.h +++ b/third_party/acados/include/acados/dense_qp/dense_qp_qpoases.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_common.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_common.h index 60d835fc5..ba97db976 100644 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_common.h +++ b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_common.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * @@ -419,6 +416,9 @@ void ocp_nlp_embed_initial_value(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp void ocp_nlp_update_variables_sqp(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, double alpha); // +int ocp_nlp_precompute_common(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); +// double ocp_nlp_line_search(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, int check_early_termination); diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_constraints_bgh.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_constraints_bgh.h index 7f7a30faf..9dbf16f6d 100644 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_constraints_bgh.h +++ b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_constraints_bgh.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * @@ -82,9 +79,6 @@ acados_size_t ocp_nlp_constraints_bgh_dims_calculate_size(void *config); // void *ocp_nlp_constraints_bgh_dims_assign(void *config, void *raw_memory); // -void ocp_nlp_constraints_bgh_dims_initialize(void *config, void *dims, int nx, int nu, int nz, int nbx, - int nbu, int ng, int nh, int dummy0, int ns); -// void ocp_nlp_constraints_bgh_dims_get(void *config_, void *dims_, const char *field, int* value); // void ocp_nlp_constraints_bgh_dims_set(void *config_, void *dims_, @@ -116,6 +110,9 @@ void *ocp_nlp_constraints_bgh_model_assign(void *config, void *dims, void *raw_m int ocp_nlp_constraints_bgh_model_set(void *config_, void *dims_, void *model_, const char *field, void *value); +// +void ocp_nlp_constraints_bgh_model_get(void *config_, void *dims_, + void *model_, const char *field, void *value); /************************************************ diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_constraints_bgp.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_constraints_bgp.h index beeec7841..eb05edf7a 100644 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_constraints_bgp.h +++ b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_constraints_bgp.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * @@ -63,7 +60,7 @@ typedef struct int nbu; int nbx; int ng; // number of general linear constraints - int nphi; // dimension of convex outer part + int nphi; // dimension of convex outer part int ns; // nsbu + nsbx + nsg + nsphi int nsbu; // number of softened input bounds int nsbx; // number of softened state bounds @@ -81,9 +78,6 @@ acados_size_t ocp_nlp_constraints_bgp_dims_calculate_size(void *config); // void *ocp_nlp_constraints_bgp_dims_assign(void *config, void *raw_memory); // -void ocp_nlp_constraints_bgp_dims_initialize(void *config, void *dims, int nx, int nu, int nz, - int nbx, int nbu, int ng, int nphi, int nq, int ns); -// void ocp_nlp_constraints_bgp_dims_get(void *config_, void *dims_, const char *field, int* value); @@ -109,6 +103,9 @@ void *ocp_nlp_constraints_bgp_assign(void *config, void *dims, void *raw_memory) // int ocp_nlp_constraints_bgp_model_set(void *config_, void *dims_, void *model_, const char *field, void *value); +// +void ocp_nlp_constraints_bgp_model_get(void *config_, void *dims_, + void *model_, const char *field, void *value); /* options */ diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_constraints_common.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_constraints_common.h index 7cadecab4..bb73c468d 100644 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_constraints_common.h +++ b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_constraints_common.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * @@ -60,11 +57,10 @@ typedef struct { acados_size_t (*dims_calculate_size)(void *config); void *(*dims_assign)(void *config, void *raw_memory); - void (*dims_initialize)(void *config, void *dims, int nx, int nu, int nz, int nbx, int nbu, int ng, - int nh, int nq, int ns); acados_size_t (*model_calculate_size)(void *config, void *dims); void *(*model_assign)(void *config, void *dims, void *raw_memory); int (*model_set)(void *config_, void *dims_, void *model_, const char *field, void *value); + void (*model_get)(void *config_, void *dims_, void *model_, const char *field, void *value); acados_size_t (*opts_calculate_size)(void *config, void *dims); void *(*opts_assign)(void *config, void *dims, void *raw_memory); void (*opts_initialize_default)(void *config, void *dims, void *opts); diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_common.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_common.h index c9fbbfb40..eb4056403 100644 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_common.h +++ b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_common.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * @@ -33,8 +30,8 @@ /// -/// \defgroup ocp_nlp_cost ocp_nlp_cost -/// +/// \defgroup ocp_nlp_cost ocp_nlp_cost +/// /// \addtogroup ocp_nlp_cost ocp_nlp_cost /// @{ @@ -62,7 +59,6 @@ typedef struct { acados_size_t (*dims_calculate_size)(void *config); void *(*dims_assign)(void *config, void *raw_memory); - void (*dims_initialize)(void *config, void *dims, int nx, int nu, int ny, int ns, int nz); void (*dims_set)(void *config_, void *dims_, const char *field, int *value); void (*dims_get)(void *config_, void *dims_, const char *field, int *value); acados_size_t (*model_calculate_size)(void *config, void *dims); @@ -91,6 +87,8 @@ typedef struct // computes the cost function value (intended for globalization) void (*compute_fun)(void *config_, void *dims, void *model_, void *opts_, void *mem_, void *work_); void (*config_initialize_default)(void *config); + void (*precompute)(void *config_, void *dims_, void *model_, void *opts_, void *memory_, void *work_); + } ocp_nlp_cost_config; // @@ -105,5 +103,5 @@ ocp_nlp_cost_config *ocp_nlp_cost_config_assign(void *raw_memory); #endif #endif // ACADOS_OCP_NLP_OCP_NLP_COST_COMMON_H_ -/// @} -/// @} +/// @} +/// @} diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_conl.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_conl.h new file mode 100644 index 000000000..2eb3f5d12 --- /dev/null +++ b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_conl.h @@ -0,0 +1,207 @@ +/* + * Copyright (c) The acados authors. + * + * This file is part of acados. + * + * 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 HOLDER 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.; + */ + + +/// \addtogroup ocp_nlp +/// @{ +/// \addtogroup ocp_nlp_cost ocp_nlp_cost +/// @{ +/// \addtogroup ocp_nlp_cost_conl ocp_nlp_cost_conl +/// \brief This module implements convex-over-nonlinear costs of the form +/// \f$\min_{x,u,z} \psi(y(x,u,z,p) - y_{\text{ref}}, p)\f$, + + +#ifndef ACADOS_OCP_NLP_OCP_NLP_COST_CONL_H_ +#define ACADOS_OCP_NLP_OCP_NLP_COST_CONL_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +// blasfeo +#include "blasfeo/include/blasfeo_common.h" + +// acados +#include "acados/ocp_nlp/ocp_nlp_cost_common.h" +#include "acados/utils/external_function_generic.h" +#include "acados/utils/types.h" + + + +/************************************************ + * dims + ************************************************/ + +typedef struct +{ + int nx; // number of states + int nz; // number of algebraic variables + int nu; // number of inputs + int ny; // number of outputs + int ns; // number of slacks +} ocp_nlp_cost_conl_dims; + +// +acados_size_t ocp_nlp_cost_conl_dims_calculate_size(void *config); +// +void *ocp_nlp_cost_conl_dims_assign(void *config, void *raw_memory); +// +void ocp_nlp_cost_conl_dims_initialize(void *config, void *dims, int nx, int nu, int ny, int ns, int nz); +// +void ocp_nlp_cost_conl_dims_set(void *config_, void *dims_, const char *field, int* value); +// +void ocp_nlp_cost_conl_dims_get(void *config_, void *dims_, const char *field, int* value); + + + +/************************************************ + * model + ************************************************/ + +typedef struct +{ + // slack penalty has the form z^T * s + .5 * s^T * Z * s + external_function_generic *conl_cost_fun; + external_function_generic *conl_cost_fun_jac_hess; + struct blasfeo_dvec y_ref; + struct blasfeo_dvec Z; // diagonal Hessian of slacks as vector + struct blasfeo_dvec z; // gradient of slacks as vector + double scaling; +} ocp_nlp_cost_conl_model; + +// +acados_size_t ocp_nlp_cost_conl_model_calculate_size(void *config, void *dims); +// +void *ocp_nlp_cost_conl_model_assign(void *config, void *dims, void *raw_memory); +// +int ocp_nlp_cost_conl_model_set(void *config_, void *dims_, void *model_, const char *field, void *value_); + + + +/************************************************ + * options + ************************************************/ + +typedef struct +{ + bool gauss_newton_hess; // dummy options, we always use a gauss-newton hessian +} ocp_nlp_cost_conl_opts; + +// +acados_size_t ocp_nlp_cost_conl_opts_calculate_size(void *config, void *dims); +// +void *ocp_nlp_cost_conl_opts_assign(void *config, void *dims, void *raw_memory); +// +void ocp_nlp_cost_conl_opts_initialize_default(void *config, void *dims, void *opts); +// +void ocp_nlp_cost_conl_opts_update(void *config, void *dims, void *opts); +// +void ocp_nlp_cost_conl_opts_set(void *config, void *opts, const char *field, void *value); + + + +/************************************************ + * memory + ************************************************/ +typedef struct +{ + struct blasfeo_dvec grad; // gradient of cost function + struct blasfeo_dvec *ux; // pointer to ux in nlp_out + struct blasfeo_dvec *tmp_ux; // pointer to ux in tmp_nlp_out + struct blasfeo_dmat *RSQrq; // pointer to RSQrq in qp_in + struct blasfeo_dvec *Z; // pointer to Z in qp_in + struct blasfeo_dvec *z_alg; ///< pointer to z in sim_out + struct blasfeo_dmat *dzdux_tran; ///< pointer to sensitivity of a wrt ux in sim_out + double fun; ///< value of the cost function +} ocp_nlp_cost_conl_memory; + +// +acados_size_t ocp_nlp_cost_conl_memory_calculate_size(void *config, void *dims, void *opts); +// +void *ocp_nlp_cost_conl_memory_assign(void *config, void *dims, void *opts, void *raw_memory); +// +double *ocp_nlp_cost_conl_memory_get_fun_ptr(void *memory_); +// +struct blasfeo_dvec *ocp_nlp_cost_conl_memory_get_grad_ptr(void *memory_); +// +void ocp_nlp_cost_conl_memory_set_RSQrq_ptr(struct blasfeo_dmat *RSQrq, void *memory); +// +void ocp_nlp_cost_conl_memory_set_Z_ptr(struct blasfeo_dvec *Z, void *memory); +// +void ocp_nlp_cost_conl_memory_set_ux_ptr(struct blasfeo_dvec *ux, void *memory_); +// +void ocp_nlp_cost_conl_memory_set_tmp_ux_ptr(struct blasfeo_dvec *tmp_ux, void *memory_); +// +void ocp_nlp_cost_conl_memory_set_z_alg_ptr(struct blasfeo_dvec *z_alg, void *memory_); +// +void ocp_nlp_cost_conl_memory_set_dzdux_tran_ptr(struct blasfeo_dmat *dzdux_tran, void *memory_); + +/************************************************ + * workspace + ************************************************/ + +typedef struct +{ + struct blasfeo_dmat W; // hessian of outer loss function + struct blasfeo_dmat W_chol; // cholesky factor of hessian of outer loss function + struct blasfeo_dmat Jt_ux; // jacobian of inner residual function + struct blasfeo_dmat Jt_ux_tilde; // jacobian of inner residual function plus gradient contribution of algebraic variables + struct blasfeo_dmat Jt_z; // jacobian of inner residual function wrt algebraic variables + struct blasfeo_dmat tmp_nv_ny; + struct blasfeo_dvec tmp_ny; + struct blasfeo_dvec tmp_2ns; +} ocp_nlp_cost_conl_workspace; + +// +acados_size_t ocp_nlp_cost_conl_workspace_calculate_size(void *config, void *dims, void *opts); + +/************************************************ + * functions + ************************************************/ + +// +void ocp_nlp_cost_conl_precompute(void *config_, void *dims_, void *model_, void *opts_, void *memory_, void *work_); +// +void ocp_nlp_cost_conl_config_initialize_default(void *config); +// +void ocp_nlp_cost_conl_initialize(void *config_, void *dims, void *model_, void *opts_, void *mem_, void *work_); +// +void ocp_nlp_cost_conl_update_qp_matrices(void *config_, void *dims, void *model_, void *opts_, void *memory_, void *work_); +// +void ocp_nlp_cost_conl_compute_fun(void *config_, void *dims, void *model_, void *opts_, void *memory_, void *work_); + +#ifdef __cplusplus +} /* extern "C" */ +#endif + +#endif // ACADOS_OCP_NLP_OCP_NLP_COST_CONL_H_ +/// @} +/// @} +/// @} diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_external.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_external.h index f2196dbee..78958270d 100644 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_external.h +++ b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_external.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * @@ -54,6 +51,7 @@ extern "C" { typedef struct { int nx; // number of states + int nz; // number of algebraic variables int nu; // number of inputs int ns; // number of slacks } ocp_nlp_cost_external_dims; @@ -63,9 +61,6 @@ acados_size_t ocp_nlp_cost_external_dims_calculate_size(void *config); // void *ocp_nlp_cost_external_dims_assign(void *config, void *raw_memory); // -void ocp_nlp_cost_external_dims_initialize(void *config, void *dims, int nx, - int nu, int ny, int ns, int nz); -// void ocp_nlp_cost_external_dims_set(void *config_, void *dims_, const char *field, int* value); // void ocp_nlp_cost_external_dims_get(void *config_, void *dims_, const char *field, int* value); @@ -122,7 +117,7 @@ typedef struct { struct blasfeo_dvec grad; // gradient of cost function struct blasfeo_dvec *ux; // pointer to ux in nlp_out - struct blasfeo_dvec *tmp_ux; // pointer to tmp_ux in nlp_out + struct blasfeo_dvec *tmp_ux; // pointer to tmp_ux in nlp_out struct blasfeo_dmat *RSQrq; // pointer to RSQrq in qp_in struct blasfeo_dvec *Z; // pointer to Z in qp_in struct blasfeo_dvec *z_alg; ///< pointer to z in sim_out @@ -157,7 +152,10 @@ void ocp_nlp_cost_external_memory_set_dzdux_tran_ptr(struct blasfeo_dmat *dzdux_ typedef struct { - struct blasfeo_dmat tmp_nv_nv; + struct blasfeo_dmat tmp_nunx_nunx; + struct blasfeo_dmat tmp_nz_nz; + struct blasfeo_dmat tmp_nz_nunx; + struct blasfeo_dvec tmp_nunxnz; struct blasfeo_dvec tmp_2ns; // temporary vector of dimension 2*ns } ocp_nlp_cost_external_workspace; @@ -168,6 +166,8 @@ acados_size_t ocp_nlp_cost_external_workspace_calculate_size(void *config, void * functions ************************************************/ +// +void ocp_nlp_cost_external_precompute(void *config_, void *dims_, void *model_, void *opts_, void *memory_, void *work_); // void ocp_nlp_cost_external_config_initialize_default(void *config); // diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_ls.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_ls.h index 3cf759504..801e9a5b8 100644 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_ls.h +++ b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_ls.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * @@ -82,30 +79,14 @@ typedef struct acados_size_t ocp_nlp_cost_ls_dims_calculate_size(void *config); -/// Assign memory pointed to by raw_memory to ocp_nlp-cost_ls dims struct +/// Assign memory pointed to by raw_memory to ocp_nlp-cost_ls dims struct /// -/// \param[in] config structure containing configuration of ocp_nlp_cost +/// \param[in] config structure containing configuration of ocp_nlp_cost /// module -/// \param[in] raw_memory pointer to memory location +/// \param[in] raw_memory pointer to memory location /// \param[out] [] /// \return dims void *ocp_nlp_cost_ls_dims_assign(void *config, void *raw_memory); - - -/// Initialize the dimensions struct of the -/// ocp_nlp-cost_ls component -/// -/// \param[in] config structure containing configuration ocp_nlp-cost_ls component -/// \param[in] nx number of states -/// \param[in] nu number of inputs -/// \param[in] ny number of residuals -/// \param[in] ns number of slacks -/// \param[in] nz number of algebraic variables -/// \param[out] dims -/// \return size -void ocp_nlp_cost_ls_dims_initialize(void *config, void *dims, int nx, - int nu, int ny, int ns, int nz); - // void ocp_nlp_cost_ls_dims_set(void *config_, void *dims_, const char *field, int* value); // @@ -117,7 +98,7 @@ void ocp_nlp_cost_ls_dims_get(void *config_, void *dims_, const char *field, int //////////////////////////////////////////////////////////////////////////////// -/// structure containing the data describing the linear least-square cost +/// structure containing the data describing the linear least-square cost typedef struct { // slack penalty has the form z^T * s + .5 * s^T * Z * s @@ -128,6 +109,8 @@ typedef struct struct blasfeo_dvec Z; ///< diagonal Hessian of slacks as vector (lower and upper) struct blasfeo_dvec z; ///< gradient of slacks as vector (lower and upper) double scaling; + int W_changed; ///< flag indicating whether W has changed and needs to be refactorized + int Cyt_or_scaling_changed; ///< flag indicating whether Cyt or scaling has changed and Hessian needs to be recomputed } ocp_nlp_cost_ls_model; // @@ -170,7 +153,7 @@ void ocp_nlp_cost_ls_opts_set(void *config, void *opts, const char *field, void -/// structure containing the memory associated with cost_ls component +/// structure containing the memory associated with cost_ls component /// of the ocp_nlp module typedef struct { @@ -237,7 +220,8 @@ acados_size_t ocp_nlp_cost_ls_workspace_calculate_size(void *config, void *dims, //////////////////////////////////////////////////////////////////////////////// - +// computations that are done once when solver is created +void ocp_nlp_cost_ls_precompute(void *config_, void *dims_, void *model_, void *opts_, void *memory_, void *work_); // void ocp_nlp_cost_ls_config_initialize_default(void *config); // diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_nls.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_nls.h index aafb6b354..5ec68cf58 100644 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_nls.h +++ b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_nls.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * @@ -38,8 +35,7 @@ /// @{ /// \addtogroup ocp_nlp_cost_nls ocp_nlp_cost_nls /// \brief This module implements nonlinear-least squares costs of the form -/// \f$\min_{x,u} \| r(x,u) - y_{\text{ref}} \|_W^2\f$. -/// @{ +/// \f$\min_{x,u,z} \| y(x,u,z,p) - y_{\text{ref}} \|_W^2\f$, #ifndef ACADOS_OCP_NLP_OCP_NLP_COST_NLS_H_ #define ACADOS_OCP_NLP_OCP_NLP_COST_NLS_H_ @@ -65,6 +61,7 @@ extern "C" { typedef struct { int nx; // number of states + int nz; // number of algebraic variables int nu; // number of inputs int ny; // number of outputs int ns; // number of slacks @@ -75,8 +72,6 @@ acados_size_t ocp_nlp_cost_nls_dims_calculate_size(void *config); // void *ocp_nlp_cost_nls_dims_assign(void *config, void *raw_memory); // -void ocp_nlp_cost_nls_dims_initialize(void *config, void *dims, int nx, int nu, int ny, int ns, int nz); -// void ocp_nlp_cost_nls_dims_set(void *config_, void *dims_, const char *field, int* value); // void ocp_nlp_cost_nls_dims_get(void *config_, void *dims_, const char *field, int* value); @@ -99,6 +94,7 @@ typedef struct struct blasfeo_dvec Z; // diagonal Hessian of slacks as vector struct blasfeo_dvec z; // gradient of slacks as vector double scaling; + int W_changed; ///< flag indicating whether W has changed and needs to be refactorized } ocp_nlp_cost_nls_model; // @@ -144,11 +140,11 @@ typedef struct struct blasfeo_dvec grad; // gradient of cost function struct blasfeo_dvec *ux; // pointer to ux in nlp_out struct blasfeo_dvec *tmp_ux; // pointer to ux in tmp_nlp_out - struct blasfeo_dvec *z_alg; ///< pointer to z in sim_out - struct blasfeo_dmat *dzdux_tran; ///< pointer to sensitivity of a wrt ux in sim_out struct blasfeo_dmat *RSQrq; // pointer to RSQrq in qp_in struct blasfeo_dvec *Z; // pointer to Z in qp_in - double fun; ///< value of the cost function + struct blasfeo_dvec *z_alg; ///< pointer to z in sim_out + struct blasfeo_dmat *dzdux_tran; ///< pointer to sensitivity of a wrt ux in sim_out + double fun; ///< value of the cost function } ocp_nlp_cost_nls_memory; // @@ -180,8 +176,11 @@ typedef struct { struct blasfeo_dmat tmp_nv_ny; struct blasfeo_dmat tmp_nv_nv; + struct blasfeo_dmat Vz; + struct blasfeo_dmat Cyt_tilde; struct blasfeo_dvec tmp_ny; - struct blasfeo_dvec tmp_2ns; // temporary vector of dimension ny + struct blasfeo_dvec tmp_2ns; + struct blasfeo_dvec tmp_nz; } ocp_nlp_cost_nls_workspace; // @@ -191,6 +190,8 @@ acados_size_t ocp_nlp_cost_nls_workspace_calculate_size(void *config, void *dims * functions ************************************************/ +// +void ocp_nlp_cost_nls_precompute(void *config_, void *dims_, void *model_, void *opts_, void *memory_, void *work_); // void ocp_nlp_cost_nls_config_initialize_default(void *config); // diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_dynamics_common.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_dynamics_common.h index f2128a857..43fe71b12 100644 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_dynamics_common.h +++ b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_dynamics_common.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * @@ -68,7 +65,6 @@ typedef struct /* dims */ acados_size_t (*dims_calculate_size)(void *config); void *(*dims_assign)(void *config, void *raw_memory); - void (*dims_initialize)(void *config, void *dims, int nx, int nu, int nx1, int nu1, int nz); void (*dims_set)(void *config_, void *dims_, const char *field, int *value); void (*dims_get)(void *config_, void *dims_, const char *field, int* value); /* model */ diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_dynamics_cont.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_dynamics_cont.h index 59a2df4f4..3afdc9f4e 100644 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_dynamics_cont.h +++ b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_dynamics_cont.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * @@ -75,10 +72,6 @@ typedef struct acados_size_t ocp_nlp_dynamics_cont_dims_calculate_size(void *config); // void *ocp_nlp_dynamics_cont_dims_assign(void *config, void *raw_memory); -// -void ocp_nlp_dynamics_cont_dims_initialize(void *config, void *dims, int nx, int nu, int nx1, - int nu1, int nz); - // void ocp_nlp_dynamics_cont_dims_set(void *config_, void *dims_, const char *field, int* value); diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_dynamics_disc.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_dynamics_disc.h index 8b2a6177b..6ea26a701 100644 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_dynamics_disc.h +++ b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_dynamics_disc.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * @@ -68,10 +65,6 @@ typedef struct acados_size_t ocp_nlp_dynamics_disc_dims_calculate_size(void *config); // void *ocp_nlp_dynamics_disc_dims_assign(void *config, void *raw_memory); -// -void ocp_nlp_dynamics_disc_dims_initialize(void *config, void *dims, int nx, int nu, int nx1, - int nu1, int nz); - // void ocp_nlp_dynamics_disc_dims_set(void *config_, void *dims_, const char *dim, int* value); diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_common.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_common.h index cd26788a5..9388f3fd2 100644 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_common.h +++ b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_common.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_convexify.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_convexify.h index df3136168..cb523525e 100644 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_convexify.h +++ b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_convexify.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_mirror.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_mirror.h index f6bd7dcaf..84a023cb6 100644 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_mirror.h +++ b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_mirror.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_noreg.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_noreg.h index c085e00d5..b571f3bac 100644 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_noreg.h +++ b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_noreg.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_project.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_project.h index 104c29720..682ea206d 100644 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_project.h +++ b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_project.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_project_reduc_hess.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_project_reduc_hess.h index e0b854bc1..7e12952c1 100644 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_project_reduc_hess.h +++ b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_project_reduc_hess.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_sqp.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_sqp.h index 74cfb042e..fdb96417f 100644 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_sqp.h +++ b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_sqp.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_sqp_rti.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_sqp_rti.h index af22c06a1..364d0f471 100644 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_sqp_rti.h +++ b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_sqp_rti.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * @@ -145,12 +142,6 @@ acados_size_t ocp_nlp_sqp_rti_workspace_calculate_size(void *config_, void *dims /************************************************ * functions ************************************************/ - -void ocp_nlp_sqp_rti_preparation_step(void *config_, void *dims_, - void *nlp_in_, void *nlp_out_, void *opts, void *mem_, void *work_); -// -void ocp_nlp_sqp_rti_feedback_step(void *config_, void *dims_, - void *nlp_in_, void *nlp_out_, void *opts_, void *mem_, void *work_); // int ocp_nlp_sqp_rti(void *config_, void *dims_, void *nlp_in_, void *nlp_out_, void *opts_, void *mem_, void *work_); diff --git a/third_party/acados/include/acados/ocp_qp/ocp_qp_common.h b/third_party/acados/include/acados/ocp_qp/ocp_qp_common.h index caf6caf2f..d1a45635e 100644 --- a/third_party/acados/include/acados/ocp_qp/ocp_qp_common.h +++ b/third_party/acados/include/acados/ocp_qp/ocp_qp_common.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * diff --git a/third_party/acados/include/acados/ocp_qp/ocp_qp_common_frontend.h b/third_party/acados/include/acados/ocp_qp/ocp_qp_common_frontend.h index 50b80850c..f65f602c1 100644 --- a/third_party/acados/include/acados/ocp_qp/ocp_qp_common_frontend.h +++ b/third_party/acados/include/acados/ocp_qp/ocp_qp_common_frontend.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * diff --git a/third_party/acados/include/acados/ocp_qp/ocp_qp_full_condensing.h b/third_party/acados/include/acados/ocp_qp/ocp_qp_full_condensing.h index 14ac97bbf..d23e658b4 100644 --- a/third_party/acados/include/acados/ocp_qp/ocp_qp_full_condensing.h +++ b/third_party/acados/include/acados/ocp_qp/ocp_qp_full_condensing.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * diff --git a/third_party/acados/include/acados/ocp_qp/ocp_qp_hpipm.h b/third_party/acados/include/acados/ocp_qp/ocp_qp_hpipm.h index 91690e458..261606b84 100644 --- a/third_party/acados/include/acados/ocp_qp/ocp_qp_hpipm.h +++ b/third_party/acados/include/acados/ocp_qp/ocp_qp_hpipm.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * diff --git a/third_party/acados/include/acados/ocp_qp/ocp_qp_hpmpc.h b/third_party/acados/include/acados/ocp_qp/ocp_qp_hpmpc.h index de6ce501b..8db53a279 100644 --- a/third_party/acados/include/acados/ocp_qp/ocp_qp_hpmpc.h +++ b/third_party/acados/include/acados/ocp_qp/ocp_qp_hpmpc.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * diff --git a/third_party/acados/include/acados/ocp_qp/ocp_qp_ooqp.h b/third_party/acados/include/acados/ocp_qp/ocp_qp_ooqp.h index 1a3b7b2fa..a535503f2 100644 --- a/third_party/acados/include/acados/ocp_qp/ocp_qp_ooqp.h +++ b/third_party/acados/include/acados/ocp_qp/ocp_qp_ooqp.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * diff --git a/third_party/acados/include/acados/ocp_qp/ocp_qp_osqp.h b/third_party/acados/include/acados/ocp_qp/ocp_qp_osqp.h index 4ae391a9f..51df1b1cd 100644 --- a/third_party/acados/include/acados/ocp_qp/ocp_qp_osqp.h +++ b/third_party/acados/include/acados/ocp_qp/ocp_qp_osqp.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * diff --git a/third_party/acados/include/acados/ocp_qp/ocp_qp_partial_condensing.h b/third_party/acados/include/acados/ocp_qp/ocp_qp_partial_condensing.h index b95a11114..844f6048f 100644 --- a/third_party/acados/include/acados/ocp_qp/ocp_qp_partial_condensing.h +++ b/third_party/acados/include/acados/ocp_qp/ocp_qp_partial_condensing.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * diff --git a/third_party/acados/include/acados/ocp_qp/ocp_qp_qpdunes.h b/third_party/acados/include/acados/ocp_qp/ocp_qp_qpdunes.h index ad4d09451..3b875caeb 100644 --- a/third_party/acados/include/acados/ocp_qp/ocp_qp_qpdunes.h +++ b/third_party/acados/include/acados/ocp_qp/ocp_qp_qpdunes.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * diff --git a/third_party/acados/include/acados/ocp_qp/ocp_qp_xcond_solver.h b/third_party/acados/include/acados/ocp_qp/ocp_qp_xcond_solver.h index d4b30e007..a78bc65bb 100644 --- a/third_party/acados/include/acados/ocp_qp/ocp_qp_xcond_solver.h +++ b/third_party/acados/include/acados/ocp_qp/ocp_qp_xcond_solver.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * @@ -84,6 +81,7 @@ typedef struct acados_size_t (*dims_calculate_size)(void *config, int N); ocp_qp_xcond_solver_dims *(*dims_assign)(void *config, int N, void *raw_memory); void (*dims_set)(void *config_, ocp_qp_xcond_solver_dims *dims, int stage, const char *field, int* value); + void (*dims_get)(void *config_, ocp_qp_xcond_solver_dims *dims, int stage, const char *field, int* value); acados_size_t (*opts_calculate_size)(void *config, ocp_qp_xcond_solver_dims *dims); void *(*opts_assign)(void *config, ocp_qp_xcond_solver_dims *dims, void *raw_memory); void (*opts_initialize_default)(void *config, ocp_qp_xcond_solver_dims *dims, void *opts); diff --git a/third_party/acados/include/acados/sim/sim_collocation_utils.h b/third_party/acados/include/acados/sim/sim_collocation_utils.h index 40a0b1c0c..045d165cb 100644 --- a/third_party/acados/include/acados/sim/sim_collocation_utils.h +++ b/third_party/acados/include/acados/sim/sim_collocation_utils.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * diff --git a/third_party/acados/include/acados/sim/sim_common.h b/third_party/acados/include/acados/sim/sim_common.h index 1838d76f8..c4bbd6ed2 100644 --- a/third_party/acados/include/acados/sim/sim_common.h +++ b/third_party/acados/include/acados/sim/sim_common.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * @@ -149,6 +146,8 @@ typedef struct bool jac_reuse; // Newton_scheme *scheme; + double newton_tol; // optinally used in implicit integrators + // workspace void *work; diff --git a/third_party/acados/include/acados/sim/sim_erk_integrator.h b/third_party/acados/include/acados/sim/sim_erk_integrator.h index 24a00c707..fd46cb4d9 100644 --- a/third_party/acados/include/acados/sim/sim_erk_integrator.h +++ b/third_party/acados/include/acados/sim/sim_erk_integrator.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * diff --git a/third_party/acados/include/acados/sim/sim_gnsf.h b/third_party/acados/include/acados/sim/sim_gnsf.h index 5524b384e..404532a73 100644 --- a/third_party/acados/include/acados/sim/sim_gnsf.h +++ b/third_party/acados/include/acados/sim/sim_gnsf.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * @@ -46,12 +43,12 @@ extern "C" { #include "acados/sim/sim_common.h" #include "blasfeo/include/blasfeo_common.h" -#include "blasfeo/include/blasfeo_d_aux.h" -#include "blasfeo/include/blasfeo_d_aux_ext_dep.h" -#include "blasfeo/include/blasfeo_d_blas.h" -#include "blasfeo/include/blasfeo_d_kernel.h" -#include "blasfeo/include/blasfeo_i_aux_ext_dep.h" -#include "blasfeo/include/blasfeo_target.h" +// #include "blasfeo/include/blasfeo_d_aux.h" +// #include "blasfeo/include/blasfeo_d_aux_ext_dep.h" +// #include "blasfeo/include/blasfeo_d_blas.h" +// #include "blasfeo/include/blasfeo_d_kernel.h" +// #include "blasfeo/include/blasfeo_i_aux_ext_dep.h" +// #include "blasfeo/include/blasfeo_target.h" /* GNSF - Generalized Nonlinear Static Feedback Model diff --git a/third_party/acados/include/acados/sim/sim_irk_integrator.h b/third_party/acados/include/acados/sim/sim_irk_integrator.h index 6851bacb3..5090aa0bb 100644 --- a/third_party/acados/include/acados/sim/sim_irk_integrator.h +++ b/third_party/acados/include/acados/sim/sim_irk_integrator.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * diff --git a/third_party/acados/include/acados/sim/sim_lifted_irk_integrator.h b/third_party/acados/include/acados/sim/sim_lifted_irk_integrator.h index 9ec2d97be..e60bb80eb 100644 --- a/third_party/acados/include/acados/sim/sim_lifted_irk_integrator.h +++ b/third_party/acados/include/acados/sim/sim_lifted_irk_integrator.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * diff --git a/third_party/acados/include/acados/utils/external_function_generic.h b/third_party/acados/include/acados/utils/external_function_generic.h index 021363f26..1e68dc155 100644 --- a/third_party/acados/include/acados/utils/external_function_generic.h +++ b/third_party/acados/include/acados/utils/external_function_generic.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * @@ -137,8 +134,8 @@ typedef struct int (*casadi_work)(int *, int *, int *, int *); const int *(*casadi_sparsity_in)(int); const int *(*casadi_sparsity_out)(int); - int (*casadi_n_in)(); - int (*casadi_n_out)(); + int (*casadi_n_in)(void); + int (*casadi_n_out)(void); double **args; double **res; double *w; @@ -195,8 +192,8 @@ typedef struct int (*casadi_work)(int *, int *, int *, int *); const int *(*casadi_sparsity_in)(int); const int *(*casadi_sparsity_out)(int); - int (*casadi_n_in)(); - int (*casadi_n_out)(); + int (*casadi_n_in)(void); + int (*casadi_n_out)(void); double **args; double **res; double *w; diff --git a/third_party/acados/include/acados/utils/math.h b/third_party/acados/include/acados/utils/math.h index fe1da875f..7156a8208 100644 --- a/third_party/acados/include/acados/utils/math.h +++ b/third_party/acados/include/acados/utils/math.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * @@ -42,6 +39,7 @@ extern "C" { #if defined(__MABX2__) double fmax(double a, double b); +int isnan(double x); #endif #define MIN(a,b) (((a)<(b))?(a):(b)) diff --git a/third_party/acados/include/acados/utils/mem.h b/third_party/acados/include/acados/utils/mem.h index 7b9efc5ed..681a371e3 100644 --- a/third_party/acados/include/acados/utils/mem.h +++ b/third_party/acados/include/acados/utils/mem.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * diff --git a/third_party/acados/include/acados/utils/print.h b/third_party/acados/include/acados/utils/print.h index f8568afb2..824d3cee2 100644 --- a/third_party/acados/include/acados/utils/print.h +++ b/third_party/acados/include/acados/utils/print.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * diff --git a/third_party/acados/include/acados/utils/strsep.h b/third_party/acados/include/acados/utils/strsep.h index 02f183559..62bdfb489 100644 --- a/third_party/acados/include/acados/utils/strsep.h +++ b/third_party/acados/include/acados/utils/strsep.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * diff --git a/third_party/acados/include/acados/utils/timing.h b/third_party/acados/include/acados/utils/timing.h index fe561d389..b0955932d 100644 --- a/third_party/acados/include/acados/utils/timing.h +++ b/third_party/acados/include/acados/utils/timing.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * diff --git a/third_party/acados/include/acados/utils/types.h b/third_party/acados/include/acados/utils/types.h index d3da0a86b..a27ef9e55 100644 --- a/third_party/acados/include/acados/utils/types.h +++ b/third_party/acados/include/acados/utils/types.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * @@ -78,7 +75,7 @@ typedef int (*casadi_function_t)(const double** arg, double** res, int* iw, doub enum return_values { ACADOS_SUCCESS, - ACADOS_FAILURE, + ACADOS_NAN_DETECTED, ACADOS_MAXITER, ACADOS_MINSTEP, ACADOS_QP_FAILURE, diff --git a/third_party/acados/include/acados_c/condensing_interface.h b/third_party/acados/include/acados_c/condensing_interface.h index 51fe82712..b4302078d 100644 --- a/third_party/acados/include/acados_c/condensing_interface.h +++ b/third_party/acados/include/acados_c/condensing_interface.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * diff --git a/third_party/acados/include/acados_c/dense_qp_interface.h b/third_party/acados/include/acados_c/dense_qp_interface.h index 4ecc77381..b3af4bf68 100644 --- a/third_party/acados/include/acados_c/dense_qp_interface.h +++ b/third_party/acados/include/acados_c/dense_qp_interface.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * @@ -41,7 +38,7 @@ extern "C" { #include "acados/dense_qp/dense_qp_common.h" -typedef enum { DENSE_QP_HPIPM, DENSE_QP_QORE, DENSE_QP_QPOASES, DENSE_QP_OOQP } dense_qp_solver_t; +typedef enum { DENSE_QP_HPIPM, DENSE_QP_QORE, DENSE_QP_QPOASES, DENSE_QP_OOQP, DENSE_QP_DAQP } dense_qp_solver_t; typedef struct { diff --git a/third_party/acados/include/acados_c/external_function_interface.h b/third_party/acados/include/acados_c/external_function_interface.h index 683897507..d4f52db85 100644 --- a/third_party/acados/include/acados_c/external_function_interface.h +++ b/third_party/acados/include/acados_c/external_function_interface.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * diff --git a/third_party/acados/include/acados_c/ocp_nlp_interface.h b/third_party/acados/include/acados_c/ocp_nlp_interface.h index 50bc0cf1a..dd3e596f8 100644 --- a/third_party/acados/include/acados_c/ocp_nlp_interface.h +++ b/third_party/acados/include/acados_c/ocp_nlp_interface.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * @@ -66,6 +63,7 @@ typedef enum { LINEAR_LS, NONLINEAR_LS, + CONVEX_OVER_NONLINEAR, EXTERNAL, INVALID_COST, } ocp_nlp_cost_t; @@ -246,6 +244,10 @@ ACADOS_SYMBOL_EXPORT int ocp_nlp_cost_model_set(ocp_nlp_config *config, ocp_nlp_ 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); +/// +ACADOS_SYMBOL_EXPORT void ocp_nlp_constraints_model_get(ocp_nlp_config *config, ocp_nlp_dims *dims, + ocp_nlp_in *in, int stage, const char *field, void *value); + /* out */ /// Constructs an output struct for the non-linear program. @@ -297,7 +299,7 @@ ACADOS_SYMBOL_EXPORT void ocp_nlp_constraint_dims_get_from_attr(ocp_nlp_config * 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); -void ocp_nlp_dynamics_dims_get_from_attr(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_out *out, +ACADOS_SYMBOL_EXPORT void ocp_nlp_qp_dims_get_from_attr(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_out *out, int stage, const char *field, int *dims_out); /* opts */ @@ -386,8 +388,6 @@ ACADOS_SYMBOL_EXPORT int ocp_nlp_precompute(ocp_nlp_solver *solver, ocp_nlp_in * /// \param nlp_out The output struct. 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); /// Computes the residuals. /// diff --git a/third_party/acados/include/acados_c/ocp_qp_interface.h b/third_party/acados/include/acados_c/ocp_qp_interface.h index 2582f142d..3dc3f1a53 100644 --- a/third_party/acados/include/acados_c/ocp_qp_interface.h +++ b/third_party/acados/include/acados_c/ocp_qp_interface.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * @@ -87,6 +84,11 @@ typedef enum { #else FULL_CONDENSING_QPOASES_NOT_AVAILABLE, #endif +#ifdef ACADOS_WITH_DAQP + FULL_CONDENSING_DAQP, +#else + FULL_CONDENSING_DAQP_NOT_AVAILABLE, +#endif #ifdef ACADOS_WITH_QORE FULL_CONDENSING_QORE, #else diff --git a/third_party/acados/include/acados_c/sim_interface.h b/third_party/acados/include/acados_c/sim_interface.h index 5dce6f153..09a05d699 100644 --- a/third_party/acados/include/acados_c/sim_interface.h +++ b/third_party/acados/include/acados_c/sim_interface.h @@ -1,8 +1,5 @@ /* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * Copyright (c) The acados authors. * * This file is part of acados. * diff --git a/third_party/acados/include/blasfeo/include/blasfeo_d_blas_api.h b/third_party/acados/include/blasfeo/include/blasfeo_d_blas_api.h index ff9e9d4c1..2eab1e409 100644 --- a/third_party/acados/include/blasfeo/include/blasfeo_d_blas_api.h +++ b/third_party/acados/include/blasfeo/include/blasfeo_d_blas_api.h @@ -50,18 +50,20 @@ #define BLASFEO_CBLAS_ENUM #ifdef FORTRAN_BLAS_API #ifndef CBLAS_H -enum CBLAS_ORDER {CblasRowMajor=101, CblasColMajor=102}; +enum CBLAS_LAYOUT {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}; +#define CBLAS_ORDER CBLAS_LAYOUT /* this for backward compatibility with CBLAS_ORDER */ #endif // CBLAS_H #else // FORTRAN_BLAS_API -enum BLASFEO_CBLAS_ORDER {BlasfeoCblasRowMajor=101, BlasfeoCblasColMajor=102}; +enum BLASFEO_CBLAS_LAYOUT {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}; +#define BLASFEO_CBLAS_ORDER BLASFEO_CBLAS_LAYOUT /* this for backward compatibility with BLASFEO_CBLAS_ORDER */ #endif // FORTRAN_BLAS_API #endif // BLASFEO_CBLAS_ENUM #endif // CBLAS_API @@ -151,15 +153,19 @@ void cblas_dswap(const int N, double *X, const int incX, double *Y, const int in // void cblas_dcopy(const int N, const double *X, const int incX, double *Y, const int incY); +// CBLAS 2 +// +void cblas_dgemv(const enum CBLAS_LAYOUT layout, const enum CBLAS_TRANSPOSE TransA, const int M, const int N, const int K, const double alpha, const double *A, const int lda, const double *X, const int incX, const double beta, 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_dgemm(const enum CBLAS_LAYOUT layout, 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_dsyrk(const enum CBLAS_LAYOUT layout, 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_dtrmm(const enum CBLAS_LAYOUT layout, 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); +void cblas_dtrsm(const enum CBLAS_LAYOUT layout, 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); @@ -240,15 +246,19 @@ void blasfeo_cblas_dswap(const int N, double *X, const int incX, double *Y, cons // void blasfeo_cblas_dcopy(const int N, const double *X, const int incX, double *Y, const int incY); +// CBLAS 2 +// +void blasfeo_cblas_dgemv(const enum BLASFEO_CBLAS_LAYOUT layout, const enum BLASFEO_CBLAS_TRANSPOSE TransA, const int M, const int N, const double alpha, const double *A, const int lda, const double *X, const int incX, const double beta, 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_dgemm(const enum BLASFEO_CBLAS_LAYOUT layout, 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_dsyrk(const enum BLASFEO_CBLAS_LAYOUT layout, 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_dtrmm(const enum BLASFEO_CBLAS_LAYOUT layout, 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); +void blasfeo_cblas_dtrsm(const enum BLASFEO_CBLAS_LAYOUT layout, 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); diff --git a/third_party/acados/include/blasfeo/include/blasfeo_target.h b/third_party/acados/include/blasfeo/include/blasfeo_target.h index 4ff4f307b..51f617a64 100644 --- a/third_party/acados/include/blasfeo/include/blasfeo_target.h +++ b/third_party/acados/include/blasfeo/include/blasfeo_target.h @@ -1,13 +1,13 @@ -#ifndef TARGET_ARMV8A_ARM_CORTEX_A57 -#define TARGET_ARMV8A_ARM_CORTEX_A57 +#ifndef TARGET_X64_INTEL_HASWELL +#define TARGET_X64_INTEL_HASWELL #endif #ifndef TARGET_NEED_FEATURE_AVX2 -/* #undef TARGET_NEED_FEATURE_AVX2 */ +#define TARGET_NEED_FEATURE_AVX2 1 #endif #ifndef TARGET_NEED_FEATURE_FMA -/* #undef TARGET_NEED_FEATURE_FMA */ +#define TARGET_NEED_FEATURE_FMA 1 #endif #ifndef TARGET_NEED_FEATURE_SSE3 @@ -27,11 +27,11 @@ #endif #ifndef TARGET_NEED_FEATURE_VFPv4 -#define TARGET_NEED_FEATURE_VFPv4 1 +/* #undef TARGET_NEED_FEATURE_VFPv4 */ #endif #ifndef TARGET_NEED_FEATURE_NEONv2 -#define TARGET_NEED_FEATURE_NEONv2 1 +/* #undef TARGET_NEED_FEATURE_NEONv2 */ #endif #ifndef LA_HIGH_PERFORMANCE diff --git a/third_party/acados/larch64/lib/libacados.so b/third_party/acados/larch64/lib/libacados.so index 35f83d415..9a28b4c9d 100644 Binary files a/third_party/acados/larch64/lib/libacados.so and b/third_party/acados/larch64/lib/libacados.so differ diff --git a/third_party/acados/larch64/lib/libblasfeo.so b/third_party/acados/larch64/lib/libblasfeo.so index 6b0e26de7..b97ed876e 100644 Binary files a/third_party/acados/larch64/lib/libblasfeo.so and b/third_party/acados/larch64/lib/libblasfeo.so differ diff --git a/third_party/acados/larch64/lib/libhpipm.so b/third_party/acados/larch64/lib/libhpipm.so index bebd5e891..cd4b1f1b5 100644 Binary files a/third_party/acados/larch64/lib/libhpipm.so and b/third_party/acados/larch64/lib/libhpipm.so differ diff --git a/third_party/acados/larch64/lib/libqpOASES_e.so.3.1 b/third_party/acados/larch64/lib/libqpOASES_e.so.3.1 index 0611c8a93..19e7a69bd 100644 Binary files a/third_party/acados/larch64/lib/libqpOASES_e.so.3.1 and b/third_party/acados/larch64/lib/libqpOASES_e.so.3.1 differ diff --git a/third_party/acados/larch64/t_renderer b/third_party/acados/larch64/t_renderer index b4ff8bc31..b6f70bde0 100755 Binary files a/third_party/acados/larch64/t_renderer and b/third_party/acados/larch64/t_renderer differ diff --git a/third_party/cluster/LICENSE b/third_party/cluster/LICENSE deleted file mode 100644 index ab8b4db7d..000000000 --- a/third_party/cluster/LICENSE +++ /dev/null @@ -1,13 +0,0 @@ -Copyright: - * fastcluster_dm.cpp & fastcluster_R_dm.cpp: - © 2011 Daniel Müllner - * fastcluster.(h|cpp) & demo.cpp & plotresult.r: - © 2018 Christoph Dalitz -All rights reserved. - -Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: - - * Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. - * 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 HOLDER 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. diff --git a/third_party/cluster/README b/third_party/cluster/README deleted file mode 100644 index acb18bc72..000000000 --- a/third_party/cluster/README +++ /dev/null @@ -1,79 +0,0 @@ -C++ interface to fast hierarchical clustering algorithms -======================================================== - -This is a simplified C++ interface to fast implementations of hierarchical -clustering by Daniel Müllner. The original library with interfaces to R -and Python is described in: - -Daniel Müllner: "fastcluster: Fast Hierarchical, Agglomerative Clustering -Routines for R and Python." Journal of Statistical Software 53 (2013), -no. 9, pp. 1–18, http://www.jstatsoft.org/v53/i09/ - - -Usage of the library --------------------- - -For using the library, the following source files are needed: - -fastcluster_dm.cpp, fastcluster_R_dm.cpp - original code by Daniel Müllner - these are included by fastcluster.cpp via #include, and therefore - need not be compiled to object code - -fastcluster.[h|cpp] - simplified C++ interface - fastcluster.cpp is the only file that must be compiled - -The library provides the clustering function *hclust_fast* for -creating the dendrogram information in an encoding as used by the -R function *hclust*. For a description of the parameters, see fastcluster.h. -Its parameter *method* can be one of - -HCLUST_METHOD_SINGLE - single link with the minimum spanning tree algorithm (Rohlf, 1973) - -HHCLUST_METHOD_COMPLETE - complete link with the nearest-neighbor-chain algorithm (Murtagh, 1984) - -HCLUST_METHOD_AVERAGE - complete link with the nearest-neighbor-chain algorithm (Murtagh, 1984) - -HCLUST_METHOD_MEDIAN - median link with the generic algorithm (Müllner, 2011) - -For splitting the dendrogram into clusters, the two functions *cutree_k* -and *cutree_cdist* are provided. - -Note that output parameters must be allocated beforehand, e.g. - int* merge = new int[2*(npoints-1)]; -For a complete usage example, see lines 135-142 of demo.cpp. - - -Demonstration program ---------------------- - -A simple demo is implemented in demo.cpp, which can be compiled and run with - - make - ./hclust-demo -m complete lines.csv - -It creates two clusters of line segments such that the segment angle between -line segments of different clusters have a maximum (cosine) dissimilarity. -For visualizing the result, plotresult.r can be used as follows -(requires R to be installed): - - ./hclust-demo -m complete lines.csv | Rscript plotresult.r - - -Authors & Copyright -------------------- - -Daniel Müllner, 2011, -Christoph Dalitz, 2018, - - -License -------- - -This code is provided under a BSD-style license. -See the file LICENSE for details. diff --git a/third_party/cluster/__init__.py b/third_party/cluster/__init__.py deleted file mode 100644 index e69de29bb..000000000 diff --git a/third_party/cluster/fastcluster.cpp b/third_party/cluster/fastcluster.cpp deleted file mode 100644 index d2b557d6f..000000000 --- a/third_party/cluster/fastcluster.cpp +++ /dev/null @@ -1,218 +0,0 @@ -// -// C++ standalone verion of fastcluster by Daniel Müllner -// -// Copyright: Christoph Dalitz, 2018 -// Daniel Müllner, 2011 -// License: BSD style license -// (see the file LICENSE for details) -// - - -#include -#include -#include - - -extern "C" { -#include "fastcluster.h" -} - -// Code by Daniel Müllner -// workaround to make it usable as a standalone version (without R) -bool fc_isnan(double x) { return false; } -#include "fastcluster_dm.cpp" -#include "fastcluster_R_dm.cpp" - -extern "C" { -// -// Assigns cluster labels (0, ..., nclust-1) to the n points such -// that the cluster result is split into nclust clusters. -// -// Input arguments: -// n = number of observables -// merge = clustering result in R format -// nclust = number of clusters -// Output arguments: -// labels = allocated integer array of size n for result -// - void cutree_k(int n, const int* merge, int nclust, int* labels) { - - int k,m1,m2,j,l; - - if (nclust > n || nclust < 2) { - for (j=0; j last_merge(n, 0); - for (k=1; k<=(n-nclust); k++) { - // (m1,m2) = merge[k,] - m1 = merge[k-1]; - m2 = merge[n-1+k-1]; - if (m1 < 0 && m2 < 0) { // both single observables - last_merge[-m1-1] = last_merge[-m2-1] = k; - } - else if (m1 < 0 || m2 < 0) { // one is a cluster - if(m1 < 0) { j = -m1; m1 = m2; } else j = -m2; - // merging single observable and cluster - for(l = 0; l < n; l++) - if (last_merge[l] == m1) - last_merge[l] = k; - last_merge[j-1] = k; - } - else { // both cluster - for(l=0; l < n; l++) { - if( last_merge[l] == m1 || last_merge[l] == m2 ) - last_merge[l] = k; - } - } - } - - // assign cluster labels - int label = 0; - std::vector z(n,-1); - for (j=0; j= cdist - // - // Input arguments: - // n = number of observables - // merge = clustering result in R format - // height = cluster distance at each merge step - // cdist = cutoff cluster distance - // Output arguments: - // labels = allocated integer array of size n for result - // - void cutree_cdist(int n, const int* merge, double* height, double cdist, int* labels) { - - int k; - - for (k=0; k<(n-1); k++) { - if (height[k] >= cdist) { - break; - } - } - cutree_k(n, merge, n-k, labels); - } - - - // - // Hierarchical clustering with one of Daniel Muellner's fast algorithms - // - // Input arguments: - // n = number of observables - // distmat = condensed distance matrix, i.e. an n*(n-1)/2 array representing - // the upper triangle (without diagonal elements) of the distance - // matrix, e.g. for n=4: - // d00 d01 d02 d03 - // d10 d11 d12 d13 -> d01 d02 d03 d12 d13 d23 - // d20 d21 d22 d23 - // d30 d31 d32 d33 - // method = cluster metric (see enum method_code) - // Output arguments: - // merge = allocated (n-1)x2 matrix (2*(n-1) array) for storing result. - // Result follows R hclust convention: - // - observabe indices start with one - // - merge[i][] contains the merged nodes in step i - // - merge[i][j] is negative when the node is an atom - // height = allocated (n-1) array with distances at each merge step - // Return code: - // 0 = ok - // 1 = invalid method - // - int hclust_fast(int n, double* distmat, int method, int* merge, double* height) { - - // call appropriate culstering function - cluster_result Z2(n-1); - if (method == HCLUST_METHOD_SINGLE) { - // single link - MST_linkage_core(n, distmat, Z2); - } - else if (method == HCLUST_METHOD_COMPLETE) { - // complete link - NN_chain_core(n, distmat, NULL, Z2); - } - else if (method == HCLUST_METHOD_AVERAGE) { - // best average distance - double* members = new double[n]; - for (int i=0; i(n, distmat, members, Z2); - delete[] members; - } - else if (method == HCLUST_METHOD_MEDIAN) { - // best median distance (beware: O(n^3)) - generic_linkage(n, distmat, NULL, Z2); - } - else if (method == HCLUST_METHOD_CENTROID) { - // best centroid distance (beware: O(n^3)) - double* members = new double[n]; - for (int i=0; i(n, distmat, members, Z2); - delete[] members; - } - else { - return 1; - } - - int* order = new int[n]; - if (method == HCLUST_METHOD_MEDIAN || method == HCLUST_METHOD_CENTROID) { - generate_R_dendrogram(merge, height, order, Z2, n); - } else { - generate_R_dendrogram(merge, height, order, Z2, n); - } - delete[] order; // only needed for visualization - - return 0; - } - - - // Build condensed distance matrix - // Input arguments: - // n = number of observables - // m = dimension of observable - // Output arguments: - // out = allocated integer array of size n * (n - 1) / 2 for result - void hclust_pdist(int n, int m, double* pts, double* out) { - int ii = 0; - for (int i = 0; i < n; i++) { - for (int j = i + 1; j < n; j++) { - // Compute euclidian distance - double d = 0; - for (int k = 0; k < m; k ++) { - double error = pts[i * m + k] - pts[j * m + k]; - d += (error * error); - } - out[ii] = d;//sqrt(d); - ii++; - } - } - } - - void cluster_points_centroid(int n, int m, double* pts, double dist, int* idx) { - double* pdist = new double[n * (n - 1) / 2]; - int* merge = new int[2 * (n - 1)]; - double* height = new double[n - 1]; - - hclust_pdist(n, m, pts, pdist); - hclust_fast(n, pdist, HCLUST_METHOD_CENTROID, merge, height); - cutree_cdist(n, merge, height, dist, idx); - - delete[] pdist; - delete[] merge; - delete[] height; - } -} diff --git a/third_party/cluster/fastcluster.h b/third_party/cluster/fastcluster.h deleted file mode 100644 index 56c63b6a5..000000000 --- a/third_party/cluster/fastcluster.h +++ /dev/null @@ -1,77 +0,0 @@ -// -// C++ standalone verion of fastcluster by Daniel Muellner -// -// Copyright: Daniel Muellner, 2011 -// Christoph Dalitz, 2018 -// License: BSD style license -// (see the file LICENSE for details) -// - -#ifndef fastclustercpp_H -#define fastclustercpp_H - -// -// Assigns cluster labels (0, ..., nclust-1) to the n points such -// that the cluster result is split into nclust clusters. -// -// Input arguments: -// n = number of observables -// merge = clustering result in R format -// nclust = number of clusters -// Output arguments: -// labels = allocated integer array of size n for result -// -void cutree_k(int n, const int* merge, int nclust, int* labels); - -// -// Assigns cluster labels (0, ..., nclust-1) to the n points such -// that the hierarchical clsutering is stopped at cluster distance cdist -// -// Input arguments: -// n = number of observables -// merge = clustering result in R format -// height = cluster distance at each merge step -// cdist = cutoff cluster distance -// Output arguments: -// labels = allocated integer array of size n for result -// -void cutree_cdist(int n, const int* merge, double* height, double cdist, int* labels); - -// -// Hierarchical clustering with one of Daniel Muellner's fast algorithms -// -// Input arguments: -// n = number of observables -// distmat = condensed distance matrix, i.e. an n*(n-1)/2 array representing -// the upper triangle (without diagonal elements) of the distance -// matrix, e.g. for n=4: -// d00 d01 d02 d03 -// d10 d11 d12 d13 -> d01 d02 d03 d12 d13 d23 -// d20 d21 d22 d23 -// d30 d31 d32 d33 -// method = cluster metric (see enum method_code) -// Output arguments: -// merge = allocated (n-1)x2 matrix (2*(n-1) array) for storing result. -// Result follows R hclust convention: -// - observabe indices start with one -// - merge[i][] contains the merged nodes in step i -// - merge[i][j] is negative when the node is an atom -// height = allocated (n-1) array with distances at each merge step -// Return code: -// 0 = ok -// 1 = invalid method -// -int hclust_fast(int n, double* distmat, int method, int* merge, double* height); -enum hclust_fast_methods { - HCLUST_METHOD_SINGLE = 0, - HCLUST_METHOD_COMPLETE = 1, - HCLUST_METHOD_AVERAGE = 2, - HCLUST_METHOD_MEDIAN = 3, - HCLUST_METHOD_CENTROID = 5, -}; - -void hclust_pdist(int n, int m, double* pts, double* out); -void cluster_points_centroid(int n, int m, double* pts, double dist, int* idx); - - -#endif diff --git a/third_party/cluster/fastcluster.os b/third_party/cluster/fastcluster.os deleted file mode 100644 index 81ae1ea4f..000000000 Binary files a/third_party/cluster/fastcluster.os and /dev/null differ diff --git a/third_party/cluster/fastcluster_R_dm.cpp b/third_party/cluster/fastcluster_R_dm.cpp deleted file mode 100644 index cbe126c15..000000000 --- a/third_party/cluster/fastcluster_R_dm.cpp +++ /dev/null @@ -1,115 +0,0 @@ -// -// Excerpt from fastcluster_R.cpp -// -// Copyright: Daniel Müllner, 2011 -// - -struct pos_node { - t_index pos; - int node; -}; - -void order_nodes(const int N, const int * const merge, const t_index * const node_size, int * const order) { - /* Parameters: - N : number of data points - merge : (N-1)×2 array which specifies the node indices which are - merged in each step of the clustering procedure. - Negative entries -1...-N point to singleton nodes, while - positive entries 1...(N-1) point to nodes which are themselves - parents of other nodes. - node_size : array of node sizes - makes it easier - order : output array of size N - - Runtime: Θ(N) - */ - auto_array_ptr queue(N/2); - - int parent; - int child; - t_index pos = 0; - - queue[0].pos = 0; - queue[0].node = N-2; - t_index idx = 1; - - do { - --idx; - pos = queue[idx].pos; - parent = queue[idx].node; - - // First child - child = merge[parent]; - if (child<0) { // singleton node, write this into the 'order' array. - order[pos] = -child; - ++pos; - } - else { /* compound node: put it on top of the queue and decompose it - in a later iteration. */ - queue[idx].pos = pos; - queue[idx].node = child-1; // convert index-1 based to index-0 based - ++idx; - pos += node_size[child-1]; - } - // Second child - child = merge[parent+N-1]; - if (child<0) { - order[pos] = -child; - } - else { - queue[idx].pos = pos; - queue[idx].node = child-1; - ++idx; - } - } while (idx>0); -} - -#define size_(r_) ( ((r_ -void generate_R_dendrogram(int * const merge, double * const height, int * const order, cluster_result & Z2, const int N) { - // The array "nodes" is a union-find data structure for the cluster - // identites (only needed for unsorted cluster_result input). - union_find nodes(sorted ? 0 : N); - if (!sorted) { - std::stable_sort(Z2[0], Z2[N-1]); - } - - t_index node1, node2; - auto_array_ptr node_size(N-1); - - for (t_index i=0; inode1; - node2 = Z2[i]->node2; - } - else { - node1 = nodes.Find(Z2[i]->node1); - node2 = nodes.Find(Z2[i]->node2); - // Merge the nodes in the union-find data structure by making them - // children of a new node. - nodes.Union(node1, node2); - } - // Sort the nodes in the output array. - if (node1>node2) { - t_index tmp = node1; - node1 = node2; - node2 = tmp; - } - /* Conversion between labeling conventions. - Input: singleton nodes 0,...,N-1 - compound nodes N,...,2N-2 - Output: singleton nodes -1,...,-N - compound nodes 1,...,N - */ - merge[i] = (node1(node1)-1 - : static_cast(node1)-N+1; - merge[i+N-1] = (node2(node2)-1 - : static_cast(node2)-N+1; - height[i] = Z2[i]->dist; - node_size[i] = size_(node1) + size_(node2); - } - - order_nodes(N, merge, node_size, order); -} diff --git a/third_party/cluster/fastcluster_dm.cpp b/third_party/cluster/fastcluster_dm.cpp deleted file mode 100644 index ee6670c20..000000000 --- a/third_party/cluster/fastcluster_dm.cpp +++ /dev/null @@ -1,1794 +0,0 @@ -/* - fastcluster: Fast hierarchical clustering routines for R and Python - - Copyright © 2011 Daniel Müllner - - - This library implements various fast algorithms for hierarchical, - agglomerative clustering methods: - - (1) Algorithms for the "stored matrix approach": the input is the array of - pairwise dissimilarities. - - MST_linkage_core: single linkage clustering with the "minimum spanning - tree algorithm (Rohlfs) - - NN_chain_core: nearest-neighbor-chain algorithm, suitable for single, - complete, average, weighted and Ward linkage (Murtagh) - - generic_linkage: generic algorithm, suitable for all distance update - formulas (Müllner) - - (2) Algorithms for the "stored data approach": the input are points in a - vector space. - - MST_linkage_core_vector: single linkage clustering for vector data - - generic_linkage_vector: generic algorithm for vector data, suitable for - the Ward, centroid and median methods. - - generic_linkage_vector_alternative: alternative scheme for updating the - nearest neighbors. This method seems faster than "generic_linkage_vector" - for the centroid and median methods but slower for the Ward method. - - All these implementation treat infinity values correctly. They throw an - exception if a NaN distance value occurs. -*/ - -// Older versions of Microsoft Visual Studio do not have the fenv header. -#ifdef _MSC_VER -#if (_MSC_VER == 1500 || _MSC_VER == 1600) -#define NO_INCLUDE_FENV -#endif -#endif -// NaN detection via fenv might not work on systems with software -// floating-point emulation (bug report for Debian armel). -#ifdef __SOFTFP__ -#define NO_INCLUDE_FENV -#endif -#ifdef NO_INCLUDE_FENV -#pragma message("Do not use fenv header.") -#else -//#pragma message("Use fenv header. If there is a warning about unknown #pragma STDC FENV_ACCESS, this can be ignored.") -//#pragma STDC FENV_ACCESS on -#include -#endif - -#include // for std::pow, std::sqrt -#include // for std::ptrdiff_t -#include // for std::numeric_limits<...>::infinity() -#include // for std::fill_n -#include // for std::runtime_error -#include // for std::string - -#include // also for DBL_MAX, DBL_MIN -#ifndef DBL_MANT_DIG -#error The constant DBL_MANT_DIG could not be defined. -#endif -#define T_FLOAT_MANT_DIG DBL_MANT_DIG - -#ifndef LONG_MAX -#include -#endif -#ifndef LONG_MAX -#error The constant LONG_MAX could not be defined. -#endif -#ifndef INT_MAX -#error The constant INT_MAX could not be defined. -#endif - -#ifndef INT32_MAX -#ifdef _MSC_VER -#if _MSC_VER >= 1600 -#define __STDC_LIMIT_MACROS -#include -#else -typedef __int32 int_fast32_t; -typedef __int64 int64_t; -#endif -#else -#define __STDC_LIMIT_MACROS -#include -#endif -#endif - -#define FILL_N std::fill_n -#ifdef _MSC_VER -#if _MSC_VER < 1600 -#undef FILL_N -#define FILL_N stdext::unchecked_fill_n -#endif -#endif - -// Suppress warnings about (potentially) uninitialized variables. -#ifdef _MSC_VER - #pragma warning (disable:4700) -#endif - -#ifndef HAVE_DIAGNOSTIC -#if __GNUC__ > 4 || (__GNUC__ == 4 && (__GNUC_MINOR__ >= 6)) -#define HAVE_DIAGNOSTIC 1 -#endif -#endif - -#ifndef HAVE_VISIBILITY -#if __GNUC__ >= 4 -#define HAVE_VISIBILITY 1 -#endif -#endif - -/* Since the public interface is given by the Python respectively R interface, - * we do not want other symbols than the interface initalization routines to be - * visible in the shared object file. The "visibility" switch is a GCC concept. - * Hiding symbols keeps the relocation table small and decreases startup time. - * See http://gcc.gnu.org/wiki/Visibility - */ -#if HAVE_VISIBILITY -#pragma GCC visibility push(hidden) -#endif - -typedef int_fast32_t t_index; -#ifndef INT32_MAX -#define MAX_INDEX 0x7fffffffL -#else -#define MAX_INDEX INT32_MAX -#endif -#if (LONG_MAX < MAX_INDEX) -#error The integer format "t_index" must not have a greater range than "long int". -#endif -#if (INT_MAX > MAX_INDEX) -#error The integer format "int" must not have a greater range than "t_index". -#endif -typedef double t_float; - -/* Method codes. - - These codes must agree with the METHODS array in fastcluster.R and the - dictionary mthidx in fastcluster.py. -*/ -enum method_codes { - // non-Euclidean methods - METHOD_METR_SINGLE = 0, - METHOD_METR_COMPLETE = 1, - METHOD_METR_AVERAGE = 2, - METHOD_METR_WEIGHTED = 3, - METHOD_METR_WARD = 4, - METHOD_METR_WARD_D = METHOD_METR_WARD, - METHOD_METR_CENTROID = 5, - METHOD_METR_MEDIAN = 6, - METHOD_METR_WARD_D2 = 7, - - MIN_METHOD_CODE = 0, - MAX_METHOD_CODE = 7 -}; - -enum method_codes_vector { - // Euclidean methods - METHOD_VECTOR_SINGLE = 0, - METHOD_VECTOR_WARD = 1, - METHOD_VECTOR_CENTROID = 2, - METHOD_VECTOR_MEDIAN = 3, - - MIN_METHOD_VECTOR_CODE = 0, - MAX_METHOD_VECTOR_CODE = 3 -}; - -// self-destructing array pointer -template -class auto_array_ptr{ -private: - type * ptr; - auto_array_ptr(auto_array_ptr const &); // non construction-copyable - auto_array_ptr& operator=(auto_array_ptr const &); // non copyable -public: - auto_array_ptr() - : ptr(NULL) - { } - template - auto_array_ptr(index const size) - : ptr(new type[size]) - { } - template - auto_array_ptr(index const size, value const val) - : ptr(new type[size]) - { - FILL_N(ptr, size, val); - } - ~auto_array_ptr() { - delete [] ptr; } - void free() { - delete [] ptr; - ptr = NULL; - } - template - void init(index const size) { - ptr = new type [size]; - } - template - void init(index const size, value const val) { - init(size); - FILL_N(ptr, size, val); - } - inline operator type *() const { return ptr; } -}; - -struct node { - t_index node1, node2; - t_float dist; -}; - -inline bool operator< (const node a, const node b) { - return (a.dist < b.dist); -} - -class cluster_result { -private: - auto_array_ptr Z; - t_index pos; - -public: - cluster_result(const t_index size) - : Z(size) - , pos(0) - {} - - void append(const t_index node1, const t_index node2, const t_float dist) { - Z[pos].node1 = node1; - Z[pos].node2 = node2; - Z[pos].dist = dist; - ++pos; - } - - node * operator[] (const t_index idx) const { return Z + idx; } - - /* Define several methods to postprocess the distances. All these functions - are monotone, so they do not change the sorted order of distances. */ - - void sqrt() const { - for (node * ZZ=Z; ZZ!=Z+pos; ++ZZ) { - ZZ->dist = std::sqrt(ZZ->dist); - } - } - - void sqrt(const t_float) const { // ignore the argument - sqrt(); - } - - void sqrtdouble(const t_float) const { // ignore the argument - for (node * ZZ=Z; ZZ!=Z+pos; ++ZZ) { - ZZ->dist = std::sqrt(2*ZZ->dist); - } - } - - #ifdef R_pow - #define my_pow R_pow - #else - #define my_pow std::pow - #endif - - void power(const t_float p) const { - t_float const q = 1/p; - for (node * ZZ=Z; ZZ!=Z+pos; ++ZZ) { - ZZ->dist = my_pow(ZZ->dist,q); - } - } - - void plusone(const t_float) const { // ignore the argument - for (node * ZZ=Z; ZZ!=Z+pos; ++ZZ) { - ZZ->dist += 1; - } - } - - void divide(const t_float denom) const { - for (node * ZZ=Z; ZZ!=Z+pos; ++ZZ) { - ZZ->dist /= denom; - } - } -}; - -class doubly_linked_list { - /* - Class for a doubly linked list. Initially, the list is the integer range - [0, size]. We provide a forward iterator and a method to delete an index - from the list. - - Typical use: for (i=L.start; L succ; - -private: - auto_array_ptr pred; - // Not necessarily private, we just do not need it in this instance. - -public: - doubly_linked_list(const t_index size) - // Initialize to the given size. - : start(0) - , succ(size+1) - , pred(size+1) - { - for (t_index i=0; i(2*N-3-(r_))*(r_)>>1)+(c_)-1] ) -// Z is an ((N-1)x4)-array -#define Z_(_r, _c) (Z[(_r)*4 + (_c)]) - -/* - Lookup function for a union-find data structure. - - The function finds the root of idx by going iteratively through all - parent elements until a root is found. An element i is a root if - nodes[i] is zero. To make subsequent searches faster, the entry for - idx and all its parents is updated with the root element. - */ -class union_find { -private: - auto_array_ptr parent; - t_index nextparent; - -public: - union_find(const t_index size) - : parent(size>0 ? 2*size-1 : 0, 0) - , nextparent(size) - { } - - t_index Find (t_index idx) const { - if (parent[idx] != 0 ) { // a → b - t_index p = idx; - idx = parent[idx]; - if (parent[idx] != 0 ) { // a → b → c - do { - idx = parent[idx]; - } while (parent[idx] != 0); - do { - t_index tmp = parent[p]; - parent[p] = idx; - p = tmp; - } while (parent[p] != idx); - } - } - return idx; - } - - void Union (const t_index node1, const t_index node2) { - parent[node1] = parent[node2] = nextparent++; - } -}; - -class nan_error{}; -#ifdef FE_INVALID -class fenv_error{}; -#endif - -static void MST_linkage_core(const t_index N, const t_float * const D, - cluster_result & Z2) { -/* - N: integer, number of data points - D: condensed distance matrix N*(N-1)/2 - Z2: output data structure - - The basis of this algorithm is an algorithm by Rohlf: - - F. James Rohlf, Hierarchical clustering using the minimum spanning tree, - The Computer Journal, vol. 16, 1973, p. 93–95. -*/ - t_index i; - t_index idx2; - doubly_linked_list active_nodes(N); - auto_array_ptr d(N); - - t_index prev_node; - t_float min; - - // first iteration - idx2 = 1; - min = std::numeric_limits::infinity(); - for (i=1; i tmp) - d[i] = tmp; - else if (fc_isnan(tmp)) - throw (nan_error()); -#if HAVE_DIAGNOSTIC -#pragma GCC diagnostic pop -#endif - if (d[i] < min) { - min = d[i]; - idx2 = i; - } - } - Z2.append(prev_node, idx2, min); - } -} - -/* Functions for the update of the dissimilarity array */ - -inline static void f_single( t_float * const b, const t_float a ) { - if (*b > a) *b = a; -} -inline static void f_complete( t_float * const b, const t_float a ) { - if (*b < a) *b = a; -} -inline static void f_average( t_float * const b, const t_float a, const t_float s, const t_float t) { - *b = s*a + t*(*b); - #ifndef FE_INVALID -#if HAVE_DIAGNOSTIC -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wfloat-equal" -#endif - if (fc_isnan(*b)) { - throw(nan_error()); - } -#if HAVE_DIAGNOSTIC -#pragma GCC diagnostic pop -#endif - #endif -} -inline static void f_weighted( t_float * const b, const t_float a) { - *b = (a+*b)*.5; - #ifndef FE_INVALID -#if HAVE_DIAGNOSTIC -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wfloat-equal" -#endif - if (fc_isnan(*b)) { - throw(nan_error()); - } -#if HAVE_DIAGNOSTIC -#pragma GCC diagnostic pop -#endif - #endif -} -inline static void f_ward( t_float * const b, const t_float a, const t_float c, const t_float s, const t_float t, const t_float v) { - *b = ( (v+s)*a - v*c + (v+t)*(*b) ) / (s+t+v); - //*b = a+(*b)-(t*a+s*(*b)+v*c)/(s+t+v); - #ifndef FE_INVALID -#if HAVE_DIAGNOSTIC -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wfloat-equal" -#endif - if (fc_isnan(*b)) { - throw(nan_error()); - } -#if HAVE_DIAGNOSTIC -#pragma GCC diagnostic pop -#endif - #endif -} -inline static void f_centroid( t_float * const b, const t_float a, const t_float stc, const t_float s, const t_float t) { - *b = s*a - stc + t*(*b); - #ifndef FE_INVALID - if (fc_isnan(*b)) { - throw(nan_error()); - } -#if HAVE_DIAGNOSTIC -#pragma GCC diagnostic pop -#endif - #endif -} -inline static void f_median( t_float * const b, const t_float a, const t_float c_4) { - *b = (a+(*b))*.5 - c_4; - #ifndef FE_INVALID -#if HAVE_DIAGNOSTIC -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wfloat-equal" -#endif - if (fc_isnan(*b)) { - throw(nan_error()); - } -#if HAVE_DIAGNOSTIC -#pragma GCC diagnostic pop -#endif - #endif -} - -template -static void NN_chain_core(const t_index N, t_float * const D, t_members * const members, cluster_result & Z2) { -/* - N: integer - D: condensed distance matrix N*(N-1)/2 - Z2: output data structure - - This is the NN-chain algorithm, described on page 86 in the following book: - - Fionn Murtagh, Multidimensional Clustering Algorithms, - Vienna, Würzburg: Physica-Verlag, 1985. -*/ - t_index i; - - auto_array_ptr NN_chain(N); - t_index NN_chain_tip = 0; - - t_index idx1, idx2; - - t_float size1, size2; - doubly_linked_list active_nodes(N); - - t_float min; - - for (t_float const * DD=D; DD!=D+(static_cast(N)*(N-1)>>1); - ++DD) { -#if HAVE_DIAGNOSTIC -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wfloat-equal" -#endif - if (fc_isnan(*DD)) { - throw(nan_error()); - } -#if HAVE_DIAGNOSTIC -#pragma GCC diagnostic pop -#endif - } - - #ifdef FE_INVALID - if (feclearexcept(FE_INVALID)) throw fenv_error(); - #endif - - for (t_index j=0; jidx2) { - t_index tmp = idx1; - idx1 = idx2; - idx2 = tmp; - } - - if (method==METHOD_METR_AVERAGE || - method==METHOD_METR_WARD) { - size1 = static_cast(members[idx1]); - size2 = static_cast(members[idx2]); - members[idx2] += members[idx1]; - } - - // Remove the smaller index from the valid indices (active_nodes). - active_nodes.remove(idx1); - - switch (method) { - case METHOD_METR_SINGLE: - /* - Single linkage. - - Characteristic: new distances are never longer than the old distances. - */ - // Update the distance matrix in the range [start, idx1). - for (i=active_nodes.start; i(members[i]); - for (i=active_nodes.start; i(members[i]) ); - // Update the distance matrix in the range (idx1, idx2). - for (; i(members[i]) ); - // Update the distance matrix in the range (idx2, N). - for (i=active_nodes.succ[idx2]; i(members[i]) ); - break; - - default: - throw std::runtime_error(std::string("Invalid method.")); - } - } - #ifdef FE_INVALID - if (fetestexcept(FE_INVALID)) throw fenv_error(); - #endif -} - -class binary_min_heap { - /* - Class for a binary min-heap. The data resides in an array A. The elements of - A are not changed but two lists I and R of indices are generated which point - to elements of A and backwards. - - The heap tree structure is - - H[2*i+1] H[2*i+2] - \ / - \ / - ≤ ≤ - \ / - \ / - H[i] - - where the children must be less or equal than their parent. Thus, H[0] - contains the minimum. The lists I and R are made such that H[i] = A[I[i]] - and R[I[i]] = i. - - This implementation is not designed to handle NaN values. - */ -private: - t_float * const A; - t_index size; - auto_array_ptr I; - auto_array_ptr R; - - // no default constructor - binary_min_heap(); - // noncopyable - binary_min_heap(binary_min_heap const &); - binary_min_heap & operator=(binary_min_heap const &); - -public: - binary_min_heap(t_float * const A_, const t_index size_) - : A(A_), size(size_), I(size), R(size) - { // Allocate memory and initialize the lists I and R to the identity. This - // does not make it a heap. Call heapify afterwards! - for (t_index i=0; i>1); idx>0; ) { - --idx; - update_geq_(idx); - } - } - - inline t_index argmin() const { - // Return the minimal element. - return I[0]; - } - - void heap_pop() { - // Remove the minimal element from the heap. - --size; - I[0] = I[size]; - R[I[0]] = 0; - update_geq_(0); - } - - void remove(t_index idx) { - // Remove an element from the heap. - --size; - R[I[size]] = R[idx]; - I[R[idx]] = I[size]; - if ( H(size)<=A[idx] ) { - update_leq_(R[idx]); - } - else { - update_geq_(R[idx]); - } - } - - void replace ( const t_index idxold, const t_index idxnew, - const t_float val) { - R[idxnew] = R[idxold]; - I[R[idxnew]] = idxnew; - if (val<=A[idxold]) - update_leq(idxnew, val); - else - update_geq(idxnew, val); - } - - void update ( const t_index idx, const t_float val ) const { - // Update the element A[i] with val and re-arrange the indices to preserve - // the heap condition. - if (val<=A[idx]) - update_leq(idx, val); - else - update_geq(idx, val); - } - - void update_leq ( const t_index idx, const t_float val ) const { - // Use this when the new value is not more than the old value. - A[idx] = val; - update_leq_(R[idx]); - } - - void update_geq ( const t_index idx, const t_float val ) const { - // Use this when the new value is not less than the old value. - A[idx] = val; - update_geq_(R[idx]); - } - -private: - void update_leq_ (t_index i) const { - t_index j; - for ( ; (i>0) && ( H(i)>1) ); i=j) - heap_swap(i,j); - } - - void update_geq_ (t_index i) const { - t_index j; - for ( ; (j=2*i+1)=H(i) ) { - ++j; - if ( j>=size || H(j)>=H(i) ) break; - } - else if ( j+1 -static void generic_linkage(const t_index N, t_float * const D, t_members * const members, cluster_result & Z2) { - /* - N: integer, number of data points - D: condensed distance matrix N*(N-1)/2 - Z2: output data structure - */ - - const t_index N_1 = N-1; - t_index i, j; // loop variables - t_index idx1, idx2; // row and column indices - - auto_array_ptr n_nghbr(N_1); // array of nearest neighbors - auto_array_ptr mindist(N_1); // distances to the nearest neighbors - auto_array_ptr row_repr(N); // row_repr[i]: node number that the - // i-th row represents - doubly_linked_list active_nodes(N); - binary_min_heap nn_distances(&*mindist, N_1); // minimum heap structure for - // the distance to the nearest neighbor of each point - t_index node1, node2; // node numbers in the output - t_float size1, size2; // and their cardinalities - - t_float min; // minimum and row index for nearest-neighbor search - t_index idx; - - for (i=0; ii} D(i,j) for i in range(N-1) - t_float const * DD = D; - for (i=0; i::infinity(); - for (idx=j=i+1; ji} D(i,j) - - Normally, we have equality. However, this minimum may become invalid due - to the updates in the distance matrix. The rules are: - - 1) If mindist[i] is equal to D(i, n_nghbr[i]), this is the correct - minimum and n_nghbr[i] is a nearest neighbor. - - 2) If mindist[i] is smaller than D(i, n_nghbr[i]), this might not be the - correct minimum. The minimum needs to be recomputed. - - 3) mindist[i] is never bigger than the true minimum. Hence, we never - miss the true minimum if we take the smallest mindist entry, - re-compute the value if necessary (thus maybe increasing it) and - looking for the now smallest mindist entry until a valid minimal - entry is found. This step is done in the lines below. - - The update process for D below takes care that these rules are - fulfilled. This makes sure that the minima in the rows D(i,i+1:)of D are - re-calculated when necessary but re-calculation is avoided whenever - possible. - - The re-calculation of the minima makes the worst-case runtime of this - algorithm cubic in N. We avoid this whenever possible, and in most cases - the runtime appears to be quadratic. - */ - idx1 = nn_distances.argmin(); - if (method != METHOD_METR_SINGLE) { - while ( mindist[idx1] < D_(idx1, n_nghbr[idx1]) ) { - // Recompute the minimum mindist[idx1] and n_nghbr[idx1]. - n_nghbr[idx1] = j = active_nodes.succ[idx1]; // exists, maximally N-1 - min = D_(idx1,j); - for (j=active_nodes.succ[j]; j(members[idx1]); - size2 = static_cast(members[idx2]); - members[idx2] += members[idx1]; - } - Z2.append(node1, node2, mindist[idx1]); - - // Remove idx1 from the list of active indices (active_nodes). - active_nodes.remove(idx1); - // Index idx2 now represents the new (merged) node with label N+i. - row_repr[idx2] = N+i; - - // Update the distance matrix - switch (method) { - case METHOD_METR_SINGLE: - /* - Single linkage. - - Characteristic: new distances are never longer than the old distances. - */ - // Update the distance matrix in the range [start, idx1). - for (j=active_nodes.start; j(members[j]) ); - if (n_nghbr[j] == idx1) - n_nghbr[j] = idx2; - } - // Update the distance matrix in the range (idx1, idx2). - for (; j(members[j]) ); - if (D_(j, idx2) < mindist[j]) { - nn_distances.update_leq(j, D_(j, idx2)); - n_nghbr[j] = idx2; - } - } - // Update the distance matrix in the range (idx2, N). - if (idx2(members[j]) ); - min = D_(idx2,j); - for (j=active_nodes.succ[j]; j(members[j]) ); - if (D_(idx2,j) < min) { - min = D_(idx2,j); - n_nghbr[idx2] = j; - } - } - nn_distances.update(idx2, min); - } - break; - - case METHOD_METR_CENTROID: { - /* - Centroid linkage. - - Shorter and longer distances can occur, not bigger than max(d1,d2) - but maybe smaller than min(d1,d2). - */ - // Update the distance matrix in the range [start, idx1). - t_float s = size1/(size1+size2); - t_float t = size2/(size1+size2); - t_float stc = s*t*mindist[idx1]; - for (j=active_nodes.start; j -static void MST_linkage_core_vector(const t_index N, - t_dissimilarity & dist, - cluster_result & Z2) { -/* - N: integer, number of data points - dist: function pointer to the metric - Z2: output data structure - - The basis of this algorithm is an algorithm by Rohlf: - - F. James Rohlf, Hierarchical clustering using the minimum spanning tree, - The Computer Journal, vol. 16, 1973, p. 93–95. -*/ - t_index i; - t_index idx2; - doubly_linked_list active_nodes(N); - auto_array_ptr d(N); - - t_index prev_node; - t_float min; - - // first iteration - idx2 = 1; - min = std::numeric_limits::infinity(); - for (i=1; i tmp) - d[i] = tmp; - else if (fc_isnan(tmp)) - throw (nan_error()); -#if HAVE_DIAGNOSTIC -#pragma GCC diagnostic pop -#endif - if (d[i] < min) { - min = d[i]; - idx2 = i; - } - } - Z2.append(prev_node, idx2, min); - } -} - -template -static void generic_linkage_vector(const t_index N, - t_dissimilarity & dist, - cluster_result & Z2) { - /* - N: integer, number of data points - dist: function pointer to the metric - Z2: output data structure - - This algorithm is valid for the distance update methods - "Ward", "centroid" and "median" only! - */ - const t_index N_1 = N-1; - t_index i, j; // loop variables - t_index idx1, idx2; // row and column indices - - auto_array_ptr n_nghbr(N_1); // array of nearest neighbors - auto_array_ptr mindist(N_1); // distances to the nearest neighbors - auto_array_ptr row_repr(N); // row_repr[i]: node number that the - // i-th row represents - doubly_linked_list active_nodes(N); - binary_min_heap nn_distances(&*mindist, N_1); // minimum heap structure for - // the distance to the nearest neighbor of each point - t_index node1, node2; // node numbers in the output - t_float min; // minimum and row index for nearest-neighbor search - - for (i=0; ii} D(i,j) for i in range(N-1) - for (i=0; i::infinity(); - t_index idx; - for (idx=j=i+1; j(i,j); - } - if (tmp(idx1,j); - for (j=active_nodes.succ[j]; j(idx1,j); - if (tmp(j, idx2); - if (tmp < mindist[j]) { - nn_distances.update_leq(j, tmp); - n_nghbr[j] = idx2; - } - else if (n_nghbr[j] == idx2) - n_nghbr[j] = idx1; // invalidate - } - // Find the nearest neighbor for idx2. - if (idx2(idx2,j); - for (j=active_nodes.succ[j]; j(idx2, j); - if (tmp < min) { - min = tmp; - n_nghbr[idx2] = j; - } - } - nn_distances.update(idx2, min); - } - } - } -} - -template -static void generic_linkage_vector_alternative(const t_index N, - t_dissimilarity & dist, - cluster_result & Z2) { - /* - N: integer, number of data points - dist: function pointer to the metric - Z2: output data structure - - This algorithm is valid for the distance update methods - "Ward", "centroid" and "median" only! - */ - const t_index N_1 = N-1; - t_index i, j=0; // loop variables - t_index idx1, idx2; // row and column indices - - auto_array_ptr n_nghbr(2*N-2); // array of nearest neighbors - auto_array_ptr mindist(2*N-2); // distances to the nearest neighbors - - doubly_linked_list active_nodes(N+N_1); - binary_min_heap nn_distances(&*mindist, N_1, 2*N-2, 1); // minimum heap - // structure for the distance to the nearest neighbor of each point - - t_float min; // minimum for nearest-neighbor searches - - // Initialize the minimal distances: - // Find the nearest neighbor of each point. - // n_nghbr[i] = argmin_{j>i} D(i,j) for i in range(N-1) - for (i=1; i::infinity(); - t_index idx; - for (idx=j=0; j(i,j); - } - if (tmp - -extern "C" { -#include "fastcluster.h" -} - - -int main(int argc, const char* argv[]) { - const int n = 11; - const int m = 3; - double* pts = new double[n*m]{59.26000137, -9.35999966, -5.42500019, - 91.61999817, -0.31999999, -2.75, - 31.38000031, 0.40000001, -0.2, - 89.57999725, -8.07999992, -18.04999924, - 53.42000122, 0.63999999, -0.175, - 31.38000031, 0.47999999, -0.2, - 36.33999939, 0.16, -0.2, - 53.33999939, 0.95999998, -0.175, - 59.26000137, -9.76000023, -5.44999981, - 33.93999977, 0.40000001, -0.22499999, - 106.74000092, -5.76000023, -18.04999924}; - - int * idx = new int[n]; - int * correct_idx = new int[n]{0, 1, 2, 3, 4, 2, 5, 4, 0, 5, 6}; - - cluster_points_centroid(n, m, pts, 2.5 * 2.5, idx); - - for (int i = 0; i < n; i++) { - assert(idx[i] == correct_idx[i]); - } - - delete[] idx; - delete[] correct_idx; - delete[] pts; -} diff --git a/tools/bodyteleop/web.py b/tools/bodyteleop/web.py index e39756964..ed94cb6d8 100644 --- a/tools/bodyteleop/web.py +++ b/tools/bodyteleop/web.py @@ -6,11 +6,16 @@ import ssl import uuid import time -from common.basedir import BASEDIR +# aiortc and its dependencies have lots of internal warnings :( +import warnings +warnings.resetwarnings() +warnings.simplefilter("always") + from aiohttp import web from aiortc import RTCPeerConnection, RTCSessionDescription import cereal.messaging as messaging +from common.basedir import BASEDIR from tools.bodyteleop.bodyav import BodyMic, WebClientSpeaker, force_codec, play_sound, MediaBlackhole, EncodedBodyVideo logger = logging.getLogger("pc") diff --git a/tools/lib/auth.py b/tools/lib/auth.py index 086027968..a1bcdb1c5 100755 --- a/tools/lib/auth.py +++ b/tools/lib/auth.py @@ -54,7 +54,7 @@ class ClientRedirectHandler(BaseHTTPRequestHandler): self.end_headers() self.wfile.write(b'Return to the CLI to continue') - def log_message(self, format, *args): # pylint: disable=redefined-builtin + def log_message(self, *args): # pylint: disable=redefined-builtin pass # this prevent http server from dumping messages to stdout diff --git a/tools/lib/filereader.py b/tools/lib/filereader.py index 215f7b218..718b853b1 100644 --- a/tools/lib/filereader.py +++ b/tools/lib/filereader.py @@ -6,6 +6,6 @@ DATA_ENDPOINT = os.getenv("DATA_ENDPOINT", "http://data-raw.comma.internal/") def FileReader(fn, debug=False): if fn.startswith("cd:/"): fn = fn.replace("cd:/", DATA_ENDPOINT) - if fn.startswith("http://") or fn.startswith("https://"): + if fn.startswith(("http://", "https://")): return URLFile(fn, debug=debug) return open(fn, "rb") diff --git a/tools/lib/framereader.py b/tools/lib/framereader.py index d9920ab12..b4845b9f0 100644 --- a/tools/lib/framereader.py +++ b/tools/lib/framereader.py @@ -70,8 +70,8 @@ def ffprobe(fn, fmt=None): try: ffprobe_output = subprocess.check_output(cmd) - except subprocess.CalledProcessError: - raise DataUnreadableError(fn) + except subprocess.CalledProcessError as e: + raise DataUnreadableError(fn) from e return json.loads(ffprobe_output) @@ -80,14 +80,14 @@ def vidindex(fn, typ): vidindex_dir = os.path.join(os.path.dirname(os.path.realpath(__file__)), "vidindex") vidindex = os.path.join(vidindex_dir, "vidindex") - subprocess.check_call(["make"], cwd=vidindex_dir, stdout=open("/dev/null", "w")) + subprocess.check_call(["make"], cwd=vidindex_dir, stdout=subprocess.DEVNULL) with tempfile.NamedTemporaryFile() as prefix_f, \ tempfile.NamedTemporaryFile() as index_f: try: subprocess.check_call([vidindex, typ, fn, prefix_f.name, index_f.name]) - except subprocess.CalledProcessError: - raise DataUnreadableError(f"vidindex failed on file {fn}") + except subprocess.CalledProcessError as e: + raise DataUnreadableError(f"vidindex failed on file {fn}") from e with open(index_f.name, "rb") as f: index = f.read() with open(prefix_f.name, "rb") as f: @@ -237,25 +237,23 @@ def decompress_video_data(rawdat, vid_fmt, w, h, pix_fmt): threads = os.getenv("FFMPEG_THREADS", "0") cuda = os.getenv("FFMPEG_CUDA", "0") == "1" - proc = subprocess.Popen( - ["ffmpeg", - "-threads", threads, - "-hwaccel", "none" if not cuda else "cuda", - "-c:v", "hevc", - "-vsync", "0", - "-f", vid_fmt, - "-flags2", "showall", - "-i", "pipe:0", - "-threads", threads, - "-f", "rawvideo", - "-pix_fmt", pix_fmt, - "pipe:1"], - stdin=tmpf, stdout=subprocess.PIPE, stderr=open("/dev/null")) - - # dat = proc.communicate()[0] - dat = proc.stdout.read() - if proc.wait() != 0: - raise DataUnreadableError("ffmpeg failed") + args = ["ffmpeg", + "-threads", threads, + "-hwaccel", "none" if not cuda else "cuda", + "-c:v", "hevc", + "-vsync", "0", + "-f", vid_fmt, + "-flags2", "showall", + "-i", "pipe:0", + "-threads", threads, + "-f", "rawvideo", + "-pix_fmt", pix_fmt, + "pipe:1"] + with subprocess.Popen(args, stdin=tmpf, stdout=subprocess.PIPE, stderr=subprocess.DEVNULL) as proc: + # dat = proc.communicate()[0] + dat = proc.stdout.read() + if proc.wait() != 0: + raise DataUnreadableError("ffmpeg failed") if pix_fmt == "rgb24": ret = np.frombuffer(dat, dtype=np.uint8).reshape(-1, h, w, 3) @@ -418,7 +416,7 @@ class VideoStreamDecompressor: elif self.pix_fmt == "yuv444p": ret = np.frombuffer(dat, dtype=np.uint8).reshape((3, self.h, self.w)) else: - assert False + raise RuntimeError(f"unknown pix_fmt: {self.pix_fmt}") yield ret result_code = self.proc.wait() diff --git a/tools/lib/logreader.py b/tools/lib/logreader.py index 46c648ef1..8f1e5b9f8 100755 --- a/tools/lib/logreader.py +++ b/tools/lib/logreader.py @@ -98,7 +98,7 @@ class LogReader: for e in ents: _ents.append(e) except capnp.KjException: - warnings.warn("Corrupted events detected", RuntimeWarning) + warnings.warn("Corrupted events detected", RuntimeWarning, stacklevel=1) self._ents = list(sorted(_ents, key=lambda x: x.logMonoTime) if sort_by_time else _ents) self._ts = [x.logMonoTime for x in self._ents]